From b35ad4b2868f47b33c58af493093e5d0a078fc9a Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 26 Aug 2024 14:26:00 +0900 Subject: [PATCH 001/217] fix(autonomous_emergency_braking): fix debug marker visual bug (#8611) fix bug by using the collision data keeper Signed-off-by: Daniel Sanchez --- .../autonomous_emergency_braking/node.hpp | 5 +--- .../src/node.cpp | 25 +++++++++++-------- 2 files changed, 16 insertions(+), 14 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp index 24eaa8516a732..c29247a978c73 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp @@ -156,10 +156,7 @@ class CollisionDataKeeper * @brief Get the closest object data * @return Object data of the closest object */ - [[nodiscard]] ObjectData get() const - { - return (closest_object_.has_value()) ? closest_object_.value() : ObjectData(); - } + [[nodiscard]] std::optional get() const { return closest_object_; } /** * @brief Get the previous closest object data diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index dc8c876bd56f6..e8744d85dc11a 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -393,12 +393,15 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) const auto diag_level = DiagnosticStatus::ERROR; stat.summary(diag_level, error_msg); const auto & data = collision_data_keeper_.get(); - stat.addf("RSS", "%.2f", data.rss); - stat.addf("Distance", "%.2f", data.distance_to_object); - stat.addf("Object Speed", "%.2f", data.velocity); - if (publish_debug_markers_) { - addCollisionMarker(data, debug_markers); + if (data.has_value()) { + stat.addf("RSS", "%.2f", data.value().rss); + stat.addf("Distance", "%.2f", data.value().distance_to_object); + stat.addf("Object Speed", "%.2f", data.value().velocity); + if (publish_debug_markers_) { + addCollisionMarker(data.value(), debug_markers); + } } + addVirtualStopWallMarker(info_markers); } else { const std::string error_msg = "[AEB]: No Collision"; @@ -476,17 +479,19 @@ bool AEB::checkCollision(MarkerArray & debug_markers) return std::make_optional(*closest_object_point_itr); }); + const bool has_collision = (closest_object_point.has_value()) + ? hasCollision(current_v, closest_object_point.value()) + : false; + // Add debug markers if (publish_debug_markers_) { const auto [color_r, color_g, color_b, color_a] = debug_colors; addMarker( - this->get_clock()->now(), path, ego_polys, objects, closest_object_point, color_r, color_g, - color_b, color_a, debug_ns, debug_markers); + this->get_clock()->now(), path, ego_polys, objects, collision_data_keeper_.get(), color_r, + color_g, color_b, color_a, debug_ns, debug_markers); } // check collision using rss distance - return (closest_object_point.has_value()) - ? hasCollision(current_v, closest_object_point.value()) - : false; + return has_collision; }; // step3. make function to check collision with ego path created with sensor data From f021d06ee5a16e625d7d2646b2497d9d69f0afd1 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 26 Aug 2024 14:36:34 +0900 Subject: [PATCH 002/217] fix(goal_planner): remove time keeper in non main thread (#8610) Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 4 ---- 1 file changed, 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 ff248fbe02a1c..c67983993de01 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 @@ -1206,8 +1206,6 @@ bool GoalPlannerModule::hasDecidedPath( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - return checkDecidingPathStatus( planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, goal_searcher) @@ -1240,8 +1238,6 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - const auto & prev_status = thread_safe_data_.get_prev_data().deciding_path_status; const bool enable_safety_check = parameters.safety_check_params.enable_safety_check; From c80eddc26daf25d975dd294c5cb428d42ed7e600 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 26 Aug 2024 15:05:12 +0900 Subject: [PATCH 003/217] fix(lane_change): update rtc status for some failure condition (#8604) update rtc status for some failure condition Signed-off-by: Go Sakayori --- .../src/interface.cpp | 6 ++++++ 1 file changed, 6 insertions(+) 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 a7cf89193b37f..979004d439bdc 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 @@ -258,11 +258,17 @@ bool LaneChangeInterface::canTransitFailureState() if (!module_type_->isValidPath()) { log_debug_throttled("Transit to failure state due not to find valid path"); + updateRTCStatus( + std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, + State::FAILED); 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; } From 1db4a65d5c6963b0430df7d7f24ec34eeed6bc3d Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Mon, 26 Aug 2024 15:26:26 +0900 Subject: [PATCH 004/217] fix(freespace_planner): fix free space planner spamming message (#8614) check data availability only when scenario is active Signed-off-by: mohammad alqudah --- .../freespace_planner_node.cpp | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) 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 8e8a962ed1071..267fd9932e781 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 @@ -416,7 +416,6 @@ void FreespacePlannerNode::onOdometry(const Odometry::ConstSharedPtr msg) void FreespacePlannerNode::updateData() { occupancy_grid_ = occupancy_grid_sub_.takeData(); - scenario_ = scenario_sub_.takeData(); { auto msgs = odom_sub_.takeData(); @@ -440,11 +439,6 @@ bool FreespacePlannerNode::isDataReady() is_ready = false; } - if (!scenario_) { - RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "Waiting for scenario."); - is_ready = false; - } - if (!odom_) { RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "Waiting for odometry."); is_ready = false; @@ -455,14 +449,15 @@ bool FreespacePlannerNode::isDataReady() void FreespacePlannerNode::onTimer() { - updateData(); - - if (!isDataReady()) { + scenario_ = scenario_sub_.takeData(); + if (!isActive(scenario_)) { + reset(); return; } - if (!isActive(scenario_)) { - reset(); + updateData(); + + if (!isDataReady()) { return; } From 3f015666774c42ed9bdeb3568ab34a563595448d Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Mon, 26 Aug 2024 16:29:11 +0900 Subject: [PATCH 005/217] refactor(ekf_localizer): fix tf2 listener (#8584) * fix tf2 listener 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> --- .../include/ekf_localizer/ekf_localizer.hpp | 5 +++++ .../ekf_localizer/src/ekf_localizer.cpp | 19 +++++++------------ 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index f3830c303ab48..650eca26d4e96 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -39,6 +39,7 @@ #include #include +#include #include #include @@ -141,6 +142,10 @@ class EKFLocalizer : public rclcpp::Node rclcpp::TimerBase::SharedPtr timer_tf_; //!< @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_; diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 707d5e585cb0c..f1e4d0c958c77 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -44,6 +44,8 @@ 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), @@ -285,21 +287,14 @@ bool EKFLocalizer::get_transform_from_tf( std::string parent_frame, std::string child_frame, geometry_msgs::msg::TransformStamped & transform) { - tf2::BufferCore tf_buffer; - tf2_ros::TransformListener tf_listener(tf_buffer); - rclcpp::sleep_for(std::chrono::milliseconds(100)); - parent_frame = erase_leading_slash(parent_frame); child_frame = erase_leading_slash(child_frame); - for (int i = 0; i < 50; ++i) { - try { - transform = tf_buffer.lookupTransform(parent_frame, child_frame, tf2::TimePointZero); - return true; - } catch (tf2::TransformException & ex) { - warning_->warn(ex.what()); - rclcpp::sleep_for(std::chrono::milliseconds(100)); - } + try { + transform = tf2_buffer_.lookupTransform(parent_frame, child_frame, tf2::TimePointZero); + return true; + } catch (tf2::TransformException & ex) { + warning_->warn(ex.what()); } return false; } From f64c4ed448c88c83e200d45f6c4e1eb196142578 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Mon, 26 Aug 2024 16:29:26 +0900 Subject: [PATCH 006/217] fix(ndt_scan_matcher): fix timestamp in service_ndt_align func (#8599) fix timestamp Signed-off-by: Yamato Ando --- localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index 3e8b9b99737c0..b59686c211b53 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -961,7 +961,8 @@ void NDTScanMatcher::service_ndt_align_main( diagnostics_ndt_align_->add_key_value("is_succeed_transform_initial_pose", true); // transform pose_frame to map_frame - const auto initial_pose_msg_in_map_frame = transform(req->pose_with_covariance, transform_s2t); + auto initial_pose_msg_in_map_frame = transform(req->pose_with_covariance, transform_s2t); + initial_pose_msg_in_map_frame.header.stamp = req->pose_with_covariance.header.stamp; map_update_module_->update_map( initial_pose_msg_in_map_frame.pose.pose.position, diagnostics_ndt_align_); From f99aa3a79b30ea39c1b160a565223d455fef3fb6 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Mon, 26 Aug 2024 17:18:30 +0900 Subject: [PATCH 007/217] fix(ekf_localizer): change roll, pitch proc dev (#8619) change roll, pitch proc dev Signed-off-by: Yamato Ando --- localization/ekf_localizer/config/ekf_localizer.param.yaml | 4 ++-- .../schema/sub/simple_1d_filter_parameters.sub_schema.json | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/localization/ekf_localizer/config/ekf_localizer.param.yaml b/localization/ekf_localizer/config/ekf_localizer.param.yaml index 4a7696ec9e65e..13319521e35ab 100644 --- a/localization/ekf_localizer/config/ekf_localizer.param.yaml +++ b/localization/ekf_localizer/config/ekf_localizer.param.yaml @@ -30,8 +30,8 @@ simple_1d_filter_parameters: #Simple1DFilter parameters z_filter_proc_dev: 1.0 - roll_filter_proc_dev: 0.01 - pitch_filter_proc_dev: 0.01 + roll_filter_proc_dev: 0.1 + pitch_filter_proc_dev: 0.1 diagnostics: # for diagnostics diff --git a/localization/ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json b/localization/ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json index ad2f638a18d5f..00679ee92ad24 100644 --- a/localization/ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json +++ b/localization/ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json @@ -13,12 +13,12 @@ "roll_filter_proc_dev": { "type": "number", "description": "Simple1DFilter - Roll filter process deviation", - "default": 0.01 + "default": 0.1 }, "pitch_filter_proc_dev": { "type": "number", "description": "Simple1DFilter - Pitch filter process deviation", - "default": 0.01 + "default": 0.1 } }, "required": ["z_filter_proc_dev", "roll_filter_proc_dev", "pitch_filter_proc_dev"], From fe953a40cd4a2c09a7cd82d6f25c1d09b2a9d86c Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 26 Aug 2024 17:21:19 +0900 Subject: [PATCH 008/217] docs(autoware_autonomous_emergency_braking): improve AEB module's README (#8612) * docs: improve AEB module's README Signed-off-by: Kyoichi Sugahara * update rss distance length Signed-off-by: Kyoichi Sugahara --------- Signed-off-by: Kyoichi Sugahara --- .../README.md | 8 +- .../image/rss_check.drawio.svg | 183 ++++++------------ 2 files changed, 65 insertions(+), 126 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/README.md b/control/autoware_autonomous_emergency_braking/README.md index 1382a24d98b0a..66d4483fbdf84 100644 --- a/control/autoware_autonomous_emergency_braking/README.md +++ b/control/autoware_autonomous_emergency_braking/README.md @@ -8,8 +8,6 @@ This module has following assumptions. -- It is used when driving at low speeds (about 15 km/h). - - The predicted path of the ego vehicle can be made from either the path created from sensors or the path created from a control module, or both. - The current speed and angular velocity can be obtained from the sensors of the ego vehicle, and it uses points as obstacles. @@ -25,7 +23,7 @@ The pros and cons of both approaches are: IMU angular velocity: - (+) Usually, it has high accuracy -- (-)Vehicle vibration might introduce noise. +- (-) Vehicle vibration might introduce noise. Steering angle: @@ -186,7 +184,7 @@ The AEB module can also prevent collisions when the ego vehicle is moving backwa When vehicle odometry information is faulty, it is possible that the MPC fails to predict a correct path for the ego vehicle. If the MPC predicted path is wrong, collision avoidance will not work as intended on the planning modules. However, the AEB’s IMU path does not depend on the MPC and could be able to predict a collision when the other modules cannot. As an example you can see a figure of a hypothetical case in which the MPC path is wrong and only the AEB’s IMU path detects a collision. -![backward driving](./image/wrong-mpc.drawio.svg) +![wrong mpc](./image/wrong-mpc.drawio.svg) ## Parameters @@ -217,6 +215,8 @@ When vehicle odometry information is faulty, it is possible that the MPC fails t ## Limitations +- The distance required to stop after collision detection depends on the ego vehicle's speed and deceleration performance. To avoid collisions, it's necessary to increase the detection distance and set a higher deceleration rate. However, this creates a trade-off as it may also increase the number of unnecessary activations. Therefore, it's essential to consider what role this module should play and adjust the parameters accordingly. + - AEB might not be able to react with obstacles that are close to the ground. It depends on the performance of the pre-processing methods applied to the point cloud. - Longitudinal acceleration information obtained from sensors is not used due to the high amount of noise. diff --git a/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg b/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg index 2d1716519631d..1d3dd824df5f0 100644 --- a/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg +++ b/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg @@ -1,134 +1,73 @@ - - - - - - - + + + + + + + + + + + + + + + + +
+
+ + Closest point distance +
+
+
+
+
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
- - Closest Point Distance -
-
-
-
- -
-
-
- - - - - - - - - - - - -
-
-
RSS distance
-
-
-
- -
-
+ + + + + + +
+
+ RSS distance +
+
+
From 1a58707d3a6fda9ad32d84a7940a1544a71f7af4 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 26 Aug 2024 19:32:54 +0900 Subject: [PATCH 009/217] fix(autoware_traffic_light_map_based_detector): output from screen to both (#8411) --- .../launch/traffic_light_map_based_detector.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_traffic_light_map_based_detector/launch/traffic_light_map_based_detector.launch.xml b/perception/autoware_traffic_light_map_based_detector/launch/traffic_light_map_based_detector.launch.xml index 9f035e7f1ae6c..39026c85c1cef 100644 --- a/perception/autoware_traffic_light_map_based_detector/launch/traffic_light_map_based_detector.launch.xml +++ b/perception/autoware_traffic_light_map_based_detector/launch/traffic_light_map_based_detector.launch.xml @@ -12,7 +12,7 @@ - + From a24e2069fa255f5bb3e35a5c6ab2dcad73eb8739 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 26 Aug 2024 19:33:34 +0900 Subject: [PATCH 010/217] fix(autoware_multi_object_tracker): output from screen to both (#8407) --- .../launch/multi_object_tracker.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_multi_object_tracker/launch/multi_object_tracker.launch.xml b/perception/autoware_multi_object_tracker/launch/multi_object_tracker.launch.xml index db76e181a6afa..88f63e00ed511 100644 --- a/perception/autoware_multi_object_tracker/launch/multi_object_tracker.launch.xml +++ b/perception/autoware_multi_object_tracker/launch/multi_object_tracker.launch.xml @@ -6,7 +6,7 @@ - + From ac95a1fc6492d874113e3ae3f70ab8adf70a3086 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 26 Aug 2024 19:39:58 +0900 Subject: [PATCH 011/217] fix(autoware_map_based_prediction): output from screen to both (#8408) --- .../launch/map_based_prediction.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_map_based_prediction/launch/map_based_prediction.launch.xml b/perception/autoware_map_based_prediction/launch/map_based_prediction.launch.xml index b65f0de892dcc..2c668639c2a56 100644 --- a/perception/autoware_map_based_prediction/launch/map_based_prediction.launch.xml +++ b/perception/autoware_map_based_prediction/launch/map_based_prediction.launch.xml @@ -7,7 +7,7 @@ - + From a3cf7bda38e1dba1c5b2aecab081ca8fd1398671 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 27 Aug 2024 07:58:40 +0900 Subject: [PATCH 012/217] fix(traffic_light_utils): fix unusedFunction (#8605) * fix:unusedFunction Signed-off-by: kobayu858 * fix:unusedFunction Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../traffic_light_utils.hpp | 7 ---- .../src/traffic_light_utils.cpp | 23 ----------- .../test/test_traffic_light_utils.cpp | 40 ------------------- 3 files changed, 70 deletions(-) diff --git a/common/traffic_light_utils/include/traffic_light_utils/traffic_light_utils.hpp b/common/traffic_light_utils/include/traffic_light_utils/traffic_light_utils.hpp index cf4ecdd9774b8..3a40c0c3b1d51 100644 --- a/common/traffic_light_utils/include/traffic_light_utils/traffic_light_utils.hpp +++ b/common/traffic_light_utils/include/traffic_light_utils/traffic_light_utils.hpp @@ -30,13 +30,6 @@ namespace traffic_light_utils { -bool isRoiValid( - const tier4_perception_msgs::msg::TrafficLightRoi & roi, uint32_t width, uint32_t height); - -void setRoiInvalid(tier4_perception_msgs::msg::TrafficLightRoi & roi); - -bool isSignalUnknown(const tier4_perception_msgs::msg::TrafficLight & signal); - void setSignalUnknown(tier4_perception_msgs::msg::TrafficLight & signal, float confidence = -1); /** diff --git a/common/traffic_light_utils/src/traffic_light_utils.cpp b/common/traffic_light_utils/src/traffic_light_utils.cpp index 8aea884510ec2..a3da21c1bb578 100644 --- a/common/traffic_light_utils/src/traffic_light_utils.cpp +++ b/common/traffic_light_utils/src/traffic_light_utils.cpp @@ -17,29 +17,6 @@ namespace traffic_light_utils { -bool isRoiValid( - const tier4_perception_msgs::msg::TrafficLightRoi & roi, uint32_t width, uint32_t height) -{ - uint32_t x1 = roi.roi.x_offset; - uint32_t x2 = roi.roi.x_offset + roi.roi.width; - uint32_t y1 = roi.roi.y_offset; - uint32_t y2 = roi.roi.y_offset + roi.roi.height; - return roi.roi.width > 0 && roi.roi.height > 0 && x1 < width && y1 < height && x2 < width && - y2 < height; -} - -void setRoiInvalid(tier4_perception_msgs::msg::TrafficLightRoi & roi) -{ - roi.roi.height = roi.roi.width = 0; -} - -bool isSignalUnknown(const tier4_perception_msgs::msg::TrafficLight & signal) -{ - return signal.elements.size() == 1 && - signal.elements[0].shape == tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN && - signal.elements[0].color == tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; -} - void setSignalUnknown(tier4_perception_msgs::msg::TrafficLight & signal, float confidence) { signal.elements.resize(1); diff --git a/common/traffic_light_utils/test/test_traffic_light_utils.cpp b/common/traffic_light_utils/test/test_traffic_light_utils.cpp index a80510693c487..a9e601370945d 100644 --- a/common/traffic_light_utils/test/test_traffic_light_utils.cpp +++ b/common/traffic_light_utils/test/test_traffic_light_utils.cpp @@ -18,46 +18,6 @@ namespace traffic_light_utils { -TEST(isRoiValid, roi_validity) -{ - tier4_perception_msgs::msg::TrafficLightRoi test_roi; - test_roi.roi.x_offset = 300; - test_roi.roi.y_offset = 200; - test_roi.roi.width = 340; - test_roi.roi.height = 200; - uint32_t img_width = 640; - uint32_t img_heigh = 480; - EXPECT_FALSE(isRoiValid(test_roi, img_width, img_heigh)); - test_roi.roi.width = 339; - EXPECT_TRUE(isRoiValid(test_roi, img_width, img_heigh)); -} - -TEST(setRoiInvalid, set_roi_size) -{ - tier4_perception_msgs::msg::TrafficLightRoi test_roi; - test_roi.roi.x_offset = 300; - test_roi.roi.y_offset = 200; - test_roi.roi.width = 300; - test_roi.roi.height = 200; - EXPECT_EQ(test_roi.roi.width, (uint32_t)300); - EXPECT_EQ(test_roi.roi.height, (uint32_t)200); - setRoiInvalid(test_roi); - EXPECT_EQ(test_roi.roi.width, (uint32_t)0); - EXPECT_EQ(test_roi.roi.height, (uint32_t)0); -} - -TEST(isSignalUnknown, signal_element) -{ - tier4_perception_msgs::msg::TrafficLight test_signal; - tier4_perception_msgs::msg::TrafficLightElement element; - element.color = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; - element.shape = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; - test_signal.elements.push_back(element); - EXPECT_TRUE(isSignalUnknown(test_signal)); - test_signal.elements[0].color = tier4_perception_msgs::msg::TrafficLightElement::RED; - EXPECT_FALSE(isSignalUnknown(test_signal)); -} - TEST(setSignalUnknown, set_signal_element) { tier4_perception_msgs::msg::TrafficLight test_signal; From e0ecdda1f7c7712b623fdbbe497fa23dca9cfbcd Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Tue, 27 Aug 2024 08:11:18 +0900 Subject: [PATCH 013/217] chore(autoware_imu_corrector): refactored the imu corrector into the autoware namespace (#8222) * chore: refactored the imu corrector into the autoware namespace Signed-off-by: Kenzo Lobos-Tsunekawa * chore: reverted to non-exported includes Signed-off-by: Kenzo Lobos-Tsunekawa --------- Signed-off-by: Kenzo Lobos-Tsunekawa Co-authored-by: Yamato Ando --- .github/CODEOWNERS | 1 + .../CMakeLists.txt | 12 ++++++------ .../README.md | 2 +- .../config/gyro_bias_estimator.param.yaml | 0 .../config/imu_corrector.param.yaml | 0 .../launch/gyro_bias_estimator.launch.xml | 6 +++--- .../launch/imu_corrector.launch.xml | 4 ++-- .../package.xml | 4 ++-- .../schema/imu_corrector.json | 0 .../src/gyro_bias_estimation_module.cpp | 7 +++---- .../src/gyro_bias_estimation_module.hpp | 4 ++-- .../src/gyro_bias_estimator.cpp | 8 ++++---- .../src/gyro_bias_estimator.hpp | 6 +++--- .../src/imu_corrector_core.cpp | 6 +++--- .../src/imu_corrector_core.hpp | 9 ++++----- .../test/test_gyro_bias_estimation_module.cpp | 4 ++-- 16 files changed, 36 insertions(+), 37 deletions(-) rename sensing/{imu_corrector => autoware_imu_corrector}/CMakeLists.txt (79%) rename sensing/{imu_corrector => autoware_imu_corrector}/README.md (99%) rename sensing/{imu_corrector => autoware_imu_corrector}/config/gyro_bias_estimator.param.yaml (100%) rename sensing/{imu_corrector => autoware_imu_corrector}/config/imu_corrector.param.yaml (100%) rename sensing/{imu_corrector => autoware_imu_corrector}/launch/gyro_bias_estimator.launch.xml (74%) rename sensing/{imu_corrector => autoware_imu_corrector}/launch/imu_corrector.launch.xml (61%) rename sensing/{imu_corrector => autoware_imu_corrector}/package.xml (90%) rename sensing/{imu_corrector => autoware_imu_corrector}/schema/imu_corrector.json (100%) rename sensing/{imu_corrector => autoware_imu_corrector}/src/gyro_bias_estimation_module.cpp (97%) rename sensing/{imu_corrector => autoware_imu_corrector}/src/gyro_bias_estimation_module.hpp (94%) rename sensing/{imu_corrector => autoware_imu_corrector}/src/gyro_bias_estimator.cpp (98%) rename sensing/{imu_corrector => autoware_imu_corrector}/src/gyro_bias_estimator.hpp (95%) rename sensing/{imu_corrector => autoware_imu_corrector}/src/imu_corrector_core.cpp (97%) rename sensing/{imu_corrector => autoware_imu_corrector}/src/imu_corrector_core.hpp (89%) rename sensing/{imu_corrector => autoware_imu_corrector}/test/test_gyro_bias_estimation_module.cpp (97%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 403fe7e0f728f..f0fdae85b78ee 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -200,6 +200,7 @@ planning/sampling_based_planner/autoware_frenet_planner/** maxime.clement@tier4. planning/sampling_based_planner/autoware_path_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/autoware_sampler_common/** maxime.clement@tier4.jp sensing/autoware_image_diagnostics/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp +sensing/autoware_imu_corrector/** taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/autoware_image_transport_decompressor/** kenzo.lobos@tier4.jp yukihiro.saito@tier4.jp sensing/autoware_pcl_extensions/** david.wong@tier4.jp kenzo.lobos@tier4.jp ryu.yamamoto@tier4.jp sensing/autoware_pointcloud_preprocessor/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp david.wong@tier4.jp kenzo.lobos@tier4.jp kyoichi.sugahara@tier4.jp melike@leodrive.ai shunsuke.miura@tier4.jp yihsiang.fang@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp diff --git a/sensing/imu_corrector/CMakeLists.txt b/sensing/autoware_imu_corrector/CMakeLists.txt similarity index 79% rename from sensing/imu_corrector/CMakeLists.txt rename to sensing/autoware_imu_corrector/CMakeLists.txt index b3be5be12b75d..5e417ce94597a 100644 --- a/sensing/imu_corrector/CMakeLists.txt +++ b/sensing/autoware_imu_corrector/CMakeLists.txt @@ -1,10 +1,10 @@ cmake_minimum_required(VERSION 3.14) -project(imu_corrector) +project(autoware_imu_corrector) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(${PROJECT_NAME} SHARED +ament_auto_add_library(imu_corrector SHARED src/imu_corrector_core.cpp ) @@ -13,14 +13,14 @@ ament_auto_add_library(gyro_bias_estimator SHARED src/gyro_bias_estimation_module.cpp ) -rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "imu_corrector::ImuCorrector" - EXECUTABLE ${PROJECT_NAME}_node +rclcpp_components_register_node(imu_corrector + PLUGIN "autoware::imu_corrector::ImuCorrector" + EXECUTABLE imu_corrector_node EXECUTOR SingleThreadedExecutor ) rclcpp_components_register_node(gyro_bias_estimator - PLUGIN "imu_corrector::GyroBiasEstimator" + PLUGIN "autoware::imu_corrector::GyroBiasEstimator" EXECUTABLE gyro_bias_estimator_node EXECUTOR SingleThreadedExecutor ) diff --git a/sensing/imu_corrector/README.md b/sensing/autoware_imu_corrector/README.md similarity index 99% rename from sensing/imu_corrector/README.md rename to sensing/autoware_imu_corrector/README.md index 2df12c94b7d3b..805c20c0cb35c 100644 --- a/sensing/imu_corrector/README.md +++ b/sensing/autoware_imu_corrector/README.md @@ -1,4 +1,4 @@ -# imu_corrector +# autoware_imu_corrector ## imu_corrector diff --git a/sensing/imu_corrector/config/gyro_bias_estimator.param.yaml b/sensing/autoware_imu_corrector/config/gyro_bias_estimator.param.yaml similarity index 100% rename from sensing/imu_corrector/config/gyro_bias_estimator.param.yaml rename to sensing/autoware_imu_corrector/config/gyro_bias_estimator.param.yaml diff --git a/sensing/imu_corrector/config/imu_corrector.param.yaml b/sensing/autoware_imu_corrector/config/imu_corrector.param.yaml similarity index 100% rename from sensing/imu_corrector/config/imu_corrector.param.yaml rename to sensing/autoware_imu_corrector/config/imu_corrector.param.yaml diff --git a/sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml b/sensing/autoware_imu_corrector/launch/gyro_bias_estimator.launch.xml similarity index 74% rename from sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml rename to sensing/autoware_imu_corrector/launch/gyro_bias_estimator.launch.xml index 100168b17171a..774b8f14f9501 100644 --- a/sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml +++ b/sensing/autoware_imu_corrector/launch/gyro_bias_estimator.launch.xml @@ -3,10 +3,10 @@ - - + + - + diff --git a/sensing/imu_corrector/launch/imu_corrector.launch.xml b/sensing/autoware_imu_corrector/launch/imu_corrector.launch.xml similarity index 61% rename from sensing/imu_corrector/launch/imu_corrector.launch.xml rename to sensing/autoware_imu_corrector/launch/imu_corrector.launch.xml index 8430f2a50a85c..456ce58750658 100755 --- a/sensing/imu_corrector/launch/imu_corrector.launch.xml +++ b/sensing/autoware_imu_corrector/launch/imu_corrector.launch.xml @@ -2,9 +2,9 @@ - + - + diff --git a/sensing/imu_corrector/package.xml b/sensing/autoware_imu_corrector/package.xml similarity index 90% rename from sensing/imu_corrector/package.xml rename to sensing/autoware_imu_corrector/package.xml index f5c719d2b4f7e..4869b5566ea05 100644 --- a/sensing/imu_corrector/package.xml +++ b/sensing/autoware_imu_corrector/package.xml @@ -1,9 +1,9 @@ - imu_corrector + autoware_imu_corrector 1.0.0 - The ROS 2 imu_corrector package + The ROS 2 autoware_imu_corrector package Yamato Ando Taiki Yamada Apache License 2.0 diff --git a/sensing/imu_corrector/schema/imu_corrector.json b/sensing/autoware_imu_corrector/schema/imu_corrector.json similarity index 100% rename from sensing/imu_corrector/schema/imu_corrector.json rename to sensing/autoware_imu_corrector/schema/imu_corrector.json diff --git a/sensing/imu_corrector/src/gyro_bias_estimation_module.cpp b/sensing/autoware_imu_corrector/src/gyro_bias_estimation_module.cpp similarity index 97% rename from sensing/imu_corrector/src/gyro_bias_estimation_module.cpp rename to sensing/autoware_imu_corrector/src/gyro_bias_estimation_module.cpp index 7bd6b38490495..18d7965470f05 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimation_module.cpp +++ b/sensing/autoware_imu_corrector/src/gyro_bias_estimation_module.cpp @@ -14,11 +14,10 @@ #include "gyro_bias_estimation_module.hpp" -#include "autoware/universe_utils/geometry/geometry.hpp" - +#include #include -namespace imu_corrector +namespace autoware::imu_corrector { /** @@ -116,4 +115,4 @@ geometry_msgs::msg::Vector3 GyroBiasEstimationModule::get_bias_base_link() const return gyro_bias_base; } -} // namespace imu_corrector +} // namespace autoware::imu_corrector diff --git a/sensing/imu_corrector/src/gyro_bias_estimation_module.hpp b/sensing/autoware_imu_corrector/src/gyro_bias_estimation_module.hpp similarity index 94% rename from sensing/imu_corrector/src/gyro_bias_estimation_module.hpp rename to sensing/autoware_imu_corrector/src/gyro_bias_estimation_module.hpp index 9eff50d296a95..ed166e4daf63c 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimation_module.hpp +++ b/sensing/autoware_imu_corrector/src/gyro_bias_estimation_module.hpp @@ -22,7 +22,7 @@ #include #include -namespace imu_corrector +namespace autoware::imu_corrector { class GyroBiasEstimationModule { @@ -36,6 +36,6 @@ class GyroBiasEstimationModule private: std::pair gyro_bias_pair_; }; -} // namespace imu_corrector +} // namespace autoware::imu_corrector #endif // GYRO_BIAS_ESTIMATION_MODULE_HPP_ diff --git a/sensing/imu_corrector/src/gyro_bias_estimator.cpp b/sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp similarity index 98% rename from sensing/imu_corrector/src/gyro_bias_estimator.cpp rename to sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp index 6882fbf068fd1..ec91311455911 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimator.cpp +++ b/sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp @@ -14,14 +14,14 @@ #include "gyro_bias_estimator.hpp" -#include "autoware/universe_utils/geometry/geometry.hpp" +#include #include #include #include -namespace imu_corrector +namespace autoware::imu_corrector { GyroBiasEstimator::GyroBiasEstimator(const rclcpp::NodeOptions & options) : rclcpp::Node("gyro_bias_validator", options), @@ -243,7 +243,7 @@ void GyroBiasEstimator::update_diagnostics(diagnostic_updater::DiagnosticStatusW stat.add("gyro_bias_threshold", f(gyro_bias_threshold_)); } -} // namespace imu_corrector +} // namespace autoware::imu_corrector #include -RCLCPP_COMPONENTS_REGISTER_NODE(imu_corrector::GyroBiasEstimator) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::imu_corrector::GyroBiasEstimator) diff --git a/sensing/imu_corrector/src/gyro_bias_estimator.hpp b/sensing/autoware_imu_corrector/src/gyro_bias_estimator.hpp similarity index 95% rename from sensing/imu_corrector/src/gyro_bias_estimator.hpp rename to sensing/autoware_imu_corrector/src/gyro_bias_estimator.hpp index 1313f2cb06507..68539a2181fd3 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimator.hpp +++ b/sensing/autoware_imu_corrector/src/gyro_bias_estimator.hpp @@ -14,9 +14,9 @@ #ifndef GYRO_BIAS_ESTIMATOR_HPP_ #define GYRO_BIAS_ESTIMATOR_HPP_ -#include "autoware/universe_utils/ros/transform_listener.hpp" #include "gyro_bias_estimation_module.hpp" +#include #include #include @@ -30,7 +30,7 @@ #include #include -namespace imu_corrector +namespace autoware::imu_corrector { class GyroBiasEstimator : public rclcpp::Node { @@ -97,6 +97,6 @@ class GyroBiasEstimator : public rclcpp::Node DiagnosticsInfo diagnostics_info_; }; -} // namespace imu_corrector +} // namespace autoware::imu_corrector #endif // GYRO_BIAS_ESTIMATOR_HPP_ diff --git a/sensing/imu_corrector/src/imu_corrector_core.cpp b/sensing/autoware_imu_corrector/src/imu_corrector_core.cpp similarity index 97% rename from sensing/imu_corrector/src/imu_corrector_core.cpp rename to sensing/autoware_imu_corrector/src/imu_corrector_core.cpp index c6e12d2481f89..a9acb45888945 100644 --- a/sensing/imu_corrector/src/imu_corrector_core.cpp +++ b/sensing/autoware_imu_corrector/src/imu_corrector_core.cpp @@ -51,7 +51,7 @@ geometry_msgs::msg::Vector3 transform_vector3( return vec_stamped_transformed.vector; } -namespace imu_corrector +namespace autoware::imu_corrector { ImuCorrector::ImuCorrector(const rclcpp::NodeOptions & options) : rclcpp::Node("imu_corrector", options), @@ -124,7 +124,7 @@ void ImuCorrector::callback_imu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_ imu_pub_->publish(imu_msg_base_link); } -} // namespace imu_corrector +} // namespace autoware::imu_corrector #include -RCLCPP_COMPONENTS_REGISTER_NODE(imu_corrector::ImuCorrector) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::imu_corrector::ImuCorrector) diff --git a/sensing/imu_corrector/src/imu_corrector_core.hpp b/sensing/autoware_imu_corrector/src/imu_corrector_core.hpp similarity index 89% rename from sensing/imu_corrector/src/imu_corrector_core.hpp rename to sensing/autoware_imu_corrector/src/imu_corrector_core.hpp index c02aa88a313a7..0c4839f6b5290 100644 --- a/sensing/imu_corrector/src/imu_corrector_core.hpp +++ b/sensing/autoware_imu_corrector/src/imu_corrector_core.hpp @@ -14,9 +14,8 @@ #ifndef IMU_CORRECTOR_CORE_HPP_ #define IMU_CORRECTOR_CORE_HPP_ -#include "autoware/universe_utils/ros/msg_covariance.hpp" -#include "autoware/universe_utils/ros/transform_listener.hpp" - +#include +#include #include #include @@ -27,7 +26,7 @@ #include #include -namespace imu_corrector +namespace autoware::imu_corrector { class ImuCorrector : public rclcpp::Node { @@ -57,6 +56,6 @@ class ImuCorrector : public rclcpp::Node std::string output_frame_; }; -} // namespace imu_corrector +} // namespace autoware::imu_corrector #endif // IMU_CORRECTOR_CORE_HPP_ diff --git a/sensing/imu_corrector/test/test_gyro_bias_estimation_module.cpp b/sensing/autoware_imu_corrector/test/test_gyro_bias_estimation_module.cpp similarity index 97% rename from sensing/imu_corrector/test/test_gyro_bias_estimation_module.cpp rename to sensing/autoware_imu_corrector/test/test_gyro_bias_estimation_module.cpp index 257552e15cbab..573dbe84d6027 100644 --- a/sensing/imu_corrector/test/test_gyro_bias_estimation_module.cpp +++ b/sensing/autoware_imu_corrector/test/test_gyro_bias_estimation_module.cpp @@ -18,7 +18,7 @@ #include -namespace imu_corrector +namespace autoware::imu_corrector { class GyroBiasEstimationModuleTest : public ::testing::Test { @@ -88,4 +88,4 @@ TEST_F(GyroBiasEstimationModuleTest, GetInsufficientDataExceptionWhenVehicleMovi ASSERT_THROW(module.update_bias(pose_list, gyro_list), std::runtime_error); } } -} // namespace imu_corrector +} // namespace autoware::imu_corrector From 88b1658ec9e6ec991c19438487aa652e34d532ce Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 27 Aug 2024 09:13:28 +0900 Subject: [PATCH 014/217] fix(image_projection_based_fusion): remove unused variable (#8634) fix: remove unused variable Signed-off-by: yoshiri --- .../src/pointpainting_fusion/node.cpp | 1 - 1 file changed, 1 deletion(-) 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 3d9b51ae7add7..f999dcd8b0f3f 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 @@ -351,7 +351,6 @@ dc | dc dc dc dc ||zc| // 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, p_z)) { - data = &painted_pointcloud_msg.data[0]; // cppcheck-suppress invalidPointerCast auto p_class = reinterpret_cast(&output[stride + class_offset]); for (const auto & cls : isClassTable_) { From 4cd89392228dfd5c08618401d41365c4099a43ae Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Tue, 27 Aug 2024 10:11:14 +0900 Subject: [PATCH 015/217] feat(autoware_universe_utils): add thread_id check to time_keeper (#8628) add thread_id check Signed-off-by: Y.Hisaki --- .../universe_utils/system/time_keeper.hpp | 2 + .../src/system/time_keeper.cpp | 15 +++- .../test/src/system/test_time_keeper.cpp | 81 ++++++++++++++----- 3 files changed, 76 insertions(+), 22 deletions(-) diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp index 6ae9ec8a4d4cb..e983d9be77e36 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp @@ -25,6 +25,7 @@ #include #include #include +#include #include namespace autoware::universe_utils @@ -169,6 +170,7 @@ class TimeKeeper std::shared_ptr current_time_node_; //!< Shared pointer to the current time node std::shared_ptr root_node_; //!< Shared pointer to the root time node + std::thread::id root_node_thread_id_; //!< ID of the thread that started the tracking autoware::universe_utils::StopWatch< std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> stop_watch_; //!< StopWatch object for tracking the processing time diff --git a/common/autoware_universe_utils/src/system/time_keeper.cpp b/common/autoware_universe_utils/src/system/time_keeper.cpp index 64f4e95f2a46e..8c715c5ccd7e3 100644 --- a/common/autoware_universe_utils/src/system/time_keeper.cpp +++ b/common/autoware_universe_utils/src/system/time_keeper.cpp @@ -14,6 +14,9 @@ #include "autoware/universe_utils/system/time_keeper.hpp" +#include +#include + #include #include @@ -129,7 +132,14 @@ void TimeKeeper::start_track(const std::string & func_name) if (current_time_node_ == nullptr) { current_time_node_ = std::make_shared(func_name); root_node_ = current_time_node_; + root_node_thread_id_ = std::this_thread::get_id(); } else { + if (root_node_thread_id_ != std::this_thread::get_id()) { + RCLCPP_WARN( + rclcpp::get_logger("TimeKeeper"), + "TimeKeeper::start_track() is called from a different thread. Ignoring the call."); + return; + } current_time_node_ = current_time_node_->add_child(func_name); } stop_watch_.tic(func_name); @@ -145,6 +155,9 @@ void TimeKeeper::comment(const std::string & comment) void TimeKeeper::end_track(const std::string & func_name) { + if (root_node_thread_id_ != std::this_thread::get_id()) { + return; + } if (current_time_node_->get_name() != func_name) { throw std::runtime_error(fmt::format( "You must call end_track({}) first, but end_track({}) is called", @@ -178,7 +191,7 @@ ScopedTimeTrack::ScopedTimeTrack(const std::string & func_name, TimeKeeper & tim time_keeper_.start_track(func_name_); } -ScopedTimeTrack::~ScopedTimeTrack() +ScopedTimeTrack::~ScopedTimeTrack() // NOLINT { time_keeper_.end_track(func_name_); } diff --git a/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp b/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp index 71ca7cc74bec5..0540fa8a283ad 100644 --- a/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp +++ b/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp @@ -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. - #include "autoware/universe_utils/system/time_keeper.hpp" #include @@ -20,34 +19,74 @@ #include #include -#include +#include #include -TEST(system, TimeKeeper) +class TimeKeeperTest : public ::testing::Test { - using autoware::universe_utils::ScopedTimeTrack; - using autoware::universe_utils::TimeKeeper; +protected: + std::ostringstream oss; + rclcpp::Node::SharedPtr node; + rclcpp::Publisher::SharedPtr publisher; + std::unique_ptr time_keeper; - rclcpp::Node node{"sample_node"}; - - auto publisher = node.create_publisher( - "~/debug/processing_time_tree", 1); + void SetUp() override + { + node = std::make_shared("test_node"); + publisher = node->create_publisher( + "~/debug/processing_time_tree", 1); + time_keeper = std::make_unique(&oss, publisher); + } +}; - TimeKeeper time_keeper(&std::cerr, publisher); +TEST_F(TimeKeeperTest, BasicFunctionality) +{ + using autoware::universe_utils::ScopedTimeTrack; - ScopedTimeTrack st{"main_func", time_keeper}; + { + ScopedTimeTrack st{"main_func", *time_keeper}; - { // funcA - ScopedTimeTrack st{"funcA", time_keeper}; - std::this_thread::sleep_for(std::chrono::seconds(1)); - } + { // funcA + ScopedTimeTrack st{"funcA", *time_keeper}; + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } - { // funcB - ScopedTimeTrack st{"funcB", time_keeper}; - std::this_thread::sleep_for(std::chrono::seconds(1)); - { // funcC - ScopedTimeTrack st{"funcC", time_keeper}; - std::this_thread::sleep_for(std::chrono::seconds(1)); + { // funcB + ScopedTimeTrack st{"funcB", *time_keeper}; + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + { // funcC + ScopedTimeTrack st{"funcC", *time_keeper}; + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } } } + + // Check if the output contains all function names + std::string output = oss.str(); + EXPECT_TRUE(output.find("main_func") != std::string::npos); + EXPECT_TRUE(output.find("funcA") != std::string::npos); + EXPECT_TRUE(output.find("funcB") != std::string::npos); + EXPECT_TRUE(output.find("funcC") != std::string::npos); +} + +TEST_F(TimeKeeperTest, MultiThreadWarning) +{ + testing::internal::CaptureStderr(); + + std::thread t([this]() { + time_keeper->start_track("ThreadFunction"); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + time_keeper->end_track("ThreadFunction"); + }); + + time_keeper->start_track("MainFunction"); + std::this_thread::sleep_for(std::chrono::milliseconds(20)); + time_keeper->end_track("MainFunction"); + + t.join(); + + std::string err = testing::internal::GetCapturedStderr(); + EXPECT_TRUE( + err.find("TimeKeeper::start_track() is called from a different thread. Ignoring the call.") != + std::string::npos); } From 1b64c31208022625ff58e16fb77c6b399ba41387 Mon Sep 17 00:00:00 2001 From: eiki <53928021+N-Eiki@users.noreply.github.com> Date: Tue, 27 Aug 2024 10:13:26 +0900 Subject: [PATCH 016/217] feat(autoware_accel_brake_map_calibrator): conditional actuation data processing based on source (#8593) * fix: Conditional Actuation Data Processing Based on Source Signed-off-by: N-Eiki * style(pre-commit): autofix * delete extra comentout, indent Signed-off-by: N-Eiki * add take validation Signed-off-by: N-Eiki * style(pre-commit): autofix --------- Signed-off-by: N-Eiki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/accel_brake_map_calibrator_node.cpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp b/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp index b361a0d2725c7..3750fdb77b258 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp +++ b/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp @@ -266,15 +266,16 @@ bool AccelBrakeMapCalibrator::get_current_pitch_from_tf(double * pitch) bool AccelBrakeMapCalibrator::take_data() { // take data from subscribers - // take actuation data - ActuationStatusStamped::ConstSharedPtr actuation_status_ptr = actuation_status_sub_.takeData(); - ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr = actuation_cmd_sub_.takeData(); - if (actuation_status_ptr) { + if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::STATUS) { + ActuationStatusStamped::ConstSharedPtr actuation_status_ptr = actuation_status_sub_.takeData(); + if (!actuation_status_ptr) return false; take_actuation_status(actuation_status_ptr); - } else if (actuation_cmd_ptr) { + } + // take actuation data + if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::COMMAND) { + ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr = actuation_cmd_sub_.takeData(); + if (!actuation_cmd_ptr) return false; take_actuation_command(actuation_cmd_ptr); - } else { - return false; } // take velocity data From 05b15541fb5ac964bd1545a74eaa36a51e9a605c Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 27 Aug 2024 10:36:17 +0900 Subject: [PATCH 017/217] ci(cppcheck): remove unnecessary unreadVariable suppression (#8635) Signed-off-by: Ryuta Kambe --- .cppcheck_suppressions | 1 - 1 file changed, 1 deletion(-) diff --git a/.cppcheck_suppressions b/.cppcheck_suppressions index 162c0394cc4d9..58002c148870c 100644 --- a/.cppcheck_suppressions +++ b/.cppcheck_suppressions @@ -6,7 +6,6 @@ missingIncludeSystem noConstructor unknownMacro unmatchedSuppression -unreadVariable unusedFunction useInitializationList useStlAlgorithm From 93802fde83be4aa7e7eae6f1c72176a6aef86d39 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 27 Aug 2024 11:17:07 +0900 Subject: [PATCH 018/217] chore(autoware_default_adapi)!: prefix autoware to package name (#8533) Signed-off-by: Takagi, Isamu --- .github/CODEOWNERS | 2 +- .../launch/autoware_api.launch.xml | 4 +-- launch/tier4_autoware_api_launch/package.xml | 2 +- localization/pose_initializer/README.md | 6 ++-- .../autoware_behavior_path_planner/README.md | 24 +++++++-------- .../CMakeLists.txt | 30 +++++++++---------- .../README.md | 4 +-- .../config/default_adapi.param.yaml} | 4 +-- .../document/autoware-state.md | 4 +-- .../document/fail-safe.md | 0 .../autoware-state-architecture.drawio.svg | 12 ++++---- .../images/autoware-state-table.drawio.svg | 0 .../document/images/localization.drawio.svg | 0 .../images/motion-architecture.drawio.svg | 0 .../document/images/motion-state.drawio.svg | 0 .../operation-mode-architecture.drawio.svg | 0 .../images/operation-mode-state.drawio.svg | 0 .../images/operation-mode-table.drawio.svg | 0 .../document/images/routing.drawio.svg | 0 .../document/interface.md | 0 .../document/localization.md | 0 .../document/motion.md | 0 .../document/operation-mode.md | 0 .../document/routing.md | 0 .../launch/default_adapi.launch.py} | 18 +++++------ .../package.xml | 4 +-- .../script/guide.py | 0 .../script/web_server.py | 0 .../src/compatibility/autoware_state.cpp | 6 ++-- .../src/compatibility/autoware_state.hpp | 4 +-- .../src/diagnostics.cpp | 6 ++-- .../src/diagnostics.hpp | 4 +-- .../src/fail_safe.cpp | 6 ++-- .../src/fail_safe.hpp | 4 +-- .../src/heartbeat.cpp | 6 ++-- .../src/heartbeat.hpp | 4 +-- .../src/interface.cpp | 6 ++-- .../src/interface.hpp | 4 +-- .../src/localization.cpp | 6 ++-- .../src/localization.hpp | 4 +-- .../src/motion.cpp | 6 ++-- .../src/motion.hpp | 4 +-- .../src/operation_mode.cpp | 6 ++-- .../src/operation_mode.hpp | 4 +-- .../src/perception.cpp | 6 ++-- .../src/perception.hpp | 4 +-- .../src/planning.cpp | 6 ++-- .../src/planning.hpp | 4 +-- .../src/routing.cpp | 6 ++-- .../src/routing.hpp | 4 +-- .../src/utils/localization_conversion.cpp | 4 +-- .../src/utils/localization_conversion.hpp | 4 +-- .../src/utils/route_conversion.cpp | 4 +-- .../src/utils/route_conversion.hpp | 4 +-- .../src/utils/topics.hpp | 4 +-- .../src/utils/types.hpp | 4 +-- .../src/vehicle.cpp | 6 ++-- .../src/vehicle.hpp | 4 +-- .../src/vehicle_door.cpp | 6 ++-- .../src/vehicle_door.hpp | 4 +-- .../src/vehicle_info.cpp | 6 ++-- .../src/vehicle_info.hpp | 4 +-- .../test/main.test.py | 4 +-- .../test/node/interface_version.py | 0 64 files changed, 141 insertions(+), 141 deletions(-) rename system/{default_ad_api => autoware_default_adapi}/CMakeLists.txt (55%) rename system/{default_ad_api => autoware_default_adapi}/README.md (93%) rename system/{default_ad_api/config/default_ad_api.param.yaml => autoware_default_adapi/config/default_adapi.param.yaml} (64%) rename system/{default_ad_api => autoware_default_adapi}/document/autoware-state.md (71%) rename system/{default_ad_api => autoware_default_adapi}/document/fail-safe.md (100%) rename system/{default_ad_api => autoware_default_adapi}/document/images/autoware-state-architecture.drawio.svg (92%) rename system/{default_ad_api => autoware_default_adapi}/document/images/autoware-state-table.drawio.svg (100%) rename system/{default_ad_api => autoware_default_adapi}/document/images/localization.drawio.svg (100%) rename system/{default_ad_api => autoware_default_adapi}/document/images/motion-architecture.drawio.svg (100%) rename system/{default_ad_api => autoware_default_adapi}/document/images/motion-state.drawio.svg (100%) rename system/{default_ad_api => autoware_default_adapi}/document/images/operation-mode-architecture.drawio.svg (100%) rename system/{default_ad_api => autoware_default_adapi}/document/images/operation-mode-state.drawio.svg (100%) rename system/{default_ad_api => autoware_default_adapi}/document/images/operation-mode-table.drawio.svg (100%) rename system/{default_ad_api => autoware_default_adapi}/document/images/routing.drawio.svg (100%) rename system/{default_ad_api => autoware_default_adapi}/document/interface.md (100%) rename system/{default_ad_api => autoware_default_adapi}/document/localization.md (100%) rename system/{default_ad_api => autoware_default_adapi}/document/motion.md (100%) rename system/{default_ad_api => autoware_default_adapi}/document/operation-mode.md (100%) rename system/{default_ad_api => autoware_default_adapi}/document/routing.md (100%) rename system/{default_ad_api/launch/default_ad_api.launch.py => autoware_default_adapi/launch/default_adapi.launch.py} (85%) rename system/{default_ad_api => autoware_default_adapi}/package.xml (94%) rename system/{default_ad_api => autoware_default_adapi}/script/guide.py (100%) rename system/{default_ad_api => autoware_default_adapi}/script/web_server.py (100%) rename system/{default_ad_api => autoware_default_adapi}/src/compatibility/autoware_state.cpp (97%) rename system/{default_ad_api => autoware_default_adapi}/src/compatibility/autoware_state.hpp (97%) rename system/{default_ad_api => autoware_default_adapi}/src/diagnostics.cpp (94%) rename system/{default_ad_api => autoware_default_adapi}/src/diagnostics.hpp (95%) rename system/{default_ad_api => autoware_default_adapi}/src/fail_safe.cpp (89%) rename system/{default_ad_api => autoware_default_adapi}/src/fail_safe.hpp (94%) rename system/{default_ad_api => autoware_default_adapi}/src/heartbeat.cpp (90%) rename system/{default_ad_api => autoware_default_adapi}/src/heartbeat.hpp (93%) rename system/{default_ad_api => autoware_default_adapi}/src/interface.cpp (87%) rename system/{default_ad_api => autoware_default_adapi}/src/interface.hpp (93%) rename system/{default_ad_api => autoware_default_adapi}/src/localization.cpp (90%) rename system/{default_ad_api => autoware_default_adapi}/src/localization.hpp (95%) rename system/{default_ad_api => autoware_default_adapi}/src/motion.cpp (97%) rename system/{default_ad_api => autoware_default_adapi}/src/motion.hpp (96%) rename system/{default_ad_api => autoware_default_adapi}/src/operation_mode.cpp (97%) rename system/{default_ad_api => autoware_default_adapi}/src/operation_mode.hpp (98%) rename system/{default_ad_api => autoware_default_adapi}/src/perception.cpp (96%) rename system/{default_ad_api => autoware_default_adapi}/src/perception.hpp (95%) rename system/{default_ad_api => autoware_default_adapi}/src/planning.cpp (97%) rename system/{default_ad_api => autoware_default_adapi}/src/planning.hpp (97%) rename system/{default_ad_api => autoware_default_adapi}/src/routing.cpp (97%) rename system/{default_ad_api => autoware_default_adapi}/src/routing.hpp (97%) rename system/{default_ad_api => autoware_default_adapi}/src/utils/localization_conversion.cpp (91%) rename system/{default_ad_api => autoware_default_adapi}/src/utils/localization_conversion.hpp (92%) rename system/{default_ad_api => autoware_default_adapi}/src/utils/route_conversion.cpp (98%) rename system/{default_ad_api => autoware_default_adapi}/src/utils/route_conversion.hpp (96%) rename system/{default_ad_api => autoware_default_adapi}/src/utils/topics.hpp (92%) rename system/{default_ad_api => autoware_default_adapi}/src/utils/types.hpp (93%) rename system/{default_ad_api => autoware_default_adapi}/src/vehicle.cpp (98%) rename system/{default_ad_api => autoware_default_adapi}/src/vehicle.hpp (98%) rename system/{default_ad_api => autoware_default_adapi}/src/vehicle_door.cpp (90%) rename system/{default_ad_api => autoware_default_adapi}/src/vehicle_door.hpp (95%) rename system/{default_ad_api => autoware_default_adapi}/src/vehicle_info.cpp (94%) rename system/{default_ad_api => autoware_default_adapi}/src/vehicle_info.hpp (93%) rename system/{default_ad_api => autoware_default_adapi}/test/main.test.py (91%) rename system/{default_ad_api => autoware_default_adapi}/test/node/interface_version.py (100%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index f0fdae85b78ee..c3774f0485153 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -222,7 +222,7 @@ system/autoware_component_monitor/** memin@leodrive.ai system/autoware_processing_time_checker/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp system/bluetooth_monitor/** fumihito.ito@tier4.jp system/component_state_monitor/** isamu.takagi@tier4.jp -system/default_ad_api/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/autoware_default_adapi/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@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 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 2efd1a595b2f4..143fbc9be5bfb 100644 --- a/launch/tier4_autoware_api_launch/launch/autoware_api.launch.xml +++ b/launch/tier4_autoware_api_launch/launch/autoware_api.launch.xml @@ -1,7 +1,7 @@ - + @@ -16,7 +16,7 @@ - + diff --git a/launch/tier4_autoware_api_launch/package.xml b/launch/tier4_autoware_api_launch/package.xml index d45d21b3ed949..dbf5d16834681 100644 --- a/launch/tier4_autoware_api_launch/package.xml +++ b/launch/tier4_autoware_api_launch/package.xml @@ -12,11 +12,11 @@ autoware_cmake ad_api_adaptors + autoware_default_adapi autoware_iv_external_api_adaptor autoware_iv_internal_api_adaptor autoware_path_distance_calculator awapi_awiv_adapter - default_ad_api rosbridge_server topic_tools diff --git a/localization/pose_initializer/README.md b/localization/pose_initializer/README.md index 94bf98f272487..2928f51f7256d 100644 --- a/localization/pose_initializer/README.md +++ b/localization/pose_initializer/README.md @@ -51,9 +51,9 @@ If the score of initial pose estimation result is lower than score threshold, ER ## Connection with Default AD API -This `pose_initializer` is used via default AD API. For detailed description of the API description, please refer to [the description of `default_ad_api`](https://github.com/autowarefoundation/autoware.universe/blob/main/system/default_ad_api/document/localization.md). +This `pose_initializer` is used via default AD API. For detailed description of the API description, please refer to [the description of `autoware_default_adapi`](https://github.com/autowarefoundation/autoware.universe/blob/main/system/autoware_default_adapi/document/localization.md). -drawing +drawing ## Initialize pose via CLI @@ -136,4 +136,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 [ad_api_adaptors](https://github.com/autowarefoundation/autoware.universe/tree/main/system/autoware_default_adapi_helpers/ad_api_adaptors), so there is no need to input them. 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 658edce2ccb3c..b6282e39e3910 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/README.md @@ -89,18 +89,18 @@ The Planner Manager's responsibilities include: ### 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/default_ad_api/document/operation-mode.md) | +| 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. diff --git a/system/default_ad_api/CMakeLists.txt b/system/autoware_default_adapi/CMakeLists.txt similarity index 55% rename from system/default_ad_api/CMakeLists.txt rename to system/autoware_default_adapi/CMakeLists.txt index 799a73508a061..2dd39b455d2d2 100644 --- a/system/default_ad_api/CMakeLists.txt +++ b/system/autoware_default_adapi/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(default_ad_api) +project(autoware_default_adapi) find_package(autoware_cmake REQUIRED) autoware_package() @@ -24,20 +24,20 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_nodes(${PROJECT_NAME} - "default_ad_api::AutowareStateNode" - "default_ad_api::DiagnosticsNode" - "default_ad_api::FailSafeNode" - "default_ad_api::HeartbeatNode" - "default_ad_api::InterfaceNode" - "default_ad_api::LocalizationNode" - "default_ad_api::MotionNode" - "default_ad_api::OperationModeNode" - "default_ad_api::PerceptionNode" - "default_ad_api::PlanningNode" - "default_ad_api::RoutingNode" - "default_ad_api::VehicleNode" - "default_ad_api::VehicleInfoNode" - "default_ad_api::VehicleDoorNode" + "autoware::default_adapi::AutowareStateNode" + "autoware::default_adapi::DiagnosticsNode" + "autoware::default_adapi::FailSafeNode" + "autoware::default_adapi::HeartbeatNode" + "autoware::default_adapi::InterfaceNode" + "autoware::default_adapi::LocalizationNode" + "autoware::default_adapi::MotionNode" + "autoware::default_adapi::OperationModeNode" + "autoware::default_adapi::PerceptionNode" + "autoware::default_adapi::PlanningNode" + "autoware::default_adapi::RoutingNode" + "autoware::default_adapi::VehicleNode" + "autoware::default_adapi::VehicleInfoNode" + "autoware::default_adapi::VehicleDoorNode" ) if(BUILD_TESTING) diff --git a/system/default_ad_api/README.md b/system/autoware_default_adapi/README.md similarity index 93% rename from system/default_ad_api/README.md rename to system/autoware_default_adapi/README.md index 7bc496010eee9..e638c335ab8f2 100644 --- a/system/default_ad_api/README.md +++ b/system/autoware_default_adapi/README.md @@ -1,4 +1,4 @@ -# default_ad_api +# autoware_default_adapi ## Notes @@ -25,7 +25,7 @@ This is a sample to call API using HTTP. This is a debug script to check the conditions for transition to autonomous mode. ```bash -$ ros2 run default_ad_api guide.py +$ ros2 run autoware_default_adapi guide.py The vehicle pose is not estimated. Please set an initial pose or check GNSS. The route is not set. Please set a goal pose. diff --git a/system/default_ad_api/config/default_ad_api.param.yaml b/system/autoware_default_adapi/config/default_adapi.param.yaml similarity index 64% rename from system/default_ad_api/config/default_ad_api.param.yaml rename to system/autoware_default_adapi/config/default_adapi.param.yaml index a15abe091764c..ddbf103878953 100644 --- a/system/default_ad_api/config/default_ad_api.param.yaml +++ b/system/autoware_default_adapi/config/default_adapi.param.yaml @@ -1,8 +1,8 @@ -/default_ad_api/node/autoware_state: +/adapi/node/autoware_state: ros__parameters: update_rate: 10.0 -/default_ad_api/node/motion: +/adapi/node/motion: ros__parameters: require_accept_start: false stop_check_duration: 1.0 diff --git a/system/default_ad_api/document/autoware-state.md b/system/autoware_default_adapi/document/autoware-state.md similarity index 71% rename from system/default_ad_api/document/autoware-state.md rename to system/autoware_default_adapi/document/autoware-state.md index e26756de1f4ba..eb31a4d41bc1d 100644 --- a/system/default_ad_api/document/autoware-state.md +++ b/system/autoware_default_adapi/document/autoware-state.md @@ -2,7 +2,7 @@ ## Overview -Since `/autoware/state` was so widely used, default_ad_api creates it from the states of AD API for backwards compatibility. +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 service `/autoware/shutdown` to change autoware state to finalizing is also supported for compatibility. @@ -11,6 +11,6 @@ The service `/autoware/shutdown` to change autoware state to finalizing is also ## Conversion This is the correspondence between AD API states and autoware states. -The launch state is the data that default_ad_api node holds internally. +The launch state is the data that this node holds internally. ![autoware-state-table](images/autoware-state-table.drawio.svg) diff --git a/system/default_ad_api/document/fail-safe.md b/system/autoware_default_adapi/document/fail-safe.md similarity index 100% rename from system/default_ad_api/document/fail-safe.md rename to system/autoware_default_adapi/document/fail-safe.md diff --git a/system/default_ad_api/document/images/autoware-state-architecture.drawio.svg b/system/autoware_default_adapi/document/images/autoware-state-architecture.drawio.svg similarity index 92% rename from system/default_ad_api/document/images/autoware-state-architecture.drawio.svg rename to system/autoware_default_adapi/document/images/autoware-state-architecture.drawio.svg index 40aebd20ae43f..f3e0129a2f3f2 100644 --- a/system/default_ad_api/document/images/autoware-state-architecture.drawio.svg +++ b/system/autoware_default_adapi/document/images/autoware-state-architecture.drawio.svg @@ -6,7 +6,7 @@ width="761px" height="381px" viewBox="-0.5 -0.5 761 381" - content="<mxfile><diagram id="X9Q9Zxk0nsySa-CThXZE" name="Page-1">5Vvfb5swEP5rIm0vUzA/kjxuWbe9TJrUh21PlQsOWAOMjGmS/fWzgx0Mpk1oEqAslVp8PhNz333nO+PO7HWy+0phFn0nAYpnYB7sZvbnGQCLhct/C8G+FDgLrxSEFAelyKoE9/gvksK5lBY4QHlNkRESM5zVhT5JU+SzmgxSSrZ1tQ2J69+awRAZgnsfxqb0Jw5YJKWWt6o6viEcRvKrl2BRdiRQKcsnySMYkK0msu9m9poSwsqrZLdGsbCdsks57sszvceJUZSyswbIieVsrx4OBfxZZZNQFpGQpDC+q6SfIpbEvNPil5QUaYDEzea8ZX67nFBOCuo3QGSQhkipOaVMfLc2UM75KyIJYnTPFSiKIcNPdRyghDM86smhHymFe00hIzhluXbnH0LAFaRjuks5N+mXYNWwXjd9flHOQLW0R6lEB0SeQWf5CnTqkGhYvR4ddxToLJxu6JzQvxwdefsnGBfykX2SZCRFh1nkDDIkOE9SzAg1kKzjtI0wQ/cZPOCw5VGzjt0Gx/GaxPw2Yqy9ccWPkJOUafLyw+U5o+QP0nq8w+clL3hClKHdi/gqtwd1w9pz2d5WwRAoakRaHFSAtLmEBsuLVrcHiFhqjdE4AbxRcMKa16Gwli9z4oT+5ZxQzlRxYga8mAmXzGDKr0NxHRO+mOK/3DAkVf381rqKEj/SpkTXwpxbWLuVYt0zt2w6ThzzlAG9Mfo1wxow2WeBW7FvgBUJjJZ9wOvGvhP6l7MPGOzjtmc4DStmTIICYD4gBxzLtOKtOWD3wYFzDaBmo7kZyRBVITjh5d5E/Mz2hoy1q/79zBltrDVqLatjbWZdOdY6BgkYybDPRX6E/D8y4ha5mchsRDUgeikrsokwpVkT9BuR56YVb80Ud7RMada9Vsc62bp2nexeyBRYMJKShBT5RMjiNWNTn2SxBlhWPJMsKlftP30BV40W/Lnp/peQf3BV87fe93knB5Wt/azLzkOb4exRRBmnGfBPRJkT+hdHGTBAVt6GjjUKdJr7PKfQOaF/+RrgGWtAgDawiNkDDB5ghs3Y/66+SbQWNlPFrGg0S473Bv5vd4e1sSK3bbA6zo3WB2D3TiTQssWjdtdHlkypivDcZKqhf3mYM7d4AgzDlOQM+1PNj+xlj/kRcPv3/7aye7j86PnK9j96p9Wry111Vx3tMCsT0oWl2r9VDsqvq4RUNPZa4weimE8e0S45KmjJgtR5hwGc9xWJhqgvt/whlYNPOJOwHNOtF96t3HphYFGZuonClF5PNIOJ12MssfvfCwOrlggw0r0wp+NemHPl9G3VhRJRwQKyTQ1A8whm4jJCO8ix5KqZFrml9BjMwTns2SF1zm50bGpmg72yCfTOJrvttMnVz8edbQDzQMchGczFDCPIqePBRHhT+piLP3yRzRF9wj56OET0h2OqON9CMeiw5Xso4usDH9GG0KksAM0isCWZvFn9bptvZy/MZ7gFVWwAN7FPS1Jy3PLQzeNewzxmdZO2vbB+uymfWzeuaxq37WyefQ3bmm96ZDD4z5ewITExCyJZzU8i0lq9WZY3q3P5ZepX/XODffcP</diagram></mxfile>" + content="<mxfile><diagram id="X9Q9Zxk0nsySa-CThXZE" name="Page-1">5VvNkps4EH4aV20uKSN+bB8TZ5K9bFWq5rCbk0sDMqgCiBJibOfpVzKSEQiPTbCBcTwHS62WLLr7a3U3mpm9TvbfKMyif0iA4hmYB/uZ/WUGgOU6Lv8SlENJ8Sy7JIQUB5KpIjzjX0gS55Ja4ADlNUZGSMxwVif6JE2Rz2o0SCnZ1dm2JK7/agZDZBCefRib1H9xwCJJtbxVNfA3wmEkf3oJFuVAAhWzfJI8ggHZaST7aWavKSGsbCX7NYqF8JRcynlfz4yeNkZRyq6aIDeWs4N6OBTwZ5VdQllEQpLC+Kmifo5YEvNBizcpKdIAicXmvGf+utxQTgrqN5TIIA2RYnNKmvhtbaLc8zdEEsTogTNQFEOGX+t6gFKd4YlPTv1EKTxoDBnBKcu1lb8LAmeQluku5d6kXYJVQ3rd+Hmj3IHqaY9SkY4aOaOd5W9op64STVe/rx13EtpZON20c4G/v3bk8q8wLuQj+yTJSIqOu8gZZEhgnqSYEWposq6nXYQZes7gUQ877jbrutviOF6TmC8j5tpbV/wJOkmZRi8/nJ4zSn4ibcQ7ft6ygldEGdq/qV9l9qAuWHsu+7vKGQIFjUjzg0ohbSahqeVNqdsjeCx1xmiYAN4kMGHN66qwlm9j4gJ/f0woY6owMQNezIRJZjDl7VC0Y8IPU/yLC4akapwvrbMo8gttUnQuzLGFtaUU6s4s2TScOOYhA3pn8Gu6NWCizwL3Qt8IJxKYLPqA1w19F/j7ow8Y6OOyZzgNK2Q8BATAfEQMOJYpxXtjwB4CA9cKQO1GMzOSIapccMLzvQexM9sb09euhrczZ7K+1si1rI65mXVjX+sYIGAkwz4n+RHyf0qPW+RmILMV2YAYpazIHgQpzZxgWI88N6V4b6S4k0VKM++1OubJ1q3zZLcnUmDBSEoSUuQPAhav6ZuGBIs1wrHimWBRserw4Qu4qbfgz00P/wn6R1d1f+hjX/ZyUtk7zLpUHtoEZ0/CyzhNh3/By1zg7+1lwAhReZt2rElop1nnuaSdC/z9zwDPOAOEV99xAW8CtIVFzDYwgBk2z4C/6sWitZCdSmpFp5l6fDDs4P1WWhsnc1uh1XHudE4Ae3BAgZZSj6qyTyyoUpnhtUFVg7+/uzNLPQGGYUpyhv1HjZPs5YBxEnCHt/+29Hu8OOl8hvsHvdsa1ORuWl1He8zKwHRhqf4PFYvydhWYis5B63xHFPPNI9olVgUt0ZC69zCC8fYIOBSjMvQHjigsxzTvhXcv816c1YmphUd6XdF0Kt6APsUevjYGVi2eYKK1Madjbcy5cRi36gKJqGAB2aWGQvMIZqIZoT3kuuSsmebBJfXk1ME16Nkjde9ucmhqRoWDogkMjia77fbJze/LXS0A84LHMSjMxQ4jyKHjwURYU/qSiy8YbHJEX7GPNkePvjmFjPMdFJOOJeBjMl+f+IK2hD7KAdBMBluCyrvl8bb5trZnPMMlqHwDuIt8WoKSU+lDF497C/GYWU7a9gL7/YZ8bl24rinctrt69i1ka775kc7gDz/CxtSJmRjJrP4hPK01mGR5t7qnX4Z+1X872E//Aw==</diagram></mxfile>" > @@ -148,14 +148,14 @@
- default_ad_api + autoware_default_adapi
(localization, routing, operation mode)
- default_ad_api... + autoware_default_adapi...
@@ -207,14 +207,14 @@
- default_ad_api + autoware_default_adapi
(autoware state)
- default_ad_api... + autoware_default_adapi... @@ -326,7 +326,7 @@ - Viewer does not support full SVG 1.1 + Text is not SVG - cannot display diff --git a/system/default_ad_api/document/images/autoware-state-table.drawio.svg b/system/autoware_default_adapi/document/images/autoware-state-table.drawio.svg similarity index 100% rename from system/default_ad_api/document/images/autoware-state-table.drawio.svg rename to system/autoware_default_adapi/document/images/autoware-state-table.drawio.svg diff --git a/system/default_ad_api/document/images/localization.drawio.svg b/system/autoware_default_adapi/document/images/localization.drawio.svg similarity index 100% rename from system/default_ad_api/document/images/localization.drawio.svg rename to system/autoware_default_adapi/document/images/localization.drawio.svg diff --git a/system/default_ad_api/document/images/motion-architecture.drawio.svg b/system/autoware_default_adapi/document/images/motion-architecture.drawio.svg similarity index 100% rename from system/default_ad_api/document/images/motion-architecture.drawio.svg rename to system/autoware_default_adapi/document/images/motion-architecture.drawio.svg diff --git a/system/default_ad_api/document/images/motion-state.drawio.svg b/system/autoware_default_adapi/document/images/motion-state.drawio.svg similarity index 100% rename from system/default_ad_api/document/images/motion-state.drawio.svg rename to system/autoware_default_adapi/document/images/motion-state.drawio.svg diff --git a/system/default_ad_api/document/images/operation-mode-architecture.drawio.svg b/system/autoware_default_adapi/document/images/operation-mode-architecture.drawio.svg similarity index 100% rename from system/default_ad_api/document/images/operation-mode-architecture.drawio.svg rename to system/autoware_default_adapi/document/images/operation-mode-architecture.drawio.svg diff --git a/system/default_ad_api/document/images/operation-mode-state.drawio.svg b/system/autoware_default_adapi/document/images/operation-mode-state.drawio.svg similarity index 100% rename from system/default_ad_api/document/images/operation-mode-state.drawio.svg rename to system/autoware_default_adapi/document/images/operation-mode-state.drawio.svg diff --git a/system/default_ad_api/document/images/operation-mode-table.drawio.svg b/system/autoware_default_adapi/document/images/operation-mode-table.drawio.svg similarity index 100% rename from system/default_ad_api/document/images/operation-mode-table.drawio.svg rename to system/autoware_default_adapi/document/images/operation-mode-table.drawio.svg diff --git a/system/default_ad_api/document/images/routing.drawio.svg b/system/autoware_default_adapi/document/images/routing.drawio.svg similarity index 100% rename from system/default_ad_api/document/images/routing.drawio.svg rename to system/autoware_default_adapi/document/images/routing.drawio.svg diff --git a/system/default_ad_api/document/interface.md b/system/autoware_default_adapi/document/interface.md similarity index 100% rename from system/default_ad_api/document/interface.md rename to system/autoware_default_adapi/document/interface.md diff --git a/system/default_ad_api/document/localization.md b/system/autoware_default_adapi/document/localization.md similarity index 100% rename from system/default_ad_api/document/localization.md rename to system/autoware_default_adapi/document/localization.md diff --git a/system/default_ad_api/document/motion.md b/system/autoware_default_adapi/document/motion.md similarity index 100% rename from system/default_ad_api/document/motion.md rename to system/autoware_default_adapi/document/motion.md diff --git a/system/default_ad_api/document/operation-mode.md b/system/autoware_default_adapi/document/operation-mode.md similarity index 100% rename from system/default_ad_api/document/operation-mode.md rename to system/autoware_default_adapi/document/operation-mode.md diff --git a/system/default_ad_api/document/routing.md b/system/autoware_default_adapi/document/routing.md similarity index 100% rename from system/default_ad_api/document/routing.md rename to system/autoware_default_adapi/document/routing.md diff --git a/system/default_ad_api/launch/default_ad_api.launch.py b/system/autoware_default_adapi/launch/default_adapi.launch.py similarity index 85% rename from system/default_ad_api/launch/default_ad_api.launch.py rename to system/autoware_default_adapi/launch/default_adapi.launch.py index ca1575a528db2..9f95b16ab640b 100644 --- a/system/default_ad_api/launch/default_ad_api.launch.py +++ b/system/autoware_default_adapi/launch/default_adapi.launch.py @@ -25,17 +25,17 @@ def create_api_node(node_name, class_name, **kwargs): return ComposableNode( - namespace="default_ad_api/node", + namespace="adapi/node", name=node_name, - package="default_ad_api", - plugin="default_ad_api::" + class_name, + package="autoware_default_adapi", + plugin="autoware::default_adapi::" + class_name, parameters=[ParameterFile(LaunchConfiguration("config"))], ) def get_default_config(): - path = FindPackageShare("default_ad_api") - path = PathJoinSubstitution([path, "config/default_ad_api.param.yaml"]) + path = FindPackageShare("autoware_default_adapi") + path = PathJoinSubstitution([path, "config/default_adapi.param.yaml"]) return path @@ -57,16 +57,16 @@ def generate_launch_description(): create_api_node("vehicle_door", "VehicleDoorNode"), ] container = ComposableNodeContainer( - namespace="default_ad_api", + namespace="adapi", name="container", package="rclcpp_components", executable="component_container_mt", - ros_arguments=["--log-level", "default_ad_api.container:=WARN"], + ros_arguments=["--log-level", "adapi.container:=WARN"], composable_node_descriptions=components, ) web_server = Node( - namespace="default_ad_api", - package="default_ad_api", + namespace="adapi", + package="autoware_default_adapi", name="web_server", executable="web_server.py", ) diff --git a/system/default_ad_api/package.xml b/system/autoware_default_adapi/package.xml similarity index 94% rename from system/default_ad_api/package.xml rename to system/autoware_default_adapi/package.xml index c2751c96e995c..5c6e10a73fa9c 100644 --- a/system/default_ad_api/package.xml +++ b/system/autoware_default_adapi/package.xml @@ -1,9 +1,9 @@ - default_ad_api + autoware_default_adapi 0.1.0 - The default_ad_api package + The autoware_default_adapi package Takagi, Isamu Ryohsuke Mitsudome Yukihiro Saito diff --git a/system/default_ad_api/script/guide.py b/system/autoware_default_adapi/script/guide.py similarity index 100% rename from system/default_ad_api/script/guide.py rename to system/autoware_default_adapi/script/guide.py diff --git a/system/default_ad_api/script/web_server.py b/system/autoware_default_adapi/script/web_server.py similarity index 100% rename from system/default_ad_api/script/web_server.py rename to system/autoware_default_adapi/script/web_server.py diff --git a/system/default_ad_api/src/compatibility/autoware_state.cpp b/system/autoware_default_adapi/src/compatibility/autoware_state.cpp similarity index 97% rename from system/default_ad_api/src/compatibility/autoware_state.cpp rename to system/autoware_default_adapi/src/compatibility/autoware_state.cpp index 1aa49383aa48f..da110a711e35a 100644 --- a/system/default_ad_api/src/compatibility/autoware_state.cpp +++ b/system/autoware_default_adapi/src/compatibility/autoware_state.cpp @@ -17,7 +17,7 @@ #include #include -namespace default_ad_api +namespace autoware::default_adapi { AutowareStateNode::AutowareStateNode(const rclcpp::NodeOptions & options) @@ -140,7 +140,7 @@ void AutowareStateNode::on_timer() pub_autoware_state_->publish(msg); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::AutowareStateNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::AutowareStateNode) diff --git a/system/default_ad_api/src/compatibility/autoware_state.hpp b/system/autoware_default_adapi/src/compatibility/autoware_state.hpp similarity index 97% rename from system/default_ad_api/src/compatibility/autoware_state.hpp rename to system/autoware_default_adapi/src/compatibility/autoware_state.hpp index eff74728efcb0..d4707ea55fd87 100644 --- a/system/default_ad_api/src/compatibility/autoware_state.hpp +++ b/system/autoware_default_adapi/src/compatibility/autoware_state.hpp @@ -28,7 +28,7 @@ // This file should be included after messages. #include "../utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class AutowareStateNode : public rclcpp::Node @@ -67,6 +67,6 @@ class AutowareStateNode : public rclcpp::Node void on_shutdown(const Trigger::Request::SharedPtr, const Trigger::Response::SharedPtr); }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // COMPATIBILITY__AUTOWARE_STATE_HPP_ diff --git a/system/default_ad_api/src/diagnostics.cpp b/system/autoware_default_adapi/src/diagnostics.cpp similarity index 94% rename from system/default_ad_api/src/diagnostics.cpp rename to system/autoware_default_adapi/src/diagnostics.cpp index 6eaaa5bf614a6..0c1550690f1b5 100644 --- a/system/default_ad_api/src/diagnostics.cpp +++ b/system/autoware_default_adapi/src/diagnostics.cpp @@ -17,7 +17,7 @@ #include #include -namespace default_ad_api +namespace autoware::default_adapi { DiagnosticsNode::DiagnosticsNode(const rclcpp::NodeOptions & options) : Node("diagnostics", options) @@ -75,7 +75,7 @@ void DiagnosticsNode::on_update(DiagGraph::ConstSharedPtr graph) pub_status_->publish(msg); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::DiagnosticsNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::DiagnosticsNode) diff --git a/system/default_ad_api/src/diagnostics.hpp b/system/autoware_default_adapi/src/diagnostics.hpp similarity index 95% rename from system/default_ad_api/src/diagnostics.hpp rename to system/autoware_default_adapi/src/diagnostics.hpp index 302ffe39159df..b382887aaa694 100644 --- a/system/default_ad_api/src/diagnostics.hpp +++ b/system/autoware_default_adapi/src/diagnostics.hpp @@ -22,7 +22,7 @@ #include #include -namespace default_ad_api +namespace autoware::default_adapi { class DiagnosticsNode : public rclcpp::Node @@ -41,6 +41,6 @@ class DiagnosticsNode : public rclcpp::Node diagnostic_graph_utils::DiagGraphSubscription sub_graph_; }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // DIAGNOSTICS_HPP_ diff --git a/system/default_ad_api/src/fail_safe.cpp b/system/autoware_default_adapi/src/fail_safe.cpp similarity index 89% rename from system/default_ad_api/src/fail_safe.cpp rename to system/autoware_default_adapi/src/fail_safe.cpp index 92191a3d65bc9..130e2f523477c 100644 --- a/system/default_ad_api/src/fail_safe.cpp +++ b/system/autoware_default_adapi/src/fail_safe.cpp @@ -14,7 +14,7 @@ #include "fail_safe.hpp" -namespace default_ad_api +namespace autoware::default_adapi { FailSafeNode::FailSafeNode(const rclcpp::NodeOptions & options) : Node("fail_safe", options) @@ -35,7 +35,7 @@ void FailSafeNode::on_state(const MrmState::ConstSharedPtr msg) } } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::FailSafeNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::FailSafeNode) diff --git a/system/default_ad_api/src/fail_safe.hpp b/system/autoware_default_adapi/src/fail_safe.hpp similarity index 94% rename from system/default_ad_api/src/fail_safe.hpp rename to system/autoware_default_adapi/src/fail_safe.hpp index 6ae20b1b46e61..268fc6d4d95e4 100644 --- a/system/default_ad_api/src/fail_safe.hpp +++ b/system/autoware_default_adapi/src/fail_safe.hpp @@ -23,7 +23,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class FailSafeNode : public rclcpp::Node @@ -39,6 +39,6 @@ class FailSafeNode : public rclcpp::Node void on_state(const MrmState::ConstSharedPtr msg); }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // FAIL_SAFE_HPP_ diff --git a/system/default_ad_api/src/heartbeat.cpp b/system/autoware_default_adapi/src/heartbeat.cpp similarity index 90% rename from system/default_ad_api/src/heartbeat.cpp rename to system/autoware_default_adapi/src/heartbeat.cpp index 4550302bb8bae..e048c347f3678 100644 --- a/system/default_ad_api/src/heartbeat.cpp +++ b/system/autoware_default_adapi/src/heartbeat.cpp @@ -16,7 +16,7 @@ #include -namespace default_ad_api +namespace autoware::default_adapi { HeartbeatNode::HeartbeatNode(const rclcpp::NodeOptions & options) : Node("heartbeat", options) @@ -36,7 +36,7 @@ HeartbeatNode::HeartbeatNode(const rclcpp::NodeOptions & options) : Node("heartb timer_ = rclcpp::create_timer(this, get_clock(), period, std::move(on_timer)); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::HeartbeatNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::HeartbeatNode) diff --git a/system/default_ad_api/src/heartbeat.hpp b/system/autoware_default_adapi/src/heartbeat.hpp similarity index 93% rename from system/default_ad_api/src/heartbeat.hpp rename to system/autoware_default_adapi/src/heartbeat.hpp index d922b88489639..8b1108d7b1bd3 100644 --- a/system/default_ad_api/src/heartbeat.hpp +++ b/system/autoware_default_adapi/src/heartbeat.hpp @@ -21,7 +21,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class HeartbeatNode : public rclcpp::Node @@ -35,6 +35,6 @@ class HeartbeatNode : public rclcpp::Node uint16_t sequence_ = 0; }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // HEARTBEAT_HPP_ diff --git a/system/default_ad_api/src/interface.cpp b/system/autoware_default_adapi/src/interface.cpp similarity index 87% rename from system/default_ad_api/src/interface.cpp rename to system/autoware_default_adapi/src/interface.cpp index 997f9e01fc6a9..0d9134102c42a 100644 --- a/system/default_ad_api/src/interface.cpp +++ b/system/autoware_default_adapi/src/interface.cpp @@ -14,7 +14,7 @@ #include "interface.hpp" -namespace default_ad_api +namespace autoware::default_adapi { InterfaceNode::InterfaceNode(const rclcpp::NodeOptions & options) : Node("interface", options) @@ -29,7 +29,7 @@ InterfaceNode::InterfaceNode(const rclcpp::NodeOptions & options) : Node("interf adaptor.init_srv(srv_, on_interface_version); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::InterfaceNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::InterfaceNode) diff --git a/system/default_ad_api/src/interface.hpp b/system/autoware_default_adapi/src/interface.hpp similarity index 93% rename from system/default_ad_api/src/interface.hpp rename to system/autoware_default_adapi/src/interface.hpp index 46c70abf17f36..ce0bdb04e2d2e 100644 --- a/system/default_ad_api/src/interface.hpp +++ b/system/autoware_default_adapi/src/interface.hpp @@ -21,7 +21,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class InterfaceNode : public rclcpp::Node @@ -33,6 +33,6 @@ class InterfaceNode : public rclcpp::Node Srv srv_; }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // INTERFACE_HPP_ diff --git a/system/default_ad_api/src/localization.cpp b/system/autoware_default_adapi/src/localization.cpp similarity index 90% rename from system/default_ad_api/src/localization.cpp rename to system/autoware_default_adapi/src/localization.cpp index 97544a7868d9c..7e6a094fb0fd2 100644 --- a/system/default_ad_api/src/localization.cpp +++ b/system/autoware_default_adapi/src/localization.cpp @@ -16,7 +16,7 @@ #include "utils/localization_conversion.hpp" -namespace default_ad_api +namespace autoware::default_adapi { LocalizationNode::LocalizationNode(const rclcpp::NodeOptions & options) @@ -36,7 +36,7 @@ void LocalizationNode::on_initialize( res->status = localization_conversion::convert_call(cli_initialize_, req); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::LocalizationNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::LocalizationNode) diff --git a/system/default_ad_api/src/localization.hpp b/system/autoware_default_adapi/src/localization.hpp similarity index 95% rename from system/default_ad_api/src/localization.hpp rename to system/autoware_default_adapi/src/localization.hpp index a24e2110fabd1..d9104f393f712 100644 --- a/system/default_ad_api/src/localization.hpp +++ b/system/autoware_default_adapi/src/localization.hpp @@ -22,7 +22,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class LocalizationNode : public rclcpp::Node @@ -42,6 +42,6 @@ class LocalizationNode : public rclcpp::Node const autoware_ad_api::localization::Initialize::Service::Response::SharedPtr res); }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // LOCALIZATION_HPP_ diff --git a/system/default_ad_api/src/motion.cpp b/system/autoware_default_adapi/src/motion.cpp similarity index 97% rename from system/default_ad_api/src/motion.cpp rename to system/autoware_default_adapi/src/motion.cpp index 9d4461fc76f1e..87d4df371abb7 100644 --- a/system/default_ad_api/src/motion.cpp +++ b/system/autoware_default_adapi/src/motion.cpp @@ -17,7 +17,7 @@ #include #include -namespace default_ad_api +namespace autoware::default_adapi { MotionNode::MotionNode(const rclcpp::NodeOptions & options) @@ -159,7 +159,7 @@ void MotionNode::on_accept( res->status.success = true; } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::MotionNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::MotionNode) diff --git a/system/default_ad_api/src/motion.hpp b/system/autoware_default_adapi/src/motion.hpp similarity index 96% rename from system/default_ad_api/src/motion.hpp rename to system/autoware_default_adapi/src/motion.hpp index 053e9b2427a10..043eb6568e141 100644 --- a/system/default_ad_api/src/motion.hpp +++ b/system/autoware_default_adapi/src/motion.hpp @@ -25,7 +25,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class MotionNode : public rclcpp::Node @@ -65,6 +65,6 @@ class MotionNode : public rclcpp::Node const autoware_ad_api::motion::AcceptStart::Service::Response::SharedPtr res); }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // MOTION_HPP_ diff --git a/system/default_ad_api/src/operation_mode.cpp b/system/autoware_default_adapi/src/operation_mode.cpp similarity index 97% rename from system/default_ad_api/src/operation_mode.cpp rename to system/autoware_default_adapi/src/operation_mode.cpp index 510788dd09d08..cd452f2fa83a7 100644 --- a/system/default_ad_api/src/operation_mode.cpp +++ b/system/autoware_default_adapi/src/operation_mode.cpp @@ -18,7 +18,7 @@ #include #include -namespace default_ad_api +namespace autoware::default_adapi { using ServiceResponse = autoware_adapi_v1_msgs::srv::ChangeOperationMode::Response; @@ -157,7 +157,7 @@ void OperationModeNode::update_state() } } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::OperationModeNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::OperationModeNode) diff --git a/system/default_ad_api/src/operation_mode.hpp b/system/autoware_default_adapi/src/operation_mode.hpp similarity index 98% rename from system/default_ad_api/src/operation_mode.hpp rename to system/autoware_default_adapi/src/operation_mode.hpp index 7cd609b5eb852..3b139ad875b8d 100644 --- a/system/default_ad_api/src/operation_mode.hpp +++ b/system/autoware_default_adapi/src/operation_mode.hpp @@ -30,7 +30,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class OperationModeNode : public rclcpp::Node { @@ -94,6 +94,6 @@ class OperationModeNode : public rclcpp::Node void change_mode(const ResponseT res, const OperationModeRequest::_mode_type mode); }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // OPERATION_MODE_HPP_ diff --git a/system/default_ad_api/src/perception.cpp b/system/autoware_default_adapi/src/perception.cpp similarity index 96% rename from system/default_ad_api/src/perception.cpp rename to system/autoware_default_adapi/src/perception.cpp index 794bbf141ca8b..c92bac2f5f139 100644 --- a/system/default_ad_api/src/perception.cpp +++ b/system/autoware_default_adapi/src/perception.cpp @@ -16,7 +16,7 @@ #include -namespace default_ad_api +namespace autoware::default_adapi { using DynamicObjectArray = autoware_ad_api::perception::DynamicObjectArray; @@ -87,7 +87,7 @@ void PerceptionNode::object_recognize( pub_object_recognized_->publish(objects); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::PerceptionNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::PerceptionNode) diff --git a/system/default_ad_api/src/perception.hpp b/system/autoware_default_adapi/src/perception.hpp similarity index 95% rename from system/default_ad_api/src/perception.hpp rename to system/autoware_default_adapi/src/perception.hpp index ff3e4801b07ac..4eb83c57293ba 100644 --- a/system/default_ad_api/src/perception.hpp +++ b/system/autoware_default_adapi/src/perception.hpp @@ -31,7 +31,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class PerceptionNode : public rclcpp::Node @@ -47,6 +47,6 @@ class PerceptionNode : public rclcpp::Node std::unordered_map hash_map, uint8_t input, uint8_t default_value); }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // PERCEPTION_HPP_ diff --git a/system/default_ad_api/src/planning.cpp b/system/autoware_default_adapi/src/planning.cpp similarity index 97% rename from system/default_ad_api/src/planning.cpp rename to system/autoware_default_adapi/src/planning.cpp index 374316e19e6b1..b81e48fada790 100644 --- a/system/default_ad_api/src/planning.cpp +++ b/system/autoware_default_adapi/src/planning.cpp @@ -22,7 +22,7 @@ #include #include -namespace default_ad_api +namespace autoware::default_adapi { template @@ -155,7 +155,7 @@ void PlanningNode::on_timer() pub_steering_factors_->publish(steering); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::PlanningNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::PlanningNode) diff --git a/system/default_ad_api/src/planning.hpp b/system/autoware_default_adapi/src/planning.hpp similarity index 97% rename from system/default_ad_api/src/planning.hpp rename to system/autoware_default_adapi/src/planning.hpp index 929eb517afa2e..f67de9f7b9221 100644 --- a/system/default_ad_api/src/planning.hpp +++ b/system/autoware_default_adapi/src/planning.hpp @@ -27,7 +27,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class PlanningNode : public rclcpp::Node @@ -62,6 +62,6 @@ class PlanningNode : public rclcpp::Node KinematicState::ConstSharedPtr kinematic_state_; }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // PLANNING_HPP_ diff --git a/system/default_ad_api/src/routing.cpp b/system/autoware_default_adapi/src/routing.cpp similarity index 97% rename from system/default_ad_api/src/routing.cpp rename to system/autoware_default_adapi/src/routing.cpp index 0f2247c3aada8..767cfc37d3f25 100644 --- a/system/default_ad_api/src/routing.cpp +++ b/system/autoware_default_adapi/src/routing.cpp @@ -45,7 +45,7 @@ ResponseStatus route_is_not_set() } // namespace -namespace default_ad_api +namespace autoware::default_adapi { RoutingNode::RoutingNode(const rclcpp::NodeOptions & options) : Node("routing", options) @@ -166,7 +166,7 @@ void RoutingNode::on_change_route( res->status = conversion::convert_call(cli_set_lanelet_route_, req); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::RoutingNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::RoutingNode) diff --git a/system/default_ad_api/src/routing.hpp b/system/autoware_default_adapi/src/routing.hpp similarity index 97% rename from system/default_ad_api/src/routing.hpp rename to system/autoware_default_adapi/src/routing.hpp index 406569aa0a36b..9033373c3a064 100644 --- a/system/default_ad_api/src/routing.hpp +++ b/system/autoware_default_adapi/src/routing.hpp @@ -24,7 +24,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class RoutingNode : public rclcpp::Node @@ -76,6 +76,6 @@ class RoutingNode : public rclcpp::Node const autoware_ad_api::routing::SetRoute::Service::Response::SharedPtr res); }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // ROUTING_HPP_ diff --git a/system/default_ad_api/src/utils/localization_conversion.cpp b/system/autoware_default_adapi/src/utils/localization_conversion.cpp similarity index 91% rename from system/default_ad_api/src/utils/localization_conversion.cpp rename to system/autoware_default_adapi/src/utils/localization_conversion.cpp index 3ddf259a4a590..1b327e2d2fc06 100644 --- a/system/default_ad_api/src/utils/localization_conversion.cpp +++ b/system/autoware_default_adapi/src/utils/localization_conversion.cpp @@ -16,7 +16,7 @@ #include -namespace default_ad_api::localization_conversion +namespace autoware::default_adapi::localization_conversion { InternalInitializeRequest convert_request(const ExternalInitializeRequest & external) @@ -37,4 +37,4 @@ ExternalResponse convert_response(const InternalResponse & internal) return external; } -} // namespace default_ad_api::localization_conversion +} // namespace autoware::default_adapi::localization_conversion diff --git a/system/default_ad_api/src/utils/localization_conversion.hpp b/system/autoware_default_adapi/src/utils/localization_conversion.hpp similarity index 92% rename from system/default_ad_api/src/utils/localization_conversion.hpp rename to system/autoware_default_adapi/src/utils/localization_conversion.hpp index 85b6e81e6cd91..d8e66a6ae44aa 100644 --- a/system/default_ad_api/src/utils/localization_conversion.hpp +++ b/system/autoware_default_adapi/src/utils/localization_conversion.hpp @@ -20,7 +20,7 @@ #include #include -namespace default_ad_api::localization_conversion +namespace autoware::default_adapi::localization_conversion { using ExternalInitializeRequest = @@ -39,6 +39,6 @@ ExternalResponse convert_call(ClientT & client, RequestT & req) return convert_response(client->call(convert_request(req))->status); } -} // namespace default_ad_api::localization_conversion +} // namespace autoware::default_adapi::localization_conversion #endif // UTILS__LOCALIZATION_CONVERSION_HPP_ diff --git a/system/default_ad_api/src/utils/route_conversion.cpp b/system/autoware_default_adapi/src/utils/route_conversion.cpp similarity index 98% rename from system/default_ad_api/src/utils/route_conversion.cpp rename to system/autoware_default_adapi/src/utils/route_conversion.cpp index 70951fc337b68..e8a748d52edee 100644 --- a/system/default_ad_api/src/utils/route_conversion.cpp +++ b/system/autoware_default_adapi/src/utils/route_conversion.cpp @@ -86,7 +86,7 @@ LaneletSegment convert(const RouteSegment & in) } // namespace -namespace default_ad_api::conversion +namespace autoware::default_adapi::conversion { ExternalRoute create_empty_route(const rclcpp::Time & stamp) @@ -170,4 +170,4 @@ ExternalResponse convert_response(const InternalResponse & internal) return external; } -} // namespace default_ad_api::conversion +} // namespace autoware::default_adapi::conversion diff --git a/system/default_ad_api/src/utils/route_conversion.hpp b/system/autoware_default_adapi/src/utils/route_conversion.hpp similarity index 96% rename from system/default_ad_api/src/utils/route_conversion.hpp rename to system/autoware_default_adapi/src/utils/route_conversion.hpp index 9a31b9e80c064..053dfd697c967 100644 --- a/system/default_ad_api/src/utils/route_conversion.hpp +++ b/system/autoware_default_adapi/src/utils/route_conversion.hpp @@ -28,7 +28,7 @@ #include #include -namespace default_ad_api::conversion +namespace autoware::default_adapi::conversion { using ExternalRoute = autoware_adapi_v1_msgs::msg::Route; @@ -62,6 +62,6 @@ ExternalResponse convert_call(ClientT & client, RequestT & req) return convert_response(client->call(convert_request(req))->status); } -} // namespace default_ad_api::conversion +} // namespace autoware::default_adapi::conversion #endif // UTILS__ROUTE_CONVERSION_HPP_ diff --git a/system/default_ad_api/src/utils/topics.hpp b/system/autoware_default_adapi/src/utils/topics.hpp similarity index 92% rename from system/default_ad_api/src/utils/topics.hpp rename to system/autoware_default_adapi/src/utils/topics.hpp index 97d91b33c9fa3..6018abb877285 100644 --- a/system/default_ad_api/src/utils/topics.hpp +++ b/system/autoware_default_adapi/src/utils/topics.hpp @@ -20,7 +20,7 @@ #include -namespace default_ad_api::utils +namespace autoware::default_adapi::utils { template @@ -39,6 +39,6 @@ void notify(PubT & pub, std::optional & prev, const MsgT & curr, FuncT && } } -} // namespace default_ad_api::utils +} // namespace autoware::default_adapi::utils #endif // UTILS__TOPICS_HPP_ diff --git a/system/default_ad_api/src/utils/types.hpp b/system/autoware_default_adapi/src/utils/types.hpp similarity index 93% rename from system/default_ad_api/src/utils/types.hpp rename to system/autoware_default_adapi/src/utils/types.hpp index 693e64a0dce55..ac4acb5fb19d6 100644 --- a/system/default_ad_api/src/utils/types.hpp +++ b/system/autoware_default_adapi/src/utils/types.hpp @@ -17,7 +17,7 @@ #include -namespace default_ad_api +namespace autoware::default_adapi { template @@ -29,6 +29,6 @@ using Cli = typename component_interface_utils::Client::SharedPtr; template using Srv = typename component_interface_utils::Service::SharedPtr; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // UTILS__TYPES_HPP_ diff --git a/system/default_ad_api/src/vehicle.cpp b/system/autoware_default_adapi/src/vehicle.cpp similarity index 98% rename from system/default_ad_api/src/vehicle.cpp rename to system/autoware_default_adapi/src/vehicle.cpp index 053e1258c7bef..5421f382795ef 100644 --- a/system/default_ad_api/src/vehicle.cpp +++ b/system/autoware_default_adapi/src/vehicle.cpp @@ -21,7 +21,7 @@ #include -namespace default_ad_api +namespace autoware::default_adapi { using GearReport = vehicle_interface::GearStatus::Message; @@ -189,7 +189,7 @@ void VehicleNode::on_timer() publish_status(); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::VehicleNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::VehicleNode) diff --git a/system/default_ad_api/src/vehicle.hpp b/system/autoware_default_adapi/src/vehicle.hpp similarity index 98% rename from system/default_ad_api/src/vehicle.hpp rename to system/autoware_default_adapi/src/vehicle.hpp index 56012152a132b..5e3818340b819 100644 --- a/system/default_ad_api/src/vehicle.hpp +++ b/system/autoware_default_adapi/src/vehicle.hpp @@ -30,7 +30,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class VehicleNode : public rclcpp::Node @@ -80,6 +80,6 @@ class VehicleNode : public rclcpp::Node void on_timer(); }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // VEHICLE_HPP_ diff --git a/system/default_ad_api/src/vehicle_door.cpp b/system/autoware_default_adapi/src/vehicle_door.cpp similarity index 90% rename from system/default_ad_api/src/vehicle_door.cpp rename to system/autoware_default_adapi/src/vehicle_door.cpp index e37e91bdda8e2..e897bc37eff42 100644 --- a/system/default_ad_api/src/vehicle_door.cpp +++ b/system/autoware_default_adapi/src/vehicle_door.cpp @@ -16,7 +16,7 @@ #include "utils/topics.hpp" -namespace default_ad_api +namespace autoware::default_adapi { VehicleDoorNode::VehicleDoorNode(const rclcpp::NodeOptions & options) @@ -36,7 +36,7 @@ void VehicleDoorNode::on_status(vehicle_interface::DoorStatus::Message::ConstSha pub_status_, status_, *msg, utils::ignore_stamp); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::VehicleDoorNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::VehicleDoorNode) diff --git a/system/default_ad_api/src/vehicle_door.hpp b/system/autoware_default_adapi/src/vehicle_door.hpp similarity index 95% rename from system/default_ad_api/src/vehicle_door.hpp rename to system/autoware_default_adapi/src/vehicle_door.hpp index e83e0a164d3f6..8f6c2da83247d 100644 --- a/system/default_ad_api/src/vehicle_door.hpp +++ b/system/autoware_default_adapi/src/vehicle_door.hpp @@ -24,7 +24,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class VehicleDoorNode : public rclcpp::Node @@ -44,6 +44,6 @@ class VehicleDoorNode : public rclcpp::Node std::optional status_; }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // VEHICLE_DOOR_HPP_ diff --git a/system/default_ad_api/src/vehicle_info.cpp b/system/autoware_default_adapi/src/vehicle_info.cpp similarity index 94% rename from system/default_ad_api/src/vehicle_info.cpp rename to system/autoware_default_adapi/src/vehicle_info.cpp index 8bf7da65f6e33..810290d1e8814 100644 --- a/system/default_ad_api/src/vehicle_info.cpp +++ b/system/autoware_default_adapi/src/vehicle_info.cpp @@ -30,7 +30,7 @@ auto create_point(double x, double y) } // namespace -namespace default_ad_api +namespace autoware::default_adapi { VehicleInfoNode::VehicleInfoNode(const rclcpp::NodeOptions & options) @@ -65,7 +65,7 @@ VehicleInfoNode::VehicleInfoNode(const rclcpp::NodeOptions & options) adaptor.init_srv(srv_dimensions_, on_vehicle_dimensions); } -} // namespace default_ad_api +} // namespace autoware::default_adapi #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::VehicleInfoNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::default_adapi::VehicleInfoNode) diff --git a/system/default_ad_api/src/vehicle_info.hpp b/system/autoware_default_adapi/src/vehicle_info.hpp similarity index 93% rename from system/default_ad_api/src/vehicle_info.hpp rename to system/autoware_default_adapi/src/vehicle_info.hpp index c7171ddf52485..f13f222fc269e 100644 --- a/system/default_ad_api/src/vehicle_info.hpp +++ b/system/autoware_default_adapi/src/vehicle_info.hpp @@ -21,7 +21,7 @@ // This file should be included after messages. #include "utils/types.hpp" -namespace default_ad_api +namespace autoware::default_adapi { class VehicleInfoNode : public rclcpp::Node @@ -34,6 +34,6 @@ class VehicleInfoNode : public rclcpp::Node autoware_adapi_v1_msgs::msg::VehicleDimensions dimensions_; }; -} // namespace default_ad_api +} // namespace autoware::default_adapi #endif // VEHICLE_INFO_HPP_ diff --git a/system/default_ad_api/test/main.test.py b/system/autoware_default_adapi/test/main.test.py similarity index 91% rename from system/default_ad_api/test/main.test.py rename to system/autoware_default_adapi/test/main.test.py index 728f8a3604ada..3f7f7083ac46e 100644 --- a/system/default_ad_api/test/main.test.py +++ b/system/autoware_default_adapi/test/main.test.py @@ -26,7 +26,7 @@ @pytest.mark.launch_test @launch_testing.markers.keep_alive def generate_test_description(): - path = get_package_share_directory("default_ad_api") + "/launch/default_ad_api.launch.py" + path = get_package_share_directory("autoware_default_adapi") + "/launch/default_adapi.launch.py" specification = importlib.util.spec_from_file_location("launch_script", path) launch_script = importlib.util.module_from_spec(specification) specification.loader.exec_module(launch_script) @@ -40,7 +40,7 @@ def generate_test_description(): class TestMain(unittest.TestCase): def test_interface_version(self, launch_service, proc_info, proc_output): - prefix = get_package_share_directory("default_ad_api") + prefix = get_package_share_directory("autoware_default_adapi") target = prefix + "/test/node/interface_version.py" action = launch.actions.ExecuteProcess(cmd=["python3", target]) with launch_testing.tools.launch_process(launch_service, action, proc_info, proc_output): diff --git a/system/default_ad_api/test/node/interface_version.py b/system/autoware_default_adapi/test/node/interface_version.py similarity index 100% rename from system/default_ad_api/test/node/interface_version.py rename to system/autoware_default_adapi/test/node/interface_version.py From 603dd13ed522e3719393ed0acbd396dc98bcbc2d Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 27 Aug 2024 12:02:07 +0900 Subject: [PATCH 019/217] feat(pid_longitudinal_controller)!: add acceleration feedback block (#8325) Signed-off-by: Yuki Takagi --- ...are_pid_longitudinal_controller.param.yaml | 4 + .../debug_values.hpp | 4 + .../lowpass_filter.hpp | 2 + .../pid_longitudinal_controller.hpp | 4 + ...re_pid_longitudinal_controller.schema.json | 10 + .../src/pid_longitudinal_controller.cpp | 34 ++- .../plot_juggler_trajectory_follower.xml | 249 +++++++++--------- .../param/longitudinal/pid.param.yaml | 4 + 8 files changed, 192 insertions(+), 119 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 f683d8b4f0736..6d9b93ab98870 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 @@ -61,6 +61,10 @@ emergency_acc: -5.0 # denotes acceleration emergency_jerk: -3.0 + # acceleration feedback + lpf_acc_error_gain: 0.98 + acc_feedback_gain: 0.0 + # acceleration limit max_acc: 3.0 min_acc: -5.0 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 e8834665de3ec..a0bceda625b21 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 @@ -58,6 +58,10 @@ class DebugValues STOP_DIST = 28, FF_SCALE = 29, ACC_CMD_FF = 30, + ERROR_ACC = 31, + ERROR_ACC_FILTERED = 32, + ACC_CMD_ACC_FB_APPLIED = 33, + SIZE // this is the number of enum elements }; diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/lowpass_filter.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/lowpass_filter.hpp index 081e78e2de214..1ec43282ca4d3 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/lowpass_filter.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/lowpass_filter.hpp @@ -61,6 +61,8 @@ class LowpassFilter1d m_x = ret; return ret; } + + void setGain(const double g) { m_gain = g; } }; } // namespace autoware::motion::control::pid_longitudinal_controller #endif // AUTOWARE__PID_LONGITUDINAL_CONTROLLER__LOWPASS_FILTER_HPP_ 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 57999372dceed..1d4192d51d98d 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 @@ -196,6 +196,10 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro }; EmergencyStateParams m_emergency_state_params; + // acc feedback + double m_acc_feedback_gain; + std::shared_ptr m_lpf_acc_error{nullptr}; + // acceleration limit double m_max_acc; double m_min_acc; 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 fbbd2dfc7a59f..ef1272582e52b 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 @@ -251,6 +251,16 @@ "description": "target jerk in an EMERGENCY state [m/s^3]", "default": "-3.0" }, + "lpf_acc_error_gain": { + "type": "number", + "description": "gain of low-pass filter for acceleration", + "default": "0.98" + }, + "acc_feedback_gain": { + "type": "number", + "description": "acceleration feedback gain", + "default": "0.0" + }, "max_acc": { "type": "number", "description": "max value of output acceleration [m/s^2]", 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 9190c065eca3c..96e2796a91d22 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -164,6 +164,13 @@ PidLongitudinalController::PidLongitudinalController( p.jerk = node.declare_parameter("emergency_jerk"); // [m/s^3] } + // parameters for acc feedback + { + const double lpf_acc_error_gain{node.declare_parameter("lpf_acc_error_gain")}; + m_lpf_acc_error = std::make_shared(0.0, lpf_acc_error_gain); + m_acc_feedback_gain = node.declare_parameter("acc_feedback_gain"); + } + // parameters for acceleration limit m_max_acc = node.declare_parameter("max_acc"); // [m/s^2] m_min_acc = node.declare_parameter("min_acc"); // [m/s^2] @@ -291,6 +298,10 @@ rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallbac update_param("kd", kd); m_pid_vel.setGains(kp, ki, kd); + double lpf_vel_error_gain{node_parameters_->get_parameter("lpf_vel_error_gain").as_double()}; + update_param("lpf_vel_error_gain", lpf_vel_error_gain); + m_lpf_vel_error->setGain(lpf_vel_error_gain); + double max_pid{node_parameters_->get_parameter("max_out").as_double()}; double min_pid{node_parameters_->get_parameter("min_out").as_double()}; double max_p{node_parameters_->get_parameter("max_p_effort").as_double()}; @@ -365,6 +376,12 @@ rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallbac update_param("emergency_jerk", p.jerk); } + // acceleration feedback + update_param("acc_feedback_gain", m_acc_feedback_gain); + double lpf_acc_error_gain{node_parameters_->get_parameter("lpf_acc_error_gain").as_double()}; + update_param("lpf_acc_error_gain", lpf_acc_error_gain); + m_lpf_acc_error->setGain(lpf_acc_error_gain); + // acceleration limit update_param("min_acc", m_min_acc); @@ -753,6 +770,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d m_pid_vel.reset(); m_lpf_vel_error->reset(0.0); + m_lpf_acc_error->reset(0.0); return changeState(ControlState::DRIVE); } @@ -844,8 +862,22 @@ PidLongitudinalController::Motion PidLongitudinalController::calcCtrlCmd( // store acceleration without slope compensation m_prev_raw_ctrl_cmd = raw_ctrl_cmd; + // calc acc feedback + const double acc_err = control_data.current_motion.acc - raw_ctrl_cmd.acc; + m_debug_values.setValues(DebugValues::TYPE::ERROR_ACC, acc_err); + m_lpf_acc_error->filter(acc_err); + m_debug_values.setValues(DebugValues::TYPE::ERROR_ACC_FILTERED, m_lpf_acc_error->getValue()); + + const double acc_cmd = raw_ctrl_cmd.acc - m_lpf_acc_error->getValue() * m_acc_feedback_gain; + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_FB_APPLIED, acc_cmd); + RCLCPP_DEBUG( + logger_, + "[acc feedback]: raw_ctrl_cmd.acc: %1.3f, control_data.current_motion.acc: %1.3f, acc_cmd: " + "%1.3f", + raw_ctrl_cmd.acc, control_data.current_motion.acc, acc_cmd); + ctrl_cmd_as_pedal_pos.acc = - applySlopeCompensation(raw_ctrl_cmd.acc, control_data.slope_angle, control_data.shift); + applySlopeCompensation(acc_cmd, control_data.slope_angle, control_data.shift); m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_SLOPE_APPLIED, ctrl_cmd_as_pedal_pos.acc); ctrl_cmd_as_pedal_pos.vel = raw_ctrl_cmd.vel; } 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 ab127c2d47b97..e458edaf6c471 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,100 +133,114 @@ - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + - - + + - + - + - + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -234,17 +248,17 @@ - + - + - + @@ -254,13 +268,13 @@ - + - + @@ -272,11 +286,10 @@ - + - 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 5027c94afe7c1..68fb172b19d2a 100644 --- a/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml +++ b/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml @@ -60,6 +60,10 @@ emergency_acc: -5.0 # denotes acceleration emergency_jerk: -3.0 + # acceleration feedback + lpf_acc_error_gain: 0.98 + acc_feedback_gain: 0.0 + # acceleration limit max_acc: 3.0 min_acc: -5.0 From 98d86b2f29d70329ebf5e84f3fc324c8c8b02fb3 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 27 Aug 2024 12:55:03 +0900 Subject: [PATCH 020/217] fix(autoware_tracking_object_merger): fix unusedFunction (#8578) fix:unusedFunction Signed-off-by: kobayu858 --- .../tracking_object_merger/utils/utils.hpp | 7 -- .../src/utils/utils.cpp | 85 ------------------- 2 files changed, 92 deletions(-) diff --git a/perception/autoware_tracking_object_merger/include/autoware/tracking_object_merger/utils/utils.hpp b/perception/autoware_tracking_object_merger/include/autoware/tracking_object_merger/utils/utils.hpp index 17a385da7cb41..f40767274ebfd 100644 --- a/perception/autoware_tracking_object_merger/include/autoware/tracking_object_merger/utils/utils.hpp +++ b/perception/autoware_tracking_object_merger/include/autoware/tracking_object_merger/utils/utils.hpp @@ -80,13 +80,6 @@ autoware_perception_msgs::msg::TrackedObjectKinematics objectKinematicsVXMerger( TrackedObject objectClassificationMerger( const TrackedObject & main_obj, const TrackedObject & sub_obj, const MergePolicy policy); -// probability merger -float probabilityMerger(const float main_prob, const float sub_prob, const MergePolicy policy); - -// shape merger -autoware_perception_msgs::msg::Shape shapeMerger( - const TrackedObject & main_obj, const TrackedObject & sub_obj, const MergePolicy policy); - // update tracked object void updateExceptVelocity(TrackedObject & main_obj, const TrackedObject & sub_obj); diff --git a/perception/autoware_tracking_object_merger/src/utils/utils.cpp b/perception/autoware_tracking_object_merger/src/utils/utils.cpp index 3a24cc0f8321d..04d7f94f2886c 100644 --- a/perception/autoware_tracking_object_merger/src/utils/utils.cpp +++ b/perception/autoware_tracking_object_merger/src/utils/utils.cpp @@ -290,31 +290,6 @@ bool objectsHaveSameMotionDirections(const TrackedObject & main_obj, const Track } } -/** - * @brief compare two tracked objects yaw is reverted or not - * - * @param main_obj - * @param sub_obj - * @return true - * @return false - */ -bool objectsYawIsReverted(const TrackedObject & main_obj, const TrackedObject & sub_obj) -{ - // get yaw - const auto main_yaw = tf2::getYaw(main_obj.kinematics.pose_with_covariance.pose.orientation); - const auto sub_yaw = tf2::getYaw(sub_obj.kinematics.pose_with_covariance.pose.orientation); - // calc yaw diff - const auto yaw_diff = std::fabs(main_yaw - sub_yaw); - const auto normalized_yaw_diff = autoware::universe_utils::normalizeRadian(yaw_diff); // -pi ~ pi - // evaluate if yaw is reverted - constexpr double yaw_threshold = M_PI / 2.0; // 90 deg - if (std::abs(normalized_yaw_diff) >= yaw_threshold) { - return true; - } else { - return false; - } -} - // object kinematics merger // currently only support velocity fusion autoware_perception_msgs::msg::TrackedObjectKinematics objectKinematicsVXMerger( @@ -409,66 +384,6 @@ TrackedObject objectClassificationMerger( } } -// probability merger -float probabilityMerger(const float main_prob, const float sub_prob, const MergePolicy policy) -{ - if (policy == MergePolicy::SKIP) { - return main_prob; - } else if (policy == MergePolicy::OVERWRITE) { - return sub_prob; - } else if (policy == MergePolicy::FUSION) { - return static_cast(mean(main_prob, sub_prob)); - } else { - std::cerr << "unknown merge policy in probabilityMerger function." << std::endl; - return main_prob; - } -} - -// shape merger -autoware_perception_msgs::msg::Shape shapeMerger( - const autoware_perception_msgs::msg::Shape & main_obj_shape, - const autoware_perception_msgs::msg::Shape & sub_obj_shape, const MergePolicy policy) -{ - autoware_perception_msgs::msg::Shape output_shape; - // copy main object at first - output_shape = main_obj_shape; - - if (main_obj_shape.type != sub_obj_shape.type) { - // if shape type is different, return main object - return output_shape; - } - - if (policy == MergePolicy::SKIP) { - return output_shape; - } else if (policy == MergePolicy::OVERWRITE) { - return sub_obj_shape; - } else if (policy == MergePolicy::FUSION) { - // write down fusion method for each shape type - if (main_obj_shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { - // if shape type is bounding box, merge bounding box - output_shape.dimensions.x = mean(main_obj_shape.dimensions.x, sub_obj_shape.dimensions.x); - output_shape.dimensions.y = mean(main_obj_shape.dimensions.y, sub_obj_shape.dimensions.y); - output_shape.dimensions.z = mean(main_obj_shape.dimensions.z, sub_obj_shape.dimensions.z); - return output_shape; - } else if (main_obj_shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { - // if shape type is cylinder, merge cylinder - // (TODO) implement - return output_shape; - } else if (main_obj_shape.type == autoware_perception_msgs::msg::Shape::POLYGON) { - // if shape type is polygon, merge polygon - // (TODO) - return output_shape; - } else { - // when type is unknown, print warning and do nothing - std::cerr << "unknown shape type in shapeMerger function." << std::endl; - return output_shape; - } - } else { - std::cerr << "unknown merge policy in shapeMerger function." << std::endl; - return output_shape; - } -} - void updateExceptVelocity(TrackedObject & main_obj, const TrackedObject & sub_obj) { // do not update if motion direction is different From f3f7a1b6801f3226acf9ddd06ffb4e827f2b468a Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 27 Aug 2024 12:57:29 +0900 Subject: [PATCH 021/217] fix(simple_planning_simulator): fix dimension (#8629) Signed-off-by: Yuki Takagi --- .../sim_model_delay_steer_acc_geared_wo_fall_guard.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp index 69a311b780ad8..ce962eba9275a 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp @@ -23,7 +23,7 @@ SimModelDelaySteerAccGearedWoFallGuard::SimModelDelaySteerAccGearedWoFallGuard( double dt, double acc_delay, double acc_time_constant, double steer_delay, double steer_time_constant, double steer_dead_band, double steer_bias, double debug_acc_scaling_factor, double debug_steer_scaling_factor) -: SimModelInterface(6 /* dim x */, 4 /* dim u */), +: SimModelInterface(7 /* dim x */, 4 /* dim u */), MIN_TIME_CONSTANT(0.03), vx_lim_(vx_lim), vx_rate_lim_(vx_rate_lim), From 61f317e08339798963e40431b30126c1a220dd94 Mon Sep 17 00:00:00 2001 From: Abraham Monrroy Cano Date: Tue, 27 Aug 2024 13:06:46 +0900 Subject: [PATCH 022/217] fix: cpp17 namespaces (#8526) Use traditional-style nameplace nesting for nvcc Signed-off-by: Yuri Guimaraes Co-authored-by: Yuri Guimaraes --- .../include/autoware/tensorrt_yolox/preprocess.hpp | 7 +++++-- perception/autoware_tensorrt_yolox/src/preprocess.cu | 7 +++++-- 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/preprocess.hpp b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/preprocess.hpp index 947d6cc6ecc95..7971fbd815deb 100644 --- a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/preprocess.hpp +++ b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/preprocess.hpp @@ -21,7 +21,9 @@ #include #include -namespace autoware::tensorrt_yolox +namespace autoware +{ +namespace tensorrt_yolox { struct Roi { @@ -195,5 +197,6 @@ extern void multi_scale_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( extern void argmax_gpu( unsigned char * dst, float * src, int d_w, int d_h, int s_w, int s_h, int s_c, int batch, cudaStream_t stream); -} // namespace autoware::tensorrt_yolox +} // namespace tensorrt_yolox +} // namespace autoware #endif // AUTOWARE__TENSORRT_YOLOX__PREPROCESS_HPP_ diff --git a/perception/autoware_tensorrt_yolox/src/preprocess.cu b/perception/autoware_tensorrt_yolox/src/preprocess.cu index ba9d456f32749..6e8ded20df709 100644 --- a/perception/autoware_tensorrt_yolox/src/preprocess.cu +++ b/perception/autoware_tensorrt_yolox/src/preprocess.cu @@ -21,7 +21,9 @@ #define MIN(x, y) x < y ? x : y -namespace autoware::tensorrt_yolox +namespace autoware +{ +namespace tensorrt_yolox { constexpr size_t block = 512; @@ -629,4 +631,5 @@ void argmax_gpu( N, dst, src, d_h, d_w, s_c, s_h, s_w, batch); } -} // namespace autoware::tensorrt_yolox +} // namespace tensorrt_yolox +} // namespace autoware From 62e71e1a5361581e33668bbd11295333d6906a3d Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Tue, 27 Aug 2024 13:10:52 +0900 Subject: [PATCH 023/217] chore(autoware_tensorrt_yolox): add Kotaro Uetake as maintainer (#8595) chore: add Kotaro Uetake as maintainer Signed-off-by: ktro2828 --- .github/CODEOWNERS | 2 +- perception/autoware_tensorrt_yolox/package.xml | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index c3774f0485153..6de0c3251696b 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -134,7 +134,7 @@ perception/autoware_raindrop_cluster_filter/** dai.nguyen@tier4.jp yoshi.ri@tier perception/autoware_shape_estimation/** kcolak@leodrive.ai yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/autoware_simple_object_merger/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp perception/autoware_tensorrt_classifier/** kotaro.uetake@tier4.jp shunsuke.miura@tier4.jp -perception/autoware_tensorrt_yolox/** dan.umeda@tier4.jp manato.hirabayashi@tier4.jp +perception/autoware_tensorrt_yolox/** dan.umeda@tier4.jp manato.hirabayashi@tier4.jp kotaro.uetake@tier4.jp perception/autoware_tracking_object_merger/** taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/autoware_traffic_light_arbiter/** kenzo.lobos@tier4.jp shunsuke.miura@tier4.jp perception/autoware_traffic_light_classifier/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp yukihiro.saito@tier4.jp diff --git a/perception/autoware_tensorrt_yolox/package.xml b/perception/autoware_tensorrt_yolox/package.xml index 3373a07d8b434..cd9dc6bac015d 100644 --- a/perception/autoware_tensorrt_yolox/package.xml +++ b/perception/autoware_tensorrt_yolox/package.xml @@ -7,6 +7,7 @@ Daisuke Nishimatsu Dan Umeda Manato Hirabayashi + Kotaro Uetake Apache License 2.0 From 6cd87782235755bc74261dc6dac558fabfccb97e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 27 Aug 2024 13:24:06 +0900 Subject: [PATCH 024/217] feat(simple_planning_simulator): print actual and expected value in test (#8630) Signed-off-by: kosuke55 --- .../test/test_simple_planning_simulator.cpp | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp index cb58628121de2..d774617dc77f1 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -221,6 +221,7 @@ void isOnForward(const Odometry & state, const Odometry & init) { double forward_thr = 1.0; double dx = state.pose.pose.position.x - init.pose.pose.position.x; + std::cout << "isOnForward: dx: " << dx << ", forward_thr: " << forward_thr << std::endl; EXPECT_GT(dx, forward_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); } @@ -228,6 +229,7 @@ void isOnBackward(const Odometry & state, const Odometry & init) { double backward_thr = -1.0; double dx = state.pose.pose.position.x - init.pose.pose.position.x; + std::cout << "isOnBackward: dx: " << dx << ", backward_thr: " << backward_thr << std::endl; EXPECT_LT(dx, backward_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); } @@ -237,6 +239,8 @@ void isOnForwardLeft(const Odometry & state, const Odometry & init) double left_thr = 0.1f; double dx = state.pose.pose.position.x - init.pose.pose.position.x; double dy = state.pose.pose.position.y - init.pose.pose.position.y; + std::cout << "isOnForwardLeft: dx: " << dx << ", forward_thr: " << forward_thr << ", dy: " << dy + << ", left_thr: " << left_thr << std::endl; EXPECT_GT(dx, forward_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); EXPECT_GT(dy, left_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); } @@ -247,6 +251,8 @@ void isOnBackwardRight(const Odometry & state, const Odometry & init) double right_thr = -0.1; double dx = state.pose.pose.position.x - init.pose.pose.position.x; double dy = state.pose.pose.position.y - init.pose.pose.position.y; + std::cout << "isOnBackwardRight: dx: " << dx << ", backward_thr: " << backward_thr + << ", dy: " << dy << ", right_thr: " << right_thr << std::endl; EXPECT_LT(dx, backward_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); EXPECT_LT(dy, right_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); } @@ -302,7 +308,6 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) const auto common_params = get_common_params(params); const auto command_type = common_params.first; const auto vehicle_model_type = common_params.second; - std::cout << "\n\n vehicle model = " << vehicle_model_type << std::endl << std::endl; // optional parameters std::optional conversion_type{}; // for ActuationCmdParamType @@ -338,7 +343,12 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) node_options.append_parameter_override("vgr_coef_b", 0.053); node_options.append_parameter_override("vgr_coef_c", 0.042); if (conversion_type.has_value()) { + std::cout << "\n\n vehicle model = " << vehicle_model_type + << ", conversion_type = " << conversion_type.value() << std::endl + << std::endl; node_options.append_parameter_override("convert_steer_cmd_method", conversion_type.value()); + } else { + std::cout << "\n\n vehicle model = " << vehicle_model_type << std::endl << std::endl; } declareVehicleInfoParams(node_options); From 05bdb5a49e4f76bc6757ed7b7f97472cc685f93f Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 27 Aug 2024 13:47:08 +0900 Subject: [PATCH 025/217] fix(simple_planning_simulator): increase test_steer_map values (#8631) Signed-off-by: kosuke55 --- .../test/actuation_cmd_map/steer_map.csv | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/simulator/simple_planning_simulator/test/actuation_cmd_map/steer_map.csv b/simulator/simple_planning_simulator/test/actuation_cmd_map/steer_map.csv index 7adb0f6a9e583..1562a7b346677 100644 --- a/simulator/simple_planning_simulator/test/actuation_cmd_map/steer_map.csv +++ b/simulator/simple_planning_simulator/test/actuation_cmd_map/steer_map.csv @@ -1,4 +1,4 @@ default,-0.6,0,0.6 --10,-0.03,-0.03,-0.03 +-10,-0.5,-0.5,-0.5 0,0.0,0.0,0.0 -10,0.03,0.03,0.03 +10,0.5,0.5,0.5 From 0a6f7441857f88f6f09bc48cdb1ab23d07a73e2d Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 27 Aug 2024 13:50:56 +0900 Subject: [PATCH 026/217] fix(autoware_probabilistic_occupancy_grid_map): fix unusedFunction (#8574) fix:unusedFunction Signed-off-by: kobayu858 --- .../utils/utils.hpp | 2 -- .../lib/utils/utils.cpp | 16 --------- .../synchronized_grid_map_fusion_node.cpp | 36 ------------------- .../synchronized_grid_map_fusion_node.hpp | 4 --- 4 files changed, 58 deletions(-) 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 a8288d2720f48..41c7294ded849 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 @@ -120,8 +120,6 @@ bool extractCommonPointCloud( const sensor_msgs::msg::PointCloud2 & obstacle_pc, const sensor_msgs::msg::PointCloud2 & raw_pc, sensor_msgs::msg::PointCloud2 & output_obstacle_pc); -unsigned char getApproximateOccupancyState(const unsigned char & value); - } // namespace utils } // namespace autoware::occupancy_grid_map 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 902de2148cffe..9d190664b8858 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/lib/utils/utils.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/utils/utils.cpp @@ -191,21 +191,5 @@ bool extractCommonPointCloud( return true; } -/** - * @brief Convert unsigned char value to closest cost value - * @param cost Cost value - * @return Probability - */ -unsigned char getApproximateOccupancyState(const unsigned char & value) -{ - if (value >= cost_value::OCCUPIED_THRESHOLD) { - return cost_value::LETHAL_OBSTACLE; - } else if (value <= cost_value::FREE_THRESHOLD) { - return cost_value::FREE_SPACE; - } else { - return cost_value::NO_INFORMATION; - } -} - } // namespace utils } // namespace autoware::occupancy_grid_map 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 0a78b10055dd0..28a5759eeb7b0 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 @@ -369,42 +369,6 @@ OccupancyGridMapFixedBlindSpot GridMapFusionNode::SingleFrameOccupancyFusion( return fused_map; } -/** - * @brief Update occupancy grid map with asynchronous input (currently unused) - * - * @param occupancy_grid_msg - */ -void GridMapFusionNode::updateGridMap( - const nav_msgs::msg::OccupancyGrid::ConstSharedPtr & occupancy_grid_msg) -{ - // get updater map origin - - // origin is set to current updater map - auto map_for_update = OccupancyGridMsgToCostmap2D(*occupancy_grid_msg); - - // update - occupancy_grid_map_updater_ptr_->update(map_for_update); -} - -nav2_costmap_2d::Costmap2D GridMapFusionNode::OccupancyGridMsgToCostmap2D( - const nav_msgs::msg::OccupancyGrid & occupancy_grid_map) -{ - nav2_costmap_2d::Costmap2D costmap2d( - occupancy_grid_map.info.width, occupancy_grid_map.info.height, - occupancy_grid_map.info.resolution, occupancy_grid_map.info.origin.position.x, - occupancy_grid_map.info.origin.position.y, 0); - - for (unsigned int i = 0; i < occupancy_grid_map.info.width; i++) { - for (unsigned int j = 0; j < occupancy_grid_map.info.height; j++) { - const unsigned int index = i + j * occupancy_grid_map.info.width; - costmap2d.setCost( - i, j, cost_value::inverse_cost_translation_table[occupancy_grid_map.data[index]]); - } - } - - return costmap2d; -} - OccupancyGridMapFixedBlindSpot GridMapFusionNode::OccupancyGridMsgToGridMap( const nav_msgs::msg::OccupancyGrid & occupancy_grid_map) { 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 691575299a8c7..23aeb76826e5f 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 @@ -66,16 +66,12 @@ class GridMapFusionNode : public rclcpp::Node const std::string & frame_id, const builtin_interfaces::msg::Time & stamp, const float & robot_pose_z, const nav2_costmap_2d::Costmap2D & occupancy_grid_map); - nav2_costmap_2d::Costmap2D OccupancyGridMsgToCostmap2D( - const nav_msgs::msg::OccupancyGrid & occupancy_grid_map); OccupancyGridMapFixedBlindSpot OccupancyGridMsgToGridMap( const nav_msgs::msg::OccupancyGrid & occupancy_grid_map); OccupancyGridMapFixedBlindSpot SingleFrameOccupancyFusion( std::vector & occupancy_grid_maps, const builtin_interfaces::msg::Time latest_stamp, const std::vector & weights); - void updateGridMap(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr & occupancy_grid_msg); - void setPeriod(const int64_t new_period); void timer_callback(); void publish(); From b90556255030cd4e64fb0a3336152f84011adcab Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 27 Aug 2024 14:04:32 +0900 Subject: [PATCH 027/217] fix(goal_planner): fix zero velocity in middle of path (#8563) * fix(goal_planner): fix zero velocity in middle of path Signed-off-by: kosuke55 * add comment Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../util.hpp | 27 ++++++++++++++++--- .../src/goal_planner_module.cpp | 10 ++++++- .../src/shift_pull_over.cpp | 6 ++++- .../src/util.cpp | 11 +++++--- 4 files changed, 45 insertions(+), 9 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 9e4d6d2f85f50..b527fa3e1dac0 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 @@ -84,12 +84,31 @@ bool isReferencePath( std::optional cropPath(const PathWithLaneId & path, const Pose & end_pose); PathWithLaneId cropForwardPoints( const PathWithLaneId & path, const size_t target_seg_idx, const double forward_length); + +/** + * @brief extend target_path by extend_length + * @param target_path original target path to extend + * @param reference_path reference path to extend + * @param extend_length length to extend + * @param remove_connected_zero_velocity flag to remove zero velocity if the last point of + * target_path has zero velocity + * @return extended path + */ PathWithLaneId extendPath( - const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path, - const double extend_length); + const PathWithLaneId & target_path, const PathWithLaneId & reference_path, + const double extend_length, const bool remove_connected_zero_velocity); +/** + * @brief extend target_path to extend_pose + * @param target_path original target path to extend + * @param reference_path reference path to extend + * @param extend_pose pose to extend + * @param remove_connected_zero_velocity flag to remove zero velocity if the last point of + * target_path has zero velocity + * @return extended path + */ PathWithLaneId extendPath( - const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path, - const Pose & extend_pose); + const PathWithLaneId & target_path, const PathWithLaneId & reference_path, + const Pose & extend_pose, const bool remove_connected_zero_velocity); std::vector createPathFootPrints( const PathWithLaneId & path, const double base_to_front, const double base_to_rear, 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 c67983993de01..4d4d31446aa3f 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 @@ -283,6 +283,10 @@ void GoalPlannerModule::onTimer() RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path"); return true; } + // TODO(someone): The generated path inherits the velocity of the path of the previous module. + // Therefore, if the velocity of the path of the previous module changes (e.g. stop points are + // inserted, deleted), the path should be regenerated. + return false; }); if (!need_update) { @@ -1628,8 +1632,12 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const const double s_end = s_current + common_parameters.forward_path_length; return route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); }); + + // 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. const auto extended_prev_path = goal_planner_utils::extendPath( - getPreviousModuleOutput().path, reference_path, common_parameters.forward_path_length); + getPreviousModuleOutput().path, reference_path, common_parameters.forward_path_length, true); // calculate search start offset pose from the closest goal candidate pose with // approximate_pull_over_distance_ ego vehicle decelerates to this position. or if no feasible diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp index 23ca76432859d..fd6b0cb639387 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -148,8 +148,12 @@ std::optional ShiftPullOver::generatePullOverPath( 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); + 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); } 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 f4b11f4f8e46d..6bceec531b653 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 @@ -389,7 +389,7 @@ PathWithLaneId cropForwardPoints( PathWithLaneId extendPath( const PathWithLaneId & target_path, const PathWithLaneId & reference_path, - const double extend_length) + const double extend_length, const bool remove_connected_zero_velocity) { const auto & target_terminal_pose = target_path.points.back().point.pose; @@ -409,6 +409,11 @@ PathWithLaneId extendPath( } auto extended_path = target_path; + auto & target_terminal_vel = extended_path.points.back().point.longitudinal_velocity_mps; + if (remove_connected_zero_velocity && target_terminal_vel < 0.01) { + target_terminal_vel = clipped_path.points.front().point.longitudinal_velocity_mps; + } + const auto start_point = std::find_if(clipped_path.points.begin(), clipped_path.points.end(), [&](const auto & p) { const bool is_forward = @@ -427,7 +432,7 @@ PathWithLaneId extendPath( PathWithLaneId extendPath( const PathWithLaneId & target_path, const PathWithLaneId & reference_path, - const Pose & extend_pose) + const Pose & extend_pose, const bool remove_connected_zero_velocity) { const auto & target_terminal_pose = target_path.points.back().point.pose; const size_t target_path_terminal_idx = autoware::motion_utils::findNearestSegmentIndex( @@ -435,7 +440,7 @@ PathWithLaneId extendPath( const double extend_distance = autoware::motion_utils::calcSignedArcLength( reference_path.points, target_path_terminal_idx, extend_pose.position); - return extendPath(target_path, reference_path, extend_distance); + return extendPath(target_path, reference_path, extend_distance, remove_connected_zero_velocity); } std::vector createPathFootPrints( From a64566ee7437075c75f30d128940dd4823e9d27a Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 27 Aug 2024 15:34:21 +0900 Subject: [PATCH 028/217] fix(tier4_camera_view_rviz_plugin): fix unusedFunction (#8639) * fix:unusedFunction Signed-off-by: kobayu858 * fix:clang format Signed-off-by: kobayu858 * fix:unusedFunction Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/bird_eye_view_controller.cpp | 3 +++ .../src/third_person_view_controller.cpp | 1 + 2 files changed, 4 insertions(+) diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp index 16c3f4b5def96..2368e07432031 100644 --- a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp +++ b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp @@ -99,6 +99,7 @@ void BirdEyeViewController::reset() y_property_->setFloat(0); } +// cppcheck-suppress unusedFunction void BirdEyeViewController::handleMouseEvent(rviz_common::ViewportMouseEvent & event) { if (event.shift()) { @@ -178,11 +179,13 @@ void BirdEyeViewController::update(float dt, float ros_dt) updateCamera(); } +// cppcheck-suppress unusedFunction void BirdEyeViewController::lookAt(const Ogre::Vector3 & point) { setPosition(point - target_scene_node_->getPosition()); } +// cppcheck-suppress unusedFunction void BirdEyeViewController::onTargetFrameChanged( const Ogre::Vector3 & old_reference_position, const Ogre::Quaternion & /*old_reference_orientation*/) diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp b/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp index ed47a15270c3a..97216f238d593 100644 --- a/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp +++ b/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp @@ -226,6 +226,7 @@ void ThirdPersonViewController::updateCamera() distance_property_->getFloat() * CAMERA_OFFSET); } +// cppcheck-suppress unusedFunction void ThirdPersonViewController::updateTargetSceneNode() { if (FramePositionTrackingViewController::getNewTransform()) { From d08dcfe995a3797d69791aaadb93be6082c3b574 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Tue, 27 Aug 2024 17:48:02 +0900 Subject: [PATCH 029/217] fix(autoware_pointcloud_preprocessor): blockage diag node add runtime error when the parameter is wrong (#8564) * fix: add runtime error Signed-off-by: vividf * Update blockage_diag_node.cpp Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> * fix: add RCLCPP error logging Signed-off-by: vividf * chore: remove unused variable Signed-off-by: vividf --------- Signed-off-by: vividf Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> --- .../src/blockage_diag/blockage_diag_node.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) 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 2f34d78b8e9a0..6703eb6b70741 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 @@ -190,6 +190,14 @@ void BlockageDiagComponent::filter( sky_blockage_range_deg_[1] = angle_range_deg_[1]; } else { for (const auto p : pcl_input->points) { + if (p.channel >= vertical_bins) { + RCLCPP_ERROR( + this->get_logger(), + "p.channel: %d is larger than vertical_bins: %d .Please check the parameter " + "'vertical_bins'.", + p.channel, vertical_bins); + throw std::runtime_error("Parameter is not valid"); + } double azimuth_deg = p.azimuth * (180.0 / M_PI); if ( ((azimuth_deg > angle_range_deg_[0]) && From bfaeb63f2147d27fd7cb42fab0d742d229035176 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 27 Aug 2024 18:07:12 +0900 Subject: [PATCH 030/217] fix(tier4_localization_rviz_plugin): fix unusedFunction (#8637) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/pose_history/pose_history_display.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp b/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp index 9e65b117b3f3f..931c675a23e7f 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp @@ -50,11 +50,13 @@ void PoseHistory::onInitialize() lines_ = std::make_unique(scene_manager_, scene_node_); } +// cppcheck-suppress unusedFunction void PoseHistory::onEnable() { subscribe(); } +// cppcheck-suppress unusedFunction void PoseHistory::onDisable() { unsubscribe(); From e434372ebada975adb0e0132ba41d645af862c65 Mon Sep 17 00:00:00 2001 From: Ismet Atabay <56237550+ismetatabay@users.noreply.github.com> Date: Tue, 27 Aug 2024 12:16:07 +0300 Subject: [PATCH 031/217] feat(autoware_tensorrt_yolox): add GPU - CUDA device option (#8245) * init CUDA device option Signed-off-by: ismetatabay Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/yolox_s_plus_opt.param.yaml | 1 + .../config/yolox_tiny.param.yaml | 1 + .../tensorrt_yolox/tensorrt_yolox.hpp | 22 ++++++++++++-- .../launch/multiple_yolox.launch.xml | 24 --------------- .../schema/yolox_s_plus_opt.schema.json | 8 ++++- .../schema/yolox_tiny.schema.json | 8 ++++- .../src/tensorrt_yolox.cpp | 30 +++++++++++++++---- .../src/tensorrt_yolox_node.cpp | 10 ++++++- .../README.md | 15 +++++----- .../traffic_light_fine_detector.param.yaml | 1 + .../src/traffic_light_fine_detector_node.cpp | 10 ++++++- 11 files changed, 87 insertions(+), 43 deletions(-) diff --git a/perception/autoware_tensorrt_yolox/config/yolox_s_plus_opt.param.yaml b/perception/autoware_tensorrt_yolox/config/yolox_s_plus_opt.param.yaml index d963074e51840..df01e2cb6eec6 100644 --- a/perception/autoware_tensorrt_yolox/config/yolox_s_plus_opt.param.yaml +++ b/perception/autoware_tensorrt_yolox/config/yolox_s_plus_opt.param.yaml @@ -36,4 +36,5 @@ 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. diff --git a/perception/autoware_tensorrt_yolox/config/yolox_tiny.param.yaml b/perception/autoware_tensorrt_yolox/config/yolox_tiny.param.yaml index e1ece63a4940f..e8b5b38503c9b 100644 --- a/perception/autoware_tensorrt_yolox/config/yolox_tiny.param.yaml +++ b/perception/autoware_tensorrt_yolox/config/yolox_tiny.param.yaml @@ -36,4 +36,5 @@ 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: 0.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. 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 6610476dc33fc..6fba801d1072b 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 @@ -89,8 +89,9 @@ class 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 tensorrt_common::BuildConfig build_config = tensorrt_common::BuildConfig(), - const bool use_gpu_preprocess = false, std::string calibration_image_list_file = std::string(), - const double norm_factor = 1.0, [[maybe_unused]] const std::string & cache_dir = "", + 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 tensorrt_common::BatchConfig & batch_config = {1, 1, 1}, const size_t max_workspace_size = (1 << 30), const std::string & color_map_path = ""); /** @@ -98,6 +99,17 @@ class TrtYoloX */ ~TrtYoloX(); + /** + * @brief select cuda device for a inference + * @param[in] GPU id + */ + bool setCudaDeviceId(const uint8_t gpu_id); + + /** + * @brief return a flag for gpu initialization + */ + bool isGPUInitialized() const { return is_gpu_initialized_; } + /** * @brief run inference including pre-process and post-process * @param[out] objects results for object detection @@ -267,7 +279,7 @@ class TrtYoloX size_t out_elem_num_per_batch_; CudaUniquePtr out_prob_d_; - StreamUniquePtr stream_{makeCudaStream()}; + StreamUniquePtr stream_; int32_t max_detections_; std::vector scales_; @@ -280,6 +292,10 @@ class TrtYoloX // flag whether preprocess are performed on GPU bool use_gpu_preprocess_; + // GPU id for inference + const uint8_t gpu_id_; + // flag for gpu initialization + bool is_gpu_initialized_; // host buffer for preprocessing on GPU CudaUniquePtrHost image_buf_h_; // device buffer for preprocessing on GPU diff --git a/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml b/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml index a039d25222490..a7952b12414b1 100644 --- a/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml +++ b/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml @@ -1,69 +1,45 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception/autoware_tensorrt_yolox/schema/yolox_s_plus_opt.schema.json b/perception/autoware_tensorrt_yolox/schema/yolox_s_plus_opt.schema.json index ce1ad6c2d0caf..a55158be80b7c 100644 --- a/perception/autoware_tensorrt_yolox/schema/yolox_s_plus_opt.schema.json +++ b/perception/autoware_tensorrt_yolox/schema/yolox_s_plus_opt.schema.json @@ -70,6 +70,11 @@ "default": true, "description": "If true, pre-processing is performed on GPU." }, + "gpu_id": { + "type": "integer", + "default": 0, + "description": "GPU ID for selecting CUDA device" + }, "calibration_image_list_path": { "type": "string", "default": "", @@ -88,7 +93,8 @@ "quantize_last_layer", "profile_per_layer", "clip_value", - "preprocess_on_gpu" + "preprocess_on_gpu", + "gpu_id" ] } }, diff --git a/perception/autoware_tensorrt_yolox/schema/yolox_tiny.schema.json b/perception/autoware_tensorrt_yolox/schema/yolox_tiny.schema.json index f47b28e47a3f8..707cd393d6828 100644 --- a/perception/autoware_tensorrt_yolox/schema/yolox_tiny.schema.json +++ b/perception/autoware_tensorrt_yolox/schema/yolox_tiny.schema.json @@ -70,6 +70,11 @@ "default": true, "description": "If true, pre-processing is performed on GPU." }, + "gpu_id": { + "type": "integer", + "default": 0, + "description": "GPU ID for selecting CUDA device" + }, "calibration_image_list_path": { "type": "string", "default": "", @@ -88,7 +93,8 @@ "quantize_last_layer", "profile_per_layer", "clip_value", - "preprocess_on_gpu" + "preprocess_on_gpu", + "gpu_id" ] } }, diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp index 675fee64812a2..b6da363a9a237 100644 --- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp +++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp @@ -156,16 +156,25 @@ 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, tensorrt_common::BuildConfig build_config, - const bool use_gpu_preprocess, std::string calibration_image_list_path, const double norm_factor, - [[maybe_unused]] const std::string & cache_dir, const tensorrt_common::BatchConfig & batch_config, - const size_t max_workspace_size, const std::string & color_map_path) + 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 tensorrt_common::BatchConfig & batch_config, const size_t max_workspace_size, + const std::string & color_map_path) +: gpu_id_(gpu_id), is_gpu_initialized_(false) { + if (!setCudaDeviceId(gpu_id_)) { + return; + } + is_gpu_initialized_ = true; + 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) { if (calibration_image_list_path.empty()) { @@ -217,7 +226,6 @@ 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); } else { @@ -262,7 +270,6 @@ TrtYoloX::TrtYoloX( throw std::runtime_error{s.str()}; */ } - // GPU memory allocation const auto input_dims = trt_common_->getBindingDimensions(0); const auto input_size = @@ -341,6 +348,16 @@ TrtYoloX::~TrtYoloX() } } +bool TrtYoloX::setCudaDeviceId(const uint8_t gpu_id) +{ + cudaError_t cuda_err = cudaSetDevice(gpu_id); + if (cuda_err != cudaSuccess) { + return false; + } else { + return true; + } +} + void TrtYoloX::initPreprocessBuffer(int width, int height) { // if size of source input has been changed... @@ -534,6 +551,9 @@ bool TrtYoloX::doInference( const std::vector & images, ObjectArrays & objects, std::vector & masks, [[maybe_unused]] std::vector & color_masks) { + if (!setCudaDeviceId(gpu_id_)) { + return false; + } if (!trt_common_->isInitialized()) { return false; } diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp index c613e7d1df52f..2455411618ceb 100644 --- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp +++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp @@ -57,6 +57,7 @@ TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options) const bool preprocess_on_gpu = this->declare_parameter("preprocess_on_gpu"); const std::string calibration_image_list_path = this->declare_parameter("calibration_image_list_path"); + const uint8_t gpu_id = this->declare_parameter("gpu_id"); std::string color_map_path = this->declare_parameter("color_map_path"); @@ -93,9 +94,16 @@ TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options) trt_yolox_ = std::make_unique( model_path, precision, label_map_.size(), score_threshold, nms_threshold, build_config, - preprocess_on_gpu, calibration_image_list_path, norm_factor, cache_dir, batch_config, + preprocess_on_gpu, gpu_id, calibration_image_list_path, norm_factor, cache_dir, batch_config, max_workspace_size, color_map_path); + if (!trt_yolox_->isGPUInitialized()) { + RCLCPP_ERROR(this->get_logger(), "GPU %d does not exist or is not suitable.", gpu_id); + rclcpp::shutdown(); + return; + } + RCLCPP_INFO(this->get_logger(), "GPU %d is selected for the inference!", gpu_id); + timer_ = rclcpp::create_timer(this, get_clock(), 100ms, std::bind(&TrtYoloXNode::onConnect, this)); diff --git a/perception/autoware_traffic_light_fine_detector/README.md b/perception/autoware_traffic_light_fine_detector/README.md index 9e69c22fdc17b..35b55c84aa087 100644 --- a/perception/autoware_traffic_light_fine_detector/README.md +++ b/perception/autoware_traffic_light_fine_detector/README.md @@ -51,13 +51,14 @@ Based on the camera image and the global ROI array detected by `map_based_detect ### Node Parameters -| Name | Type | Default Value | Description | -| -------------------------- | ------ | --------------------------- | ------------------------------------------------------------------ | -| `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" | -| `approximate_sync` | bool | false | Flag for whether to ues approximate sync policy | +| Name | Type | Default Value | Description | +| -------------------------- | ------- | --------------------------- | ------------------------------------------------------------------ | +| `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" | +| `approximate_sync` | bool | false | Flag for whether to ues approximate sync policy | +| `gpu_id` | integer | 0 | ID for the selecting CUDA GPU device | ## Assumptions / Known limits 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 0265d0c4c7abb..36d4413472a0b 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,3 +5,4 @@ fine_detector_precision: fp16 fine_detector_score_thresh: 0.3 fine_detector_nms_thresh: 0.65 + 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 fec26b762dfe9..5963efe611c00 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 @@ -60,6 +60,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"); + 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 score_thresh_ = declare_parameter("fine_detector_score_thresh", 0.3); @@ -86,7 +87,14 @@ TrafficLightFineDetectorNode::TrafficLightFineDetectorNode(const rclcpp::NodeOpt trt_yolox_ = std::make_unique( model_path, precision, num_class, score_thresh_, nms_threshold, build_config, cuda_preprocess, - calib_image_list, scale, cache_dir, batch_config); + gpu_id, calib_image_list, scale, cache_dir, batch_config); + + if (!trt_yolox_->isGPUInitialized()) { + RCLCPP_ERROR(this->get_logger(), "GPU %d does not exist or is not suitable.", gpu_id); + rclcpp::shutdown(); + return; + } + RCLCPP_INFO(this->get_logger(), "GPU %d is selected for the inference!", gpu_id); using std::chrono_literals::operator""ms; timer_ = rclcpp::create_timer( From 94b5c33387176e28d17173a365b6dd1bfc12f227 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 27 Aug 2024 18:51:41 +0900 Subject: [PATCH 032/217] refactor(ekf_localizer): removed proc_cov_*_d_ from EKFLocalizer (#8640) Removed proc_cov_*_d_ from EKFLocalizer Signed-off-by: Shintaro Sakoda --- .../include/ekf_localizer/ekf_localizer.hpp | 5 ----- localization/ekf_localizer/src/ekf_localizer.cpp | 10 ---------- 2 files changed, 15 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 650eca26d4e96..332d4e0837e54 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -160,11 +160,6 @@ class EKFLocalizer : public rclcpp::Node double ekf_dt_; - /* process noise variance for discrete model */ - double proc_cov_yaw_d_; //!< @brief discrete yaw process noise - double proc_cov_vx_d_; //!< @brief discrete process noise in d_vx=0 - double proc_cov_wz_d_; //!< @brief discrete process noise in d_wz=0 - bool is_activated_; EKFDiagnosticInfo pose_diag_info_; diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index f1e4d0c958c77..10c706f4032b6 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -52,11 +52,6 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) twist_queue_(params_.twist_smoothing_steps), last_angular_velocity_(0.0, 0.0, 0.0) { - /* convert to continuous to discrete */ - proc_cov_vx_d_ = std::pow(params_.proc_stddev_vx_c * ekf_dt_, 2.0); - proc_cov_wz_d_ = std::pow(params_.proc_stddev_wz_c * ekf_dt_, 2.0); - proc_cov_yaw_d_ = std::pow(params_.proc_stddev_yaw_c * ekf_dt_, 2.0); - is_activated_ = false; /* initialize ros system */ @@ -132,11 +127,6 @@ void EKFLocalizer::update_predict_frequency(const rclcpp::Time & current_time) /* Register dt and accumulate time delay */ ekf_module_->accumulate_delay_time(ekf_dt_); - - /* Update discrete proc_cov*/ - proc_cov_vx_d_ = std::pow(params_.proc_stddev_vx_c * ekf_dt_, 2.0); - proc_cov_wz_d_ = std::pow(params_.proc_stddev_wz_c * ekf_dt_, 2.0); - proc_cov_yaw_d_ = std::pow(params_.proc_stddev_yaw_c * ekf_dt_, 2.0); } } last_predict_time_ = std::make_shared(current_time); From 1458bbc99c569393c42467b73f73944a0065a5f5 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 27 Aug 2024 19:32:02 +0900 Subject: [PATCH 033/217] fix(autoware_mission_planner): fix unusedFunction (#8642) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/mission_planner/arrival_checker.cpp | 11 ----------- .../src/mission_planner/arrival_checker.hpp | 1 - 2 files changed, 12 deletions(-) diff --git a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp b/planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp index da14712dd6c64..41502d8c3c2c3 100644 --- a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp +++ b/planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp @@ -43,17 +43,6 @@ void ArrivalChecker::set_goal(const PoseWithUuidStamped & goal) goal_with_uuid_ = goal; } -void ArrivalChecker::modify_goal(const PoseWithUuidStamped & modified_goal) -{ - if (!goal_with_uuid_) { - return; - } - if (goal_with_uuid_.value().uuid.uuid != modified_goal.uuid.uuid) { - return; - } - set_goal(modified_goal); -} - bool ArrivalChecker::is_arrived(const PoseStamped & pose) const { if (!goal_with_uuid_) { diff --git a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp b/planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp index 708b3de40bdab..d2e9a7408b791 100644 --- a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp @@ -33,7 +33,6 @@ class ArrivalChecker explicit ArrivalChecker(rclcpp::Node * node); void set_goal(); void set_goal(const PoseWithUuidStamped & goal); - void modify_goal(const PoseWithUuidStamped & modified_goal); bool is_arrived(const PoseStamped & pose) const; private: From 7fea75b9cc5441f8ba26246cc58cee7956161336 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 27 Aug 2024 19:32:47 +0900 Subject: [PATCH 034/217] fix(autoware_costmap_generator): fix unusedFunction (#8641) fix:unusedFunction Signed-off-by: kobayu858 --- .../object_map_utils.hpp | 23 ------------------- .../object_map_utils.cpp | 19 --------------- 2 files changed, 42 deletions(-) diff --git a/planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp b/planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp index f4911cc428d36..55a032fc8bb5a 100644 --- a/planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp +++ b/planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp @@ -52,29 +52,6 @@ namespace object_map { -/*! - * Publishes in_gridmap using the specified in_publisher - * @param[in] in_gridmap GridMap object to publish - * @param[in] in_publisher Valid Publisher object to use - */ -void PublishGridMap( - const grid_map::GridMap & in_gridmap, - const rclcpp::Publisher::SharedPtr in_publisher); - -/*! - * Convert and publishes a GridMap layer to a standard Ros OccupancyGrid - * @param[in] in_gridmap GridMap object to extract the layer - * @param[in] in_publisher ROS Publisher to use to publish the occupancy grid - * @param[in] in_layer Name of the layer to convert - * @param[in] in_min_value Minimum value in the layer - * @param[in] in_max_value Maximum value in the layer - */ - -void PublishOccupancyGrid( - const grid_map::GridMap & in_gridmap, - const rclcpp::Publisher::SharedPtr in_publisher, - const std::string & in_layer, double in_min_value, double in_max_value, double in_height); - /*! * Projects the in_area_points forming the road, stores the result in out_grid_map. * @param[out] out_grid_map GridMap object to add the road grid diff --git a/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp index 4ce452814008c..f719f7a81cbf2 100644 --- a/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp +++ b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp @@ -37,25 +37,6 @@ namespace object_map { -void PublishGridMap( - const grid_map::GridMap & in_gridmap, - const rclcpp::Publisher::SharedPtr in_publisher) -{ - auto message = grid_map::GridMapRosConverter::toMessage(in_gridmap); - in_publisher->publish(*message); -} - -void PublishOccupancyGrid( - const grid_map::GridMap & in_gridmap, - const rclcpp::Publisher::SharedPtr in_publisher, - const std::string & in_layer, double in_min_value, double in_max_value, double in_height) -{ - nav_msgs::msg::OccupancyGrid message; - grid_map::GridMapRosConverter::toOccupancyGrid( - in_gridmap, in_layer, in_min_value, in_max_value, message); - message.info.origin.position.z = in_height; - in_publisher->publish(message); -} void FillPolygonAreas( grid_map::GridMap & out_grid_map, From d6610284d08b9f2a42a01fba9538ab5abeaee074 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 28 Aug 2024 01:02:09 +0900 Subject: [PATCH 035/217] fix(autoware_planning_validator): fix unusedFunction (#8646) fix:unusedFunction Signed-off-by: kobayu858 --- .../include/autoware/planning_validator/utils.hpp | 4 ---- planning/autoware_planning_validator/src/utils.cpp | 14 -------------- 2 files changed, 18 deletions(-) diff --git a/planning/autoware_planning_validator/include/autoware/planning_validator/utils.hpp b/planning/autoware_planning_validator/include/autoware/planning_validator/utils.hpp index 04cfed07a1671..7d8aca14aff77 100644 --- a/planning/autoware_planning_validator/include/autoware/planning_validator/utils.hpp +++ b/planning/autoware_planning_validator/include/autoware/planning_validator/utils.hpp @@ -28,10 +28,6 @@ namespace autoware::planning_validator using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -std::pair getMaxValAndIdx(const std::vector & v); - -std::pair getMinValAndIdx(const std::vector & v); - std::pair getAbsMaxValAndIdx(const std::vector & v); Trajectory resampleTrajectory(const Trajectory & trajectory, const double min_interval); diff --git a/planning/autoware_planning_validator/src/utils.cpp b/planning/autoware_planning_validator/src/utils.cpp index ae580a7a7c6f1..0a70b4d415dcb 100644 --- a/planning/autoware_planning_validator/src/utils.cpp +++ b/planning/autoware_planning_validator/src/utils.cpp @@ -46,20 +46,6 @@ void takeSmaller(double & v_min, size_t & i_min, double v, size_t i) } } // namespace -std::pair getMaxValAndIdx(const std::vector & v) -{ - const auto iter = std::max_element(v.begin(), v.end()); - const auto idx = std::distance(v.begin(), iter); - return {*iter, idx}; -} - -std::pair getMinValAndIdx(const std::vector & v) -{ - const auto iter = std::min_element(v.begin(), v.end()); - const auto idx = std::distance(v.begin(), iter); - return {*iter, idx}; -} - std::pair getAbsMaxValAndIdx(const std::vector & v) { const auto iter = std::max_element( From 2f4a26a328c256f36aedc9016bd9f26e8c7f9893 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 28 Aug 2024 10:12:25 +0900 Subject: [PATCH 036/217] fix(autoware_path_optimizer): fix unusedFunction (#8644) fix:unusedFunction Signed-off-by: kobayu858 --- .../path_optimizer/utils/trajectory_utils.hpp | 4 ---- .../src/utils/trajectory_utils.cpp | 23 ------------------- 2 files changed, 27 deletions(-) diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/trajectory_utils.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/trajectory_utils.hpp index 3cacdc2e1ecaf..c9900d2ce8225 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/trajectory_utils.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/trajectory_utils.hpp @@ -132,10 +132,6 @@ std::vector convertToReferencePoints( std::vector sanitizePoints(const std::vector & points); -void compensateLastPose( - const PathPoint & last_path_point, std::vector & traj_points, - const double delta_dist_threshold, const double delta_yaw_threshold); - geometry_msgs::msg::Point getNearestPosition( const std::vector & points, const int target_idx, const double offset); diff --git a/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp b/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp index 8e15cdb852893..bcfc7e53ee67d 100644 --- a/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp +++ b/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp @@ -97,29 +97,6 @@ std::vector sanitizePoints(const std::vector & p return output; } -void compensateLastPose( - const PathPoint & last_path_point, std::vector & traj_points, - const double delta_dist_threshold, const double delta_yaw_threshold) -{ - if (traj_points.empty()) { - traj_points.push_back(convertToTrajectoryPoint(last_path_point)); - return; - } - - const geometry_msgs::msg::Pose last_traj_pose = traj_points.back().pose; - - const double dist = autoware::universe_utils::calcDistance2d( - last_path_point.pose.position, last_traj_pose.position); - const double norm_diff_yaw = [&]() { - const double diff_yaw = - tf2::getYaw(last_path_point.pose.orientation) - tf2::getYaw(last_traj_pose.orientation); - return autoware::universe_utils::normalizeRadian(diff_yaw); - }(); - if (dist > delta_dist_threshold || std::fabs(norm_diff_yaw) > delta_yaw_threshold) { - traj_points.push_back(convertToTrajectoryPoint(last_path_point)); - } -} - geometry_msgs::msg::Point getNearestPosition( const std::vector & points, const int target_idx, const double offset) { From 93237800734bfcfa236564252a26fb6760c37e7d Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 28 Aug 2024 13:23:40 +0900 Subject: [PATCH 037/217] fix(autoware_static_centerline_generator): fix unusedFunction (#8647) * fix:unusedFunction Signed-off-by: kobayu858 * fix:unusedFunction Signed-off-by: kobayu858 * fix:compile error Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/static_centerline_generator_node.cpp | 121 ------------------ .../src/static_centerline_generator_node.hpp | 1 - .../src/utils.cpp | 23 ---- .../src/utils.hpp | 2 - 4 files changed, 147 deletions(-) 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 index e9958b74059a5..5e2ddc6579bf3 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -177,20 +177,6 @@ std::vector resample_trajectory_points( return autoware::motion_utils::convertToTrajectoryPointArray(resampled_input_traj); } -bool arePointsClose( - const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, const double epsilon) -{ - return std::abs(p1.x - p2.x) < epsilon && std::abs(p1.y - p2.y) < epsilon; -} - -bool areSameDirection( - const double yaw, const geometry_msgs::msg::Point & start_point, - const geometry_msgs::msg::Point & end_point) -{ - return autoware::universe_utils::normalizeRadian( - yaw - std::atan2(end_point.y - start_point.y, end_point.x - start_point.x)) < M_PI_2; -} - std::vector convertToGeometryPoints(const LineString2d & lanelet_points) { std::vector points; @@ -597,115 +583,8 @@ void StaticCenterlineGeneratorNode::on_plan_path( response->message = ""; } -RoadBounds StaticCenterlineGeneratorNode::update_road_boundary( - const std::vector & centerline) -{ - const double max_ego_lon_offset = vehicle_info_.front_overhang_m + vehicle_info_.wheel_base_m; - const double min_ego_lon_offset = -vehicle_info_.rear_overhang_m; - const double max_ego_lat_offset = - vehicle_info_.wheel_tread_m / 2.0 + vehicle_info_.left_overhang_m; - const double ego_lat_offset = max_ego_lat_offset + footprint_margin_for_road_bound_; - - std::vector ego_left_bound; - std::vector ego_right_bound; - for (size_t i = 0; i < centerline.size(); ++i) { - const auto & centerline_point = centerline.at(i).pose; - if (i == 0) { - // Add the first bound point - ego_left_bound.push_back(autoware::universe_utils::calcOffsetPose( - centerline_point, min_ego_lon_offset, ego_lat_offset, 0.0) - .position); - ego_right_bound.push_back(autoware::universe_utils::calcOffsetPose( - centerline_point, min_ego_lon_offset, -ego_lat_offset, 0.0) - .position); - } - - if (i == centerline.size() - 1) { - // Add the last bound point - const auto ego_left_bound_last_point = - autoware::universe_utils::calcOffsetPose( - centerline_point, max_ego_lon_offset, ego_lat_offset, 0.0) - .position; - if (!arePointsClose(ego_left_bound.back(), ego_left_bound_last_point, 1e-6)) { - ego_left_bound.push_back(ego_left_bound_last_point); - } - const auto ego_right_bound_last_point = - autoware::universe_utils::calcOffsetPose( - centerline_point, max_ego_lon_offset, -ego_lat_offset, 0.0) - .position; - if (!arePointsClose(ego_right_bound.back(), ego_right_bound_last_point, 1e-6)) { - ego_right_bound.push_back(ego_right_bound_last_point); - } - } else { - // Calculate new bound point depending on the orientation - const auto & next_centerline_point = centerline.at(i + 1).pose; - const double diff_yaw = autoware::universe_utils::normalizeRadian( - tf2::getYaw(next_centerline_point.orientation) - tf2::getYaw(centerline_point.orientation)); - const auto [ego_left_bound_new_point, ego_right_bound_new_point] = [&]() { - if (0 < diff_yaw) { - return std::make_pair( - autoware::universe_utils::calcOffsetPose(centerline_point, 0.0, ego_lat_offset, 0.0) - .position, - autoware::universe_utils::calcOffsetPose( - centerline_point, max_ego_lon_offset, -ego_lat_offset, 0.0) - .position); - } - return std::make_pair( - autoware::universe_utils::calcOffsetPose( - centerline_point, max_ego_lon_offset, ego_lat_offset, 0.0) - .position, - autoware::universe_utils::calcOffsetPose(centerline_point, 0.0, -ego_lat_offset, 0.0) - .position); - }(); - - // Check if the bound will be longitudinally monotonic. - if (areSameDirection( - tf2::getYaw(centerline_point.orientation), ego_left_bound.back(), - ego_left_bound_new_point)) { - ego_left_bound.push_back(ego_left_bound_new_point); - } - if (areSameDirection( - tf2::getYaw(centerline_point.orientation), ego_right_bound.back(), - ego_right_bound_new_point)) { - ego_right_bound.push_back(ego_right_bound_new_point); - } - } - } - - // Publish marker - MarkerArray ego_footprint_bounds_marker_array; - { - auto left_bound_marker = autoware::universe_utils::createDefaultMarker( - "map", now(), "road_bounds", 0, Marker::LINE_STRIP, - autoware::universe_utils::createMarkerScale(0.05, 0.0, 0.0), - autoware::universe_utils::createMarkerColor(1.0, 0.5, 0.7, 0.8)); - left_bound_marker.lifetime = rclcpp::Duration(0, 0); - for (const auto & ego_left_bound_point : ego_left_bound) { - left_bound_marker.points.push_back(ego_left_bound_point); - } - ego_footprint_bounds_marker_array.markers.push_back(left_bound_marker); - } - { - auto right_bound_marker = autoware::universe_utils::createDefaultMarker( - "map", now(), "road_bounds", 1, Marker::LINE_STRIP, - autoware::universe_utils::createMarkerScale(0.05, 0.0, 0.0), - autoware::universe_utils::createMarkerColor(1.0, 0.5, 0.7, 0.8)); - right_bound_marker.lifetime = rclcpp::Duration(0, 0); - for (const auto & ego_right_bound_point : ego_right_bound) { - right_bound_marker.points.push_back(ego_right_bound_point); - } - ego_footprint_bounds_marker_array.markers.push_back(right_bound_marker); - } - pub_debug_ego_footprint_bounds_->publish(ego_footprint_bounds_marker_array); - - return RoadBounds{ego_left_bound, ego_right_bound}; -} - void StaticCenterlineGeneratorNode::validate() { - // const auto selected_centerline = centerline_handler_.get_selected_centerline(); - // const auto road_bounds = update_road_boundary(selected_centerline); - std::cerr << std::endl << "############################################## Validation Results " "##############################################" 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 index fd2314d42e46f..17abb3e446994 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp @@ -132,7 +132,6 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response); void visualize_selected_centerline(); - RoadBounds update_road_boundary(const std::vector & centerline); // parameter template diff --git a/planning/autoware_static_centerline_generator/src/utils.cpp b/planning/autoware_static_centerline_generator/src/utils.cpp index 1a8e0eae2fbd9..c045a50fec0d7 100644 --- a/planning/autoware_static_centerline_generator/src/utils.cpp +++ b/planning/autoware_static_centerline_generator/src/utils.cpp @@ -256,28 +256,5 @@ MarkerArray create_delete_all_marker_array( return marker_array; } -std::pair, std::vector> -calcBoundsFromLanelets(const lanelet::ConstLanelets lanelets) -{ - std::vector left_bound; - std::vector right_bound; - for (const auto & lanelet : lanelets) { - for (const auto & lanelet_left_bound_point : lanelet.leftBound()) { - geometry_msgs::msg::Point left_bound_point; - left_bound_point.x = lanelet_left_bound_point.x(); - left_bound_point.y = lanelet_left_bound_point.y(); - left_bound_point.z = lanelet_left_bound_point.z(); - left_bound.push_back(left_bound_point); - } - for (const auto & lanelet_right_bound_point : lanelet.rightBound()) { - geometry_msgs::msg::Point right_bound_point; - right_bound_point.x = lanelet_right_bound_point.x(); - right_bound_point.y = lanelet_right_bound_point.y(); - right_bound_point.z = lanelet_right_bound_point.z(); - right_bound.push_back(right_bound_point); - } - } - return std::make_pair(left_bound, right_bound); -} } // 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 index be60f6249e93f..f4d15d3dcfd4f 100644 --- a/planning/autoware_static_centerline_generator/src/utils.hpp +++ b/planning/autoware_static_centerline_generator/src/utils.hpp @@ -61,8 +61,6 @@ Marker create_points_marker( MarkerArray create_delete_all_marker_array( const std::vector & ns_vec, const rclcpp::Time & now); -std::pair, std::vector> -calcBoundsFromLanelets(const lanelet::ConstLanelets lanelets); } // namespace utils } // namespace autoware::static_centerline_generator From bda870618b97e78b278a0910576145ba84b402d6 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 28 Aug 2024 13:24:03 +0900 Subject: [PATCH 038/217] fix(tier4_state_rviz_plugin): fix unusedFunction (#8608) * fix:unusedFunction Signed-off-by: kobayu858 * fix:clang format Signed-off-by: kobayu858 * fix:revert custom button Signed-off-by: kobayu858 * fix:revert custom container Signed-off-by: kobayu858 * fix:revert custom icon label Signed-off-by: kobayu858 * fix:revert custom label Signed-off-by: kobayu858 * fix:revert custom segment button Signed-off-by: kobayu858 * fix:revert custom slider Signed-off-by: kobayu858 * fix:revert custom toggle switch Signed-off-by: kobayu858 * fix:revert custom label Signed-off-by: kobayu858 * fix:add blank line Signed-off-by: kobayu858 * fix:revert custom botton item Signed-off-by: kobayu858 * fix:remove declaration Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/custom_button.cpp | 3 +++ .../src/custom_container.cpp | 13 ++----------- .../src/custom_icon_label.cpp | 2 ++ .../tier4_state_rviz_plugin/src/custom_label.cpp | 2 ++ .../src/custom_segmented_button.cpp | 3 +++ .../src/custom_segmented_button_item.cpp | 16 +++++----------- .../src/custom_slider.cpp | 1 + .../src/custom_toggle_switch.cpp | 1 + .../src/include/custom_container.hpp | 2 -- .../src/include/custom_segmented_button_item.hpp | 3 --- 10 files changed, 19 insertions(+), 27 deletions(-) diff --git a/common/tier4_state_rviz_plugin/src/custom_button.cpp b/common/tier4_state_rviz_plugin/src/custom_button.cpp index 0ef2628577135..26d9d699038d8 100644 --- a/common/tier4_state_rviz_plugin/src/custom_button.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_button.cpp @@ -53,11 +53,13 @@ QSize CustomElevatedButton::sizeHint() const return QSize(width, height); } +// cppcheck-suppress unusedFunction QSize CustomElevatedButton::minimumSizeHint() const { return sizeHint(); } +// cppcheck-suppress unusedFunction void CustomElevatedButton::updateStyle( const QString & text, const QColor & bgColor, const QColor & textColor, const QColor & hoverColor, const QColor & disabledBgColor, const QColor & disabledTextColor) @@ -71,6 +73,7 @@ void CustomElevatedButton::updateStyle( update(); // Force repaint } +// cppcheck-suppress unusedFunction void CustomElevatedButton::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_container.cpp b/common/tier4_state_rviz_plugin/src/custom_container.cpp index 0b0aa1ccd6ed5..c82ca685ca9ba 100644 --- a/common/tier4_state_rviz_plugin/src/custom_container.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_container.cpp @@ -26,17 +26,7 @@ CustomContainer::CustomContainer(QWidget * parent) : QFrame(parent), cornerRadiu setLayout(layout); } -void CustomContainer::setCornerRadius(int radius) -{ - cornerRadius = radius; - update(); -} - -int CustomContainer::getCornerRadius() const -{ - return cornerRadius; -} - +// cppcheck-suppress unusedFunction QGridLayout * CustomContainer::getLayout() const { return layout; // Provide access to the layout @@ -50,6 +40,7 @@ QSize CustomContainer::sizeHint() const return QSize(width, height); } +// cppcheck-suppress unusedFunction QSize CustomContainer::minimumSizeHint() const { return sizeHint(); diff --git a/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp b/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp index 6e4d32d40f7fb..28458d7c79d71 100644 --- a/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp @@ -50,11 +50,13 @@ QSize CustomIconLabel::sizeHint() const return QSize(size, size); } +// cppcheck-suppress unusedFunction QSize CustomIconLabel::minimumSizeHint() const { return sizeHint(); } +// cppcheck-suppress unusedFunction void CustomIconLabel::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_label.cpp b/common/tier4_state_rviz_plugin/src/custom_label.cpp index 1f96fc0d45095..59df84138b890 100644 --- a/common/tier4_state_rviz_plugin/src/custom_label.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_label.cpp @@ -46,11 +46,13 @@ QSize CustomLabel::sizeHint() const return QSize(width, height); } +// cppcheck-suppress unusedFunction QSize CustomLabel::minimumSizeHint() const { return sizeHint(); } +// cppcheck-suppress unusedFunction void CustomLabel::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp b/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp index 8063bdc0fbc28..3f93df006415e 100644 --- a/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp @@ -40,6 +40,7 @@ CustomSegmentedButtonItem * CustomSegmentedButton::addButton(const QString & tex return button; } +// cppcheck-suppress unusedFunction QButtonGroup * CustomSegmentedButton::getButtonGroup() const { return buttonGroup; @@ -54,11 +55,13 @@ QSize CustomSegmentedButton::sizeHint() const // layout->itemAt(0)->widget()->height() + 10); } +// cppcheck-suppress unusedFunction QSize CustomSegmentedButton::minimumSizeHint() const { return sizeHint(); } +// cppcheck-suppress unusedFunction void CustomSegmentedButton::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp b/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp index f2d15260c4e41..3c671c988f936 100644 --- a/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp @@ -32,17 +32,6 @@ CustomSegmentedButtonItem::CustomSegmentedButtonItem(const QString & text, QWidg setCursor(Qt::PointingHandCursor); } -void CustomSegmentedButtonItem::setColors( - const QColor & bg, const QColor & checkedBg, const QColor & activeText, - const QColor & inactiveText) -{ - bgColor = bg; - checkedBgColor = checkedBg; - activeTextColor = activeText; - inactiveTextColor = inactiveText; - update(); -} - // void CustomSegmentedButtonItem::updateSize() // { // QFontMetrics fm(font()); @@ -51,12 +40,14 @@ void CustomSegmentedButtonItem::setColors( // setFixedSize(width, height); // } +// cppcheck-suppress unusedFunction void CustomSegmentedButtonItem::setHovered(bool hovered) { isHovered = hovered; updateCheckableState(); } +// cppcheck-suppress unusedFunction void CustomSegmentedButtonItem::setCheckableButton(bool checkable) { setCheckable(checkable); @@ -71,18 +62,21 @@ void CustomSegmentedButtonItem::updateCheckableState() update(); } +// cppcheck-suppress unusedFunction void CustomSegmentedButtonItem::setDisabledButton(bool disabled) { isDisabled = disabled; updateCheckableState(); } +// cppcheck-suppress unusedFunction void CustomSegmentedButtonItem::setActivated(bool activated) { isActivated = activated; update(); } +// cppcheck-suppress unusedFunction void CustomSegmentedButtonItem::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_slider.cpp b/common/tier4_state_rviz_plugin/src/custom_slider.cpp index cf3f7c3d4638f..16dfda19a87bf 100644 --- a/common/tier4_state_rviz_plugin/src/custom_slider.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_slider.cpp @@ -19,6 +19,7 @@ CustomSlider::CustomSlider(Qt::Orientation orientation, QWidget * parent) setMinimumHeight(40); // Ensure there's enough space for the custom track } +// cppcheck-suppress unusedFunction void CustomSlider::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp b/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp index 3b58ded626439..b171fa554cd01 100644 --- a/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp @@ -30,6 +30,7 @@ QSize CustomToggleSwitch::sizeHint() const return QSize(50, 30); // Preferred size of the toggle switch } +// cppcheck-suppress unusedFunction void CustomToggleSwitch::paintEvent(QPaintEvent *) { QPainter p(this); diff --git a/common/tier4_state_rviz_plugin/src/include/custom_container.hpp b/common/tier4_state_rviz_plugin/src/include/custom_container.hpp index 5142b409ebc88..ef81ef2417d52 100644 --- a/common/tier4_state_rviz_plugin/src/include/custom_container.hpp +++ b/common/tier4_state_rviz_plugin/src/include/custom_container.hpp @@ -31,12 +31,10 @@ class CustomContainer : public QFrame // Methods to set dimensions and corner radius void setContainerHeight(int height); void setContainerWidth(int width); - void setCornerRadius(int radius); // Getters int getContainerHeight() const; int getContainerWidth() const; - int getCornerRadius() const; QGridLayout * getLayout() const; // Add a method to access the layout protected: diff --git a/common/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp b/common/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp index 33eb9fe16aa31..ee6f48e285975 100644 --- a/common/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp +++ b/common/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp @@ -30,9 +30,6 @@ class CustomSegmentedButtonItem : public QPushButton public: explicit CustomSegmentedButtonItem(const QString & text, QWidget * parent = nullptr); - void setColors( - const QColor & bg, const QColor & checkedBg, const QColor & activeText, - const QColor & inactiveText); void setActivated(bool activated); void setCheckableButton(bool checkable); void setDisabledButton(bool disabled); From 75706db18fe2f83c5c138d77269fa90b6467f37b Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Wed, 28 Aug 2024 16:53:34 +0900 Subject: [PATCH 039/217] refactor(start_planner): remove redundant calculation in shift pull out (#8623) * fix redundant calculation Signed-off-by: Go Sakayori * fix unneccesary modification for comment Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- .../src/shift_pull_out.cpp | 65 ++++++++++--------- 1 file changed, 33 insertions(+), 32 deletions(-) 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 2b63ff6df0db2..712b8c3ce265d 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 @@ -61,6 +61,8 @@ std::optional ShiftPullOut::plan( return std::nullopt; } + const auto lanelet_map_ptr = planner_data_->route_handler->getLaneletMapPtr(); + // get safe path for (auto & pull_out_path : pull_out_paths) { universe_utils::ScopedTimeTrack st("get safe path", *time_keeper_); @@ -79,8 +81,6 @@ std::optional ShiftPullOut::plan( shift_path.points.begin() + pull_out_end_idx + 1); } - const auto lanelet_map_ptr = planner_data_->route_handler->getLaneletMapPtr(); - // if lane departure check override is true, and if the initial pose is not fully within a lane, // cancel lane departure check const bool is_lane_departure_check_required = std::invoke([&]() -> bool { @@ -269,26 +269,38 @@ std::vector ShiftPullOut::calcPullOutPaths( }); bool has_non_shifted_path = false; + + // if shift length is too short, add non sifted path + constexpr double MINIMUM_SHIFT_LENGTH = 0.01; + const double shift_length = arc_position_start.distance; + const bool is_smaller_than_minimum = std::abs(shift_length) < MINIMUM_SHIFT_LENGTH; + + if (is_smaller_than_minimum) { + candidate_paths.push_back(non_shifted_path); + has_non_shifted_path = true; + } + + // calculate pull out distance, longitudinal acc, terminal velocity + const size_t shift_start_idx = + findNearestIndex(road_lane_reference_path.points, start_pose.position); + const double road_velocity = + road_lane_reference_path.points.at(shift_start_idx).point.longitudinal_velocity_mps; + + // clip from ego pose + PathWithLaneId road_lane_reference_path_from_ego = road_lane_reference_path; + road_lane_reference_path_from_ego.points.erase( + road_lane_reference_path_from_ego.points.begin(), + road_lane_reference_path_from_ego.points.begin() + shift_start_idx); + + const auto curvatures_and_segment_lengths = + autoware::motion_utils::calcCurvatureAndSegmentLength(road_lane_reference_path_from_ego.points); + for (double lateral_acc = minimum_lateral_acc; lateral_acc <= maximum_lateral_acc; lateral_acc += acc_resolution) { PathShifter path_shifter{}; path_shifter.setPath(road_lane_reference_path); - // if shift length is too short, add non sifted path - constexpr double MINIMUM_SHIFT_LENGTH = 0.01; - const double shift_length = getArcCoordinates(road_lanes, start_pose).distance; - if (std::abs(shift_length) < MINIMUM_SHIFT_LENGTH && !has_non_shifted_path) { - candidate_paths.push_back(non_shifted_path); - has_non_shifted_path = true; - continue; - } - - // calculate pull out distance, longitudinal acc, terminal velocity - const size_t shift_start_idx = - findNearestIndex(road_lane_reference_path.points, start_pose.position); - const double road_velocity = - road_lane_reference_path.points.at(shift_start_idx).point.longitudinal_velocity_mps; const double shift_time = PathShifter::calcShiftTimeFromJerk(shift_length, lateral_jerk, lateral_acc); const double longitudinal_acc = std::clamp(road_velocity / shift_time, 0.0, /* max acc */ 1.0); @@ -297,17 +309,12 @@ std::vector ShiftPullOut::calcPullOutPaths( minimum_shift_pull_out_distance); const double terminal_velocity = longitudinal_acc * shift_time; - // clip from ego pose - PathWithLaneId road_lane_reference_path_from_ego = road_lane_reference_path; - road_lane_reference_path_from_ego.points.erase( - road_lane_reference_path_from_ego.points.begin(), - road_lane_reference_path_from_ego.points.begin() + shift_start_idx); // before means distance on road lane // Note: the pull_out_distance is the required distance on the shifted path. Now we need to - // calculate the distance on the center line used for the shift path generation. However, since - // the calcBeforeShiftedArcLength is an approximate conversion from center line to center line - // (not shift path to centerline), the conversion result may too long or short. To prevent too - // short length, take maximum with the original distance. + // calculate the distance on the center line used for the shift path_shifter generation. + // However, since the calcBeforeShiftedArcLength is an approximate conversion from center line + // to center line (not shift path to centerline), the conversion result may too long or short. + // To prevent too short length, take maximum with the original distance. // TODO(kosuke55): update the conversion function and get rid of the comparison with original // distance. const double pull_out_distance_converted = std::max( @@ -326,10 +333,6 @@ std::vector ShiftPullOut::calcPullOutPaths( double pull_out_distance = pull_out_distance_converted; double min_curvature_after_distance_converted = std::numeric_limits::max(); - const auto curvatures_and_segment_lengths = - autoware::motion_utils::calcCurvatureAndSegmentLength( - road_lane_reference_path_from_ego.points); - const auto update_arc_length = [&](size_t i, const auto & segment_length) { arc_length += (i == curvatures_and_segment_lengths.size() - 1) ? segment_length.first + segment_length.second @@ -374,9 +377,7 @@ std::vector ShiftPullOut::calcPullOutPaths( // get shift end pose const auto shift_end_pose_ptr = std::invoke([&]() { - const auto arc_position_shift_start = - lanelet::utils::getArcCoordinates(road_lanes, start_pose); - const double s_start = arc_position_shift_start.length + before_shifted_pull_out_distance; + const double s_start = arc_position_start.length + before_shifted_pull_out_distance; const double s_end = s_start + std::numeric_limits::epsilon(); const auto path = route_handler.getCenterLinePath(road_lanes, s_start, s_end, true); return path.points.empty() From e5ac1a55a431adc9cf60ac549eb2b1927ff5e475 Mon Sep 17 00:00:00 2001 From: Giovanni Muhammad Raditya Date: Wed, 28 Aug 2024 17:15:29 +0900 Subject: [PATCH 040/217] feat(universe_utils): add SAT implementation for 2D convex polygon collision check (#8239) --- common/autoware_universe_utils/CMakeLists.txt | 1 + .../universe_utils/geometry/sat_2d.hpp | 30 +++++++ .../src/geometry/sat_2d.cpp | 80 +++++++++++++++++++ .../test/src/geometry/test_geometry.cpp | 56 ++++++++++--- 4 files changed, 158 insertions(+), 9 deletions(-) create mode 100644 common/autoware_universe_utils/include/autoware/universe_utils/geometry/sat_2d.hpp create mode 100644 common/autoware_universe_utils/src/geometry/sat_2d.cpp diff --git a/common/autoware_universe_utils/CMakeLists.txt b/common/autoware_universe_utils/CMakeLists.txt index 526ffd8dcc83a..5ffd313b7e03b 100644 --- a/common/autoware_universe_utils/CMakeLists.txt +++ b/common/autoware_universe_utils/CMakeLists.txt @@ -16,6 +16,7 @@ ament_auto_add_library(autoware_universe_utils SHARED src/geometry/boost_polygon_utils.cpp src/geometry/random_convex_polygon.cpp src/geometry/gjk_2d.cpp + src/geometry/sat_2d.cpp src/math/sin_table.cpp src/math/trigonometry.cpp src/ros/msg_operation.cpp diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/sat_2d.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/sat_2d.hpp new file mode 100644 index 0000000000000..c79322f554fe3 --- /dev/null +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/sat_2d.hpp @@ -0,0 +1,30 @@ +// 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__UNIVERSE_UTILS__GEOMETRY__SAT_2D_HPP_ +#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__SAT_2D_HPP_ + +#include "autoware/universe_utils/geometry/boost_geometry.hpp" + +namespace autoware::universe_utils::sat +{ +/** + * @brief Check if 2 convex polygons intersect using the SAT algorithm + * @details faster than boost::geometry::overlap() but speed decline sharply as vertices increase + */ +bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); + +} // namespace autoware::universe_utils::sat + +#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__SAT_2D_HPP_ diff --git a/common/autoware_universe_utils/src/geometry/sat_2d.cpp b/common/autoware_universe_utils/src/geometry/sat_2d.cpp new file mode 100644 index 0000000000000..eae1de39bb589 --- /dev/null +++ b/common/autoware_universe_utils/src/geometry/sat_2d.cpp @@ -0,0 +1,80 @@ +// 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/universe_utils/geometry/sat_2d.hpp" + +namespace autoware::universe_utils::sat +{ + +namespace +{ +/// @brief calculate the edge normal of two points +Point2d edge_normal(const Point2d & p1, const Point2d & p2) +{ + return {p2.y() - p1.y(), p1.x() - p2.x()}; +} + +/// @brief project a polygon onto an axis and return the minimum and maximum values +std::pair project_polygon(const Polygon2d & poly, const Point2d & axis) +{ + double min = poly.outer()[0].dot(axis); + double max = min; + for (const auto & point : poly.outer()) { + double projection = point.dot(axis); + if (projection < min) { + min = projection; + } + if (projection > max) { + max = projection; + } + } + return {min, max}; +} + +/// @brief check if two projections overlap +bool projections_overlap( + const std::pair & proj1, const std::pair & proj2) +{ + return proj1.second >= proj2.first && proj2.second >= proj1.first; +} + +/// @brief check is all edges of a polygon can be separated from the other polygon with a separating +/// axis +bool has_no_separating_axis(const Polygon2d & polygon, const Polygon2d & other) +{ + for (size_t i = 0; i < polygon.outer().size(); ++i) { + const size_t next_i = (i + 1) % polygon.outer().size(); + const Point2d edge = edge_normal(polygon.outer()[i], polygon.outer()[next_i]); + const auto projection1 = project_polygon(polygon, edge); + const auto projection2 = project_polygon(other, edge); + if (!projections_overlap(projection1, projection2)) { + return false; + } + } + return true; +} +} // namespace + +/// @brief check if two convex polygons intersect using the SAT algorithm +/// @details this function uses the Separating Axis Theorem (SAT) to determine if two convex +/// polygons intersect. If projections overlap on all tested axes, the function returns `true`; +/// otherwise, it returns `false`. Note that touching polygons (e.g., at a point or along an edge) +/// will be considered as not intersecting. +bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2) +{ + return has_no_separating_axis(convex_polygon1, convex_polygon2) && + has_no_separating_axis(convex_polygon2, convex_polygon1); +} + +} // namespace autoware::universe_utils::sat diff --git a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp index f36ea8d169e4a..55d70307f1314 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp @@ -15,6 +15,7 @@ #include "autoware/universe_utils/geometry/boost_geometry.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/geometry/random_convex_polygon.hpp" +#include "autoware/universe_utils/geometry/sat_2d.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" #include "autoware/universe_utils/system/stop_watch.hpp" @@ -1840,7 +1841,10 @@ TEST(geometry, intersect) } } -TEST(geometry, intersectPolygon) +TEST( + geometry, + DISABLED_intersectPolygon) // GJK give different result for edge test (point sharing and edge + // sharing) compared to SAT and boost::geometry::intersect { { // 2 triangles with intersection autoware::universe_utils::Polygon2d poly1; @@ -1854,6 +1858,7 @@ TEST(geometry, intersectPolygon) boost::geometry::correct(poly1); boost::geometry::correct(poly2); EXPECT_TRUE(autoware::universe_utils::intersects_convex(poly1, poly2)); + EXPECT_TRUE(autoware::universe_utils::sat::intersects(poly1, poly2)); } { // 2 triangles with no intersection (but they share an edge) autoware::universe_utils::Polygon2d poly1; @@ -1867,6 +1872,7 @@ TEST(geometry, intersectPolygon) boost::geometry::correct(poly1); boost::geometry::correct(poly2); EXPECT_FALSE(autoware::universe_utils::intersects_convex(poly1, poly2)); + EXPECT_FALSE(autoware::universe_utils::sat::intersects(poly1, poly2)); } { // 2 triangles with no intersection (but they share a point) autoware::universe_utils::Polygon2d poly1; @@ -1880,6 +1886,7 @@ TEST(geometry, intersectPolygon) boost::geometry::correct(poly1); boost::geometry::correct(poly2); EXPECT_FALSE(autoware::universe_utils::intersects_convex(poly1, poly2)); + EXPECT_FALSE(autoware::universe_utils::sat::intersects(poly1, poly2)); } { // 2 triangles sharing a point and then with very small intersection autoware::universe_utils::Polygon2d poly1; @@ -1895,6 +1902,7 @@ TEST(geometry, intersectPolygon) EXPECT_FALSE(autoware::universe_utils::intersects_convex(poly1, poly2)); poly1.outer()[1].y() += 1e-12; EXPECT_TRUE(autoware::universe_utils::intersects_convex(poly1, poly2)); + EXPECT_TRUE(autoware::universe_utils::sat::intersects(poly1, poly2)); } { // 2 triangles with no intersection and no touching autoware::universe_utils::Polygon2d poly1; @@ -1908,6 +1916,7 @@ TEST(geometry, intersectPolygon) boost::geometry::correct(poly1); boost::geometry::correct(poly2); EXPECT_FALSE(autoware::universe_utils::intersects_convex(poly1, poly2)); + EXPECT_FALSE(autoware::universe_utils::sat::intersects(poly1, poly2)); } { // triangle and quadrilateral with intersection autoware::universe_utils::Polygon2d poly1; @@ -1922,6 +1931,7 @@ TEST(geometry, intersectPolygon) boost::geometry::correct(poly1); boost::geometry::correct(poly2); EXPECT_TRUE(autoware::universe_utils::intersects_convex(poly1, poly2)); + EXPECT_TRUE(autoware::universe_utils::sat::intersects(poly1, poly2)); } } @@ -1933,16 +1943,21 @@ TEST(geometry, intersectPolygonRand) constexpr auto max_values = 1000; autoware::universe_utils::StopWatch sw; + for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { double ground_truth_intersect_ns = 0.0; double ground_truth_no_intersect_ns = 0.0; double gjk_intersect_ns = 0.0; double gjk_no_intersect_ns = 0.0; + double sat_intersect_ns = 0.0; + double sat_no_intersect_ns = 0.0; int intersect_count = 0; polygons.clear(); + for (auto i = 0; i < polygons_nb; ++i) { polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); } + for (auto i = 0UL; i < polygons.size(); ++i) { for (auto j = 0UL; j < polygons.size(); ++j) { sw.tic(); @@ -1953,6 +1968,7 @@ TEST(geometry, intersectPolygonRand) } else { ground_truth_no_intersect_ns += sw.toc(); } + sw.tic(); const auto gjk = autoware::universe_utils::intersects_convex(polygons[i], polygons[j]); if (gjk) { @@ -1960,27 +1976,49 @@ TEST(geometry, intersectPolygonRand) } else { gjk_no_intersect_ns += sw.toc(); } + + sw.tic(); + const auto sat = autoware::universe_utils::sat::intersects(polygons[i], polygons[j]); + if (sat) { + sat_intersect_ns += sw.toc(); + } else { + sat_no_intersect_ns += sw.toc(); + } + + EXPECT_EQ(ground_truth, gjk); + EXPECT_EQ(ground_truth, sat); + if (ground_truth != gjk) { - std::cout << "Failed for the 2 polygons: "; + std::cout << "Failed for the 2 polygons with GJK: "; + std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j]) + << std::endl; + } + + if (ground_truth != sat) { + std::cout << "Failed for the 2 polygons with SAT: "; std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j]) << std::endl; } - EXPECT_EQ(ground_truth, gjk); } } + std::printf( "polygons_nb = %d, vertices = %ld, %d / %d pairs with intersects\n", polygons_nb, vertices, intersect_count, polygons_nb * polygons_nb); + std::printf( - "\tIntersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n", - ground_truth_intersect_ns / 1e6, gjk_intersect_ns / 1e6); + "\tIntersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n\t\tSAT = %2.2f ms\n", + ground_truth_intersect_ns / 1e6, gjk_intersect_ns / 1e6, sat_intersect_ns / 1e6); + std::printf( - "\tNo Intersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n", - ground_truth_no_intersect_ns / 1e6, gjk_no_intersect_ns / 1e6); + "\tNo Intersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n\t\tSAT = %2.2f ms\n", + ground_truth_no_intersect_ns / 1e6, gjk_no_intersect_ns / 1e6, sat_no_intersect_ns / 1e6); + std::printf( - "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n", + "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n\t\tSAT = %2.2f ms\n", (ground_truth_no_intersect_ns + ground_truth_intersect_ns) / 1e6, - (gjk_no_intersect_ns + gjk_intersect_ns) / 1e6); + (gjk_no_intersect_ns + gjk_intersect_ns) / 1e6, + (sat_no_intersect_ns + sat_intersect_ns) / 1e6); } } From 441bfcfe01a2f09f82810f4f741faff525ce6011 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 28 Aug 2024 17:16:21 +0900 Subject: [PATCH 041/217] fix(out_of_lane): fix noConstructor cppcheck warning (#8636) Signed-off-by: Maxime CLEMENT --- .../src/out_of_lane_module.hpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) 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 5225a6dd4abd9..fc0cd4ac539ca 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 @@ -30,6 +30,7 @@ #include #include +#include #include #include @@ -58,17 +59,17 @@ class OutOfLaneModule : public PluginModuleInterface out_of_lane::EgoData & ego_data, const PlannerData & planner_data, std::optional & previous_slowdown_pose_, const double slow_velocity); - out_of_lane::PlannerParam params_; + out_of_lane::PlannerParam params_{}; inline static const std::string ns_ = "out_of_lane"; - std::string module_name_; - rclcpp::Clock::SharedPtr clock_; - std::optional previous_slowdown_pose_; - rclcpp::Time previous_slowdown_time_; + std::string module_name_{"uninitialized"}; + rclcpp::Clock::SharedPtr clock_{nullptr}; + std::optional previous_slowdown_pose_{std::nullopt}; + rclcpp::Time previous_slowdown_time_{0}; protected: // Debug - mutable out_of_lane::DebugData debug_data_; + mutable out_of_lane::DebugData debug_data_{}; }; } // namespace autoware::motion_velocity_planner From a91af79f23ac27e9c436b18b1251821ed42db247 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 28 Aug 2024 17:17:14 +0900 Subject: [PATCH 042/217] fix(obstacle_velocity_limiter): more stable virtual wall (#8499) Signed-off-by: Maxime CLEMENT --- .../src/obstacle_velocity_limiter.cpp | 48 ++++++++----------- .../src/obstacle_velocity_limiter.hpp | 20 +------- .../src/obstacle_velocity_limiter_module.cpp | 11 +++-- .../src/obstacle_velocity_limiter_module.hpp | 11 ++--- .../src/parameters.hpp | 15 +++--- .../src/trajectory_preprocessing.cpp | 33 ++++++++----- .../src/trajectory_preprocessing.hpp | 17 +++---- .../src/node.cpp | 7 ++- 8 files changed, 72 insertions(+), 90 deletions(-) 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 945b94782023b..1f788a73a3f42 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 @@ -1,4 +1,4 @@ -// Copyright 2022 TIER IV, Inc. +// 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. @@ -27,15 +27,6 @@ namespace autoware::motion_velocity_planner::obstacle_velocity_limiter { -double calculateSafeVelocity( - const TrajectoryPoint & trajectory_point, const double dist_to_collision, - const double time_buffer, const double min_adjusted_velocity) -{ - return std::min( - static_cast(trajectory_point.longitudinal_velocity_mps), - std::max(min_adjusted_velocity, dist_to_collision / time_buffer)); -} - multi_polygon_t createPolygonMasks( const autoware_perception_msgs::msg::PredictedObjects & dynamic_obstacles, const double buffer, const double min_vel) @@ -123,15 +114,9 @@ std::vector calculate_slowd autoware::motion_utils::VirtualWalls & virtual_walls) { std::vector slowdown_intervals; - double time = 0.0; + size_t previous_slowdown_index = trajectory.size(); for (size_t i = 0; i < trajectory.size(); ++i) { auto & trajectory_point = trajectory[i]; - if (i > 0) { - const auto & prev_point = trajectory[i - 1]; - time += static_cast( - autoware::universe_utils::calcDistance2d(prev_point, trajectory_point) / - prev_point.longitudinal_velocity_mps); - } // First linestring is used to calculate distance if (projections[i].empty()) continue; projection_params.update(trajectory_point); @@ -139,20 +124,25 @@ std::vector calculate_slowd projections[i][0], footprints[i], collision_checker, projection_params); if (dist_to_collision) { const auto min_feasible_velocity = - velocity_params.current_ego_velocity - velocity_params.max_deceleration * time; - + velocity_params.current_ego_velocity - + velocity_params.max_deceleration * + rclcpp::Duration(trajectory_point.time_from_start).seconds(); + + const auto safe_velocity = std::max( + static_cast(*dist_to_collision - projection_params.extra_length) / + static_cast(projection_params.duration), + velocity_params.min_velocity); slowdown_intervals.emplace_back( trajectory_point.pose.position, trajectory_point.pose.position, - std::max( - min_feasible_velocity, - calculateSafeVelocity( - trajectory_point, - static_cast(*dist_to_collision - projection_params.extra_length), - static_cast(projection_params.duration), velocity_params.min_velocity))); - - autoware::motion_utils::VirtualWall wall; - wall.pose = trajectory_point.pose; - virtual_walls.push_back(wall); + std::max(min_feasible_velocity, safe_velocity)); + + // with consecutive slowdowns only add a virtual wall for the first one + if (previous_slowdown_index + 1 != i) { + autoware::motion_utils::VirtualWall wall; + wall.pose = trajectory_point.pose; + virtual_walls.push_back(wall); + } + previous_slowdown_index = i; } } return slowdown_intervals; 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 aeeaabeb9b510..d7d2de63b33f8 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 @@ -1,4 +1,4 @@ -// Copyright 2022 TIER IV, Inc. +// 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. @@ -24,19 +24,10 @@ #include #include -#include #include namespace autoware::motion_velocity_planner::obstacle_velocity_limiter { - -/// @brief calculate the apparent safe velocity -/// @param[in] trajectory_point trajectory point for which to calculate the apparent safe velocity -/// @param[in] dist_to_collision distance from the trajectory point to the apparent collision -/// @return apparent safe velocity -double calculateSafeVelocity( - const TrajectoryPoint & trajectory_point, const double dist_to_collision); - /// @brief calculate trajectory index that is ahead of the given index by the given distance /// @param[in] trajectory trajectory /// @param[in] ego_idx index closest to the current ego position in the trajectory @@ -124,15 +115,6 @@ std::vector calculate_slowd ProjectionParameters & projection_params, const VelocityParameters & velocity_params, autoware::motion_utils::VirtualWalls & virtual_walls); -/// @brief copy the velocity profile of a downsampled trajectory to the original trajectory -/// @param[in] downsampled_trajectory downsampled trajectory -/// @param[in] trajectory input trajectory -/// @param[in] start_idx starting index of the downsampled trajectory relative to the input -/// @param[in] factor downsampling factor -/// @return input trajectory with the velocity profile of the downsampled trajectory -TrajectoryPoints copyDownsampledVelocity( - const TrajectoryPoints & downsampled_traj, TrajectoryPoints trajectory, const size_t start_idx, - const int factor); } // namespace autoware::motion_velocity_planner::obstacle_velocity_limiter #endif // OBSTACLE_VELOCITY_LIMITER_HPP_ 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 acf1dc1878087..35135089c0c8c 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 @@ -1,4 +1,4 @@ -// Copyright 2022 TIER IV, Inc. +// 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. @@ -15,7 +15,6 @@ #include "obstacle_velocity_limiter_module.hpp" #include "debug.hpp" -#include "forward_projection.hpp" #include "map_utils.hpp" #include "obstacle_velocity_limiter.hpp" #include "parameters.hpp" @@ -23,6 +22,7 @@ #include #include +#include #include #include #include @@ -31,7 +31,6 @@ #include -#include #include #include @@ -160,6 +159,9 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan( preprocessing_params_.max_duration); auto downsampled_traj_points = obstacle_velocity_limiter::downsampleTrajectory( original_traj_points, start_idx, end_idx, preprocessing_params_.downsample_factor); + if (prev_inserted_point_) { + obstacle_velocity_limiter::add_trajectory_point(downsampled_traj_points, *prev_inserted_point_); + } obstacle_velocity_limiter::ObstacleMasks obstacle_masks; const auto preprocessing_us = stopwatch.toc("preprocessing"); stopwatch.tic("obstacles"); @@ -203,6 +205,9 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan( } virtual_wall_marker_creator.add_virtual_walls(virtual_walls); virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); + if (!result.slowdown_intervals.empty()) { + prev_inserted_point_ = result.slowdown_intervals.front().from; + } const auto total_us = stopwatch.toc(); RCLCPP_DEBUG( 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 e06ca4fffae28..65e24c2dff349 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 @@ -1,4 +1,4 @@ -// Copyright 2022 TIER IV, Inc. +// 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. @@ -15,9 +15,7 @@ #ifndef OBSTACLE_VELOCITY_LIMITER_MODULE_HPP_ #define OBSTACLE_VELOCITY_LIMITER_MODULE_HPP_ -#include "obstacles.hpp" #include "parameters.hpp" -#include "types.hpp" #include #include @@ -29,6 +27,7 @@ #include #include #include +#include #include #include #include @@ -38,8 +37,6 @@ #include #include -#include -#include #include #include @@ -59,8 +56,8 @@ class ObstacleVelocityLimiterModule : public PluginModuleInterface private: inline static const std::string ns_ = "obstacle_velocity_limiter"; std::string module_name_; - rclcpp::Clock::SharedPtr clock_{}; - rclcpp::Time prev_inserted_point_time_{}; + rclcpp::Clock::SharedPtr clock_; + std::optional prev_inserted_point_; // parameters obstacle_velocity_limiter::PreprocessingParameters preprocessing_params_; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/parameters.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/parameters.hpp index 30ed9ae65a8a0..1824bf128e63e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/parameters.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/parameters.hpp @@ -1,4 +1,4 @@ -// Copyright 2022 TIER IV, Inc. +// 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. @@ -22,6 +22,7 @@ #include +#include #include #include @@ -45,7 +46,7 @@ struct ObstacleParameters int8_t occupancy_grid_threshold{}; double dynamic_obstacles_buffer{}; double dynamic_obstacles_min_vel{}; - std::vector static_map_tags{}; + std::vector static_map_tags; bool filter_envelope{}; bool ignore_on_path{}; double ignore_extra_distance{}; @@ -125,7 +126,7 @@ struct ProjectionParameters double velocity{}; double heading{}; // parameters specific to the bicycle model - int points_per_projection = 5; + int64_t points_per_projection = 5; double wheel_base{}; double steering_angle{}; double steering_angle_offset{}; @@ -172,11 +173,11 @@ struct ProjectionParameters return true; } - bool updateNbPoints(const rclcpp::Logger & logger, const int nb_points) + bool updateNbPoints(const rclcpp::Logger & logger, const int64_t nb_points) { if (nb_points < 2) { RCLCPP_WARN( - logger, "Cannot use less than 2 points per projection. Using value %d instead.", + logger, "Cannot use less than 2 points per projection. Using value %ld instead.", points_per_projection); return false; } @@ -217,7 +218,7 @@ struct PreprocessingParameters static constexpr auto MAX_LENGTH_PARAM = "trajectory_preprocessing.max_length"; static constexpr auto MAX_DURATION_PARAM = "trajectory_preprocessing.max_duration"; - int downsample_factor{}; + int64_t downsample_factor{}; double start_distance{}; bool calculate_steering_angles{}; double max_length{}; @@ -232,7 +233,7 @@ struct PreprocessingParameters max_length = node.declare_parameter(MAX_LENGTH_PARAM); max_duration = node.declare_parameter(MAX_DURATION_PARAM); } - bool updateDownsampleFactor(const int new_downsample_factor) + bool updateDownsampleFactor(const int64_t new_downsample_factor) { if (new_downsample_factor > 0) { downsample_factor = new_downsample_factor; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp index f56b50635c96e..c064f2c717625 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp @@ -1,4 +1,4 @@ -// Copyright 2022 TIER IV, Inc. +// 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. @@ -14,13 +14,17 @@ #include "trajectory_preprocessing.hpp" +#include "types.hpp" + +#include #include +#include #include #include -#include +#include namespace autoware::motion_velocity_planner::obstacle_velocity_limiter { @@ -57,7 +61,7 @@ size_t calculateEndIndex( TrajectoryPoints downsampleTrajectory( const TrajectoryPoints & trajectory, const size_t start_idx, const size_t end_idx, - const int factor) + const int64_t factor) { if (factor < 1) return trajectory; TrajectoryPoints downsampled_traj; @@ -79,19 +83,24 @@ void calculateSteeringAngles(TrajectoryPoints & trajectory, const double wheel_b const auto d_heading = heading - prev_heading; prev_heading = heading; point.front_wheel_angle_rad = - std::atan2(wheel_base * d_heading, point.longitudinal_velocity_mps * dt); + static_cast(std::atan2(wheel_base * d_heading, point.longitudinal_velocity_mps * dt)); } } -TrajectoryPoints copyDownsampledVelocity( - const TrajectoryPoints & downsampled_traj, TrajectoryPoints trajectory, const size_t start_idx, - const int factor) +void add_trajectory_point(TrajectoryPoints & trajectory, const geometry_msgs::msg::Point & point) { - const auto size = std::min(downsampled_traj.size(), trajectory.size()); - for (size_t i = 0; i < size; ++i) { - trajectory[start_idx + i * factor].longitudinal_velocity_mps = - downsampled_traj[i].longitudinal_velocity_mps; + const auto segment_idx = motion_utils::findNearestSegmentIndex(trajectory, point); + const auto lat_offset = motion_utils::calcLateralOffset(trajectory, point, segment_idx); + if (lat_offset < 1.0) { + const auto lon_offset_to_segment = + motion_utils::calcLongitudinalOffsetToSegment(trajectory, segment_idx, point); + const auto inserted_idx = + motion_utils::insertTargetPoint(segment_idx, lon_offset_to_segment, trajectory); + if (inserted_idx) { + trajectory[*inserted_idx].longitudinal_velocity_mps = + trajectory[segment_idx].longitudinal_velocity_mps; + trajectory[*inserted_idx].acceleration_mps2 = trajectory[segment_idx].acceleration_mps2; + } } - return trajectory; } } // namespace autoware::motion_velocity_planner::obstacle_velocity_limiter diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.hpp index cb9fe40e64907..b328b552c6862 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.hpp @@ -1,4 +1,4 @@ -// Copyright 2022 TIER IV, Inc. +// 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. @@ -45,7 +45,7 @@ size_t calculateEndIndex( /// @return downsampled trajectory TrajectoryPoints downsampleTrajectory( const TrajectoryPoints & trajectory, const size_t start_idx, const size_t end_idx, - const int factor); + const int64_t factor); /// @brief recalculate the steering angle of the trajectory /// @details uses the change in headings for calculation @@ -53,15 +53,10 @@ TrajectoryPoints downsampleTrajectory( /// @param[in] wheel_base wheel base of the vehicle void calculateSteeringAngles(TrajectoryPoints & trajectory, const double wheel_base); -/// @brief copy the velocity profile of a downsampled trajectory to the original trajectory -/// @param[in] downsampled_trajectory downsampled trajectory -/// @param[in] trajectory input trajectory -/// @param[in] start_idx starting index of the downsampled trajectory relative to the input -/// @param[in] factor downsampling factor -/// @return input trajectory with the velocity profile of the downsampled trajectory -TrajectoryPoints copyDownsampledVelocity( - const TrajectoryPoints & downsampled_traj, TrajectoryPoints trajectory, const size_t start_idx, - const int factor); +/// @brief insert a point in the trajectory and fill its velocity and acceleration data +/// @param[inout] trajectory input trajectory +/// @param[in] point point to insert in the trajectory +void add_trajectory_point(TrajectoryPoints & trajectory, const geometry_msgs::msg::Point & point); } // namespace autoware::motion_velocity_planner::obstacle_velocity_limiter #endif // TRAJECTORY_PREPROCESSING_HPP_ 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 9a08616b8fe7b..9aa376ed5f26a 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 @@ -332,9 +332,12 @@ void MotionVelocityPlannerNode::insert_slowdown( const auto to_insert_idx = autoware::motion_utils::insertTargetPoint(to_seg_idx, slowdown_interval.to, trajectory.points); if (from_insert_idx && to_insert_idx) { - for (auto idx = *from_insert_idx; idx <= *to_insert_idx; ++idx) + for (auto idx = *from_insert_idx; idx <= *to_insert_idx; ++idx) { trajectory.points[idx].longitudinal_velocity_mps = - static_cast(slowdown_interval.velocity); + std::min( // prevent the node from increasing the velocity + trajectory.points[idx].longitudinal_velocity_mps, + static_cast(slowdown_interval.velocity)); + } } else { RCLCPP_WARN(get_logger(), "Failed to insert slowdown point"); } From 0d99cae619d6a224032afc5a1860cb92adffce2b Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 28 Aug 2024 17:50:15 +0900 Subject: [PATCH 043/217] ci(cppcheck): remove unnecessary noConstructor suppression (#8632) Signed-off-by: Ryuta Kambe --- .cppcheck_suppressions | 1 - 1 file changed, 1 deletion(-) diff --git a/.cppcheck_suppressions b/.cppcheck_suppressions index 58002c148870c..a0e7bcce350f5 100644 --- a/.cppcheck_suppressions +++ b/.cppcheck_suppressions @@ -3,7 +3,6 @@ checkersReport missingInclude missingIncludeSystem -noConstructor unknownMacro unmatchedSuppression unusedFunction From 6d0262bbddbebdcd05c1174f725e9aabbf9a9821 Mon Sep 17 00:00:00 2001 From: Nagi70 <114723428+Nagi70@users.noreply.github.com> Date: Thu, 29 Aug 2024 07:01:23 +0900 Subject: [PATCH 044/217] fix(object_recognition_utils): fix unusedFunction (#8523) fix: unusedFunction Signed-off-by: Nagi70 --- .../include/object_recognition_utils/conversion.hpp | 1 - common/object_recognition_utils/src/conversion.cpp | 11 ----------- 2 files changed, 12 deletions(-) diff --git a/common/object_recognition_utils/include/object_recognition_utils/conversion.hpp b/common/object_recognition_utils/include/object_recognition_utils/conversion.hpp index 6d07d161bf069..207f76a1c31a8 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/conversion.hpp +++ b/common/object_recognition_utils/include/object_recognition_utils/conversion.hpp @@ -28,7 +28,6 @@ using autoware_perception_msgs::msg::TrackedObjects; DetectedObject toDetectedObject(const TrackedObject & tracked_object); DetectedObjects toDetectedObjects(const TrackedObjects & tracked_objects); TrackedObject toTrackedObject(const DetectedObject & detected_object); -TrackedObjects toTrackedObjects(const DetectedObjects & detected_objects); } // namespace object_recognition_utils #endif // OBJECT_RECOGNITION_UTILS__CONVERSION_HPP_ diff --git a/common/object_recognition_utils/src/conversion.cpp b/common/object_recognition_utils/src/conversion.cpp index ac65b35c6809a..c9c057ad93644 100644 --- a/common/object_recognition_utils/src/conversion.cpp +++ b/common/object_recognition_utils/src/conversion.cpp @@ -68,15 +68,4 @@ TrackedObject toTrackedObject(const DetectedObject & detected_object) tracked_object.shape = detected_object.shape; return tracked_object; } - -TrackedObjects toTrackedObjects(const DetectedObjects & detected_objects) -{ - TrackedObjects tracked_objects; - tracked_objects.header = detected_objects.header; - - for (const auto & detected_object : detected_objects.objects) { - tracked_objects.objects.push_back(toTrackedObject(detected_object)); - } - return tracked_objects; -} } // namespace object_recognition_utils From cfe319c547f123bf42e4f33c61594d8be8eaef1f Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 29 Aug 2024 07:02:45 +0900 Subject: [PATCH 045/217] fix(autoware_velocity_smoother): fix unusedFunction (#8649) fix:unusedFunction Signed-off-by: kobayu858 --- .../velocity_smoother/trajectory_utils.hpp | 11 -- .../src/trajectory_utils.cpp | 136 ------------------ 2 files changed, 147 deletions(-) diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/trajectory_utils.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/trajectory_utils.hpp index 29033b69d7a66..d20f82538e4d5 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/trajectory_utils.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/trajectory_utils.hpp @@ -43,12 +43,6 @@ std::vector calcTrajectoryIntervalDistance(const TrajectoryPoints & traj std::vector calcTrajectoryCurvatureFrom3Points( const TrajectoryPoints & trajectory, size_t idx_dist); -void setZeroVelocity(TrajectoryPoints & trajectory); - -double getMaxVelocity(const TrajectoryPoints & trajectory); - -double getMaxAbsVelocity(const TrajectoryPoints & trajectory); - void applyMaximumVelocityLimit( const size_t from, const size_t to, const double max_vel, TrajectoryPoints & trajectory); @@ -63,11 +57,6 @@ bool isValidStopDist( const double v_end, const double a_end, const double v_target, const double a_target, const double v_margin, const double a_margin); -std::optional applyDecelFilterWithJerkConstraint( - const TrajectoryPoints & input, const size_t start_index, const double v0, const double a0, - const double min_acc, const double decel_target_vel, - const std::map & jerk_profile); - std::optional> updateStateWithJerkConstraint( const double v0, const double a0, const std::map & jerk_profile, const double t); diff --git a/planning/autoware_velocity_smoother/src/trajectory_utils.cpp b/planning/autoware_velocity_smoother/src/trajectory_utils.cpp index b796e2aeb91de..68f05438d38c8 100644 --- a/planning/autoware_velocity_smoother/src/trajectory_utils.cpp +++ b/planning/autoware_velocity_smoother/src/trajectory_utils.cpp @@ -219,36 +219,6 @@ std::vector calcTrajectoryCurvatureFrom3Points( return k_arr; } -void setZeroVelocity(TrajectoryPoints & trajectory) -{ - for (auto & tp : trajectory) { - tp.longitudinal_velocity_mps = 0.0; - } -} - -double getMaxVelocity(const TrajectoryPoints & trajectory) -{ - double max_vel = 0.0; - for (const auto & tp : trajectory) { - if (tp.longitudinal_velocity_mps > max_vel) { - max_vel = tp.longitudinal_velocity_mps; - } - } - return max_vel; -} - -double getMaxAbsVelocity(const TrajectoryPoints & trajectory) -{ - double max_vel = 0.0; - for (const auto & tp : trajectory) { - double abs_vel = std::fabs(tp.longitudinal_velocity_mps); - if (abs_vel > max_vel) { - max_vel = abs_vel; - } - } - return max_vel; -} - void applyMaximumVelocityLimit( const size_t begin, const size_t end, const double max_vel, TrajectoryPoints & trajectory) { @@ -428,112 +398,6 @@ bool isValidStopDist( return true; } -std::optional applyDecelFilterWithJerkConstraint( - const TrajectoryPoints & input, const size_t start_index, const double v0, const double a0, - const double min_acc, const double decel_target_vel, - const std::map & jerk_profile) -{ - double t_total{0.0}; - for (const auto & it : jerk_profile) { - t_total += it.second; - } - - std::vector ts; - std::vector xs; - std::vector vs; - std::vector as; - std::vector js; - const double dt{0.1}; - double x{0.0}; - double v{0.0}; - double a{0.0}; - double j{0.0}; - - for (double t = 0.0; t < t_total; t += dt) { - // Calculate state = (x, v, a, j) at t - const auto state = updateStateWithJerkConstraint(v0, a0, jerk_profile, t_total); - if (!state) { - return {}; - } - std::tie(x, v, a, j) = *state; - if (v > 0.0) { - a = std::max(a, min_acc); - ts.push_back(t); - xs.push_back(x); - vs.push_back(v); - as.push_back(a); - js.push_back(j); - } - } - // Calculate state = (x, v, a, j) at t_total - const auto state = updateStateWithJerkConstraint(v0, a0, jerk_profile, t_total); - if (!state) { - return {}; - } - std::tie(x, v, a, j) = *state; - if (v > 0.0 && !xs.empty() && xs.back() < x) { - a = std::max(a, min_acc); - ts.push_back(t_total); - xs.push_back(x); - vs.push_back(v); - as.push_back(a); - js.push_back(j); - } - - const double a_target{0.0}; - const double v_margin{0.3}; - const double a_margin{0.1}; - if (!isValidStopDist(v, a, decel_target_vel, a_target, v_margin, a_margin)) { - RCLCPP_WARN_STREAM( - rclcpp::get_logger("autoware_velocity_smoother").get_child("trajectory_utils"), - "validation check error"); - return {}; - } - - TrajectoryPoints output_trajectory{input}; - - if (xs.empty()) { - output_trajectory.at(start_index).longitudinal_velocity_mps = decel_target_vel; - output_trajectory.at(start_index).acceleration_mps2 = 0.0; - for (unsigned int i = start_index + 1; i < output_trajectory.size(); ++i) { - output_trajectory.at(i).longitudinal_velocity_mps = decel_target_vel; - output_trajectory.at(i).acceleration_mps2 = 0.0; - } - return output_trajectory; - } - - const std::vector distance_all = calcArclengthArray(output_trajectory); - const auto it_end = std::find_if( - distance_all.begin(), distance_all.end(), [&xs](double x) { return x > xs.back(); }); - const std::vector distance{distance_all.begin() + start_index, it_end}; - - if ( - !interpolation_utils::isIncreasing(xs) || !interpolation_utils::isIncreasing(distance) || - !interpolation_utils::isNotDecreasing(xs) || !interpolation_utils::isNotDecreasing(distance)) { - return {}; - } - - if ( - xs.size() < 2 || vs.size() < 2 || as.size() < 2 || distance.empty() || - distance.front() < xs.front() || xs.back() < distance.back()) { - return {}; - } - - const auto vel_at_wp = interpolation::lerp(xs, vs, distance); - const auto acc_at_wp = interpolation::lerp(xs, as, distance); - - for (unsigned int i = 0; i < vel_at_wp.size(); ++i) { - output_trajectory.at(start_index + i).longitudinal_velocity_mps = vel_at_wp.at(i); - output_trajectory.at(start_index + i).acceleration_mps2 = acc_at_wp.at(i); - } - for (unsigned int i = start_index + vel_at_wp.size(); i < output_trajectory.size(); ++i) { - output_trajectory.at(i).longitudinal_velocity_mps = decel_target_vel; - output_trajectory.at(i).acceleration_mps2 = 0.0; - } - - return output_trajectory; -} - std::optional> updateStateWithJerkConstraint( const double v0, const double a0, const std::map & jerk_profile, const double t) { From f7f4e6c166cce14048e109efda4359e6cb2e4929 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 29 Aug 2024 07:03:03 +0900 Subject: [PATCH 046/217] fix(autoware_behavior_path_dynamic_obstacle_avoidance_module): fix unusedFunction (#8652) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/scene.cpp | 19 ------------------- 1 file changed, 19 deletions(-) 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 4d8cdef20a67a..8f7deffebf5ac 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 @@ -179,25 +179,6 @@ double calcDiffAngleAgainstPath( return diff_yaw; } -[[maybe_unused]] double calcDiffAngleBetweenPaths( - const std::vector & path_points, const PredictedPath & predicted_path) -{ - const size_t nearest_idx = autoware::motion_utils::findNearestSegmentIndex( - path_points, predicted_path.path.front().position); - const double ego_yaw = tf2::getYaw(path_points.at(nearest_idx).point.pose.orientation); - - constexpr size_t max_predicted_path_size = 5; - double signed_max_angle{0.0}; - for (size_t i = 0; i < std::min(max_predicted_path_size, predicted_path.path.size()); ++i) { - const double obj_yaw = tf2::getYaw(predicted_path.path.at(i).orientation); - const double diff_yaw = autoware::universe_utils::normalizeRadian(obj_yaw - ego_yaw); - if (std::abs(signed_max_angle) < std::abs(diff_yaw)) { - signed_max_angle = diff_yaw; - } - } - return signed_max_angle; -} - double calcDistanceToPath( const std::vector & points, const geometry_msgs::msg::Point & target_pos, const size_t target_idx) From b007acf10eb52d7851c9e0cf762f16ca9fb53e0f Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 29 Aug 2024 07:03:39 +0900 Subject: [PATCH 047/217] fix(autoware_behavior_path_side_shift_module): fix unusedFunction (#8655) fix:unusedFunction Signed-off-by: kobayu858 --- .../behavior_path_side_shift_module/utils.hpp | 8 ---- .../src/utils.cpp | 40 ------------------- 2 files changed, 48 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/utils.hpp index a36eaabcf928c..d5888ab6a79d1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/utils.hpp @@ -29,16 +29,8 @@ using tier4_planning_msgs::msg::PathWithLaneId; void setOrientation(PathWithLaneId * path); -bool getStartAvoidPose( - const PathWithLaneId & path, const double start_distance, const size_t nearest_idx, - Pose * start_avoid_pose); - bool isAlmostZero(double v); -Point transformToGrid( - const Point & pt, const double longitudinal_offset, const double lateral_offset, const double yaw, - const TransformStamped & geom_tf); - } // namespace autoware::behavior_path_planner #endif // AUTOWARE__BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/utils.cpp index 60fc5f74a3e1a..f30895c10d64d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/utils.cpp @@ -53,49 +53,9 @@ void setOrientation(PathWithLaneId * path) } } -bool getStartAvoidPose( - const PathWithLaneId & path, const double start_distance, const size_t nearest_idx, - Pose * start_avoid_pose) -{ - if (!start_avoid_pose) { - return false; - } - if (nearest_idx >= path.points.size()) { - return false; - } - - double arclength = 0.0; - for (size_t idx = nearest_idx + 1; idx < path.points.size(); ++idx) { - const auto pt = path.points.at(idx).point; - const auto pt_prev = path.points.at(idx - 1).point; - const double dx = pt.pose.position.x - pt_prev.pose.position.x; - const double dy = pt.pose.position.y - pt_prev.pose.position.y; - arclength += std::hypot(dx, dy); - - if (arclength > start_distance) { - *start_avoid_pose = pt.pose; - return true; - } - } - - return false; -} - bool isAlmostZero(double v) { return std::fabs(v) < 1.0e-4; } -Point transformToGrid( - const Point & pt, const double longitudinal_offset, const double lateral_offset, const double yaw, - const TransformStamped & geom_tf) -{ - Point offset_pt, grid_pt; - offset_pt = pt; - offset_pt.x += longitudinal_offset * cos(yaw) - lateral_offset * sin(yaw); - offset_pt.y += longitudinal_offset * sin(yaw) + lateral_offset * cos(yaw); - tf2::doTransform(offset_pt, grid_pt, geom_tf); - return grid_pt; -} - } // namespace autoware::behavior_path_planner From cf3ba7f9dc49b597f51b677fce9f56d5a8bf1820 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 29 Aug 2024 07:04:22 +0900 Subject: [PATCH 048/217] fix(autoware_behavior_path_start_planner_module): fix unusedFunction (#8659) fix:unusedFunction Signed-off-by: kobayu858 --- .../debug.hpp | 39 ------------------- .../util.hpp | 2 - .../src/debug.cpp | 30 -------------- .../src/start_planner_module.cpp | 1 - .../src/util.cpp | 12 +----- 5 files changed, 1 insertion(+), 83 deletions(-) delete mode 100644 planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/debug.hpp delete mode 100644 planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/debug.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/debug.hpp deleted file mode 100644 index 81358f37132f5..0000000000000 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/debug.hpp +++ /dev/null @@ -1,39 +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__BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ - -#include "autoware/behavior_path_start_planner_module/data_structs.hpp" - -#include -#include - -namespace autoware::behavior_path_planner -{ -using autoware::behavior_path_planner::StartPlannerDebugData; - -void updateSafetyCheckDebugData( - StartPlannerDebugData & data, const PredictedObjects & filtered_objects, - const TargetObjectsOnLane & target_objects_on_lane, - const std::vector & ego_predicted_path) -{ - data.filtered_objects = filtered_objects; - data.target_objects_on_lane = target_objects_on_lane; - data.ego_predicted_path = ego_predicted_path; -} - -} // namespace autoware::behavior_path_planner - -#endif // AUTOWARE__BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/util.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/util.hpp index 09485e68852a3..60c5ccedd93f5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/util.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/util.hpp @@ -49,8 +49,6 @@ PathWithLaneId getBackwardPath( const Pose & current_pose, const Pose & backed_pose, const double velocity); lanelet::ConstLanelets getPullOutLanes( const std::shared_ptr & planner_data, const double backward_length); -Pose getBackedPose( - const Pose & current_pose, const double & yaw_shoulder_lane, const double & back_distance); std::optional extractCollisionCheckSection( const PullOutPath & path, const double collision_check_distance_from_end); } // namespace autoware::behavior_path_planner::start_planner_utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/debug.cpp deleted file mode 100644 index 1b25d8eac8846..0000000000000 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/debug.cpp +++ /dev/null @@ -1,30 +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/behavior_path_start_planner_module/debug.hpp" - -namespace autoware::behavior_path_planner -{ - -void updateSafetyCheckDebugData( - StartPlannerDebugData & data, const PredictedObjects & filtered_objects, - const TargetObjectsOnLane & target_objects_on_lane, - const std::vector & ego_predicted_path) -{ - data.filtered_objects = filtered_objects; - data.target_objects_on_lane = target_objects_on_lane; - data.ego_predicted_path = ego_predicted_path; -} - -} // namespace autoware::behavior_path_planner 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 5c3c62b947af2..6c88bf006b5d3 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 @@ -18,7 +18,6 @@ #include "autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_utils.hpp" -#include "autoware/behavior_path_start_planner_module/debug.hpp" #include "autoware/behavior_path_start_planner_module/util.hpp" #include "autoware/motion_utils/trajectory/trajectory.hpp" diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp index 0d4a4366b2714..219efb3084f1c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp @@ -72,17 +72,6 @@ PathWithLaneId getBackwardPath( return backward_path; } -Pose getBackedPose( - const Pose & current_pose, const double & yaw_shoulder_lane, const double & back_distance) -{ - Pose backed_pose; - backed_pose = current_pose; - backed_pose.position.x -= std::cos(yaw_shoulder_lane) * back_distance; - backed_pose.position.y -= std::sin(yaw_shoulder_lane) * back_distance; - - return backed_pose; -} - lanelet::ConstLanelets getPullOutLanes( const std::shared_ptr & planner_data, const double backward_length) { @@ -103,6 +92,7 @@ lanelet::ConstLanelets getPullOutLanes( /*forward_only_in_route*/ true); } +// cppcheck-suppress unusedFunction std::optional extractCollisionCheckSection( const PullOutPath & path, const double collision_check_distance_from_end) { From 7011ea141952790a53dc02ff1b48ef17d1f5a228 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 29 Aug 2024 07:05:36 +0900 Subject: [PATCH 049/217] fix(autoware_behavior_path_planner_common): fix unusedFunction (#8654) * fix:unusedFunction 0-2 Signed-off-by: kobayu858 * fix:unusedFunction 3-5 Signed-off-by: kobayu858 * fix:unusedFunction Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../utils/path_utils.hpp | 9 - .../utils/utils.hpp | 21 --- .../src/marker_utils/utils.cpp | 1 + .../static_drivable_area.cpp | 14 -- .../src/utils/parking_departure/utils.cpp | 10 -- .../src/utils/path_utils.cpp | 143 ---------------- .../src/utils/utils.cpp | 155 +----------------- 7 files changed, 4 insertions(+), 349 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_utils.hpp index 45bdb296f6575..dc371e3063822 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_utils.hpp @@ -67,11 +67,6 @@ void clipPathLength( void clipPathLength( PathWithLaneId & path, const size_t target_idx, const BehaviorPathPlannerParameters & params); -std::pair getPathTurnSignal( - const lanelet::ConstLanelets & current_lanes, const ShiftedPath & path, - const ShiftLine & shift_line, const Pose & pose, const double & velocity, - const BehaviorPathPlannerParameters & common_parameter); - PathWithLaneId convertWayPointsToPathWithLaneId( const autoware::freespace_planning_algorithms::PlannerWaypoints & waypoints, const double velocity, const lanelet::ConstLanelets & lanelets); @@ -83,8 +78,6 @@ std::vector dividePath( void correctDividedPathVelocity(std::vector & divided_paths); -bool isCloseToPath(const PathWithLaneId & path, const Pose & pose, const double distance_threshold); - // only two points is supported std::vector splineTwoPoints( const std::vector & base_s, const std::vector & base_x, const double begin_diff, @@ -103,8 +96,6 @@ PathWithLaneId calcCenterLinePath( PathWithLaneId combinePath(const PathWithLaneId & path1, const PathWithLaneId & path2); -std::optional getFirstStopPoseFromPath(const PathWithLaneId & path); - BehaviorModuleOutput getReferencePath( const lanelet::ConstLanelet & current_lane, const std::shared_ptr & planner_data); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp index 03e6c2d7f8167..7ac9993ee8b01 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp @@ -104,8 +104,6 @@ FrenetPoint convertToFrenetPoint( return frenet_point; } -std::vector getIds(const lanelet::ConstLanelets & lanelets); - // distance (arclength) calculation double l2Norm(const Vector3 vector); @@ -126,14 +124,6 @@ double getArcLengthToTargetLanelet( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelet & target_lane, const Pose & pose); -double getDistanceBetweenPredictedPaths( - const PredictedPath & path1, const PredictedPath & path2, const double start_time, - const double end_time, const double resolution); - -double getDistanceBetweenPredictedPathAndObject( - const PredictedObject & object, const PredictedPath & path, const double start_time, - const double end_time, const double resolution); - /** * @brief Check collision between ego path footprints with extra longitudinal stopping margin and * objects. @@ -223,8 +213,6 @@ PathWithLaneId refinePathForGoal( const double search_radius_range, const double search_rad_range, const PathWithLaneId & input, const Pose & goal, const int64_t goal_lane_id); -bool containsGoal(const lanelet::ConstLanelets & lanes, const lanelet::Id & goal_id); - bool isAllowedGoalModification(const std::shared_ptr & route_handler); bool checkOriginalGoalIsInShoulder(const std::shared_ptr & route_handler); @@ -269,10 +257,6 @@ Polygon2d toPolygon2d(const lanelet::ConstLanelet & lanelet); Polygon2d toPolygon2d(const lanelet::BasicPolygon2d & polygon); -std::vector getTargetLaneletPolygons( - const lanelet::ConstLanelets & lanelets, const Pose & pose, const double check_length, - const std::string & target_type); - PathWithLaneId getCenterLinePathFromLanelet( const lanelet::ConstLanelet & current_route_lanelet, const std::shared_ptr & planner_data); @@ -283,11 +267,6 @@ PathWithLaneId getCenterLinePath( const Pose & pose, const double backward_path_length, const double forward_path_length, const BehaviorPathPlannerParameters & parameter); -PathWithLaneId setDecelerationVelocity( - const RouteHandler & route_handler, const PathWithLaneId & input, - const lanelet::ConstLanelets & lanelet_sequence, const double lane_change_prepare_duration, - const double lane_change_buffer); - // object label std::uint8_t getHighestProbLabel(const std::vector & classification); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp index d57c2339041f4..09a23197d8092 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp @@ -341,6 +341,7 @@ MarkerArray createObjectsMarkerArray( return msg; } +// cppcheck-suppress unusedFunction MarkerArray createDrivableLanesMarkerArray( const std::vector & drivable_lanes, std::string && ns) { 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 d861f3459a3e6..3d5908bc4e02f 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 @@ -622,20 +622,6 @@ std::vector updateBoundary( return updated_bound; } -[[maybe_unused]] geometry_msgs::msg::Point calcCenterOfGeometry(const Polygon2d & obj_poly) -{ - geometry_msgs::msg::Point center_pos; - for (const auto & point : obj_poly.outer()) { - center_pos.x += point.x(); - center_pos.y += point.y(); - } - - center_pos.x = center_pos.x / obj_poly.outer().size(); - center_pos.y = center_pos.y / obj_poly.outer().size(); - center_pos.z = center_pos.z / obj_poly.outer().size(); - - return center_pos; -} } // namespace autoware::behavior_path_planner::utils::drivable_area_processing namespace autoware::behavior_path_planner::utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp index 4301742a18fa7..5fea6b501ba24 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp @@ -104,16 +104,6 @@ void initializeCollisionCheckDebugMap(CollisionCheckDebugMap & collision_check_d collision_check_debug_map.clear(); } -void updateSafetyCheckTargetObjectsData( - StartGoalPlannerData & data, const PredictedObjects & filtered_objects, - const TargetObjectsOnLane & target_objects_on_lane, - const std::vector & ego_predicted_path) -{ - data.filtered_objects = filtered_objects; - data.target_objects_on_lane = target_objects_on_lane; - data.ego_predicted_path = ego_predicted_path; -} - std::pair getPairsTerminalVelocityAndAccel( const std::vector> & pairs_terminal_velocity_and_accel, const size_t current_path_idx) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp index 7873a4b421297..5b234198d9137 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp @@ -209,127 +209,6 @@ void clipPathLength( clipPathLength(path, target_idx, params.forward_path_length, params.backward_path_length); } -std::pair getPathTurnSignal( - const lanelet::ConstLanelets & current_lanes, const ShiftedPath & path, - const ShiftLine & shift_line, const Pose & pose, const double & velocity, - const BehaviorPathPlannerParameters & common_parameter) -{ - TurnIndicatorsCommand turn_signal; - turn_signal.command = TurnIndicatorsCommand::NO_COMMAND; - const double max_time = std::numeric_limits::max(); - const double max_distance = std::numeric_limits::max(); - if (path.shift_length.size() < shift_line.end_idx + 1) { - return std::make_pair(turn_signal, max_distance); - } - const auto base_link2front = common_parameter.base_link2front; - const auto vehicle_width = common_parameter.vehicle_width; - const auto shift_to_outside = vehicle_width / 2; - const auto turn_signal_shift_length_threshold = - common_parameter.turn_signal_shift_length_threshold; - const auto turn_signal_minimum_search_distance = - common_parameter.turn_signal_minimum_search_distance; - const auto turn_signal_search_time = common_parameter.turn_signal_search_time; - constexpr double epsilon = 1e-6; - const auto arc_position_current_pose = lanelet::utils::getArcCoordinates(current_lanes, pose); - - // Start turn signal when 1 or 2 is satisfied - // 1. time to shift start point is less than prev_sec - // 2. distance to shift point is shorter than tl_on_threshold_long - - // Turn signal on when conditions below are satisfied - // 1. lateral offset is larger than tl_on_threshold_lat for left signal - // smaller than tl_on_threshold_lat for right signal - // 2. side point at shift start/end point cross the line - const double distance_to_shift_start = - std::invoke([¤t_lanes, &shift_line, &arc_position_current_pose]() { - const auto arc_position_shift_start = - lanelet::utils::getArcCoordinates(current_lanes, shift_line.start); - return arc_position_shift_start.length - arc_position_current_pose.length; - }); - - const auto time_to_shift_start = - (std::abs(velocity) < epsilon) ? max_time : distance_to_shift_start / velocity; - - const double diff = - path.shift_length.at(shift_line.end_idx) - path.shift_length.at(shift_line.start_idx); - - Pose shift_start_point = path.path.points.at(shift_line.start_idx).point.pose; - Pose shift_end_point = path.path.points.at(shift_line.end_idx).point.pose; - Pose left_start_point = shift_start_point; - Pose right_start_point = shift_start_point; - Pose left_end_point = shift_end_point; - Pose right_end_point = shift_end_point; - { - const double start_yaw = tf2::getYaw(shift_line.start.orientation); - const double end_yaw = tf2::getYaw(shift_line.end.orientation); - left_start_point.position.x -= std::sin(start_yaw) * (shift_to_outside); - left_start_point.position.y += std::cos(start_yaw) * (shift_to_outside); - right_start_point.position.x -= std::sin(start_yaw) * (-shift_to_outside); - right_start_point.position.y += std::cos(start_yaw) * (-shift_to_outside); - left_end_point.position.x -= std::sin(end_yaw) * (shift_to_outside); - left_end_point.position.y += std::cos(end_yaw) * (shift_to_outside); - right_end_point.position.x -= std::sin(end_yaw) * (-shift_to_outside); - right_end_point.position.y += std::cos(end_yaw) * (-shift_to_outside); - } - - bool left_start_point_is_in_lane = false; - bool right_start_point_is_in_lane = false; - bool left_end_point_is_in_lane = false; - bool right_end_point_is_in_lane = false; - { - for (const auto & llt : current_lanes) { - if (lanelet::utils::isInLanelet(left_start_point, llt, 0.1)) { - left_start_point_is_in_lane = true; - } - if (lanelet::utils::isInLanelet(right_start_point, llt, 0.1)) { - right_start_point_is_in_lane = true; - } - if (lanelet::utils::isInLanelet(left_end_point, llt, 0.1)) { - left_end_point_is_in_lane = true; - } - if (lanelet::utils::isInLanelet(right_end_point, llt, 0.1)) { - right_end_point_is_in_lane = true; - } - } - } - - const bool cross_line = std::invoke([&]() { - constexpr bool temporary_set_cross_line_true = - true; // due to a bug. See link: - // https://github.com/autowarefoundation/autoware.universe/pull/748 - if (temporary_set_cross_line_true) { - return true; - } - return ( - left_start_point_is_in_lane != left_end_point_is_in_lane || - right_start_point_is_in_lane != right_end_point_is_in_lane); - }); - - if ( - time_to_shift_start < turn_signal_search_time || - distance_to_shift_start < turn_signal_minimum_search_distance) { - if (diff > turn_signal_shift_length_threshold && cross_line) { - turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; - } else if (diff < -turn_signal_shift_length_threshold && cross_line) { - turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; - } - } - - // calc distance from ego vehicle front to shift end point. - const double distance_from_vehicle_front = - std::invoke([¤t_lanes, &shift_line, &arc_position_current_pose, &base_link2front]() { - const auto arc_position_shift_end = - lanelet::utils::getArcCoordinates(current_lanes, shift_line.end); - return arc_position_shift_end.length - arc_position_current_pose.length - base_link2front; - }); - - if (distance_from_vehicle_front >= 0.0) { - return std::make_pair(turn_signal, distance_from_vehicle_front); - } - - return std::make_pair(turn_signal, max_distance); -} - PathWithLaneId convertWayPointsToPathWithLaneId( const autoware::freespace_planning_algorithms::PlannerWaypoints & waypoints, const double velocity, const lanelet::ConstLanelets & lanelets) @@ -431,18 +310,6 @@ void correctDividedPathVelocity(std::vector & divided_paths) } } -bool isCloseToPath(const PathWithLaneId & path, const Pose & pose, const double distance_threshold) -{ - for (const auto & point : path.points) { - const auto & p = point.point.pose.position; - const double dist = std::hypot(pose.position.x - p.x, pose.position.y - p.y); - if (dist < distance_threshold) { - return true; - } - } - return false; -} - // only two points is supported std::vector splineTwoPoints( const std::vector & base_s, const std::vector & base_x, const double begin_diff, @@ -579,16 +446,6 @@ PathWithLaneId combinePath(const PathWithLaneId & path1, const PathWithLaneId & return filtered_path; } -std::optional getFirstStopPoseFromPath(const PathWithLaneId & path) -{ - for (const auto & p : path.points) { - if (std::abs(p.point.longitudinal_velocity_mps) < 0.01) { - return p.point.pose; - } - } - return std::nullopt; -} - BehaviorModuleOutput getReferencePath( const lanelet::ConstLanelet & current_lane, const std::shared_ptr & planner_data) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp index fd55d38518cda..0785a639034d7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp @@ -99,53 +99,7 @@ double l2Norm(const Vector3 vector) return std::sqrt(std::pow(vector.x, 2) + std::pow(vector.y, 2) + std::pow(vector.z, 2)); } -double getDistanceBetweenPredictedPaths( - const PredictedPath & object_path, const PredictedPath & ego_path, const double start_time, - const double end_time, const double resolution) -{ - double min_distance = std::numeric_limits::max(); - for (double t = start_time; t < end_time; t += resolution) { - const auto object_pose = object_recognition_utils::calcInterpolatedPose(object_path, t); - if (!object_pose) { - continue; - } - const auto ego_pose = object_recognition_utils::calcInterpolatedPose(ego_path, t); - if (!ego_pose) { - continue; - } - double distance = autoware::universe_utils::calcDistance3d(*object_pose, *ego_pose); - if (distance < min_distance) { - min_distance = distance; - } - } - return min_distance; -} - -double getDistanceBetweenPredictedPathAndObject( - const PredictedObject & object, const PredictedPath & ego_path, const double start_time, - const double end_time, const double resolution) -{ - auto clock{rclcpp::Clock{RCL_ROS_TIME}}; - auto t_delta{rclcpp::Duration::from_seconds(resolution)}; - double min_distance = std::numeric_limits::max(); - rclcpp::Time ros_start_time = clock.now() + rclcpp::Duration::from_seconds(start_time); - rclcpp::Time ros_end_time = clock.now() + rclcpp::Duration::from_seconds(end_time); - const auto obj_polygon = autoware::universe_utils::toPolygon2d(object); - for (double t = start_time; t < end_time; t += resolution) { - const auto ego_pose = object_recognition_utils::calcInterpolatedPose(ego_path, t); - if (!ego_pose) { - continue; - } - Point2d ego_point{ego_pose->position.x, ego_pose->position.y}; - - double distance = boost::geometry::distance(obj_polygon, ego_point); - if (distance < min_distance) { - min_distance = distance; - } - } - return min_distance; -} - +// cppcheck-suppress unusedFunction bool checkCollisionBetweenPathFootprintsAndObjects( const autoware::universe_utils::LinearRing2d & local_vehicle_footprint, const PathWithLaneId & ego_path, const PredictedObjects & dynamic_objects, const double margin) @@ -249,24 +203,6 @@ double calcLongitudinalDistanceFromEgoToObjects( return min_distance; } -std::vector calcObjectsDistanceToPath( - const PredictedObjects & objects, const PathWithLaneId & ego_path) -{ - std::vector distance_array; - for (const auto & obj : objects.objects) { - const auto obj_polygon = autoware::universe_utils::toPolygon2d(obj); - LineString2d ego_path_line; - ego_path_line.reserve(ego_path.points.size()); - for (const auto & p : ego_path.points) { - boost::geometry::append( - ego_path_line, Point2d(p.point.pose.position.x, p.point.pose.position.y)); - } - const double distance = boost::geometry::distance(obj_polygon, ego_path_line); - distance_array.push_back(distance); - } - return distance_array; -} - template bool exists(std::vector vec, T element) { @@ -457,16 +393,6 @@ PathWithLaneId refinePathForGoal( } } -bool containsGoal(const lanelet::ConstLanelets & lanes, const lanelet::Id & goal_id) -{ - for (const auto & lane : lanes) { - if (lane.id() == goal_id) { - return true; - } - } - return false; -} - bool isInLanelets(const Pose & pose, const lanelet::ConstLanelets & lanes) { for (const auto & lane : lanes) { @@ -771,16 +697,6 @@ double getSignedDistance( return arc_goal.length - arc_current.length; } -std::vector getIds(const lanelet::ConstLanelets & lanelets) -{ - std::vector ids; - ids.reserve(lanelets.size()); - for (const auto & llt : lanelets) { - ids.push_back(llt.id()); - } - return ids; -} - PathPointWithLaneId insertStopPoint(const double length, PathWithLaneId & path) { const size_t original_size = path.points.size(); @@ -1034,50 +950,6 @@ Polygon2d toPolygon2d(const lanelet::BasicPolygon2d & polygon) : autoware::universe_utils::inverseClockwise(ret); } -std::vector getTargetLaneletPolygons( - const lanelet::PolygonLayer & map_polygons, lanelet::ConstLanelets & lanelets, const Pose & pose, - const double check_length, const std::string & target_type) -{ - std::vector polygons; - - // create lanelet polygon - const auto arclength = lanelet::utils::getArcCoordinates(lanelets, pose); - const auto llt_polygon = lanelet::utils::getPolygonFromArcLength( - lanelets, arclength.length, arclength.length + check_length); - const auto llt_polygon_2d = lanelet::utils::to2D(llt_polygon).basicPolygon(); - - // If the number of vertices is not enough to create polygon, return empty polygon container - if (llt_polygon_2d.size() < 3) { - return polygons; - } - - Polygon2d llt_polygon_bg; - llt_polygon_bg.outer().reserve(llt_polygon_2d.size() + 1); - for (const auto & llt_pt : llt_polygon_2d) { - llt_polygon_bg.outer().emplace_back(llt_pt.x(), llt_pt.y()); - } - llt_polygon_bg.outer().push_back(llt_polygon_bg.outer().front()); - - for (const auto & map_polygon : map_polygons) { - const std::string type = map_polygon.attributeOr(lanelet::AttributeName::Type, ""); - // If the target_type is different - // or the number of vertices is not enough to create polygon, skip the loop - if (type == target_type && map_polygon.size() > 2) { - // create map polygon - Polygon2d map_polygon_bg; - map_polygon_bg.outer().reserve(map_polygon.size() + 1); - for (const auto & pt : map_polygon) { - map_polygon_bg.outer().emplace_back(pt.x(), pt.y()); - } - map_polygon_bg.outer().push_back(map_polygon_bg.outer().front()); - if (boost::geometry::intersects(llt_polygon_bg, map_polygon_bg)) { - polygons.push_back(map_polygon_bg); - } - } - } - return polygons; -} - // TODO(Horibe) There is a similar function in route_handler. std::shared_ptr generateCenterLinePath( const std::shared_ptr & planner_data) @@ -1172,31 +1044,9 @@ PathWithLaneId getCenterLinePath( return resampled_path_with_lane_id; } -// for lane following -PathWithLaneId setDecelerationVelocity( - const RouteHandler & route_handler, const PathWithLaneId & input, - const lanelet::ConstLanelets & lanelet_sequence, const double lane_change_prepare_duration, - const double lane_change_buffer) -{ - auto reference_path = input; - if ( - route_handler.isDeadEndLanelet(lanelet_sequence.back()) && - lane_change_prepare_duration > std::numeric_limits::epsilon()) { - for (auto & point : reference_path.points) { - const double lane_length = lanelet::utils::getLaneletLength2d(lanelet_sequence); - const auto arclength = lanelet::utils::getArcCoordinates(lanelet_sequence, point.point.pose); - const double distance_to_end = - std::max(0.0, lane_length - std::abs(lane_change_buffer) - arclength.length); - point.point.longitudinal_velocity_mps = std::min( - point.point.longitudinal_velocity_mps, - static_cast(distance_to_end / lane_change_prepare_duration)); - } - } - return reference_path; -} - // TODO(murooka) remove calcSignedArcLength using findNearestSegmentIndex inside the // function +// cppcheck-suppress unusedFunction PathWithLaneId setDecelerationVelocity( const PathWithLaneId & input, const double target_velocity, const Pose target_pose, const double buffer, const double deceleration_interval) @@ -1643,6 +1493,7 @@ lanelet::ConstLanelets getLaneletsFromPath( return lanelets; } +// cppcheck-suppress unusedFunction std::string convertToSnakeCase(const std::string & input_str) { std::string output_str = std::string{static_cast(std::tolower(input_str.at(0)))}; From 47275fb594e5fa322b7bfbdf1ff4470a08e326d6 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 29 Aug 2024 10:15:27 +0900 Subject: [PATCH 050/217] fix(autoware_behavior_velocity_crosswalk_module): fix unusedFunction (#8665) fix:unusedFunction Signed-off-by: kobayu858 --- .../autoware/behavior_velocity_crosswalk_module/util.hpp | 2 -- .../src/util.cpp | 6 ------ 2 files changed, 8 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 260ba58fd7d93..34e67cee12af2 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 @@ -95,8 +95,6 @@ std::set getCrosswalkIdSetOnPath( const tier4_planning_msgs::msg::PathWithLaneId & path, const lanelet::LaneletMapPtr lanelet_map, const std::shared_ptr & overall_graphs); -bool checkRegulatoryElementExistence(const lanelet::LaneletMapPtr & lanelet_map_ptr); - std::optional> getPathEndPointsOnCrosswalk( const PathWithLaneId & ego_path, const lanelet::BasicPolygon2d & polygon, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp index 755a32b08e024..a72c866a85cef 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp @@ -105,12 +105,6 @@ std::set getCrosswalkIdSetOnPath( return crosswalk_id_set; } -bool checkRegulatoryElementExistence(const lanelet::LaneletMapPtr & lanelet_map_ptr) -{ - const auto all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr); - return !lanelet::utils::query::crosswalks(all_lanelets).empty(); -} - /** * @brief Calculate path end (= first and last) points on the crosswalk * From e6792028765d2c6de914d04361087c8310488ba3 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 29 Aug 2024 10:18:25 +0900 Subject: [PATCH 051/217] fix(reaction_analyzer): fix include hierarchy of tf2_eigen (#8663) Fixed include hierarchy of tf2_eigen Signed-off-by: Shintaro Sakoda --- tools/reaction_analyzer/include/subscriber.hpp | 2 +- tools/reaction_analyzer/include/topic_publisher.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/reaction_analyzer/include/subscriber.hpp b/tools/reaction_analyzer/include/subscriber.hpp index ff251251373e2..d2a8363e15bf3 100644 --- a/tools/reaction_analyzer/include/subscriber.hpp +++ b/tools/reaction_analyzer/include/subscriber.hpp @@ -16,7 +16,7 @@ #define SUBSCRIBER_HPP_ #include #include -#include +#include #include #include diff --git a/tools/reaction_analyzer/include/topic_publisher.hpp b/tools/reaction_analyzer/include/topic_publisher.hpp index 0c01561fec508..4517b1f793e6c 100644 --- a/tools/reaction_analyzer/include/topic_publisher.hpp +++ b/tools/reaction_analyzer/include/topic_publisher.hpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include #include From 81934e4b6beb00a443edfc03380e1c25b2321056 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Thu, 29 Aug 2024 10:42:58 +0900 Subject: [PATCH 052/217] refactor(map_projection_loader)!: prefix package and namespace with autoware (#8420) * add autoware_ prefix Signed-off-by: a-maumau * add autoware_ prefix Signed-off-by: a-maumau --------- Signed-off-by: a-maumau Co-authored-by: SakodaShintaro --- .github/CODEOWNERS | 2 +- launch/tier4_map_launch/launch/map.launch.xml | 2 +- launch/tier4_map_launch/package.xml | 2 +- .../CMakeLists.txt | 4 ++-- .../README.md | 6 +++--- .../config/map_projection_loader.param.yaml | 0 .../docs/map_projector_type.svg | 0 .../load_info_from_lanelet2_map.hpp | 9 ++++++--- .../map_projection_loader/map_projection_loader.hpp | 9 ++++++--- .../launch/map_projection_loader.launch.xml | 4 ++-- .../package.xml | 4 ++-- .../schema/map_projection_loader.schema.json | 0 .../src/load_info_from_lanelet2_map.cpp | 5 ++++- .../src/map_projection_loader.cpp | 9 ++++++--- .../test/data/map_projector_info_local.yaml | 0 .../data/map_projector_info_local_cartesian_utm.yaml | 0 .../test/data/map_projector_info_mgrs.yaml | 0 .../data/map_projector_info_transverse_mercator.yaml | 0 .../test/test_load_info_from_lanelet2_map.cpp | 11 +++++++---- ...st_node_load_local_cartesian_utm_from_yaml.test.py | 8 ++++---- .../test/test_node_load_local_from_yaml.test.py | 8 ++++---- .../test/test_node_load_mgrs_from_yaml.test.py | 8 ++++---- ...st_node_load_transverse_mercator_from_yaml.test.py | 8 ++++---- .../autoware_static_centerline_generator/package.xml | 2 +- .../src/static_centerline_generator_node.cpp | 8 ++++---- 25 files changed, 62 insertions(+), 47 deletions(-) rename map/{map_projection_loader => autoware_map_projection_loader}/CMakeLists.txt (93%) rename map/{map_projection_loader => autoware_map_projection_loader}/README.md (90%) rename map/{map_projection_loader => autoware_map_projection_loader}/config/map_projection_loader.param.yaml (100%) rename map/{map_projection_loader => autoware_map_projection_loader}/docs/map_projector_type.svg (100%) rename map/{map_projection_loader/include => autoware_map_projection_loader/include/autoware}/map_projection_loader/load_info_from_lanelet2_map.hpp (76%) rename map/{map_projection_loader/include => autoware_map_projection_loader/include/autoware}/map_projection_loader/map_projection_loader.hpp (80%) rename map/{map_projection_loader => autoware_map_projection_loader}/launch/map_projection_loader.launch.xml (51%) rename map/{map_projection_loader => autoware_map_projection_loader}/package.xml (91%) rename map/{map_projection_loader => autoware_map_projection_loader}/schema/map_projection_loader.schema.json (100%) rename map/{map_projection_loader => autoware_map_projection_loader}/src/load_info_from_lanelet2_map.cpp (93%) rename map/{map_projection_loader => autoware_map_projection_loader}/src/map_projection_loader.cpp (91%) rename map/{map_projection_loader => autoware_map_projection_loader}/test/data/map_projector_info_local.yaml (100%) rename map/{map_projection_loader => autoware_map_projection_loader}/test/data/map_projector_info_local_cartesian_utm.yaml (100%) rename map/{map_projection_loader => autoware_map_projection_loader}/test/data/map_projector_info_mgrs.yaml (100%) rename map/{map_projection_loader => autoware_map_projection_loader}/test/data/map_projector_info_transverse_mercator.yaml (100%) rename map/{map_projection_loader => autoware_map_projection_loader}/test/test_load_info_from_lanelet2_map.cpp (90%) rename map/{map_projection_loader => autoware_map_projection_loader}/test/test_node_load_local_cartesian_utm_from_yaml.test.py (94%) rename map/{map_projection_loader => autoware_map_projection_loader}/test/test_node_load_local_from_yaml.test.py (93%) rename map/{map_projection_loader => autoware_map_projection_loader}/test/test_node_load_mgrs_from_yaml.test.py (93%) rename map/{map_projection_loader => autoware_map_projection_loader}/test/test_node_load_transverse_mercator_from_yaml.test.py (94%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 6de0c3251696b..89b9fa0eb8f38 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -101,7 +101,7 @@ localization/yabloc/yabloc_particle_filter/** anh.nguyen.2@tier4.jp kento.yabuuc localization/yabloc/yabloc_pose_initializer/** 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 map/autoware_map_height_fitter/** anh.nguyen.2@tier4.jp isamu.takagi@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 map/map_loader/** 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 -map/map_projection_loader/** 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 +map/autoware_map_projection_loader/** 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 map/autoware_map_tf_generator/** 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 map/util/lanelet2_map_preprocessor/** 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 perception/autoware_bytetrack/** manato.hirabayashi@tier4.jp yoshi.ri@tier4.jp diff --git a/launch/tier4_map_launch/launch/map.launch.xml b/launch/tier4_map_launch/launch/map.launch.xml index 051cf64d7752e..bd97963bd1268 100644 --- a/launch/tier4_map_launch/launch/map.launch.xml +++ b/launch/tier4_map_launch/launch/map.launch.xml @@ -59,7 +59,7 @@
- + diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml index b364d8eaffebc..76ff341b56cf9 100644 --- a/launch/tier4_map_launch/package.xml +++ b/launch/tier4_map_launch/package.xml @@ -18,9 +18,9 @@ ament_cmake_auto autoware_cmake + autoware_map_projection_loader autoware_map_tf_generator map_loader - map_projection_loader ament_lint_auto autoware_lint_common diff --git a/map/map_projection_loader/CMakeLists.txt b/map/autoware_map_projection_loader/CMakeLists.txt similarity index 93% rename from map/map_projection_loader/CMakeLists.txt rename to map/autoware_map_projection_loader/CMakeLists.txt index 87f519ab22572..19c5a98ec8b46 100644 --- a/map/map_projection_loader/CMakeLists.txt +++ b/map/autoware_map_projection_loader/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(map_projection_loader) +project(autoware_map_projection_loader) find_package(autoware_cmake REQUIRED) autoware_package() @@ -12,7 +12,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "MapProjectionLoader" + PLUGIN "autoware::map_projection_loader::MapProjectionLoader" EXECUTABLE ${PROJECT_NAME}_node EXECUTOR SingleThreadedExecutor ) diff --git a/map/map_projection_loader/README.md b/map/autoware_map_projection_loader/README.md similarity index 90% rename from map/map_projection_loader/README.md rename to map/autoware_map_projection_loader/README.md index aa620256d977b..11246c092231e 100644 --- a/map/map_projection_loader/README.md +++ b/map/autoware_map_projection_loader/README.md @@ -1,8 +1,8 @@ -# map_projection_loader +# autoware_map_projection_loader ## Feature -`map_projection_loader` is responsible for publishing `map_projector_info` that defines in which kind of coordinate Autoware is operating. +`autoware_map_projection_loader` is responsible for publishing `map_projector_info` that defines in which kind of coordinate Autoware is operating. This is necessary information especially when you want to convert from global (geoid) to local coordinate or the other way around. - If `map_projector_info_path` DOES exist, this node loads it and publishes the map projection information accordingly. @@ -92,4 +92,4 @@ map_origin: Note that these parameters are assumed to be passed from launch arguments, and it is not recommended to directly write them in `map_projection_loader.param.yaml`. -{{ json_to_markdown("map/map_projection_loader/schema/map_projection_loader.schema.json") }} +{{ json_to_markdown("map/autoware_map_projection_loader/schema/map_projection_loader.schema.json") }} diff --git a/map/map_projection_loader/config/map_projection_loader.param.yaml b/map/autoware_map_projection_loader/config/map_projection_loader.param.yaml similarity index 100% rename from map/map_projection_loader/config/map_projection_loader.param.yaml rename to map/autoware_map_projection_loader/config/map_projection_loader.param.yaml diff --git a/map/map_projection_loader/docs/map_projector_type.svg b/map/autoware_map_projection_loader/docs/map_projector_type.svg similarity index 100% rename from map/map_projection_loader/docs/map_projector_type.svg rename to map/autoware_map_projection_loader/docs/map_projector_type.svg diff --git a/map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/load_info_from_lanelet2_map.hpp similarity index 76% rename from map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp rename to map/autoware_map_projection_loader/include/autoware/map_projection_loader/load_info_from_lanelet2_map.hpp index 750b90fe495bd..2f1db14529ad0 100644 --- a/map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp +++ b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/load_info_from_lanelet2_map.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ -#define MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ +#ifndef AUTOWARE__MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ +#define AUTOWARE__MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ #include #include @@ -24,6 +24,9 @@ #include +namespace autoware::map_projection_loader +{ tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename); +} // namespace autoware::map_projection_loader -#endif // MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ +#endif // AUTOWARE__MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ diff --git a/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp similarity index 80% rename from map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp rename to map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp index 05bc6e64e1675..feb7483f37811 100644 --- a/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp +++ b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ -#define MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ +#ifndef AUTOWARE__MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ +#define AUTOWARE__MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ #include "rclcpp/rclcpp.hpp" @@ -22,6 +22,8 @@ #include +namespace autoware::map_projection_loader +{ tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename); tier4_map_msgs::msg::MapProjectorInfo load_map_projector_info( const std::string & yaml_filename, const std::string & lanelet2_map_filename); @@ -35,5 +37,6 @@ class MapProjectionLoader : public rclcpp::Node using MapProjectorInfo = map_interface::MapProjectorInfo; component_interface_utils::Publisher::SharedPtr publisher_; }; +} // namespace autoware::map_projection_loader -#endif // MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ +#endif // AUTOWARE__MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ diff --git a/map/map_projection_loader/launch/map_projection_loader.launch.xml b/map/autoware_map_projection_loader/launch/map_projection_loader.launch.xml similarity index 51% rename from map/map_projection_loader/launch/map_projection_loader.launch.xml rename to map/autoware_map_projection_loader/launch/map_projection_loader.launch.xml index 13418a7e97423..224598e23d048 100644 --- a/map/map_projection_loader/launch/map_projection_loader.launch.xml +++ b/map/autoware_map_projection_loader/launch/map_projection_loader.launch.xml @@ -1,10 +1,10 @@ - + - + diff --git a/map/map_projection_loader/package.xml b/map/autoware_map_projection_loader/package.xml similarity index 91% rename from map/map_projection_loader/package.xml rename to map/autoware_map_projection_loader/package.xml index c36c22c29a0fd..ca25cbf728d26 100644 --- a/map/map_projection_loader/package.xml +++ b/map/autoware_map_projection_loader/package.xml @@ -1,9 +1,9 @@ - map_projection_loader + autoware_map_projection_loader 0.1.0 - map_projection_loader package as a ROS 2 node + autoware_map_projection_loader package as a ROS 2 node Yamato Ando Masahiro Sakamoto Kento Yabuuchi diff --git a/map/map_projection_loader/schema/map_projection_loader.schema.json b/map/autoware_map_projection_loader/schema/map_projection_loader.schema.json similarity index 100% rename from map/map_projection_loader/schema/map_projection_loader.schema.json rename to map/autoware_map_projection_loader/schema/map_projection_loader.schema.json diff --git a/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp b/map/autoware_map_projection_loader/src/load_info_from_lanelet2_map.cpp similarity index 93% rename from map/map_projection_loader/src/load_info_from_lanelet2_map.cpp rename to map/autoware_map_projection_loader/src/load_info_from_lanelet2_map.cpp index 18306e8d39e25..ce4cda5c2c677 100644 --- a/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp +++ b/map/autoware_map_projection_loader/src/load_info_from_lanelet2_map.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "map_projection_loader/load_info_from_lanelet2_map.hpp" +#include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp" #include "tier4_map_msgs/msg/map_projector_info.hpp" @@ -23,6 +23,8 @@ #include +namespace autoware::map_projection_loader +{ tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename) { lanelet::ErrorMessages errors{}; @@ -58,3 +60,4 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::str msg.vertical_datum = tier4_map_msgs::msg::MapProjectorInfo::WGS84; return msg; } +} // namespace autoware::map_projection_loader diff --git a/map/map_projection_loader/src/map_projection_loader.cpp b/map/autoware_map_projection_loader/src/map_projection_loader.cpp similarity index 91% rename from map/map_projection_loader/src/map_projection_loader.cpp rename to map/autoware_map_projection_loader/src/map_projection_loader.cpp index e5b95b613b0d1..18ad425c1fd9a 100644 --- a/map/map_projection_loader/src/map_projection_loader.cpp +++ b/map/autoware_map_projection_loader/src/map_projection_loader.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "map_projection_loader/map_projection_loader.hpp" +#include "autoware/map_projection_loader/map_projection_loader.hpp" -#include "map_projection_loader/load_info_from_lanelet2_map.hpp" +#include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp" #include @@ -23,6 +23,8 @@ #include #include +namespace autoware::map_projection_loader +{ tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename) { YAML::Node data = YAML::LoadFile(filename); @@ -93,6 +95,7 @@ MapProjectionLoader::MapProjectionLoader(const rclcpp::NodeOptions & options) adaptor.init_pub(publisher_); publisher_->publish(msg); } +} // namespace autoware::map_projection_loader #include -RCLCPP_COMPONENTS_REGISTER_NODE(MapProjectionLoader) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::map_projection_loader::MapProjectionLoader) diff --git a/map/map_projection_loader/test/data/map_projector_info_local.yaml b/map/autoware_map_projection_loader/test/data/map_projector_info_local.yaml similarity index 100% rename from map/map_projection_loader/test/data/map_projector_info_local.yaml rename to map/autoware_map_projection_loader/test/data/map_projector_info_local.yaml diff --git a/map/map_projection_loader/test/data/map_projector_info_local_cartesian_utm.yaml b/map/autoware_map_projection_loader/test/data/map_projector_info_local_cartesian_utm.yaml similarity index 100% rename from map/map_projection_loader/test/data/map_projector_info_local_cartesian_utm.yaml rename to map/autoware_map_projection_loader/test/data/map_projector_info_local_cartesian_utm.yaml diff --git a/map/map_projection_loader/test/data/map_projector_info_mgrs.yaml b/map/autoware_map_projection_loader/test/data/map_projector_info_mgrs.yaml similarity index 100% rename from map/map_projection_loader/test/data/map_projector_info_mgrs.yaml rename to map/autoware_map_projection_loader/test/data/map_projector_info_mgrs.yaml diff --git a/map/map_projection_loader/test/data/map_projector_info_transverse_mercator.yaml b/map/autoware_map_projection_loader/test/data/map_projector_info_transverse_mercator.yaml similarity index 100% rename from map/map_projection_loader/test/data/map_projector_info_transverse_mercator.yaml rename to map/autoware_map_projection_loader/test/data/map_projector_info_transverse_mercator.yaml diff --git a/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp b/map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp similarity index 90% rename from map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp rename to map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp index 7d66388c1a91e..26658e88682a2 100644 --- a/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp +++ b/map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "map_projection_loader/load_info_from_lanelet2_map.hpp" +#include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp" #include #include @@ -92,7 +92,8 @@ TEST(TestLoadFromLanelet2Map, LoadMGRSGrid) save_dummy_mgrs_lanelet2_map(mgrs_coord, output_path); // Test the function - const auto projector_info = load_info_from_lanelet2_map(output_path); + const auto projector_info = + autoware::map_projection_loader::load_info_from_lanelet2_map(output_path); // Check the result EXPECT_EQ(projector_info.projector_type, "MGRS"); @@ -106,7 +107,8 @@ TEST(TestLoadFromLanelet2Map, LoadLocalGrid) save_dummy_local_lanelet2_map(output_path); // Test the function - const auto projector_info = load_info_from_lanelet2_map(output_path); + const auto projector_info = + autoware::map_projection_loader::load_info_from_lanelet2_map(output_path); // Check the result EXPECT_EQ(projector_info.projector_type, "local"); @@ -119,7 +121,8 @@ TEST(TestLoadFromLanelet2Map, LoadNoLocalGrid) save_dummy_mgrs_lanelet2_map_with_one_zero_point(output_path); // Test the function - const auto projector_info = load_info_from_lanelet2_map(output_path); + const auto projector_info = + autoware::map_projection_loader::load_info_from_lanelet2_map(output_path); // Check the result EXPECT_EQ(projector_info.projector_type, "MGRS"); diff --git a/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py b/map/autoware_map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py similarity index 94% rename from map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py rename to map/autoware_map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py index 0d0b5cb31afba..495f0092bb01f 100644 --- a/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py +++ b/map/autoware_map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py @@ -39,12 +39,12 @@ @pytest.mark.launch_test def generate_test_description(): map_projector_info_path = os.path.join( - get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH ) map_projection_loader_node = Node( - package="map_projection_loader", - executable="map_projection_loader_node", + package="autoware_map_projection_loader", + executable="autoware_map_projection_loader_node", output="screen", parameters=[ { @@ -122,7 +122,7 @@ def test_node_link(self): # Load the yaml file directly map_projector_info_path = os.path.join( - get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH ) with open(map_projector_info_path) as f: yaml_data = yaml.load(f, Loader=yaml.FullLoader) diff --git a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py b/map/autoware_map_projection_loader/test/test_node_load_local_from_yaml.test.py similarity index 93% rename from map/map_projection_loader/test/test_node_load_local_from_yaml.test.py rename to map/autoware_map_projection_loader/test/test_node_load_local_from_yaml.test.py index 6a17ff340b19f..8517f09e2006b 100644 --- a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py +++ b/map/autoware_map_projection_loader/test/test_node_load_local_from_yaml.test.py @@ -39,12 +39,12 @@ @pytest.mark.launch_test def generate_test_description(): map_projector_info_path = os.path.join( - get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH ) map_projection_loader_node = Node( - package="map_projection_loader", - executable="map_projection_loader_node", + package="autoware_map_projection_loader", + executable="autoware_map_projection_loader_node", output="screen", parameters=[ { @@ -122,7 +122,7 @@ def test_node_link(self): # Load the yaml file directly map_projector_info_path = os.path.join( - get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH ) with open(map_projector_info_path) as f: yaml_data = yaml.load(f, Loader=yaml.FullLoader) diff --git a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py b/map/autoware_map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py similarity index 93% rename from map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py rename to map/autoware_map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py index 37cfd9936bf20..ad19e61f9f111 100644 --- a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py +++ b/map/autoware_map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py @@ -39,12 +39,12 @@ @pytest.mark.launch_test def generate_test_description(): map_projector_info_path = os.path.join( - get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH ) map_projection_loader_node = Node( - package="map_projection_loader", - executable="map_projection_loader_node", + package="autoware_map_projection_loader", + executable="autoware_map_projection_loader_node", output="screen", parameters=[ { @@ -122,7 +122,7 @@ def test_node_link(self): # Load the yaml file directly map_projector_info_path = os.path.join( - get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH ) with open(map_projector_info_path) as f: yaml_data = yaml.load(f, Loader=yaml.FullLoader) diff --git a/map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py b/map/autoware_map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py similarity index 94% rename from map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py rename to map/autoware_map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py index 7bccdc7875454..ed2eb45535089 100644 --- a/map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py +++ b/map/autoware_map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py @@ -39,12 +39,12 @@ @pytest.mark.launch_test def generate_test_description(): map_projector_info_path = os.path.join( - get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH ) map_projection_loader_node = Node( - package="map_projection_loader", - executable="map_projection_loader_node", + package="autoware_map_projection_loader", + executable="autoware_map_projection_loader_node", output="screen", parameters=[ { @@ -122,7 +122,7 @@ def test_node_link(self): # Load the yaml file directly map_projector_info_path = os.path.join( - get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH ) with open(map_projector_info_path) as f: yaml_data = yaml.load(f, Loader=yaml.FullLoader) diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml index 2480c4bd02753..931b815b176c3 100644 --- a/planning/autoware_static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -19,6 +19,7 @@ autoware_geography_utils autoware_lanelet2_extension autoware_map_msgs + autoware_map_projection_loader autoware_mission_planner autoware_motion_utils autoware_path_optimizer @@ -32,7 +33,6 @@ global_parameter_loader interpolation map_loader - map_projection_loader osqp_interface rclcpp rclcpp_components 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 index 5e2ddc6579bf3..256cd2386c431 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -14,6 +14,8 @@ #include "static_centerline_generator_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/universe_utils/geometry/geometry.hpp" @@ -25,8 +27,6 @@ #include "centerline_source/bag_ego_trajectory_based_centerline.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "map_loader/lanelet2_map_loader_node.hpp" -#include "map_projection_loader/load_info_from_lanelet2_map.hpp" -#include "map_projection_loader/map_projection_loader.hpp" #include "type_alias.hpp" #include "utils.hpp" @@ -356,8 +356,8 @@ void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_ // load map by the map_loader package map_bin_ptr_ = [&]() -> LaneletMapBin::ConstSharedPtr { // load map - map_projector_info_ = - std::make_unique(load_info_from_lanelet2_map(lanelet2_input_file_path)); + map_projector_info_ = std::make_unique( + autoware::map_projection_loader::load_info_from_lanelet2_map(lanelet2_input_file_path)); const auto map_ptr = Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, *map_projector_info_); if (!map_ptr) { From e709b1019d27af1083b23a2334ebcb11fff9de5d Mon Sep 17 00:00:00 2001 From: Rein Appeldoorn Date: Thu, 29 Aug 2024 04:19:52 +0200 Subject: [PATCH 053/217] fix(autoware_pointcloud_preprocessor): resolve issue with FLT_MAX not declared on Jazzy (#8586) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit fix(pointcloud-preprocessor): FLT_MAX not declared Fixes compilation error on Jazzy: error: ‘FLT_MAX’ was not declared in this scope Signed-off-by: Rein Appeldoorn --- .../downsample_filter/faster_voxel_grid_downsample_filter.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp index c0e41239057f0..9a01ba3ddc1b1 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp @@ -14,6 +14,8 @@ #include "autoware/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp" +#include + namespace autoware::pointcloud_preprocessor { From 09eda6223566a2448ed2401eddf556c3d545024a Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Thu, 29 Aug 2024 15:04:04 +0900 Subject: [PATCH 054/217] feat(ekf_localizer): input ekf_dt to simple1dfilter (#8622) input ekf_dt to simple1dfilter Signed-off-by: Yamato Ando Co-authored-by: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> --- .../include/ekf_localizer/ekf_localizer.hpp | 11 +++-------- localization/ekf_localizer/src/ekf_localizer.cpp | 12 ++++++------ 2 files changed, 9 insertions(+), 14 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 332d4e0837e54..d247c817874fb 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -60,22 +60,20 @@ class Simple1DFilter var_ = 1e9; proc_var_x_c_ = 0.0; }; - void init(const double init_obs, const double obs_var, const rclcpp::Time & time) + void init(const double init_obs, const double obs_var) { x_ = init_obs; var_ = obs_var; - latest_time_ = time; initialized_ = true; }; - void update(const double obs, const double obs_var, const rclcpp::Time & time) + void update(const double obs, const double obs_var, const double dt) { if (!initialized_) { - init(obs, obs_var, time); + init(obs, obs_var); return; } // Prediction step (current variance) - double dt = (time - latest_time_).seconds(); double proc_var_x_d = proc_var_x_c_ * dt * dt; var_ = var_ + proc_var_x_d; @@ -83,8 +81,6 @@ class Simple1DFilter double kalman_gain = var_ / (var_ + obs_var); x_ = x_ + kalman_gain * (obs - x_); var_ = (1 - kalman_gain) * var_; - - latest_time_ = time; }; void set_proc_var(const double proc_var) { proc_var_x_c_ = proc_var; } [[nodiscard]] double get_x() const { return x_; } @@ -95,7 +91,6 @@ class Simple1DFilter double x_; double var_; double proc_var_x_c_; - rclcpp::Time latest_time_; }; class EKFLocalizer : public rclcpp::Node diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 10c706f4032b6..e77a1156bf049 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -456,9 +456,9 @@ void EKFLocalizer::update_simple_1d_filters( double pitch_var = pose.pose.covariance[COV_IDX::PITCH_PITCH] * static_cast(smoothing_step); - z_filter_.update(z, z_var, pose.header.stamp); - roll_filter_.update(rpy.x, roll_var, pose.header.stamp); - pitch_filter_.update(rpy.y, pitch_var, pose.header.stamp); + 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_); } void EKFLocalizer::init_simple_1d_filters( @@ -473,9 +473,9 @@ void EKFLocalizer::init_simple_1d_filters( double roll_var = pose.pose.covariance[COV_IDX::ROLL_ROLL]; double pitch_var = pose.pose.covariance[COV_IDX::PITCH_PITCH]; - z_filter_.init(z, z_var, pose.header.stamp); - roll_filter_.init(rpy.x, roll_var, pose.header.stamp); - pitch_filter_.init(rpy.y, pitch_var, pose.header.stamp); + z_filter_.init(z, z_var); + roll_filter_.init(rpy.x, roll_var); + pitch_filter_.init(rpy.y, pitch_var); } /** From 50d92d6b12e537533ccdcc4fa18c16fe042a2edf Mon Sep 17 00:00:00 2001 From: SaltUhey <111027815+SaltUhey@users.noreply.github.com> Date: Thu, 29 Aug 2024 15:13:57 +0900 Subject: [PATCH 055/217] feat(tier4_localization_rviz_plugin): add visualization of pose with covariance history (#8191) * display PoseWithCovariance History Signed-off-by: yuhei * Correct spelling errors and year Signed-off-by: yuhei * Add arrows clear() Signed-off-by: yuhei * Extension to 3D in matrix calculations Signed-off-by: yuhei * style(pre-commit): autofix * Correcting spelling mistakes and adding includes Signed-off-by: yuhei --------- Signed-off-by: yuhei Co-authored-by: Yamato Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CMakeLists.txt | 2 + .../tier4_localization_rviz_plugin/README.md | 45 ++- .../classes/PoseWithCovarianceHistory.png | Bin 0 -> 18815 bytes .../ex_pose_with_covariance_history.png | Bin 0 -> 300066 bytes .../package.xml | 1 + .../plugins/plugin_description.xml | 5 + .../pose_with_covariance_history_display.cpp | 285 ++++++++++++++++++ .../pose_with_covariance_history_display.hpp | 109 +++++++ 8 files changed, 441 insertions(+), 6 deletions(-) create mode 100644 common/tier4_localization_rviz_plugin/icons/classes/PoseWithCovarianceHistory.png create mode 100644 common/tier4_localization_rviz_plugin/images/ex_pose_with_covariance_history.png create mode 100644 common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp create mode 100644 common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp diff --git a/common/tier4_localization_rviz_plugin/CMakeLists.txt b/common/tier4_localization_rviz_plugin/CMakeLists.txt index 847c5e8af5fbc..eba48f27635e3 100644 --- a/common/tier4_localization_rviz_plugin/CMakeLists.txt +++ b/common/tier4_localization_rviz_plugin/CMakeLists.txt @@ -15,6 +15,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/pose_history/pose_history_display.cpp src/pose_history_footprint/display.hpp src/pose_history_footprint/display.cpp + src/pose_with_covariance_history/pose_with_covariance_history_display.hpp + src/pose_with_covariance_history/pose_with_covariance_history_display.cpp ) target_link_libraries(${PROJECT_NAME} diff --git a/common/tier4_localization_rviz_plugin/README.md b/common/tier4_localization_rviz_plugin/README.md index 60a923f15b563..5f5e35ea3dc19 100644 --- a/common/tier4_localization_rviz_plugin/README.md +++ b/common/tier4_localization_rviz_plugin/README.md @@ -2,20 +2,31 @@ ## Purpose -This plugin can display the history of the localization obtained by ekf_localizer or ndt_scan_matching. +This plugin can display the localization history obtained by ekf_localizer, ndt_scan_matching, and GNSS. +If the uncertainty of the estimated pose is given, it can also be displayed. ## Inputs / Outputs ### Input -| Name | Type | Description | -| ------------ | --------------------------------- | ---------------------------------------------------------------------------------------------- | -| `input/pose` | `geometry_msgs::msg::PoseStamped` | In input/pose, put the result of localization calculated by ekf_localizer or ndt_scan_matching | +### Pose History + +| Name | Type | Description | +| ------------ | --------------------------------- | ----------------------------------------------------------------------------------------------------- | +| `input/pose` | `geometry_msgs::msg::PoseStamped` | In input/pose, put the result of localization calculated by ekf_localizer, ndt_scan_matching, or GNSS | + +### Pose With Covariance History + +| Name | Type | Description | +| ---------------------------- | ----------------------------------------------- | --------------------------------------------------------------------------------------------------------------------- | +| `input/pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | In input/pose_with_covariance, put the result of localization calculated by ekf_localizer, ndt_scan_matching, or GNSS | ## Parameters ### Core Parameters +### Pose History + | Name | Type | Default Value | Description | | ----------------------- | ------ | ------------- | -------------------------- | | `property_buffer_size_` | int | 100 | Buffer size of topic | @@ -24,6 +35,26 @@ This plugin can display the history of the localization obtained by ekf_localize | `property_line_alpha_` | float | 1.0 | Alpha of Line property | | `property_line_color_` | QColor | Qt::white | Color of Line property | +### Pose With Covariance History + +| Name | Type | Default Value | Description | +| ------------------------------- | ------ | -------------- | -------------------------------- | +| `property_buffer_size_` | int | 100 | Buffer size of topic | +| `property_path_view_` | bool | true | Use path property or not | +| `property_shape_type_` | string | Line | Line or Arrow | +| `property_line_width_` | float | 0.1 | Width of Line property [m] | +| `property_line_alpha_` | float | 1.0 | Alpha of Line property | +| `property_line_color_` | QColor | Qt::white | Color of Line property | +| `property_arrow_shaft_length` | float | 0.3 | Shaft length of Arrow property | +| `property_arrow_shaft_diameter` | float | 0.15 | Shaft diameter of Arrow property | +| `property_arrow_head_length` | float | 0.2 | Head length of Arrow property | +| `property_arrow_head_diameter` | float | 0.3 | Head diameter of Arrow property | +| `property_arrow_alpha_` | float | 1.0 | Alpha of Arrow property | +| `property_arrow_color_` | QColor | Qt::white | Color of Arrow property | +| `property_sphere_scale_` | float | 1.0 | Scale of Sphere property | +| `property_sphere_alpha_` | float | 0.5 | Alpha of Sphere property | +| `property_sphere_color_` | QColor | (204, 51, 204) | Color of Sphere property | + ## Assumptions / Known limits TBD. @@ -32,7 +63,9 @@ TBD. 1. Start rviz and select Add under the Displays panel. ![select_add](./images/select_add.png) -2. Select tier4_localization_rviz_plugin/PoseHistory and press OK. +2. Select tier4_localization_rviz_plugin/PoseHistory or PoseWithCovarianceHistory. Next, press OK. ![select_localization_plugin](./images/select_localization_plugin.png) -3. Enter the name of the topic where you want to view the trajectory. +3. Enter the name of the topic where you want to view the trajectory and the covariance. ![select_topic_name](./images/select_topic_name.png) +4. You can view the trajectory and the covariance. + ![ex_pose_with_covariance_history](./images/ex_pose_with_covariance_history.png) diff --git a/common/tier4_localization_rviz_plugin/icons/classes/PoseWithCovarianceHistory.png b/common/tier4_localization_rviz_plugin/icons/classes/PoseWithCovarianceHistory.png new file mode 100644 index 0000000000000000000000000000000000000000..6a67573717ae18b6008e00077defb27256415663 GIT binary patch literal 18815 zcmc#)ig}7!VL~0BI3P>4u>jX{5WQyQGE==@gXiZcsv`yJ3)ShVHnpzyIKV zx%UIl!@PCQ*=Oy&*IwtGaAid)9L!gkAP@*gMjEOL0wKly`$K;YTnXsp8Ulf2BxRtY zY95&f%V-`irs2ZJD-E_>W|QJ#$f(lDGUzn9FhfdJ6ls+f7g13tl1h)8=nGVpD&-eU zEXJbkUMvxiN-bt%sdy?0Ws#;2U}Tww$D9k?tJrv3b90N4w6q7mY>Vu>j)cq`Gq>&g ztxVotd7x=_%0QrfCTU6#h!Tqc9R&LG1r-?ts`)>?Y`h5pRS_lWag8OXawfXJHk9@r zwSCxzbPRm-g9n1hq$!Q)8a9)#!i(M_cz&h|6vnpsyKVD7twGSL0-4KL6Q=BD1ZeP- zzfzYzWVM-q+?d)>KwJl;5;rOeaVP-p8?mb$R~c z!r4STVAB1bJ?W`Q1N^wk6a>;QVI%JxOu}Vf{^G|)Co3MGH{(9RMV<;nHU4Za)%KSC z`;I=`QN*K~)?CjlT%q3CJ0d$G%J_7^;$JI4Ms3f{6oyJDbjK_N!4ju2 z&$?3P$rm$WTureE-aq`r%H%qf&xx}1+^E65XE7*U*@ASHv#;8ex#{Xeuo?I&+x*og zCp;~E10-qE582|U!y4K~`SF#B31Gjpj3?LDSx6hf<#=NRr5x>o;P$^l9osYrEfL{WYjQydU9;g?K5#3k=W*FphTCuCHewl5&`Uu9F)(f>MMOxB>pE z88huBN|GrNq|eH~M(ELpl-tdZkMhs%;OV+^2?6{7^3=m>h4(Sn1AF4SLTeDL;O9g! zBWaM6c%X0DechlP8B_BUQ^1_B5ImG0q$&AGba@Q1!Sx#uv;b)FNlKJ%FF!gu4goAi z+jugMiX+lt3%Db%$x}1fa)yh%A&xxGW-Lle9BaRZcr(Jl8YJvmXVoM8b*d?nDn zr>xqjT|4gjOmgjyb!-I_L=1WSO(};jF5)F9(KK9k$6juv0YKyrQRHz_DK~8jI2)+w zm-Yt$QfvYLhOutzxp@d+SUG4qO=vJ%C2^D=7atD;N#3;^c;DQzmR&&!oPfkcBJT}x-4FY#kT02m@DxoqS-{xT|$ z3PAj4Y06h5S$bR{FjZhmf2ImPCOB3Cm{OLqda0jhqvfLSxmZ+?A2<^h+z64sYjMk*OaM^512bTNz1yJX#3oL;p>F~$69vB)J^K&J0kyCuHxo2qc9?N7 zpx^)Vh!`XhEMW3-8hQ#=jbwx3L_Yk3cspR5f1h~;US}c=&En=n$AFqJRa-Trw&}AF z#AgA`>wx2@JWAg4l9l5}1GY|0Z9CNsXNdgw(z**Vj@S4BOp0I}AA5Z|Zl~>Z3kVbj zqQ+>~?`j3P7S~|HAAK#cX8I@4)zn@Yx%DiDRJ@~c4bTC4ySPXJL&So)v8RA@6#{J%M_y$DCRzdd0*FPR zEH--gPG5+|{w5Yegr~;hMSkzb)vYj91mGV5xcRrf*}fIu`8(Gk(oJHQTMWSTlpe3W z7U|f@97Ozui1Pqn>xtK!34&Gp1$<#-lg>4RGs7K!6%!+v&|>f%Vhw^400u&sGY~q5 zJ^R2hK)+x%+?N_ujGMppd5=D@{V_pS_0HC2*7x*eApoKv>S`$MhIW>f zMXBEn^5P16FfqDGOxdOTX$;a&7%;G-28$P)$1&8Il!2^?K;(-9A|F432ZYVYM^|}I z3>OV1q`?mb9wc7}dJzwJ)_0FSe8o7Cm(><8hzS0{vBcWu7VZ9!xVd$!*%0qZqPEJb=%hJ$Z_L zz~Miu9bQOq9)39Df;+w>C4k8SnA^IR``!NH4|SUf61t|;@Y}Cs7L7w2kT8`ufki#> z(|*WcvwwZbRQK{xx%^U^9it@ui(i`PZ(a!{U!?$lf%er!QwQi?Jq@BTnXsQ0^KiZy z)@H)?s!l`=|Lg4jvo;>IFs7CP;9l8V4UpAo>sjIq#`%v=kuRv~Dh zsiW)pz26t!@MhZgf>?_yj35jsQu16~;-8_l{?rj9%$d(V-9L6Mv^t{|GGZ5-C`W&WqNh29e6d|hsvmvzE$*g zQmyMXe|TD_9?2}u%kdXf_x#(4xd=B4sAmzB{R*=+ZDMv*{0=ZZw`U z1zHnRLzGA%_kVvk=&UnLH`*nK6OLz)IZ+1RaP z$_a6)pzGO}t0_(S2EeN@?u0pWGf^QOT;Fy&fIf+061Vv&k6#eQ9E?CJbN7 zR~KK=eS#kf?q9C)BZqF)@T7l`iF(-E2|R4|?91b}4Ez)Kk2FyYsGq$iY-#*_u@~1} zergZr={EWSme9lc1Lvw@G~X6iq*U zJ>6TJJ1l)Wu8Wk+%I_jO@X>ttg#2Gtvr6H&5?wENhU3wfOD|1HK$EE0JWPIo?o%@w7QX>1z=lRIcDYmm^RdaH!J$U0qdKjR{v?Nj@k8=mLg z!QaffX+{G^hFLx>yzv{!{4I7+*?C}Mw;W;Akw&+^oGNB zKbo1D;RxOCe8*HY+Wq2Z{a&$bq>kL0E*5uqV%bZU97(Rgg}axR>R3#V{3&SGo$cMU zo>il+6}(CD_7>Sn+RG>LD*ZH>q}A^P_|jLN;2-ZSZ)e^-CR7g&UCtF)C)#ml2sjLp zna0G_?3W<_14PCTp7u%y`1jJLdPCb;WW==}ZA1fH$8?tCsR>bJF?vJ$I|J{? zlTYZ~d#P!IC7nc5MI zRsbBkP4l%D7PaBB{&6DKt4yR^NwBqPM*lr^I~U=AH?+LJ*&C$ZAXr^~8P$6rvc|OQ z@5*T^JLt$TP5T0t(=wiG^sXg zEd~AVuZVrio-s!T&LrqYTve>D*P81_=>7;qF3oJb%9-_$ zl7tF5{GK`$Y)Po@y_Df6U|SUSg7!xbv_*4yVe!Q#Ebc;ZcwoSK)rHUB2ho1zr!2(h z%dVk7oadz}SQ849EKz@)p|3b8py_+bZq+KNZ|#0KdDLC_ZhWXy#9XXyyOh3&D_KBd$d5r~dZ&@?gHCJhG5mniAQ@R>y{O zFvmlJ?JS~a-%K~9k;T?h@u&=-btl<6W(Mr?#p_#Nvx_0v`ilrR<$^+%&Dej}o4vNPn* z;owRb6rB0y*XFvkd6OhCQqGB6I?r)a!X@j6i&CJJ1K0a?>M~fR$7l@HLqkBtR{DNi z#>_e~=e6CHkiV3$L3^TB!NYiWD6Xr+?LjRJ218fc9?44c9VrfHEASeRf4u5=;4Pz2 zbmAarlXGC+<}+MNXuEB2%{j_j84W=YGt*J6aB$pdMP%f^yA?e@n6EWm{~fLLbbmH# zB#6dX=5Pv<(zsg%*jkAKL5r0knZM%tivqc1CatP(x82cXPdwWwcmjs-W@q|ImYY99 zYwlE~Y-hze~lk`x3mjPB!27mzk`xg^y;8^_L_ahVv6~)|t~mfqeU``w(TZ zxrTjOPssfK`oySR$6>Am1>m)tK+)!_P=0!6FfqlwTf!xubMJn*u$lh(uwJ8c<*Bgn zDIx;XIk9`S^Zs-&ZN{2BW%h21L^x#Hy{t&3#$u%2EIrNNs9uMGjS4;G4WkVIc79S?9<_)}5sGh^o2GGu01pfp6?z7wr_`sf6M}tS@hT zNCXk5MDOIEc)b#>BL5Byp4r;f?uV$qGqs%c8FpR1U>>e-v`u`iQ65*US#Q)pH|_z0GX?kiG%%(LOU!%Ckq@v`f@JK|pfX2{xiK)~<5soB5N zZ^n6hgiX)Z0q$xxBO+$zshAz%JT;G?R^ui!yaQF=CYolEefA_D418x5EBtuv6S_T# zt>8C5ZK^P2{Tk3jP{74C9i5Z*XB90Em|L^1Lp$Ty?ZVFx%zQ38_!1Hlo_wx*Jxm>5 z;cSTnM62^vnW0! zv(<%*u%dQ#ZEdDm`^UPysNb89-plAwdG@K0)y_jBD-qUQUN%)_5(TsN78%{K)f*=5FXVTI-5jC-M0r)_e2{Uu>Io;LFZ)WTSayCh zH$y%7yq?2_WZ>t-lJJ(ErM5;8)CMsVjU&indTZFQ!V%ji9)yN-+O%Xp_zMN?x2c&~ z$h26bQIZIOY$0|Hl-A{A>HW>D%Vl99Us^*}%6q+6(o_lL&Dq|Mo_&23{zG+CyVGoa zZdPuB-3?-rE;hgTQB^{1j%hnpE81vUZxe{q7+r62)9R zQjuMBfm(#Ms?@4Z$;Ik^iw9oWqRW`6isW|}$3~+7uuRp_uSRo5+uoV%o;%fYOqe&( z|2-;yrIE5RJ-g8wo6hVoIj1wlF#nl)eXp0d4XYB-b^eG|Cv?<)1s7iS_r5%WWTvIf z2b#SW2vI-|e@Dud15=%5ScGn5xI-4JpMXeprsukuG_&3pJ9vw|;{D{iSX$ZsyN-QS zIkazCCe z5tjTIqBD|W;A`f4 z(o2%2vBi}U($ZixbedSg2KMZ`WSTOQSc*AmMXpEHQN>d_Ts3UpJGs9*!n#G=T_Pyr zRXRI_^rJ$49%InZRr>IOdrQ?H&qWVYSv0t<)_MjA=@l6!>}m{uAv-nCbu4CkNL1I0 zszx2HgbeMhEPPFWT{;-iq%i3PmyXoFdjD&`g5k23{NZw;w9<>q|Iu^oZgl-bE6dSw z^mlKsUR{#$i%`XX%3&%n7Tqbvr-=iv3Vn!kYG;%8(aknQHmT914|hK(l9+ATj)ON8U+A7k}qtQoh z(o1n!2r2de-qqvX8LPa^T2)TVwotK{{5PUlaF}h}t$?CyJIDXX_j2AsLij`a@Rsi6 zT9`WmSJ@(5~J3(YDA@J|o3An#c=nA#EWWa`laHX*T$SjobapA&u?(UWP+Q{C%@7Q}QA^ zJNv{`cm#_$-9Pc`0QTcIA;7WaQ;?NPKQ)wA2wg2XAF*`a%1+DL{Ei|8qxs#0>_+qE zIygdQ6ZJGXrnY0=Ug)~OeO>jx(RvJib8E2<`5+hRj<=UQ`XSK&;bJyBjKUK-vv>=H zGCKa(@!Sj)ME<{YC-0A1b(Bqx63NF8LaQ+pwr7++?Y;83W-@6>tv_S?kk#VM|MVs2LY-DySvyPfa--K5g8|I^)y zxR)i5=c%cxpXe{y&Af@{;>*~{b02i&{aB_$54p;>&#@87qjme%iw$;g@1y3hdBV!k zZH`JGW7Tng^Ak~%}#;Q-2Kv@J$5 zPoiIQ%EmkU-JkTeJJ;0SF{mVKykranq(ebDsHb&e)<5FL`@L~x6=ryQdf$-7vCQ0< zVKw1(9v>zMv~Hr4MzS?k%k=W&z-eNFmOLHeG{ZZM>d@B7MqQoA_xwa^NGPaDE9_=G zqs6AdhWYsONzd@+OaTr-8XOBq(wvBuPJ?Raqs7jrj-Q(vB?55luOh~nXxNd`{VH~I zM;8yWZJr7r(}dDk^xNhxwsalXR!sA1N(T6xx8%3 z9i?;He4?%(U&RqXs^zm7y_}z_XZ`rKJWdqi+!lDPbqjFCc03mCyq$|H4*?12d18Xu zsc9-IL6-9k#5yU9z|37?M|bFc*A_tKQa1XE*M2$dVt-b%RtQm5BcL!+`EtBIz{=SB z>EVhR7s6-iy&6K2n(c0w;sbP}fDO(N@z^>W*1LXDq9TP$lSj^&IGFi{KpGIP-++mV zR2tI$TwO=$)6FcJ+Rs%5-rd7wzS5;BWefCwh}pkOiJM7&g&1R6o^Ft!tBsfjK$~LV zchl!;(BZ>dy(Cy;~wVJ*0yFzq6!EcXR5$rY?4gI54mUi2JbS2$QJGSQ5Xyxt;M>AF4Sv@28`bN@} zlqwK4bFtGi`_*QHwN9+3#N)ub$|i36r9T2zdP63$?>Q-i9luzG2$gB(w!3~+Q&2P3 ztg~7hwvPLAu**HR*1BKO`siW+cbQb!0_qL(aGzg2%;p*MKf-C??dsxN<>Sk(?%vrz zzc_PV+EeGDFeZ;i84*ZtW=H3=#2j|W^|ND<(N6Ys^vYL`H`p!um`KLX43QJ|#XvZ& z5VNDI>gv4*nZ&heTY8$rMpSG1;mfQ=IFry0%W*2X;r!dHgLxC(0(fUSoX7 zwNjEXD0t!s_`m5$=5BFW$;8yBAcYLBacVr_p>vrk2KwkD((ynWWJf^m6M0>Rs^j&K zcuG{Bb;k~FsXL?edF#}7S zHZDLmq@^Y_Y4fI*ecn|MwalQipJKC!`&+AEi=Oxumg^tYvS0s6v}&dED>#4Eap zAJNq9yf;-G>9>swxt+fKLmkVyKVy>_Z%8^@94F5{sE|(%yu=RF} zU|f+?>1X;0!Jp9#;p0r9dszlE)NBFz%Xb>g4B!|F;iIe%Rte_9u|W9MNnz3b-6obM zRP{c^sD1ZD1@8DThqDat@NK>7r_aG&(BpD|3!JTXho#kHn#b%IMn={-%208He(I{j z8s5K{sLB<8*d9?YNvdlAkE1Xq4M&^5V`}zED!eajyno=M;-hVhny2RT;+R}Z9r4hs zHg0|z%N0-eaMaHz%=Q`>bdt9ENtBg7zrZD9*0FRwt#|ss^{%z@XNh|0y-*Iz&V$F+ z5b1tlj^6+i1CSkW24b4a6t9GRb-61JetIWG3TakcE8lU{iJ1*WfY zhT3M?F_AEMwx8^2o>J9?B73d2M-Ao0yblIV=w|pGk7+ zChG0Dy~rHOK1Z}(>0iZDOF^?7HV2aYQZklSUv5SgTzl!7E#o4p(rOC24ScRx|^VD=~3JdRynp4w?)W(5A0 z)_C3;5w{#ut;AeK9af+D3$6?#Btje>?{BQL*L-vD2I8Ik7Vg!@QnLe zppa1pgsr!=`wq1_mTHZ}C3xl@K9Vf_gQQRAD_36GdaZ87H=x1+REu&}7i5gjPv`MP z?=NN3^VvFySA4Is?wUDmnv~`eOyF%d=CNUipe$ZOJ}FZgXz3+QW*Yt>xpMko-JL05 zks6_=q<8Zb!SRc%GSdhvd#^TbuH?h6Nef0sA3Wjvs`Q+zGw6AI#HO>wHLBBX;iyJI zFZ5A$b~Ji_KEX=v=l0q7@oKkklDfM5JEnZw<(BE1>)c*>-8TRsJgfKBDNYu#C!HGU zbLvbP6<#?=;4iU0T&Pb*LBnMo{A)%V&E)8oVNDoVfNMGIGqDC~Tscy8s*HW5h(C^+ zG%$nRO&>=ccGarn_c)}SF|TH0#$7Cx8+pN%20+veAhSU?RF1MOcSo&5t!{_L=^j!S zwpKQodunYpRvLi#(OCA4LtJoKXSCHK;j8k9qyr5?e~KQ|t>1+SXe) z>)&;E*Mlsb=gfL7YJkKP1nqI#dXEOw6i8@(OKrTvK3jR+J9~Xn-iY+EwA~bLWlsRR z23NE2O*dU)=1+e<1VW`GQj_6h3MbAnyDHL5QY*f|gl9W++|d2#xN2PS<3Ii9G|AA= zOQyQ5g5I}YLVzr($N9aHm+H&mo*)(pv+|j@cP5Nnz1nAZ%$JsKX2hLXNhUIS$$QnG z1AL<~%s^invTXLbb=gI`FD6^i`_j_7{ay3FG_nui=Feq_SET$RM11j`*GRQ*M5-@2 zd2E<{+liz^%K)8H_K-`#W19`%J018J8$M5t{XUL%67!Kv?T5Y6%HoSPfj9xo@SRNA zO&i%cnz)EbdPRxH)73v%VP9f)rk1ApgoAeZVYB+))9p8Bqd4&bBR~*`oNY>09O~N2 z!Rp>7KnHX=U8>;-697~ZJ_sN<+Irs|Hl_`;G1z694OixT`*V|Cz_YBGLc(tM@Kohm z>JD&MYd3Xf+B|B;lk$xwEPD9_~%=V(vx(C@a6Y-H$#=bfVOn57$&>rkwrVs4#bi zIXh7e(IM6w&y9tw+~I(;y6HV5=yM_(oXxC~r9=|;e>##2d}?n{dgmZtm$kdn2_X2$ zZn1&1c*eQwvMIIRLX^A-fxxJ(8WBPe?||LSuy z{t{iR`A!>-41uqe*4_8|FWHQLq|ffyeq*aJzDYNo!z||t!@KwR;k$ICGOlv)`wp!Q zFe7=&V)-C1g>f{5f5E>X@5^pc*;|x_)H3t0Wj(Hdf}t6f7dj;Lm3y|b61$Fgis3HI zZZTE=iadp@o=Y|={({-`cL3Mp!SitW{cQ0t++xA?d#mq<7jHsy-_FH#^te&BG6e9=TM4K?yE4$gLtJB{QzeetB zryUa6*x1vKi=Ur?^*FjI-@8jse%C$IlbLGM)=y!06b)*c>gqrMkCt)IoHxxwf;h>K zI$ZxUI0Qd&(@HM3+nD1SE<}@A-dyZ1FM9v|iBvCi@E-ah@k7-!4x7-5u`g+?MqO*l zm)P-Zzu$iR6iAlY+w9>D6kT>tx3it8Zf2XNw7OwQn=-dqz_;&l(OUI~)JrvPrtJfn zwVGJjkAIYJ@iHeSyf)eOw~G0ZJld2UGPIIZu3h{4455%Qbz6lZW74FexmYeYM;8aI z$K-h3Y^GFFCuw>-YX)_9?Ig^9A4wx1xQ2#eYVG!-LK}|bv$R8@eqlJgC_fD*}q9KhIE1f_i#O7_ zT)%x`)T#K2OJP6!v6Vb?t~cc+MQq6?;as!glC6mA<(e z<%lFRX`h0@1C67z0NHWh|ZjuVZ|V8t@FP@kIUYdtPp)2I9s3B_BXeBp}-ZP z5|l~AJ-|-~e7adHXKm6rZHQ~nBqb!qRwUhuE_?tsh^Kl=Hlz{jJv5 z%a`iA?S8PdtMf0~>M^6t2;7z3^z?rn(s|R}N+Jo!JO1-*rxQyqqw0F6X>RM!ACLOT zz2%2LmeJ%LT4#%}#EGCHI_{2UWy@EDyhONJs|(RvT?Z?St5 zJe~uJKn9oH8ehO#Qs>h$z{xbsOPOK-DR@vG_GmD%r#DqpIINVFeAg~=yeiV@S@ycUgHP|m(|5vgek*ZEH4RdwK{d$6jL>+4X z`4ChMuWjS9nJF{!ij95ygn<6)v21l;z0gZ@UjZab`9s9KK++(ZU}hS#jlPp@YHsdX+N+j<%}bAm_k9)T8@LAgyH4JzSyw>)>XO5eYZ-f(KZq4CZ8KAE}&p33a#nAw#ZL!zhkYZa0_fy&Jh12UfTAj4W?< z)O2(X-CC!M1+7n}8-n0j-m&cbyUhc#29lDYkyrH{#~wfcNz*@%?SyYHR3jK#qYkg` zfOxt;Xp>!NetI3?-j2$*c6E0peFJ1k0qtRyN~0J}eb0QIcI)6yPMaCaqc?e?=5%L0 z!wWTLgHwtNdLFYf->C5f&&TSGJKKO9egTz|q7H=dL_|bSuP9CLa~>76 znCtPqJkWLkR->ldp7iOcx({hE83#s3x$hnxA+ElF{8rgnRi*qnM5H$vfR4=(~l-hR-WQi)59iT6|TZNDzuRd5R$FCqNF)uguYRz#H!g{_d46@8|;6d)C31g+?wwl9UWUN!_7@iU(y8@`IP%@=plBH%=02yJ&ynGhwto!JlUOX z4ZlnR=UHTX(m73bJ`MY1G35^fepmv;GCh*P+1Gq7e{QeWW1q~jSlc~K9=z&1x!R5Sw+>Pg|4d7B*QMP1eov^xZ{boH28L>~l{Zhb#6){LZ zm@6K(L>wtG?EU!}!s|J9nZo{zoX5(&q`-6B*F~kgn1RWbz(S1+KjtWyba%eqCgn)S zFN@z*^(@_A3M$`75z6`%5E_kQVPm~8vUW(0-)Xpgi@MOw2BBVq0JDHsQp!G~mGIp` zt+g8jO^5Tn$1Dr}bH1cx#Vy}6vXegp0~5m=T_@{(WO?uY<)bNy2_cW;Z}e~9$_)RA z&R+=3N)8DzIPSQK_PD=ZR~&XP^$^GwPJke6@_WV`6v&1R5CO#>3rm*Q23Pe8MP7zS zN4FFUff1Z$-rRg+ zUOSJkl&izPHIn6>?4GZlL7(#}f01PSSIocavf%MkVJQEWW_pySvMFl!k06}^LD&vwY0rFM7Sdo{5 z!^6JOK>wyp&Wqx=>r``x(>dQU>14zTUKY_wnmZX{if`ugWtEtf5;FbfaR!RPMaJd=iiHkN)+{o zw=7_sEj@pbvWiNnS(}3oHAP5B$P(ALz1hl~T>aEY-XZhaZD8r8xs7nX)xEONDCjv; zOUTNmo&)Iqji8`liKzLOKAgKFJ{IZWuJ!WaoUryyAsQa}xqK??8(ZCEx7KBV%c+g} zKb}#TJ3DI#oj_gNy)Lv4->#&&w<8@3lV0qv{JbmRz6E=*>$kXAjlB;|IzAm_X;uCB zv75{DlZUCPX_L_PUzBOWE8nZ-zMA|iD#R`FU!}FRHDgRnO#Q#U-C^A-YHAzgg4T%^ zfT5UUrP9zgG!1;~y?UlKy%*}N2#Hw+^T|{6+|stQd7Vod9abu&XJ-I|3zTY{NPshIIhMP4(e)?%0Uv@SDj|pppr_Jb?SU%^oes09s*d=hLG% ze`5g7Pg|}#S=k6d+Fsg@%%xAxPEJlx7nk#=$7MiN?f*(I2$fs2BE8qna6zlDpw#AvWn%g%t!02^>Yj~m`Jc$>iH%XJ+e zZKMxoZxEm;V0$ox2?Us2H~)s3I>H<)HIzL9C2*B2%2% zuoz$qGG)~AC_jk0_89l)-w}Kjrep=sU*p1KA%bo<^)Jj!7x@I^8msO> z4>V)boi5cC6{?m%cYKi1zpQXO7Sj9MjcR~0ZwA;qj*h|~Zix)e+JeBwbFm_`UgUBj zgZ3CD_k(a;jH;dGQ*p3Bd%O`FzipXyFXu?vx-t zRRt(cFcEnGVV%fzDOH|TTM%e0EhS#yS{w_?&t<&+7NqhCIwh;+O2Q)sTsc~YfC3bU zq)x}416#3Ue7ioXI|D~PEaz~kUWr15fPZx;b=F9Tzwr0+<&|tGXq@ z-!p+0U!6Y(5C2L=UkFUuSvc=t6~zQS+H_VW)Q7oK9zW$`$z@cCY7+mxgHfQ2uQhZ-Bg6F)mmEz|j=0p4I}11k?as_b+mA%#j1I8iXEwQXk2s&yQGt+}5bJPGb zYs;@L`=D=*mVrBcjz(@?+%AG&0^6ZbXHPVwwQtYzgjukZEJ2bVC7?Lfli&RQ%4ql> zZ3Bjstq?yQBdHTP-^B*^9^)d5i0V_-08a5k6bqU|cZ>@XF)H;$15M;U%QGN@6}Z0a%$-dB3&%`n1N7*~lrtIJ9})K!Z&`SKbd?mA;INup)SGh_}|FuM4}K3U^9Fb8+f3I)=dOLQaPRBqE3YvwXIT1%t;9*xKkQh>Kn}+ z;Q<4<$i;f+^O`#E1n{wLZ`^)rpKs3y{DkQ8RNlH1vu<1qB`m4Ar|D>VgG6BuM+f>~Dm_|t=53>L+p^5?Ap9utF zppJ$KnZyZs@R1KmMUXW&i^`seS3FLP#h)k*_YGfPxP+Lf^-x z_sPQj+kVNDcrI(6;l2Q!R|cD$^7tp7bf7;!t@&f~h=LG73c#aHVNd&EsO|JDJ9OOx z4GDygnsW{dr3{vF5xpd#k62wqCZIlHJHXZfU5XlU_yV<>Rk0;H^GfkD(N zC8;^cd!U6lfJ^KX0@2Cm4 zd=8d)ev_63t*c7*w-JRN1{3v+Dme+gIiEr$x928QNy2pGAlduak_Nks{AB%r4d$fH zGhrW1qRbq8d%BIF&*L}E-fw%oD&cP&m%}Rqb%t5mz_v?@_2O7|JOgdKNWi}S@&06z zP{QC}7)~36DkZQSelp`cI3;!}dXmDmA1C4Sk2IJkXca2?Rq1CeU5pr=Z$Eb|MA79r zy57rE7PN*8KqGRYA39>(eT2c|(NGsfr{%mU54|>P>rf=dU$a zVl0M^67U>rcEgp*DN>+P_xfhO3&BA|ja^IR9nZ)3c|`h+cLeVW#xuq+3uv}nG%A6$ z#JM=Sf#pn?8f_ORN$Xqfs`b>*IN!zY+eSWe1i~INHf-G~8xDL(&1R?cv=sOgWv}k5 zvteF@Dw-i34yuxg_Ahk2WZ_t?;YIDiHl87$aT0m1go-04L)r0u>_1x^n=umxKkx@T zXKB)YVqzl*IYMPkmI~jo$xVn-{?=xiJ8`YE6AE&DmVLZJomVQhqu;I!nEhjZSW}A& z9aUJDnK_|~5?EL>2L>l;*|=qJIbzC{IPFmO%Mz2JRMpR3A?xzA_EP8?g@56F6FM$q zslHsKdNUki-|0=HpNsVPE(Hds%j;8TT#?q*MZ~(-<~C%b_A2|X}`fHdwvLeljj~n5@a2L|D4uGt&g#XQX&30uL+(&sRQi{`=)W|ELz*%Z{nK;cEHSxzI zsrA`<4Rz6Z8InRbWPpDMuP7)CHtM(&gT2jMVmcA6EvW4pd-}Qk^8M1f ztkSjGqJ~jOXiyi^+0T{nVA#S8`(S%RprmWLq)G}RWd2UQ3q_lH)oTEP+*uVvg!LsN zp4D^TqM1J4uq;@HeYBs!V3ZI;JIi2~d7$Bqe6W{zYP=5{*J{>)N}3r95vhNZ5{>PP zuI(%1IF+xoU4$(JU!{WLTR0_#*HMh#ml-ls=i#wjLt?A2l@z+gU?w4~g&W3HA^s`4 z4F}UB7IHlO-A+nWfeRdy@gjRdiHelQl{X=Mi%^&FKd0*<@l5nI+3Vc#h{rC$Kmoe- zvpZ3bMn*|-qZj5396y5q;CzC9kn7s`b9To2s502|i^nLOu-LIIk#*-sAS;X19xv|T z{0*ls}liCZmq|f?Z;8zxgGkM?Er0=gxe!}5B)Cfts%zx+KRG~>%xK$^Qwgd zxLTF&cv9bZ<-o^?!iTp33(@-}y0vl_)2I~G)HF}92jl3v=#<)O=E7Rmdy2oglf|Hk z9aQ(|WOUn)IJ?Ev)&Fx6bF6)kaLn)DLr)thofgM!&@~!rT^O7bt@e5Or7|3fA$%9Z zdcgKVh^j?@4Sr`l^A=M|1^Pj?Yjm{L@U2TTmvgF?=HwY>`I&p}76Dqk08?8TUT-A< znh@%m4Kr8Z2eAG|xkt@vbVWTWWo?7J*w`48u>8$6i$5I*42V{tPKX%OlI`)B z()!3ib)k>8#b55^e=w>k^6=B1ZbJ{JnSv5WmCH4hd6f6{<7;|@XRLCWiDm99yGhA{}Wd_r0D9El$(X5~ZD@6Yeq%JJ_WnN-%QoT_^& zls{`|J%9EnfAEk~Gyx};)G-ocS*iS3?;B@s#A40HNR)|D9E{SnkxmA^FH@JMsvova zX8&ayT=lAu;Am_z@Z2<%$ z6{BjEfS{w}t2VXwOJOAH%tlL96JNh1#=Wf*>*+C=wXQ*vNIs(oaU1*ElJg~AWBoz3 zYsEM6%XU&tu#eu|7g)PJi(C|&tXR}Xn&hnaxd#gx>+j>0Lv??-YpZnq{-}DCX85D* z_dAPe6Sn6vuwUIAo->ylZ}KI6nQVFL;mT@J6n=}jh-Pjuf%pEv++Pdkdj*Zwp7DBP zrhTtVw6{gZP)&6$66l-|HJ4w8%;eg~^EPs4nrqIew2C|SrN%S*vk{KJr_g;`Y{qKK za@>)WYnnH1$Y7g~H208STe0$q*DizuUr(^Zw@=B+o)Nq~aS$e4yGfT@>daH^DKIsz z)cwow6@MRvpi+T4eltCU8Nd3QQI$>-+ zFgW?Ai;?m(M6`3~3t0MUNoj|7dB1(@$eb{5jiAiUXxRcsX%N7syb8a-?5DbXQY&dt z%QtBuucYrm*1Dmz5?dn{A0>WU5x4YjETQ|M(8cAmSNvkb`2Ku7q`f}>zYyO<$8g@x zUzs*Gk#M%Gr7AVQ9ITO)uwuolOW^S4&Y0P4a>%SIVE2Gjj|O|=mQu{^v#Iu?g_u(5R=+V-wf&8^chyn4kgY80C{bYAldhLKCoo`h9f)w_=Um8!5STwbwF{_U3Tizp{AyHC84h8bs|GATle zy3F*$Rqlvr6MURu^<;ctoJ-C-Z#8oO_$tvow?$;EY1DOi-(^S-2TIzlGbRuwb&;-U z7yZw0dus6-cg1D}!{`%wA1C;jA;~pKJ=T-XVnJJKHRncn?@V?ZaEO-)De!(_{cb?PQZM`vF>be}<$+yB>x!n%iMG>Ka&r0;UkQJwE7Mk z$`Z}Z4DInTXYHvlPzHtdM7q)!O@~4(CDCwL6=&P!6H8`ZIu8IG){ebnFOOsgJi5#J zo*23$q%3OfclD3VJx10L$%S6mR#0O{Z-fm;yH{W~(%~1?#@9nDw|X-FV4WFNNE?u= zNsUpZB9>X39R6ko>B{E@palselu!fi@;2{*99+kw!vd7==a0k1U~mtD?VxZfC+5?F zS*Nm{8|Z%mvGF+lu?k#)zW_q@WO_h`!~-H-wk-C(55!&CS9;0~tCO{qo!|0Ld`A4R z!?{Ezel$sA7!Q>QFASC6a)j3Q9elimCP?JOd_Bc7+iW%D38BRl_}=XI4MruG!$~Y! z)#3G0Ing0FLqmnq)N|04xKy0c__kp$%3zYQ=jbnv1!pZF??**9r5!AA6QQz8HaBac z-)DvlmLg^;&QlPoDNzVPj2csI+Sp_GZ>Y~5tTw?OOsB`~G>Igi6#!z}vZxRn z_mZ3%^Wj5E=1-Gbo9g3YL(lz--KY}z4P9;Rev`lWf1j9yQ{VAp+Sf5=7Hy=={c`2yJadWY-BAQd=Lk{ z_R5BjK&)=KT9B)gLV{1>rb2!28ThgAIW#%qO5B*yF`N0*A1srvHd0v*yWIk#^?)Ts zM5jSs*i*xFz2D7|(i500ZVx1J5^<9kp}e$hGHAC2LutRtBH%ytYf07!h%N|p$O_p@ zM76*Ze2pGv`4>e77PC@W+j}V~VvZ$pJA7_u0J6SUt6#Bso7y)~k6x^LN|Y_7g&3t~ zc23kDyJ8C;xg3Hmb~#>n;^|83;U1180$1Uh7VPe5U0Yj3=xI`|HIDic);1 z%Zx)#tB~cm_w^{1mrymqhd`i6ceMi`P*4dL1i~7qi~&@l{y)Y0VJg~EDlzW{YoEjk QxT*u><#`b=z=h}h2b9~@i2wiq literal 0 HcmV?d00001 diff --git a/common/tier4_localization_rviz_plugin/images/ex_pose_with_covariance_history.png b/common/tier4_localization_rviz_plugin/images/ex_pose_with_covariance_history.png new file mode 100644 index 0000000000000000000000000000000000000000..24f4be1c8546fea5c9cd65bc79fd26ee74ae47b1 GIT binary patch literal 300066 zcmbrmdpwixA3v^x6h(!UV`t}Ma%RO_Cy|o#VMWXNIA>-hQgZ0%%#u*fhnx?~aYc+| z!!U;!u{n$lv+Z~Je7@hu*VPjS9^~LqQBqNzsr#a&KAZ7O z<>G8|?n&i~v#F66HD;bYRaGVBzc!WMHNe4flH>Y6m+uB=EH*)(iCRa@Ab+#^Z6FVt ztzMjZeeu(9Zl!V@t>yMT8|LeIgiHBh>FtxVr=s6u)?Qcb51kv6vz=H`{dl{)C(z75 z(pJqawzwj!=6&|jw9gOk9o;9JeR~cTyIvn@ows~x-$C5_+@l9&j?tI0H7tp>A!k$y zKW6oR!E!|vsGO!S$00{JL#D#fLgJ8!?Q>Cw_4l9p>&Ny8RRsNqU-t& z*%lYoG)9Q^l*W~`yj)KO>ShJA-8XL1=lEhWns478o#5s7Ur-LEq>_CytAn){+19y!w5X`)q_No-8~M>@M1#`o0={$_S8Pk!mWu6j zQGJ;wU0q$Rlxb34Q$yN17~h?!tICxD)wT@m)yy)5VBf^YANtSh5;G(_ogu{0(RPA2 z+FpZ~tDjd`=w%DTtNye_y4{>N^^3rIuQN4rfzDeks zQ;X|wzCW1UR4gtoW)6RNqsQ8q&ean7_Yzs@KGR(>f$esTmO+a#U|ZHBOLPXMdmemu zSgN}umKv#~o!-;up*EI0(({mCTU(o=CBc{pDYj^%P)Zn?2sPnDze6aji|NKXp=}s|5xIf>)L|HN`WT2z*c}zOAc^dpv^SDFn~yzmz}F(%*k%RR=RZ zF5Wq<41U4kjy-M5=AU_3X?;1a47!?p;KZU64A#-Z$vHXfF*~dD#p@W7EGHr&vayng zTpXbe6Ny30A$FZOi=^1JcC9WA;N|7DlN+^+^Hn;2Pe;6=dNZVOQ07a&iz--pb`Wx4!^y>- zhZoc(vI9gDG2beR4%;?41f5n{Qe;7^)Q^$V4SnKRtX0MgHdzs>fbhC`o*%5ImEgtM znCVpp6An*(8txRZO z;;yfM{uG4GHm>7rd7SQWyZpNXZ3thc_giOwyRIL3_x0I1Is=aA&&JLBmo+z2BD__F zuf1-6E-RpixO#S&K-k04NE>kn+dMi2Y}DDQHK&K8H0t!U6CNcP3O*Bjx2>}Z+Fyb< zrgsvPk|Wi+wH12btA0#@V`68Q*PG-&(MZVbE0^j78x#BimTR6gSowB0UDLEy9s~pg zl*sp15hI30$C?pguD)k}Rr3+*;Ur#gh`fQ%>HHJ^iQ&|AV*AKQ8oyUe+o^p|F1INE zsI7xO`tVZ7@RdmNSdeSlRBxs>M;1k*q!3MfG?07{EKw+H2HIN{#M}zt$cJ~9Gdxv= z52-uwBwm1kuFYM_OF8eQ?RxU}3SRunJwI9Aq$v1(%oL?(dzH#g8>s`vG8@8%}$T3fmuTx?1(_gS}D@aDxqUMaJ zt&VdeeXJ?nUNvU*=7)XIt}+arMgv8TG*w9twnoF;7aDRmQxSp5M+|RI>d_hNcu*(l z;k!)mEhW*qooHLu=n$&dER}jRjfq;#MBEo9{Dj*ry;<)hKw*?GmZmb*vYP_J{2 zCqf`~S|bpC+{RnPNNQ%T!p9zw{ke!qsPWF}cexi9)^Kvw)5~iL6x?XtDp1#PT@hKN zx^xJ^GK(}9*f2CSb|nJ4PaQwU1BJj+fbWIW^z? zDx^@GKa_-;CFFZ3Cg&Q`FiOJlvz-%k7-N62t<+!xU!rY!nT%)X@Q9_ZNY@l!CMln$ z5O#tDRuCK$%-;H-hN&$tKN82IfuQ-tGZ`(n@)y}nQv7Yj+M2PaNpp1UdbDj=VscZv z?*gv4)kr>&wfXuPL|yO2KPxH$g{H+3N^grC{hU;s zZ+qTHUJDaDA2ShM*@a@&okKS(ctYXcIqkQPOjGs+#@^RY!JNzCd$9 zyS0u*ieIpdkC$GPTV1%x&#+GAuuo!6TC*OmbQ~Lp!W_xgG`kb5A&(m_wr56&64gi+ zbN~7hWI>;~y6J_fU#tvCT|sP2#_(X@?6LYc!ixC5UC|Cr@2vh)8xU-RDU9A7E1``f zv2iDG9%@H0%FWxWM%!!o5cy|!cGmf1_qs!=2nf7^ z)23P+k=bQiADDHeUyu_-aZqdxJ;EcxL;%B&v3L z6ra<--`(BaWV`ZoqTp!AEz>#93DL>Mgat>a!oJCKgRz%DF%KFIRL!C9&30ZAFPyj%U zb&}wnfYtEou=$_oz-4)0{WJo-= zjGmmE`?lUs4lHkIc%hNt8yx%$UGnt+?CrwAj9LOY5G*0eXx$U^Rv}tn6aayP zY#NbeyGs%4VxYQ89(>P3`tE6Im{QZC5X;MidvdF|vCWHQpq`Ae^Gchq4 z)wm{LSYo1x&mj9Z*w>VZ8vPf2xm5`Rpi@H#_`ty7lG4!-)-?nVy!|58FZD!X@GQSd*=PM zhK7e*9;md;&Yo9OSKq}UDJjW$S+85AsHCKx_CZQN3FcKApe1%N#^85I0wz)73>L1M zZcG;~bLygwcC;Ww>r1zjIga%VRLH@-=3skigI+ZNgK@9FU?zJ98(TxGdn(}ijCk~g zo(kgu`@oXuR$ZShI;RF=+@U%A1i0`3sg*%C7Y|mwA=TM7!0=t@tIm}tM#yRk_VrO% z2s^w)g5u5rKIY|8yn%qBf=L5=xEW#*2EC9~Gal+*q9~F3=-9uO<1?YC%8$e04zAak z0=;USlAmu>HA*RH1wS58Yy()!t;!}F+qd4G=dwO9)(p06@apda0JQ8>$g=7D7ceao z0w3qp!^(M4JJ|H<3Q68y4?9n198bhV2QSu!$R*rzXFjxk3SbgA5u|0#EG-MN=*Y^3 zyGUB4X=6m!kVZmzeZ7s3r)~Mjt!O(=O#5*>4mZjwqpTDN)ZAV`bCfZvX(WQxAFOYl`^-)bG0BJl2&}28sSBQD|HP0K{ZpG?TO4AD)>Xf2^1i6Y zl#TPW55x|K-Mj7P0?icO7;(+&i^9%tBJavzyL;S{pVl9q1Ngr?L#w7oGCnB1j}!)U`Ws&l}qgEB8!XVEippDT2Rmk z!E&N(e}51OsNUkzQqI8q#CTKKWlO)DeyNYIDE?aDtSX4-otg0^K2JS+pahCe_%G-W ziZfBt(g=xzZh#W<%k83FonOcEy`bXPc{A5PXeXNtSrlHBoU)>S3TU>jDG$(`4WUHg zylNIQ#^PR)$xBPqrK~@thfgOsktQC-g=9^$n2g%+O%?F@?xfJcrV>T3hc+p(p%I(s zD&!2(@;Gah81GLq{}h%wIy+;?yQ;B)YHDiBbNxAWHXj2^qceV;(x;zUlC3reWhET} zgK?HNZ^;0z)7iNXfT0+vSnd+EO8NKt0z`$J?3epul`yYwFwH`gwvG=56-xH@CPi>Uq}pgC%fq-;>A0@Oh!je$@{$Hc^3d%c&q*&D=-2M;uE&ZbAF6$EY2 ztP_YIawh{e;#XxWtwhb;2i-{c@X6GDlSU>)2YM1by!%I$_cid5k8=n(?7znd3ky@| z1s%Qtu1{@KBRBeGc^)#0yZnLnUe^D+AKREXlR z&CueL)-!D9%o*^>!kXyg1VriC`QO$d748Fvb1+I<*TYWZO+!cTx4jUy$Frr{tq3eHePF z(oq>>YmOhvYc9QkLL>>v>*IH&gq_HikuQtyq0M8Rtf6|{9|_Kka9*V|96obag}?VFRh!({l;-uN47@7%3S{$$(&>qbuY(->OjGhrW$wtjBpgay%Z&33S@Y#|7G&x`Zm?BYL6$H-996Ipw`s-TfXAng- z1qgX1L^Pdc!-%?5&A^@rOB`W*%ad{V$3=(b3tiLE(2&~pHY3BELYu_Tzqvl?y&F4S zndd>#$8Pnd)Ithy-F{iW2(Yk6zMELi&Ie`=g`lD#qU zgzqpWKVWF{M;LP*FVrc^^%wQqPP=FSSy2mDCwwFM`l(59mV+=qRXg~Q8wSa4C#32> z9m}0RtJdQW6s^;d0jT~SL5wm$8XRA9w>`n-939PYr?*D)^d9gqQ{sy;NEQy!$~!R_P{)e8 z>k}VuGR9b}v84#SChoDBdVqjo^u_yWUafB@PvvW2Tdo`f`i+DO; zZs`b;Z>XvHCW8e(`OoXKaPmm9z}%f0B!9R*qmSat2#Rv5z~0beBr`?ozTIw=gCU8J z@=M&bay7Y{-wZwUxfhmkE9ua+fnU1nN%8i)_x>$;1-F#%o-N&DE^WR`K=d|y3(8)I zBqWu55>fZM2Uwk^rU6B%{!_TRkbR;5{qcq%zK|?{L+&{{b6tP^zTZWI>wIZ`N)EsXYj9S3aBnrWy%LhXMC9VYUjdS&W3oMe?=G>pK)#jQ07ruE*J>e6 z<3hW5Ryh#OL49d$jLATKHIvkwMs6%;+g8H%N~6d6mOypWy#6?!dVr&}aWz)^%I(+X zV9y3&w_7B(cL7e|%Vr_)vw-vfk-Ku(pRQRt<9w{MgT(9f$*=!sNN*{(w+} z*$97MCI+M>X$l=%9yP+J>29EK?|q8(BdpGgp2e?lxiK$%v836bJsoHPYhZ@16GEQZ?5h~i3FN#P;I@Ns+7+Ek6;!_ z?cUf;xO0BDyiw|f{=5QC6T?Sgbc*2CBAtq-Y_EZkRA zyFB6Z(}i^{K*Ruqo1Dz%PYf1Y{sr3t1)Dw$|t^iD+O(NGvtc z9VRby2KxC;;qn0e6(Mds<@c7>1M(jr#x})ILz^7tk{P{u{MA$5;G(RQ0=jm$E8|QS z2`jzyM&(#j)P1Kf^DfDCOLbh+8VdW77VpfZB5vQ!+SZStHdv~!#;qskl z#s|btW2vo1JmDw4B0qN`UE8Zq99<<>7I~m-vWX7pMI#fI-H(Tr6VyH-3xnYUz0{h7 z;d4b+p3uNac+V{!V_rT!`>u_7|35bbl%70_FCO-&M>`30o%_pEYcG{1eZIX>q+=vz zgg%6NdCh&{>8fxn=MGBDuuYmuQ#`GfZY&A}c+q@y@9}ovhZLr2WSS@o$G<##K*6pS zxCpa*`5}2g73iH2+7Ms?bE8o3pn$t2AaQTryovlq!ngkpsT@8Cq~;!VqTI&_TC~2_ zZ?~#6#t$4x9v)@;_}zwy#zN7-!SX6zH-=_(H`q_!;nN}thg1v`nM~%-CWBMYrb1m< z!?&#E@34%vk1nS7jIu4HWcb^{A9r!5TX+!1#yT(($T+}h8_Ti;>gQBzTCH>X zQ}}mFi*CYyjNliOqp~=`x%Uz$3tL&vS`9Ez>)*!q^H<^uI>+{v@UV8VQfil z764iLBJ3b7daoXJqjG7sYJ(TXwh8kd4%m>Xu$FVX;6IA?*6;NsBE0eLsX|=a3?k(g z<6wEK;)T0k2%e)2LD(MlJ*7)Pj96lhFUe={4RZWVy${RY-Kdg8y{n+<2S{LJi@mJ| z6N)hlm}5Z40~m6*MkW`|W5$kF5xv6S0DtTm1I_?2y?_TM9Dn70qOXMf z2r*kYb5w*qgWgVVMYPiR`1n?UUiYI4M%Rp1t?tmQW)N_nX0h4MkH@?{FujGvOdGXv zXGDpd*_&!^oThmE6(D=>?|g`HzaQ_AFp!1Sw6eFCx9bk!i%*A>@h=bQ=IBe8dLHaH zwU8tTJt*ug4dqqxs&;p3Mlb^B1FCzytUU>bX`3DH2J68CssX(e>atuIZfSrb-zi)m z(L2&mEnd!)kfNj)pi7&BJ+Q{F+r^ya@7Z>zmaC@s z2X1bmZT!= z7et{mDcmV5!*A=_CJzGue&C4twBn0sstGAo400eolcbbz_BuDk$-#-h9iIw`*^+vZ zTJ^lJ({uV`rI)uiAHer@#n${61qz8l->kLQP8L zVQ)#rj$SySf$*K(*r+|cRJmBCk)WJu!h^^-*KDXP7u$n+V~A}o(Acgn_=)EKpJub0 z+SriDh?d#}ol-wwAE z$QR5On&c^5WG^o(N$CYO*o%sbAKR*?md6FVu0+E+E2^uXHUuptC0zJDd$7lFaC^wf zzgI=KQ1R03OL}^Gfp7z5Uj#yI3C-3UN6^Q9A}$<1n6aRJ_V89%S8UDBr7O0rneF`j zB3|H6S6M3~Bx{fP>7Ul^-$>`|EDn5V?#^&jG7Lc~6y3w3o(FU@sDU`$B_gOu@^C4L zVi%=~>T~Q>;B8UdXEy?kJcRpw9V7Oepb3k$ng8@5I%SFDL)R@-q7jmOxa zz%36C4`3#R-H(Immn)v%xCk(^^nY#h436;da66Z7)R`=A!di6Y%jL=<_b{Li$0U(U zf6N&)x2@P^0rSLZDw~^#HYaZ(|_~ysEr$+Zb;j8TE07d@vNWxLcyBh zfpq=hpx3vTR}5bQrKzNHx6LzCZWl;GWdb3F9I^Uca${BC2Z>Jf+Pi zgOc8UF>k#iirK)`G)LDEBN`^A^a`mL&bHdL4BWc!j+xIdpQ$Aq?X!3<&;NdVy8BsH zc2mT$`wKd|S-`;ie6m^2eD~UENjd1ZiBLIycE#ri6h_10LBUTO#f1^*(*ozy?sHG= zwwi(7W zld-2kJ9qZNc<103I5{uW-)$IEpwa21k;#<;Y08W??7xj zoeVnY+)-ohttOxDX zg%1I(edl1^6?I>B;u1jp>x>uK7{*3C1+7=7_DTdK8|$e((L5q}QkVMw4CqDqp2cU@pnJX8+GIAwH z84tWuV7~*V4|oTVm)1kYfIYO)p&0QP!2Dx012hryK;<&{353J)%E~9I#-u3{b2@Qw z38E@=_WJ9tX>+ndYhE3s`$CU%D%F5A1UT(1fVzJu_SF)-Vq?qJN%w)Jn1uqTYtTjE z#UUx=mA6M?FMdfFHNr-E;#p10P7{@1*|v8(Jk;Pw391g}KPWqksA07H@5_IxnH6qc zbtDG(a`PGjNf7O|3mwX*4&^m#6c@JFDNcrsR2sQoU#@6=f2{;cwE7;9Z` zOrnhU?OaX#F~;OZNHZD3%E*%jDG|V;_C0y5-N^=l0UQnoggJ>H@$Y!Q_GthKa#B>A z)#t31r5!}Mrz$)NlvxlR5HoTSmxEEPi8CUGx9|S|QW$(baQ-wXtqS42zHwJ_^qF(2 z#>xP%A)Gj!OLF2dw(=IcMH`Y&0Ue76`>uk4!4Offx49yG>oXG2eIgBGD45rVNKGH^G*@d7r)?g*v6b@bc_)BV(xHux|6B9U++MzWr+=TTMt;QvWS5UFlu4 z6QK&LsYgPeMuS@NSBF>Jo4xh}``RR6*u8M;gLdKvZ>h|D!9e!fEw;c8kvO&Pf+lkL z$fyjhbrtc2I~*H4Sk;;vKXA*O`~Azb;ZpnV`nTETl?b#qBnyz{iLoGJaU3IL64OTx z%#;Nw4#66)F+bN-g9YJ{nC>-$l)T~IkWbalQo5diym+V;-aOLmAs5#K2o7keexhGD z|70cg5Gs_P24^vxQuVrNi`JMs@3t6)?Rjtca(~dQ10&F}jJIKAxz9t0tcw9?T`!2N z(WD&?&0e&-TQ~%XIHq3JByLr*uT1psC|$(4KG>DTKUg!OXi!eWtb z+WqKA`gj=MSF?OcADQincvWNjEf?9tF{7>)dw=_8b>ID^R;+||ud<;8EgTh#zXJB1 zmzTPl8pnTVZ=oX3*IaIZ}nOql1M z9olHfI2LJPN42tKFb|+tJ@?F4M}MX4D*uG zcptRZRZoBDt88i_<2uEi4(h=Yj3|j<+2}J(yMc!JIk$V6p3*@RF+2jiYoDg$Ib)<# zS2caoLUmMeeM6qaYU8Z#Dyw4+T-&-Z>2&Y$^zA0OHjWjHxL>M*U)IQ5!f0u8-**oV zwO*N&!IJ{hA(P#zu4%moW{we0^kO$kyL#-Ok_Sr4i>tf{xox^pnNDHQcLzGv-b6CT zN+I@wj1U%Y!QbJAXV3#hoUZph|A|m$kGPl0o13Y=t=8&Rv6Kz)^gIMATFE}x>$9ME zrSv@HoE-3`gW%lY4M4O0yYZKAY4(ZTYp-vxm+z3t^TeKzP29p43d;;-zXQ^pK{7Kn|YT>v4sP9UWK zTjmU~BXe@jaNKf#(CNGAcwg80eM)Nzb%n)Pa)QJ8L1DMfrkq<4Wvsh}}x}&C^!=X(HZEbCJp+gZOc6-Kos>N6+ z*a_hNW;DFQ{8`@`4IM^NbrgTK=mKGB#p+eu?$s)H{IUeA4fz#F^n@T_fG(@-gMQgh zmS%ao4{Rx)yB;~|Ge_fF@M8pc%KM6fP)MCdH?F-jUo7oS1@-Z!F!{wD8YzVGM>4tU zJLwcDOf5Ydq;tSd#b7Wz?!UIeFsxow_h<=#O%!!oks+4uGF=H31~PlKK}!zz5g?2Q znlWpK@lYJ5#Vg%CP(-!nLd()AX9#0>lqiYnt356h4GMv~lVo*P4WeWeGeKy1JV%}YW7EmZ&vVoJA{!h zS~>{?%P8GB9Hfioj7|Dni#8#uhRR>Ij_c)6mkqU7p=iX#8=BeQ;A z@I`5vg2|pD0s|lb0NQ^>L!(7u-E{Nv^<*a?(@-y+N+kt0*xS|nA0RTu>2}5UV^;-e zi{cgfMFGJhy3TlPNj}0PisCCyVv*p_!c@Ot46r)T;8Gj)ifeBV9&tlq_jWEg-}^=l z_v#UK6@*&P0cj|Dvl>nSxltgD{>Nsw zm-t`A?`nFo4C=#Zea3Vg$HWFTfBS>NyH#;VI;Msx8=LI}Q9;}V*e4*a3X);H@{COq zN~mNKtwLAf;{#(Cyt^TwEqr@;9dbXzT~qD9VLoyfg%Lr zmmpNKAH*X}II1Z3n>Wg?1&5KV@EK))66<0M?$$S7g5jI~jQ_41O?>nHqmp<-vi|f3 z5hMc9q{K@LS(!3y1et;z)p26#%WgR(2-J>fc+siQt=yt6L^_TTY~arK7HdEFVt>+0 zxWBaqRN%U1sakPEfF?uHnPY}}52~<2*Tb|YTcq4Rsk%?^O)z=$+Z#QWTEbT1S<~1*xS^ zPPWBxoZR(S?yCKT;k8T4(XR}5#{_sHc38>Uz%3!#%nOrkM`Doj&**O>Ww)|)fG^q# zB+vB)e5R7oMn|*YUFkn6SL!uW?+6E{;cD;;_ccV1jn>~hfB-2NQ78~E!HcB#3uUiW z3Gf&3A5RIIT^ZfUX!qw_1=j$;%r=lUVPV;ukl?kse!D++7G$bVCobLl4bjrbk&<~9 z3xdOUtj$!ZhPP?M9%=xVaYsf7o=QGr=)Lgpck{FzEmW5j^|7Ika){N~&|vE$MG8sS zi4|RiY`x-->>ka%N%wH__>YhelCm;D$m5qU=751%SFr`pdgxdaASS*omm8lMQtm<9 z<@ld6g=CK%Na=o-%+kc^vY$w7zxPQnw)S9@AvV#3q2%ZJZrIKF41=k_Z-Penpkbr4 zEb)iJbd?srBRZJaRa!0=_lv;Z7iin=q#T2D^8RUeE?L$o@d`YUR~mq z_q$r@$u7p&_;}!nV;-}d&6fa+FKcSDzou(nia%obs^O|geCOzkJ>l~pQZLCG*_?pj z4nMpZr@r>#@t8>9!R=Ic9RN|OmVXZtJQEU^Js%}{=h%)#V>|OxR@-EyiSOlT!Mai>U|BVGnZkH4lX*m0u zkIWdJ7U@_~2`_)X8wU(5u)Rtgnqt9V!Odc~6;4Bm65S4q-j!PstNh7-h7%=?&5|9% zLDpiur`l?1KxjB+--$~t#TlRx>yS3XT_+od!n%dj4CrU+3Y;>sd7G|T2A)xr0H|p- z^R0b%m1C1bScG-jhDv#VLfvBUa5;z~^W(THVV@}{YQ%WxZ%_&KMQTcnvH&N~Ot?0i z)wt?B-c18!F+*w*efMx$!%O&}9x51OlP?SPnxNJcTq)~7s}~Qbfw=BbPSP3dt;)+F zcESln!(2AkMDGmPgR7}2r2LCdJ&h>wgyjY zWWlQfK%W4D8Q2YOcYp43&hGZq5eG;>^GIdC%MVSTVIpG*4fVmQ7^`6d07DI5=@0^L zIY2BXwI4-5npE5QVkwu2`?y+qPqe$kx!TQMO~wUG1sV-K{Jd*qIlAHH%ZHg!is)^> z`+D<3x!)etfevk3S)g~IG`|c#@9zT+x|1rq zyZ+)pX6Y#)3i+%|bwoZQEUYV~-sCQ4Oz+RFuZBC~W3UI2yqk;Vu8Y`uBvW@HKY;5| zPEL+~8iIY|@{ugXrJ;lSZnC{F3@VBpu3&-|SBIXL5qZ<2!to=2pvJXZ%EU4o>7Tq~e(*w>rYLzYJCrb~47^s+<> z$%F&~w-ODWrvm7O!bO$n<_L5mNXGN&ZG6>S8iL^4xbt>&4_T08)XJ={1#vtd2*`9w z#m?&0C@Ve*`1y3UJ)xh-QzX*0lNugYnxP(5(gYw9S2tVem&uMyLunw z4^YmkYz}dNY<~jayC50~%xmzA#^ZPRjYzk_U}hc7EJ*VDl;c|I^AA$N&QE{b_*>Jy{IsA)!bA5@33@q7ZdmgkyRi6IaQV%!QNTe<`dbPj^vT!|J z5Ow@z94OvZQtbEEda_rmswh2?H0X8_7?c3uY3xdpHlA0lq*Ur)S7y__ccd2}u>gI= zMCrkyF}y?Aq3M<5XhsA21%P^_iI4o=fEqy9n^-V)!Wu+xS@xD|XPVf{sg0E{WgM&v zd2DvO21FWylrr4}nt&7ny2r!HRQ`*hOj}G&QF+u7H7=hOy4xUXzxpZ|vdf;@h4B zjMd|GbtijZMYgnDKGm^Ip(t?FmNNjT{5)}kHuk<6LVRv*AsJ*%stLGc=2PkV4x#@! zL`e5Zu!l;jK$akDYwPn%?5am)$vsBKH=*Vy%3gVEw9*Kt{5tCMm|0ho`Kk)Kju{8Z>P{pqH z&j8!j%O|&JMKTu_m1UELZJN9NlFC6zB+dQ-nNY~gMaUK_#G z@*1l*7e)u{r-e2}iX@m^)V{h6(oce&0>TEvD}CW```|-J$dV{(rXI|RjCMD_{DZZ0 zL0JW%mbhtz3b+UUXTm#ocRCpWlx8+_DF=jfBIbVmUJq>Y@Yrr5?mQrrF~!ng>Y8$v z&RpEl>KefEY879xpY1-JmSc)es*vLd^a@Wtza$+dw-z4k5M|fs95O2hr02FqG=s?+ zjVLGW8gzd^-%!CvRq$j4C@`Bu{LU-Fiy>In5({B9c;2VF$qq;QFw~uu$T1s5J?!_l zAqp|es$tMW)}6+}X!Muv*dWjT6A$g3Xj&1^z1;P7=l52E2xYpu_Y}avEonK~tZ+*Q zYaI?ya1Dd>I6uqaKQn)5Eo!J2K}P{c_;1=83_sB~fs?i}86$BlYSvW3-_54xyi?9X zax3OP&c7d10_?X}&wC--3R?IgMoN_fQUydA~(76*g>Fze3#1B)0VS0&c{+(_o4~07VVWBzsR+V)YD? zU_eUX#Jo2)5BK+1O}>+a0RqkPP8edVuX_St-h^Z~6Oh(Pbz1p$beI^S+QRRfpj`l# zz{D@n?GM4~KRzCCZUuI}b~44QKBv%aKWZ>QJWcVa-;fO^pNOxxm{nYvd}7a>UG@5- z)Ot;0Ga%SH?zGC1rM`!O9E3pYc$=_M2MJ*?pM!%s$7aE(OYAYJ?xz!Mlk%!z4+Q}i z1ME9P-^1zIr(#bh`!)2t)YjE7?{+laJakXk8cH^cR-5;!E&V1}zY4}lj-oKaX$II|qH0B<@+Z?Xo}9foiv9Bm>nY55cm1~=}I@rH)+gC zxwP_?yItUEDTw|i>TT@@y>X{TvsMy$Tx|@TKwa(L=|ca-?(U3C8@s~M3?n}0xuY@Ni+N)0af`Fd**Cc zwBz0+qY!t}J9oQtqgm==t07R8=hMfFExLA>F-1w;Cd$O7vFJzkRdVlh0%q#&}{*9I^(D#>M9^q+q zeoO{QH~aPUPR_{P3|g%&Ht568ccA0Ef?1yulwVejcfNLZe=c19iS+G|9%mF{)-mr} zw}11^L!mxCrq?8OK%XD^3HpZ+V|F%A#I}ae0iq&88CW1w?c}JVokUBGuXfdT{X~sa zmAS@g-U4j<>*umD5Z+sU1xtOA4?;9;d=R;hRu6?8kR>Q{9U1=WZGYk@#KPly#la^n z9RE4d@OI4{r&o-4#<_&)R`E4F3b8ZLINO()=o&X1ls|A8bn?&PrNFuY0{~7)B>JTz zA@QB`!@{5G@RCJm*!*ya0;Wax_PZNeZ+VANlAY#(?2%e&4fXV%I{yLiE*u%tzhb>v z^~v|mHgF380H)X!&(hq@Wt<>mbtoBKe`7%)69GjLgqak>#r^P>x%#|SJOcQh>Peog zQ~f{lUX#QtT|ZzKs%y$)I`2EJVK@ZvrE!MXeUOW_sMw6trN%Q}W=24;*=hQKmzP~N zpdT3c6ys=no^#DxPRHQiq0J}_E*#U}AxV%ur@CjtP1Z(e^mM;c?CBtrv^*D8;THGe z_jPitO@a5@SdSk9N3GDwy?QJiQC<*#%c|uGMV2(5w`)G^u zlA<6JpQUbJlw5Sy5OwtSE-h2AQ?FNHYUrE(pkk;+Wsrnu6I*mCz-YC;bOwUs)_@nB zVnx8$mpvW`YpvgUefBa4L*soVw(vt6i&~3hvLKCuWR|i6D50@!?Rn&C#KwH6rwAYrwP)jNv> zrx+UT)TCZ(Omc_!6Vh8vx<}eA;wg7An1HHQW^aZ;oB{|DQ=639{%;mQaK{t`GkJg3 z#6rOc);FpsP@BC(LB-sGP%A6SU?RAAr*Ehusp>pl)qxH1>cnt`~L^jYcIi+j;b0$R)i z{YR7Y?Ta29tT&B-8+I3Chg*~}f#6IT*fAZm!u+o@yeNItIEMcTt}?g3z(>?Z6)EJ` zyDwnjSjN1IB>HP*7TSvxIEUe^=6)3y>Aj&H67| z49Z4it-P$Nx;WYthCkpQnDFR>Qwk#m&XvJ!XLpNTPyID9qgM$xH~eJbXU^!ZnA2)d z!{#^?5!Ev{PZhZR8QJ)$dI*;UyZP1Z>U`y|7TWzoUWD_Ri~dW2T4FmpY__wr{F6e( zQhV{~yVHmr4{aU49`a+_ItxSd-pfJXwyM@sCe464YBz+sbLp=eJ_JwRPy11^mWegm zhA{+?!+`>Z;IdM9!txeAUb~NOtVtl6GFZn!(v8Q}z`*It)SWrIdQOlLf9;v(8jH@j ziaYdBTfpmS+x1UtwKL-oy^QRMLXrkiBf@)wqld`5)z_ig0RC-%4>IAv~ z@LNA{kAKqqIx6rFsKu9t zz!>Q9gJ1x64~Nt3UolrU}NF^0ygKM4Qo{-FQ-HKcD{1lA1j9R+#BxnPhU^WGit?yOu zU?;RP6O25=*8dFF>AKUOX9`uL&R#!dTpRytH@MrtRWN~`nM%?G!4^QJz-<;D4d}wm zwnuay;HlsS2XHTk>RaFdgrJN!1)2{2jf*L4kVDL9i0PsbDvmFP1Em*K!95&6jI*xi z(w~oGQnytHa0jr*v9Ecv=Pm9-tsdcM>X~ug5J<()|8syUO zU5r{TEm$YZs0E8!SPxYitUjlTH@};^k8WnbAgcswO9b*>|KxvZxOp;!R!3gC+`DTD zsr}Scb60P^=T+(V{~j39-?o{~heS9G3FJg@-(oN-KgP-%F~Bt2a;J#*L^^SM_Cjug zLR+3p-rA99QX$Q1zhOBg>}sOzN^u zRx$SHQ}jNV^tvZBA~b}67F_H8f82Dro7cB=I-u|8e5mMOr3KIvAkYk?)6}H(BR9-I z1c8NNZ%Dv>-{vB!=4}g?I|g;IJ7H6j=8g+Y4=KgV?tj^yc=7G)ps+9zUs0huCJg;( z32!iBwlW;+tCo9V;n$Y*Bl7mDbLS+cO8~!JBnR`6DlQj80+RyR#c@Q6p=?FIYb?0W z3ZSWa3?R#o>7|><=NR6-qTE)}ag*e$D&Oc77ESUvxHSGFpoS_j%fQ z8@;>NMS5)PY4$whGS2%zDFiqnWJlPll zD<47&f!n3jp{$YGd&PdMHR-UyU0m!^#51Hgzx+k&g^~*VbI}L4*S@L!e{8)4RFv!Y zJwA4TsDOY7s7Ojnw}OatigY?4B@8JoC?FuA#L$R1AWC%#NPYt(|QAk(`&u^{q?{csfVJE|*wdGMc3w_HVWbe8n=4(@OJ*WBY;2L2DsP}pA~4fGP_ z3&tHpz(6nlIbfc`lr_7rb>q$#d*iw5z=iSE#n${q-)mub+Sl<*qLnUy>BXWXvQI zpSH_yG6X+HkVHS_hQONxmP8sk*i_)a2XoCEPCN`n^i{Id^8qwE|WN9sk3y1FlUL6cZ^#=UJ6y) ztgos0!?5ANRYtK}4=-wM&Y`nWqmVQNnNyNz>bKq}_s2sr8$QsiV^|_F;*U|bt>N=9{7!RN5I!{=X{3g_9duD(DZ!6es_C+27RzC6%& zURjai;s-tr*iJe=+sfhKD$W@FVs;=Poz=9$4oBqArXnxGgzwahGYq}h9mef#EdTn1 z(JtbpWcCXbFSDj@*`rSb>1qD(&W^F@#xH(tw9l~!%o?sBTh*rV=q+ZCaYlnWn?`2nK$r*aA$jFqzLl2PU5<<%QW z;Sx%epal2y|EsUrnlHtUZ0n^K$6@j|0?uNTC@>GpWyh;s+tci$N&h(Y@L(=rk8gKx z{GeW?ydG`>JXxr0J;%Ik9xWywA7;n88pG&Hz*cC0{=2OC9Hk1v9gZp2sQJ2#a$cvt zC6B`4-ZHG={qjGiCcPfNA5$wl>Xw^D@2wlRyjg4V-!-lz;cmrExwxw9k@X9qo8cEW zI*$hU)Q^WacKXlcFm77GC~4p&G~*EjnkEe&`sXBiRL6s_w2Kr7E3KHwk7HaLIgXVu z8r}1@ZKhthN3_sN_86n}&+zCD#G!)i*zdR6$jWx^vHcxZeoh-is5)gvoj2Dx5sm-( z^UC9|68pXb$r+RzKYt>C(uX+>-V4IfgZ6$oT)66U{Rm{0Uf4prnOOx_oXMV5z3Maa-TL7Z z1_|OPipFISn+M>60K;e>zgGjH4t4ef)apD{eEFB+?Hx=e!8hrZ>$w{tn&CFX>5Vg) z)Yy4E_FxxFcDQVz(=+(6GiMFjV2L(t&_U06N)N?U$%#OB)c>JhJb&7w0Vfuhow(KQ zxOhVLUbVZ+aPM#bOY;%<)lE%9H}ideKscaWLZ~kxiC&)-uxrz9T|3yTKXu)Z^v<=R zUK)TPC4~1zlt@0?;IUdBh{ZZ`nG+XMS+iQ+xTbW?jMO7Xm-`(ZXFX~kodwFTZhvQv z% zRqO3z4~0@c;JRPBpINN|i?Z9@$dNP|&|U5OohVv*Tk);+?n=1&odT!NU*;tJV4{>h zGUSr$E0$xGn8@#;_G8e$r?vw_22x9qv|axi#^)VuoC%6^{f?Q5yg2dOW)FOeag_8= z>#<(GAbeXCT%;Ns@K`!TFgUVnm7tk#V5Cx`y1dp7emZ3M!Q!~;%B1s|+#+q}`0t+a z==JK8DX)MPM+NeZYvzgENyl1sK5#Fhu$7GZw(WMXgCC@Q?x5^ga4cgK#elY^Tz>fv z_c!i9zQ?3?Jy@pkYh||z!d3kySHX{+3YIvT_&0a%vUG#xLer#3JSI;~o+oG>477U`Cp^(AGP9{Ash7 zo!VkjKT>zOMK8-nlJbeszkMGMel1e4% zo#{GrpkJoBpPw`b8y~LSV8v|Nyw+EsS;Mspd-q)h@6uIbUjESieQA8oz0FC|RJQNr z-e+2qT|(#3sjyiO*;MvpWk>%uD|l{#e2e+YsCNSudE!CySh(?3+H^Df8&f67g^_RK z&?$*AFazjd=?76rrQL2a`<>#i-|)FUmQ`QP4F7h~PC@ga2C%D^6bOp|%&{mOe3?V&!2mQ%q@ja*^ALmw70#)CxZKZ z>81BpXTD1MKs^O^Blfs}u^-^u(eS>az%l3R8DE-?qXuJwvb(>|(wbh{`RaLWxREdO z1>)Y_zs>fXyxRSQZ$k4O9YyG(3h}zuSK9vf-5B|S4RHnv6-FzB@o5`G_g?3uTff#x zRa|f1*Y#GJ8m~_6BJJB1auI4eomHIPAeIG2nFQ;^&3n`?lH}9~jbp6iexI%2JfDL3 z9y!bSw5$^ELYNIuzgfl%#7YMubvOz1wf>E=Xm1e~N`n<94hhEmh&pB8tS9&4=|y!1 z;<|0eZHFIK;tN=js3IpbOFX)`;r(FGE>yq~{kiov*N zVtF&lq>vP%G2ER+jg3p)WSH+~ieC)78PKIfzMP}3v7u>gC-^Z*d+U11Zc}U{gPW01 zKYk)jd=E`yGsO|#na->h8XUX>BBfI=(u$MQPCMQwh zMZ0N^p)=#nejq##Pp*Wwr^EAP>m~VC2fCAxEzuw=x^?xK~Jt^z`eIVlMezm1ZWfLwr zi~6oZ@+f>(Z8icy^Sz0=jPw$-gHKc4wSk<0xeMACj5gEVe|+y#)tU^I-LULBYq*p}=m76HSGVQ!UE`P^O}7i* z&L*YiB0WW)Zb35Hfr0kS6AH}6jP$~$MTSz7i#>j+@td^EnDBaGd9l&^wnkOseFm*7 zrXJjN=?B9^@n?~qTJxFv+l_wTv&jEJa6Pwa@q7*a__Gq8 z%7tJUS`>Xj?l;R@9}uocRvN<4AgF@&_hm?`AZXoUW2x{D$`_U9US(CS4%%e=0v+Nl zG-gkfj+~z~>)c(lDAz4_P{lf>T~6^?EQ;jkbc9wc|NbsC3UUXTLLD&3-DfAh5{ma< z@)`d`n&7CU@K|)rbK}DKb#7;|k_n~=P)S8SByd0~GylwqjF^Q$c1ZvAI3spzMJi}g3q0>2(t zMOR&hv0YR9j5GJJhkv?JnQt*iEK0>> z*}wnjMC0;2@{s9dAnP*=A%-$@&b1++JI;bth>6;LNvDQu;ID}gb7ugbSiI2Ux;N-LgD3w=n>ErxaHbm? zOwWBlQ2T>rq|^>MMd8!PB2{ zxJ3MrI*tJ@lAM}FKho6NPn_)_9q)@fWTrPPs(Ua}@lnRXcmH4?>rZT`6)V%2-=Fd? z$G$~s{iETU;Ih=B*OfiYB6-sbNzXljMwA5Cdww7FVDy<#D!vtst$Lh7>~UB1|cDGD$uDIYfpT-a`T|I}&ji$(>^OBRpf{*a@z~ zuIU*zr~j0cE&5A14|`H8z&qk(lx*!J36c@Zi?vHN{$Nn|0m(>jb?*gDn+5LKuyo_R zAf7unvUBL|oF8CMK!iZ64DvOk#&U*e=X^?OTM37s4~JiapVDL=F>YZ{sAogmd>AOQ zf0apG&&(!_EIt>WCFl0Iz{|z4wWk|)-sZghuD(OPVPnAS-ys{VSi*Cq&TcA$iYQJ^ zYOfzQFbE)$0*x(T`5Q?Ja%NZFylyT2=4c%Mrk4D45Ou5X4?tyFA#H#iTWJx~`?NxZ z_1FbECU|Mapx|HI_87Mnk9D3BLQR8xBNd8_P_oID^uLBsF z&MkDAS0Gcgybh(dSCn}M?Al|a4;D!&K7$L@LF&Q`$adGKICdsYLF>oV<3I6 zu`T<8^sdK;i6aRg2p!3(9{!N}NEUH+tBXrZw9gnC7fcI74>IZrXJ1arEFBmL_lekg zoODyO$Ugcud)@ew?>Pywk2V~&82z9JZEv?GzEw-;enb|Yd@C`if{oPvC{gqJ&Yzkw zm;9wpR-ee!BOf2VnKC}lBmAB69v8D5ba?uB)ZPD&nIXu1eoBJ-hB+o*5La;pR0Jz6E zW!3_`eLp{j0H!2CSDNe#>)X~-Kk>J$tqDau+xBIG)1KO2(Py_J287$s{RiNJx|6dR z)c0+gQYg8?bYdLzm;sWBU&xr%sA79MO19!ZB?le1j;>E3oLwfz>O$hhcoz{|tK$`D>}8cocZb77z?;@opD z)}Qh^*RVA1-etO@a+uaRr+?0WUCUNgFiNS7QNeI$)u&ZTuxwyPkW%4$j8Sh%Ugo|O zc5*La?mj#eQ)T`o6<33l3{Lg%u-D1`80|2|FHq+&P}=@)oFj)aXQ^wPi!dl^kM~YT z>z^egWglqlq^1zEU3oSo7CglqrIBf<_XjG)QACqiLhR(1nlHVI)y6a9h;aFSe71YT zC81+wZ#csL_Eo3$LM1>_X$L3z!DF_5O@1PdI!YNsnZueb)DpM<_?1wHZLT%4W?rZb z$yCE&kT-=6tqizjxp}acXGq&b2<=EGnhRMXKU9}p$&EzO=-63;xu~vTm zosn#e{kT(}kBN<7y$`j5yp_t!lzzOab~cXA=|RRFOj`n0XUMSe{9R2^D;)K=zkeK# z@KuVBZrDR#)+#AEeP2*L>*+}yBlEl_@m(x#Xz<0$o->uhjx-Xa$*}oq8Dz}^L#jVG z)fHviymm|=qo|FY;-t>-^fZz*!_ky}4&WTJpHY)=QGQK*iG94@cmJ0c6L%-cD%mm; zr~MGO8Mhd(t=hT8*~*0}%U&z8^|{HJoXdlGBICE?W_kH5U3e?=Qsi8XzL}X~<*-_> zFUDtjrxhi|@;i1;JZiFK*ET9koA4^jAp2#4{ey7*85wnNHct2Ai;6>1W2ZSD&33Rp zP+lz4Z7-9#F)va-fTFv)DU5 zw7Oax^u_KR`Q=IUzS{51+EG7icp>z`&oi{J@og#4IKwA@KHWx z$*+34uPU`HefF)e9T@=+16?wI0R;_%!mz~o^<>kSTD#?Z`zAtThVLLv&_&+Ux zKTFI!E!IB>_tuqpg%$yFbg-x5mz9my`_SrV2CidT)E`T@pIJNy=Rq1LOpFS1yxVW3 zVx4fOUcLTJOciHq38!V0H|j~teb!KLv{)MVQkQ!2_iwc>l(=4|KvUeR(dhLq`ctOXbl@28&- zg#YG(Or4SWg7@?HPj5As>t{kw#%vko>V_P(3|H%CfjO36gu4ana+yu)n?44LhM;@` z<807?hIS|91xSZ0wO_txm7H1!dO~?WgM|2ZRO(o#WHQkO&(V^+s~^n@c*4dJRWzat zsG-yev3~ldf1POc7FAc}08Z9FqrJ697kiWIQoOT!8}mXXqfq6#j>932!wjC8nh59i z3tpgKCaKy%NI@VFqym)HxQXc5C?$?K7=wxHL>64KZ$niU>*No&wzg&_SLpi0_3-HU zgqtnu82-_xbncjTX=WU95TSbWHg8)=*pw^&bYZU4wHpmuHqQzGSh~GnA%WrRI{q_sWoyHL>34#Tki{Hc2w&E}^lXM$Fws3ShnA9ij zIPh?DFWcDFjx$BQ7f{1qUbpCX5ebM^dY#ZnTM|;3TIx7V+~5CE(ZyMe`*V7{b5Qr+ zhji@D+nYMP=tCptZJvBNI)oCIWVLOMNV@K6oN6t*CLaFgHo1z5%Ca8}2A(OHdo$?Z zB5lqow(c#xXe7abd2JOnN0doONGPhRN_>tn=5-~HJ&oy2*kK+J4(p8Ly;xOxHd{=d zxzgcUJ1cDw=hUmmKO96t89u;w10jk99mT1;NvhUU##7#!yJZy>j;`}%>MRA3?~Nqv zMjsGsQU2OSl>4)F-)oZaOQs5gTBw|`Zcm((VL*w0$?Zkag+OCb@BS|Rca0y-n+84$ zTyOoQ)SqpbzgnMldjPefL#{=Am0aF*_{vF2UK2Tq(k_9XbVWiE^Lf33xp!Xa;;z;Y zDXh~bwfKa;m9n=Qg+Db_r(?Aqu84H0egS6{M*r+@^EoF9eA$^^L-)UW{)S_vBuL!T zTT8y6&z}K`;{Js_dg--q@>K5G|HvL39rc3B&uh^{C8?7^PZS1(GJjMo=$_Z8u~ZzD zbqR#+wH;o3&K@=S!Y%X_htc(TsER2GOyzpS)*IK^#P#y^h6| ztf-^ohELSuhC%J{2C*x6!?%$*b@6bBf;!)^X^PNvUQ{mY?ibSg@qTg%RbP=2FuaU(3tj98Yvl>g1 zvhE13f85Ou$!9{vtER>=C5>>QikVfY6>?|eFb^HZWW%VmBu=+uOfij9Kdx1>M0)+{ zMJ+8 zGxb%~_lKlGzMb{Cy8T|yp%KOW54(*o;(JswBt0o^)_f3G+hr_ox3!H@EC&pddtdLv zy#{q&XWX>%H^WF5*KBD)qIkomz2Noz+K+Da$&3E8%V&bFpfcQYl5^2riC8=^~XuxysEe;~Q7J3O}03=3JQ16h`hv^^W`s6`b-)QGHp;BM2d>0oT{W0w#zLM8D-ld%z=WN=^eS(-tVgCOXZlqs( zg)ZM=Y$}Ns${7@EALUS-FgicU@%a|J)r#Nc(6g7Vzq|A#_7o%$_~MnF8BTx^ip_UL ziAPVbn2WxqzN3axZ-XEVhX}-=n)!MHbmaP5@VJV&BZzN^@B6L~+|8!*8&_m#2i-fv zu$X6Q>a`~?AE}RT4jytG7HQ^h>FJ@Qp`n3q@NI5=(L11B{4%@3>E&3s0@m7POiW~Gft~;cPT;RPy=*EdCEqcX8rZ}S#UAknTv3Y}==VcEKIC3+ zHJd#;8m-l>_`b5{vXGO3X#AhDC}y=QY?a=IY1ZK<66>P=j7mk@Qh;gR7fa?=6`L2v zjXmXc<74WSTo_>{;ZPw_uc62B%E7H8q?!fsN*$>j$h~we=e^X~RWAXnH@)L!Ha6X< z7rg^Nx?SijX6cpTu?l>v$?;+#)U-c_*Lp~Hn<2UQWmXD9!<0*MRrA8chq^SJ0hEv8Ydnhd@Q^sh^H7QeZs1|;Fz0L3p$F)s zz1w4%HGX+wYh}_m+Hn}zq??(VP1UaWs<9i9@_QZQmv>}MvS`&g;bsV8SuJgng)@`WL_&P0i*PaI>cDon+b%<-4QAbk;Acy(M+q-Lxc}q{;c~hop#C6eA z?@rpGi=8YJg>KC~VzxvclOMf`hS#0#>}yK9_F1iWoL&8ITv+Ach(ht=v?j8>j$?4W zFOa=8x3%1`6MWA2q&VB}oEJ)Fix{VC(CSO5*(ODd*YOQcK^+Oli=nBWpk)Jr3=G(Q z&!qmk>KQr_%j;)wHqrP`T=F16O85E&Q(9%4Gl0XDDfTmL1b%vaVmKLx? z(%+9Bf>zcZiYU;#fc8ZU{v+6Zr`MRqzCK*^w}ulch+PJY(~qp_t-idaXi!QmX3J{H zEqfewS(f6bI=x;yD&!eEC$pBC8NFhZLhm3vu_hs&db{WQm!KR z6Oe{OSG2D6x|@&=PCaM+0$f;w-I1}ekR_tAU|bvjXjjk6lUJ^)^6>GoYg^p^aF3gZ zr+C?jn}%xL?v%2mimT|{X_uoXWXLKsf=sfz$=+`eE*M@*i||C2*FgRvf+DKwJm3iBF1K2>MRtxriDwAyndHMuKrn< z$gyJ;xGUk483a6*TZJQov^TYe%r*-oP$2IC zBs(2^*mxj#Qtb1z%VSUpL9>UN`Fe5jet5f!!*B)aXVW2%i^(fJsY;5Sf_`Pye4a-Zu>Q7D$eIOI@%`%;fK@z; zd70tX;KHz-SO2~I)gGnWagOpE{5z}{u!Nst6kr;Z!TG*a4Nug`*rA4%Sj#(eg_B@N zU}Gb+5GfV0_7zX?@-J?7H&NBlnEYV2XUBZxu(M*5DDi4f`UfTLo8y&5Ma$KD^m~oq z*uJrF_n%#EoTms2HRYavz`HIMTPxh%xw*&@CxiaG-#btYK-`dz+SHIsV}Teyi~xHo zL=!+t&}hRxlB#re@$l&?E$S7zrgU>14r+4)8iw}3NwJa2C1RKuhZ-eY6XTYycY*e1Ypaza&_fIQl?kHd4}1)I@`rj=~?)j zlhZC2M<0m_97hz`ULR2OkD3(gyJ)xgK?zVr8^L_OR=E|O#(3ppD27ic28ga>IIYPB ztp_6wOP}0LAXbV+oo`?HW^nOD{@L;zJbI_dQBoja+n0o|oWZ45TKk!~E~y&k>%Cuo zC=(Dhxx91YR?Io6Tpp8BZhMXjtvPwub-xV2ygbp$tp44G`80r2c64-ntAiLy!6fzE zK_tRgCK|rLBMfFrRN0;?UiKrIXlYSfczV)8w2H2><`XAv*y@A0Hp-gejgoN-DG@**m9ifFpHI0}o9E z#6T;?66@4#9f7U|0Qca8LNKIghh1jmkZwrTLIANc;0U5Y-LJ#&ONp5aT`~n8+BeP@ z>;~wvr77RHvG*l{Fa)<={};`w>nfZX7?o;G4svnr%?P9PYt^DnTW-HS<&&wBx{EIk zXiQ#YSf78}Dt#TfDOPN}7>)O;i^{h0g@**HjbTr-ji>3`dlPKe<4IA2G!wWxZMM(q zFbty$Edbaz>`wDp`TH}O?XRK*goT4aYvP~nJFX~`0eeZz(fk-Lm^hH1Ew;@^u=uA; zZNgTFDZ$@F8HV;>$>UkwpIIo(FZ>IcRZxma(7W*16*ruGH}LC&R0J!oqGxaF+Yx?H zyR?WCyyd4tJpJAkQK z5AXWRzVxT=v%9eFy?2JJELKL;Hn(y~Pb|ZYyShEA|E=!zm7yr*J?SsL4+3l(xw5pQ zRDL^j(vm-sl$(P;_MF0b^;EII=z!fxM3dZH7!^BduMNV-#vb4xvjToj>eE#R`^1%A z9gU9!DF#Uoa&V#ZeP5(zvjnVX>t9LL?e~l?9O~mwKYk7kxJv!d6l#HdIYV%*r9cTCy+wvy1> zop+>#9B(+3doM=5d9K4^R^t{n{OTKMpCF);-Ov?{YsfJy0SIaDC+c%@;|+=+ZJNTo zye4-OFs6f$eDu~6j_~D5xOR_!1=GfSc|f{^u%_a1dML!1@x9UUR@vQ8vPDG>1~d@1 z&mBDk@f%{wFEI+Tblq#~fc}!I9sp2*-|i^ZOw$XiyEAv`C@jVR!&4?ZGhVb;29w{~ z_uKUk%nPk^4KmREVf}jjGzsfrwuSE+1o~<*9y5clw;rB(FkX@^*!ND2>LqUC#Ux#@ z+*MTe14e`JryEm1eapMYcGV2K_|Mej^fkoWa|FwZw{bj3EtsRomvpwdoU7qYF*S64 zjd4NVFo12wbg-hUJd;)Ea`hv(jfYt7&Y-!P#H6HO(k7;+cK}Wq8DUUQlV}z2hm7!R z>-WVhEXWxT!od?&Q1Izy+$16<_C2oFbGu6JqLBrfTfh%Hu8R`bJqY zRl55KQjlVoy%Q~&%25oV!R+Ikq$maX0J5Db+o#E%5qMYd1$zgf9(lvj9PPh$4LSnS zWrTYVb&fvw1WaUXHPbdUO;&<;vW#!yu>r^sVo{(NVI)nh!u!=XH9d|1|Hq_OK|@g& zp^hJ4y>JJP!|)75DVdq_TVW8NERcm4I=?BG>Z@0EPRH0Xv#-MufIqZSK*2PqKt&+Q zQskK8>`k`NhsngA5ipE>+*6&Fh&;HbOhyVf{Ch+!0TE${4b31>Amg||e{95Yx zuF|szXuN+64ard}aMP%)B(a3Jr-|TQV8L2{D6Hq^Q)L7$w0acoj@}TjD zJ_t+{j1nz=H3bo#jl@w{|3S}d*6;#=n+foD+9d}c9d1Zby}3GdjijX@P-q^Iwoii9 zEbJ1Kg^CZXF-1~fPn7~MS{^b1DYQ*}e%T_3?y~l(|BXC5;7+RE;D!M6$xkjIE#1Y( z{>{7JuDoR_*jObQz1{r8>yGY!T;PJ2K`k1%L)^jKI%PLZ-mpAOW~LH9j(Og*w7K$C z5DTL>Mf&oaP*QjdW5Pn?`o*KH7I77hG%V6s6|o0Aoz0o@p`@jz<>kjZOZ1mBy&C}G zjQ!GtVxWnE9Lv!Dadq{E@c?q*5naeBtv+`X7@o?~z5Wq?0X5RMOnEWiE&kdx&O0ug zGXyU<2{fNmy4WPC!-NK|pYo0y(m(w>8+YLc6%|jX+_|HO#VRBC#fLs+clXW}CGNDi zvWBUPFBc6ZWMQM$_pwbs2p&*gjhRuhszDAV^IUWIM%Qa9;fwUmo*QyIoT9nAhNZqc z?W<-};--`mWwh;bLRx+;&2f1CFQ{<_@*BT-w4}>y5bj6hRJ`+0`W=M0jX-csQ)Lz4tLl*5Pfv|%1J1CwtSSO z{pNoN6wDHfqy5M++NYqB8+4$7rUy_P3%ceC$KE-2rU4Yg6u}GT_Df>V{h%6uC$b8E zX-bR&y4teEB9cT9nnc@k&n@+otLJ>OES%5L`|#0yw53kzE?mqyy&EBA32SN7)L zcD3hit8T`3A|G8=IA18xm62M=&n-^VNR(A9XCo|OA@O;<2 zrGX_14oNls>2`;8X%ROWybV}0GGE1NZDX^t;1uBVFv`Utnf6I$b<&)?pQi*P z%>$$?Tkn#;J!CtWmJVsFNpa8iF&D%XFONyK6_Z_5Al<~1ft3hgv}&p-D;SG#FOe!4XKr*Bx`@C z0OD{MEmcoC4z9`W*2*(}RhqF-hgv)beWfovX*H9x)oj#Ukvsw!uz{GFcyz-U??z+0gdAGb`VZVoOZy_a zWOKn>S9+q14moN-NcT~4RLgyYOf!PkthDsgq|VNWb}q~bAUaEycL~@}CETP^$ImZq z_|@}LXvjbV2Zc1;GyR0t+$@k@koGdK7kCzD#S~nY@uh?5L~HBgQIkJ^6k9#s7_woSQj5D+g zz{40&PuCq;lR672M9l5?If#zXMQIK_Fvs4LR!79nMh8k#^m2rY#aFsHt7ye)uXl(b z0C`lz{1L`0+pEq-clCCbjE=^LEWTU&*0e0BYQy1ZHf8w5t3wE%j?dKO_z5~oZaZzp zpAb6WT|w&yOe_qZ05GKfR7zCz1R^zg7qpL8prpz}48aP8oGb|ydb6UIA!*%@K@rqsb4aI^Tr5Cl=|3%Y; zzv?jJ+0QGVT+|;c!>~q*;^D0TsPo@K0Y9hM*}McB3-el zUp2f^*iX;}04f;z=K}WYSJ*j22E8|A^3M-$Ky%G~^UF|f25|%r6akMp3%fur#YDv-qVbXesgUv4<KJ(#NlwpR+XT1fGRYs1_y%_@Cw+~Q=1?`z_L7&pUeE>qD%fb%%HwwB%eRk zxi%3@ZGgw)i>sL{a{+to7Kj5VA2D|yfWks29ox* z$#ryejOUVWI~h_bZ!*E=2*h;r|7iiBk>BJT?Se|QF5BAAZZ=!}1DR@pfBvDoe-V%8 zY}a+h3s#oc)*YdEfv%_O&ilMs<+rB{d++p59NRdWsuZ)XimWl3fXap=UKz5ChV(jh zgtjh0D4dzb4{p(x%zLlva|zlK4|ilwxx<{04K}@XGFrBqkT)(*_&pIwCU&Wo1ae{89i8;LXst0>E+PEoB@LB%4}g;8DgF?(7(#&r0a}g>rQr%lCvf4supGx-yO5DT z!8K&rJ!#dTzbrc$?9-pxYvV4`lOLCAEUPy*Gz@YahLYk=vHr73F)7hMq5JX5tkkEE z70ki5b1FW?&-9;!a&j{KB?Q={xe#I^h}4ke4f%ebY?&_c`A~^}b@$Ww=arHe!f2F} z#0A_)Qi?;SkkVhLVS>9S8}!klxErm&N47KzxwN-+2Zb;Si0NfVL}U83BDbuQ4>>AJ~sX5=7ZQu+4LhkBl*1SACXbx8S4uSxz+urtqHlh>F2Wn*t`1e4loeV;Z z?=5I@1iCJR z2qxVKgsc&`2j}PKuNabYb(Qm>##OGypxj)}RN#D@Oq2fry+(i|4S(9MoMNtSb8jzo zPDFM9ORr%dNTHKqeL z4G|jL5lE>FSQY&zYyvNzmB1LCW%1`+XC=*@{mn+K@UuYa_J=Simw#Wm*cW8omnemB z&%6zEs=<8=H@m!}dEHp~I~UF*`u(T_^D*V5@FCRLoCxG0zT1UgR3Jfwk?lX+o(h3~DP3IFYBw0OLz_yh2BqYHs4he>gr(;gR3 zIJYaQHv57f2taIrZvI*Kw!A#mc@Ay~E(huoNII_hj)JUWr`m<0d^b2A{p=>(?he>a zeT!jc|F5ptP?L45&IC(>B%-IJ?R)Y-Hb;Oq|u&Wllibw4zf@plax z%FA1sxzi+F=yW7!nX=at3=qGMMFj^R8wohrtMVeSNnx!}!vrZ(FH%^@ZpsF-g3*R* zbgVHk z=95I3oB-ChgjcCSt4u%Dy?+RydQ`7*wbsEci)w?4wISnKL80G*J!D{TS#N=js|M%J zd^!g|fWilkaNsM&q+KhAktgurWfx%wRU>?jAM9^J$N@Y|1`xPO$a*I~og)=elcZV` zqAy87F~CxNQ|X1Ej%dn+L$0p!$(9?(1j?@or0ht!Or0E;&#mC}a|hhFSpUIG@6^{d zH8maOFIcr%vexP_+MHK~I?Kjq#A7Isg?XB|b28{kF%tkV5c1`1Q)Zbcsi#e~;NgTjlgf5*;3EM*5hc9?@FB=H1O)}5 za``bfcIVtt?hz1XL(W)EWZ`ez7_uk9_v_vx>|LHfhczrsf{$GrY^(ID1MQNZ7LWOC zlRua^KQ?)LQr)tsju&TUl+enjaa*f}!nd;ouslHYCi z?|e200m}b%*8jq}wyUr5`0-smCL`BBD%5!G(10o<*?hGWTt)!p0I4A#a0kr_RExk4 zsHaPXE&1Xlxqn`WP=Fr`} zw1I=OT(SObk(Ab4og4%L%1-z(Zx!nwEkZYY!c~VlZa$7BGwIndL>vg%XdFxDI(xf&czqMgjy32WtZ)RF>S=pIxhZm7`w4nM6@4QutxV`U zfU;*s!7G*2(?E!62d8MLlmQZO23uSjZdp=Th7EYfvB9^M5u^w_U<~3}p$s2oyz2T3 z(rpKvR$Yt7o*|YB+-@xaz&b0vb}nLUt)v;kI&_54fr_Lc1=8A-Rf5%A*)#8DUqW|} zKoPHu34%zm`19$BvuxcZz7|h+;1WTdi-2#r{%qOoL*Lf1aOi=t;Um`u+@WQKesmi{ zIU5c*Cb(Iv)tQ@zH?ES$P^G2*$m%KifcSSAdSL4?JmXdfAM*XE65T-5NU^PEeGila zFbByX;r5)-zrt}606E0Qvl=*P&<`TaGduIB=oQWnB2qF4wclW9*&zuU*^;$-?F>m{N(X{y0 zV#Dxn)UF_Ev-wz(SG>5TboA%{3!aQe{R`vL8q2+lAFZ-y>tUUT0Bv8OdtKkySat2# z$a#9Q;KP#UxiZ&pQCL!%cL_XrZ|fqg4Xh?hn=pQ|h8Ivthhb|JXZ{#>tHEDji%{>t zJBjk1`n$HM_WVra9DZ_8j>G>(hM~5h&z2v4AzvVFa>+gV;=w!nto@As!a)(o%eY0Z zcx5QDj4LZNIm~Ts!!{H9TTu+4eTKd{K0DA~1=khlU(Ls)_O~YIA0}WKr9*oU-U*VEOMb^`p7@t|gJbF8XA~S!m~iyc@OvBf zBFp&0s*izBJVPkZ(NJPAc=sHd^!2XZDMm9*gZX}s@E+>h_)(?7va1Q&ekOa=zD6z#sAJf_a$EYxm6Jcx zxN$}}iJAgQ?XtJxP#r*4zXr0Q8yClPbRNd>_Cch8mGdkOu!0lBBn)EC2vR#tmNdhH zql$g)InijbN^$xErvas>$x`3Lx2w4?yz;i+CckTEl7Ng zvSrdLyMH9LJ0$M{FZPL>SjzerTUj;~;-I;K=RXenox58xmJ=z5!t9#TYKmP@ap11Ln+Yu>?xu8NUxlN`o-kw`I2-`09TP)9?g>LdUIZCcfpK*ZXyX<&&9Nq+ zkVd?Q&DDTr!2u?fP|(-GAc-U=jIV$`1HRy2khxONfk;QO8{HOTe>>xgqf$n$ES8{o zJ)Uy&o43v-m**Yj6rY?Q`nnkFG`d9g!2NshF>Uc>HxhInME_=KvL~C_riHGOl!lz@ z2=1yL{oarrc4(V`&VVm0dNIcXt^{JE`|PP*A=z+62?hId`uBZy6Rd}Z%zmn?S&wfT z#KB@l^&94t(qW)4cmCPo^(|G2Bf(E|9PlOp0nBzMXaV@Ctah0`T^Nb?f+`Bw>Cboq z2lZ+07s@Y_CazRUwZ?5YbfD#?WO{0n@lpLz{joFGu~}cBM}*Hju3_VcLY*%+j2yU~ z?sZD~sf)?)bRqU~DXUf0Lrv!VbQf*@L+wdDZF9JkX)Yx!sXIQ^FPm7VdmS8<3Uq2~ zYLee|l0BL81h*Yv!kP$DP#TfWO$~FR))TT@x1i5N{7n9m{V7Qsmkbd5 zLC>zLO_^Kk;h)si+UDpt_n|d_;%R8euvtl2__5kstNu+t4~ovcSfBN#BWImQU|ftL zp$DlnFx3D=K3MvhIt{oNS5&kuU_Q|xYVE#Qs1P+)J~x8C!F->zx3?VyG2{zpy5a&^ zSZ0n!#>~>{w$zOza$qcj3j_A%!jij6^a@6}Bx>Qskm?$kbn^mRKavm%n#~c~>K8dV zIn^PHP(K3e2Y(;PXz(IfTl!LJWN}!Ya05v>FM84=`vZCrWB9EpeT#DdhTg`PKw(gv zA`Q#Su~>Gy+nv2VZqd(f-U@A^gZ;ewpZSylIDQ3sPG02!=2Q1>h)`-h zy>hc~K;`89rgQ}O8h~~#9TwfGx0B7oxaNWgj2D4?2ufB!)1XQcyXW?yZ({4wc*B{_ z64=?b0)}Ce0sHuXW&6er`>oH4GC`YlcxkAeAI~J&=)X+|jD*w`#Isxvws;PeBQ#Bi zjiIK8$O$+S?X_xN;-1X7`~Wi9P-i#JUXK?oASnqwsYaGDuN4x>dewX31m+wsO+?sE zWt>OSQESQzoRNhN8OK|_NJt?N@0%sKS(c;X1O}Q21qh+=1yB<7dzKK@fuA68&`{U_ zDgz&aWM2s*UH=VYKaks70~hJE6DK4|~!h*#JXQ-;^2z$#Xsk*1w`9gpYb8HMRG_;aA~*nNdK zwJfATIj^*Zk>Rwa3<#`8ANp+?eyf4OqCx6PV^)B69>}9sxZNev!nAMxM;#c>d__Qs zxz!ZGy{Me|vf$;n-nn(kb$KQ7Yl=>gxS*^Hx^lC0@Il~?MuU*P{^>not5+Pn6#t{or(A{GLQQU)Puq0$OSNr;3r3@L4sqJnfO z0wXOkbf}a{DK#_-0ulovB_Q&Dj_>!a^}oK~U3YmGF7G%q=bZi9`>8#<)#Ll!du>W_ zM9_IKXbkbj**g8;?r4}*8Y&cuKkh!X~|v28%&1pB-+Wp73&uEp>zA(ijHE= z98Q+4w9Y4gt5OerxcZPgqB#1}Zq@ZIa)KEXgm*IH1*&*=0FDKy<&Y!*U^SyNx9*G{ z%(#V__-!1MATo0;v%`3rglpPN#2H+`H52p|mO+bOc@{YLVY<+Gvl^jN#zv!amYR0U zhGjpF*M0JLU^HFa|2(srl7imW=_SbzleG!Fq*ltKIla>ZkM2MquGRO6VTZ>=OZ&ojkQQS_O>`5@veU z?g#sY%ny<&a=Vl~@_MaTc01*j?e6cWaVa)-H|^Nvk{EBU(W(*>H}8@8Vd~=b8Ik7y z18Z;Cl(_F_6XRWlITI~ev+UAT`2>qrfyAFccQH(pvxC`nA*aKAfCiVkKY_9O>tS6j zt+(j+slo0zi=Z9YTuripnt)*Iz=8~RR1VmNOLKJQLSWxM1JMo6=s2ds1>EliO*@4G zc8fhgpSZGZJ4OD26fUhvH{&jiNs40YEI#1d&rbs7qk|fTn0^|>lP|){XNQJ zFFI}RlA-4{Us2=1t#)z_y(wku%T@p7t9%+u&qW$~B4+h;`w4}w&M9m9mbA&%@q34v z;#rHq8bZ&XG#8d$f$$XiN8&%$p*i$Z%e6ExHC+#Y1QZS&Q*5^+K3VGPuRyLh0Yd)% z)v(MK(2xEheWN(bCScRJTo9!_zQv^z)%gD6#p)Y4;Ng~b_^p^F^kcz8@zSsdg=Zt+ z_pZGspBnvwpY8Ov&;5IsMfSLk9d%re5qD-FI2HWeR7c=@Xp_$NulStP12T4SGQk`E z9O&w2_J6rFdz$-6!Y)nr-TnPtpR(K;rO`#69g?n6czk>}U44v%A34Uw>}5mF3_tF7 zm*Nxu)bUzM)hz`XM7sOi1x^fg?RGkUUcb=w;JoFNfGH@sutb#}y5#TY=H%vz+|kN3g z65XMRi~A0TqJJEeJ9CuoSEb&sH7IRBZ=p^n0(yFXKJ5KGNuWp2-Cb)ix(Rk4^Md$X zmtB--AzJ#+ax0G&D6M#PN{27Box-z5-8TiewqWnvcES7HF=w7XE;KfdxHeT7eg?{V z#SDww4C<(lLuXIVplUUqYPFQ-ID`dQK4(_%0Zk~4*8X^dczNFt8cV-iT!^!-GK!jX z$Y2nvZnh9|_JoRReBA0x*xGTCP*XnW?;*y5;jk`t*6SI|*RDDTpr;V#l8g;`^C zlzb%3zme{>ijqVy>s?0AVOQI%2!oHJ@iPYXow>-IVj91N$?Q^|m zoGTnHeXextKSe2%BHa@b9zX{HpkKsw)`ER0yEt_G_~Mg3ehGu1XWY;JOOW8)+0MUv zRD?@rXhHFfys6j*^zns!M29D^2^LvA{n+f+9xk_~hM;{XT&P9BFTplK-GpDi-{*I` ztx^+sYL1fOzB$(taKXOV2Bi9WtttE;llJLt#MD6mg7~8D65C+?_b9hMV&JXkNHXH5ABB;$ZN=y_ ztDb#Ic;r8sQ8d00*p}Y%j2^%pwA67;!_QjGaDRVUwf83-lzM3OfyzI5ZwPo6-=ZXT z>h-m#>q)1n-JMwcIr+%b-x>%$81}Q2YjCXn9&7l$iH8XwO331Ln7Tn$C=Q)f zEOsBrc|S}a%?cY4*#ce_i68GwpC@rm0L}Wj5L!CTsW>1%6SacloNeLYqGZwCq=$^T zGB*)1(ryv5#@N?Om-X2~B^?9*x{oeT`kjETR>!%b7y;t_JskUceTdN)_&I=GYcFH& zfJW_kx7ES=bbF1UnvZNcu*==XXgr^ek)ZO_1-X_k1!QT4rH@aSJM3^ z76c<`3Oh8LhUHaPY5X5o@~QAeidJP+Rh2~16PZKor~Q;0v0xHUCK|Yv`%ed)wzWhW zHrl`gP~SP|K%m9L!}APkN@mYV=Jqe`6LVM^b^AYlcQeZO=m|Hk`?*j~5Ns0IwY|8= zim{RpGhj#{c)=BP2)$hPM=o6Pj}J%Kj;v2(C{#lihuCuL1m|i!6!}%$uk3%d0CmKw z5DWq7qu0&MeD4>D1ZeUkh8ZoG+s4aIx>;ET4B7R%&k=hi(3jzh?w;@v-tr%`m`MjB zLUbl#CcHJ*nU5#LqZ?sOZkMHfD;zCcpJ|OV5u^kmXYEzVptkSO!Y?v%0fyYal{>C6 zxS2k@yN~E*=43|C-0*5W?>qKKL(0`C9b}HJ7wkdrIqLa*lJLd=(RIK3`a6M{9-8P2 zqTL7AXfgy#G#F$CwFYQs;C*2zUp>~+as?Yl>0Ik=x%*_F2Uk5Wk>7rI{cumBLrg@3 zY_n%ToOg8V4-c)H%V(_r3~CD6FC2~;pbB8)2hA~3&+6H6okNURxL(xE&1c&kE9$TT z;+cqxbdolst!bT$f-c{ld;K4_6~+Ow0#v{-z4;kSDTp`Rwd{nqXgMI|lc}%w>zGTR z;YbDA#`~W}z35+vyNSyMA)nVs*2)*=SGDaLE8X&pM!)Tmpt969sMuaX@nbWGs`)Bbp!y>rE5 zUg0jHw7KhLy-#u`jLP6fzI;P8ZFkysi5oe4jrH_de#otY^o)>9*$v8{>Dqh$zcmih z^Wpc;m5^radk-Jlo%$;hrZVq-ktc7%wEc{ERfmmrpq0k<6s{osYIFQIL3t;`JtOh2 zFE`z})wG*=!y1gmif84lJ^%!zQKel8J zn9g(qnA z$Gay7iqC&Nl;D6q43ua!AOzGi%#|pvFxKEla0cuOBwV$Wmh04vA!lvRP__cwvSEIj z54XMSoCQz@(bx8gCcQqO0s?Gg>vVXS0N;ezP#GFej)N!x+UFYT<>{nFM7SZ^f@C5*X{0KXM7PKfH1{7_ti( z2@85gfg!Uz7<*<((TeH_F`Ey(`m~WNNJI7x+xolBLl}I4TNC{r+sQkqYXBAEPIMz+ z_m9RJ@)H9u{f_C__dPt+HimM&3 z%&F+`@Hdz`+IGs>g}Tbe;{PYKJ5oty(4tbFt>^amVE@t7y{0ga5v0`h+aZH;1~nb8 z3BhN5OZq)K3 zXuTjA4)W6hP|~sYPrM1&{jl$A_Tj~N(I$@CNQc1T@Hl5lNcXjSi*O`srGZh4rq(#< zi2rzZz+h4)qHH-L_)iisJNz zanNq%Gfw3K=b-Xfr$X2EWqlX@)WtTg3*VqnA>h5dGtOSGezL$$CjXyX+I*olNeiV7^%ey;Y$d++0>Dbgo0!85&3Vtnh5l3w38nvg z)VInNQ`*XA4)Z_mjaA#9U&SJt%@L*S|5Y_~Ci1oz|ACJhSsvCM*7uwh0!)3WAx8QF zEU&Kd-FKMxe@97l<(@roApnAH=Je4%Cyybg2YpB9@4H|9Ti*tk?B25*w5^4YZRS5+ zuYIPKv?g%IIpHzq;xpFFKSaytByvpO1jZ9O8?!+iFCrP_ zj_^4N)(JOfX3%G@(Fxh-pQ8F_XC3>Nr!lvn4`?5WO{FI|pF{bjPPKD{F7|Y?gd%w}lX-3O1ls9LcgKd~`PBT_<~X zg^PwSkR_gxF1||?sbl?+lkwyJ?GtaJE~c#EDO>wm(7tJq@95CU^wN)kLRMf{|fBDk8@C`C0U*2{vJ?BRy~}# zk84fFiHqLmCs@a3Q~xl2hWl&%&(12j1Jnd4zK5)wg!?G7|C57`+f-yP!L%dL;ccc2 zDd?lLyGq&DEKYqaW#(x0T76C{5_e`?mV7wIzwJjG7v8zn2_|+FHZ$w!!Nqn>0O0?r zG__p}M-<{CLl%Ui$rW%i#2{V&+-|LGoep<>7WT-xEk4h4Ew?`0y?RBpQty5JFfAn) zsc*#>xqO^dUFYwdEznlmkzT=FClAyXtH0I zPNw`ftiU*6`PzPSfb0c@xF^FE!FMhTMXq^lKfCf8HDx|DDg)O(W+*dk$axPm;48)o zY-Mf*uRM_O3e}QF`O4uPXk)~ee@zh{s_&y^zej%#3YV>~CgD(G=mW{i6BQBXKyK2{ zJCN3ZrUSBHv;w5Dw#;)bx)FBhwc~{nGjW|n&a;+Vs3fT}yzRmo!!LzaaRiD!UNH0# z$}y9~=5}~xhZZFP4Ad+=jzsuevl-={T#<6pt9ROmgTH?bQc4`(b$V1CUo!Q*dz52{ zy!y=-pFYpmG*{29oLR#$w}nnjQz293dcBh9kM}+bmh!@>j8pGdl9OU( zf`-)f@`5^OKI&to8tw$!vng-rg6Y^`A;8l%kn<`k$q5>J&WC#LL=HRy)f#hP zh|!xrK8MoYDRF>P7)IcfgLDQm;T6O_7$0+L`lQ6(U!T_!lHa)FEpG5@V_Lhs+)82t zYk^Ib2esd#DOFB-2D|_|a6+<%j+7o{G4QmagBqS1>$m$~3{J`)heD z+S8kD$bGqY;lZ~+DMz2AGw|CFG?v+<}uHE0QM_-!omRe|H`kq&iRq*qR=A!#QO|Iqr?)QDm%l#xG zZenlW)VJdelE=kdMH7BcdfYDPY!4rr7nd?N9G94A81hXLbA$c|)oPba;2+_K$3jyq z;aM6K^_hTb38nhy*Mm|%`_>WlL8V_K!)sb1TwZ`}%fp-4rCldd-Jh9syC^5;o^HmC z^wGIR>Q>T$)`)^9MDyqK}jN*OJjjASoTn84aB-tfX)f)clc4H z77&cH(9lTp$By-=3tU0(pDtdh7*S3#yv}@Dqey;AdF@cbV(|3GW6Pp~xlsp35A?QI zPqiK&ZG(9IJG`mkloGokMcGq~p)VyKq?TrxO&Zr#rrx}v!#|awqCYx|B<91xvQ{HQ zsil6Y1G<@W(a}Gy>aKq5(3%*J4N zPYB9_5km_N=V9DB{?eauGUnpp@{c*zhlCQQ8C@iM;zbIt`eb%n0UQgPAco3>1kUY6 z-Y}?Fu6xjT;-71MnwpwNhf@ZA5n~57Jja(S23B~J0)2PpA9*&?TuowIm4Bp4W}&a8 zrG;&iPmJVw!O{$Z2iA> zTc7Ev&R71uAuv&sh}9r4-J+F2@k7Bmg<4NX9E)!Lo*$Y-h_}87TOX+R^8x^tKvN3G z^6M6_`taX(K<6cFg=90eTE_e=+kTkc5%`*TMb4|^G zAHy_W4!9Uti1+^>t%S7jVdV5It@95ugWNFu3xGaOEd|X@SWb20#GkWGU?pBKLgvll z_wucglYVW7sMrS#*&3Vp&26W*VTCo(lgTjrEPZ5K5S6Ty+QflO4nolk7Uk}nYaeEI zRv+E6SCV-3$(vCTdeLT@4R(+z&Iqz?QCT@nJP^dG11kGs;OZ8$mQ-?7Mn9o{0c2tt zAUC2fhQjpVhVRT|fBun}9Xvw}ZyzhPMjx{;U{p!0JY8UG~7@joQc8Ttpu@D9tSU9H7T{gUq`>kp}@0|oU{x}ns2W{=` zN5|2c!{;*jv;WbHZmY=omKj@qokByl(%C(ag&dYNNKFCN2E^w{^wiwQ8}eb{{SeCW z0p$)s8|(xFK(DZ&A1n5bo&46vPM^=dwA)}-l6gSQArmJQA_*Wf% z*DqUHsMp4AJ+aou&d8|p7hj(NqjX{hcsVvYBJZcGz-}#xEz&* z;OZ9HIy$rP^w~djVAO=_b?AV0BhrCeo$URDpk_xi$^tlKF7bt`B>6dLb#urlyT5Pa z5TfH=p+L=0miYAFe`eRv0wf(MaL zcx74L!#b}MY)ax*1rYpsor2Z0<}b+W0w@lO$hhZg{+RIas#D2(aumy=yi#?TY)j&$ zLP{g+5>H-eR4M8zcdRqlyc&JDV_a#%fEl)_prf(ppzz+KIv0mw4jQX;xkJ7Up3|bF(7Zk~jt|&U>ahP`y^=Rd@ zcu}TLoAZZG&A9inHQfpJj&-R=OncHq@@T9i=#xP$ok;Z##<^6t5YarXu;50SRd?%tm^!W%VxSW1-SGM4uV%M zsGE)Yx~jI;Us+V6(jf#rDc5Lgl%zW=cFnh#IV5{(?kaguxOI14?f%EFJ5- zesLzrlIc;dBh5+8GtP6#yl$P`&uBLtcukg~EBGnNexH*EqIQHbWzK|6{~9rHi@olzC4=nj3xTQb#d5IaJC`Gts;KzYU> z2cQ`!C7KK9hfNz#Wq>nZw-UBqoY0@*pFiwpfq3HlcjO@nxueboeQ0y!TPbj7_@=l} z*=S*6U`U(e%aNzG0Kve29pjEn*kcX836E(VTbt>ab7`DL_1&~ zgk1nqh>%+UMUBRVoz;E3 z+Crv9oJQaAw%s>-l_yQC`26I;o}+x`MgL@!WFW~`{_x;?!$24PQyD40oNzl3@5PO* za&fPOi@j`4cU#*<_uSEu!f_p{gyr5E*#VyZkBbba4zI~BEu*~V9cmMF8z9FRL|17& z(rnb|6!dfOcl=fOJ1bynqu$TA%`BGR{wn+LytYKU2>ZoZiN2<7W4d4zq7f{uCaXnH zg#rz74wDndhM>Fw%6*{T1H$o@bU|lC0t_%Z5v?A+OI#K2xOee4LPl@74!`K6%|5+m zK9|(Lx%{JuKBx{|&n1WcLWhT%RL5YU%5E{1P5vtCr2tD6$?;3`9Tf9HJGSbo&5<1I zi4AYf#X#(#W0Q^T8n&<19(ATa9PCRk-hk&%yA^c+9gaKf2H;v$OkHPKW!Z8KG|!zK z*7Hkd@B5&QU@USyecsDj*B-eoxt$v1iy;n7hVr7(+4*mgf$aE7l9{gOX8-1?B9YhG zsCU1 z&K}Hk)6&v18Q{d^+l~C6>x6qx9L4IXetSX^f;(c;^!DX|HKz&x3Zx~~-WvKWalI3( z^3`vsMZH6-UUgKAZHt0}p1Z=I{Ce06glNGv1FDNKpo6YP4aRRFA^a4hG|_cmy?QoH zt^DoVKk+h2Z3(+2LJ5CS*TuA{Tk15)}$WDAu zKPFI>(SxosU2pNA4cNA)K62xynoPD2Xsx}bU6R|cnz8d1w|b#Snh`JBYzS}adV(`y zp^iAo=#(weCed(w(p)&Llx$HOBsx>Shn&X~W$JJMN~Tv}l)rDWJ(mX}qte$(r& zy?7uyh*_oXkdvedp&w$ktk)RahzLtljV32zFQrz`z(ZuFFpw*Jw;q5hDbo# z#;t^-I6?V+^KKM)Ld9-)U5;odcMz@CaFU+KJfT%$ed2V2mDpQ?ua8g&VAnHSbz+&o zCS;tcm}YVQMtkQ{VpZ`QJ&hECR8HX!P_zWuZL-@>3U-Q}7Xvvc){yx<YFz2r}*%_kE#hJ zpmD(5Yot?7)QS#6;u+n(?cZ1Oo!8FLPW6fmw0u|qcre(OdR~lf#pg<9y$U_(9>N-! z`Lti}vMzqo`QWp2jEW({=}h<=F}D5T6XO>`dIyR$4OWl)8U(hs?(xz#h&|x_Ev++m zF~l5-Tk!_DgpYN;8Sf?-QgZmY?{G@b8Xh}(9sO4l>nl;3H6Aiz@8egc->apThLs4~ z0G}G15n&QR$l1+>VX}%H5F#jpYk!W;6v~vOntzquyLh{2Ro`@oGb9KgZv3Z2!}q!_ zl?&V(a#nF|bcm4{Vr_pUl-(;}#cg+erp3u;{oz3fv9yz;UP0^wo-%!bS zBd&QC>xyx1s*q&$8ok!twN=0kcBXk`#O&}E-gkv&WV10y$3yri7qE1CR{j3r&V__oy1B@W{ zmu}oQ4I8xbZ%f<2zXIti#)F$?b)B@_@F2$`2|@lsp;vD8FFu*X*MI8cr^Bo)VQ}@A zI~pJbDfXMAB}W1@NNYPMhv&E6dHsuT+~9e;#dT+A=j5KW5;eYfuB`8#oWEBNhpsff z++4uZPPe)UL3`EpQ^s%ptEawno!ZmAF)&x%%wwdmBrwqdOe*r=ro>mDzNWlZ?(kI| zl^yw!hjX>kSoaIbFl;Bsx3vtLNZ(^5Lr18tLb=NsoSK7SZgMcvdLc%d_Hwp zf|NnUBp^VuvapC(-c^%7f?IoIx(Y`I0x+OCNpilftD^D# zhL!5F_9YWp9riQiN9_*xQCw=Bv#R}?=^%0Z_bu%f|4x=U%0X9+RqKyt{=@v?q;Q%L zO>zYb_2s%ZfoAGt*Bv*~DxRrGjpl>31uKPxOytJ-j!C&>gMuo~%nhiRF$+2~Iy7T@ zt5kPca)NF6BunhQ&3XT;1$cNq>7-4REfwfbf5m)xK{=_ z?f{N#OZ9zhD7MomAYO`oHU~I8->%zAWLc(zSrd!gxis9}oFLtA&FPN6qB0k|!&kfJ#h#Tj*{M1gp#U9=kzA z74XA@PWX7C6~eHN{)MnzfWe={0-@{peN-r{bi?HSrqYj@{=t3-xjqB~LdAX-BXVb6 z@5HX7m#QRLHq{o7QbLY)TIrLPef!&cs2w`2t8Z&&;A6rQ?PSLPZr(*F=O(vR+l4*O z75R5>7x7uOH=rQp92mDVRY`wh;8F%2u-`E^`eVnAlNm!k)7x0~Z@(pT6d;NMtG2rb%L9CB5mMhhdK2kw+4o<2lv#JU5aa|fFS?5xFN?PD z*<^&I#TSK?N{Y5XpN9cJln;uCof|F~3C=o|Db3kH z@AvqmF|w1qqa0I5NdDFR&5}EDoMUFH4a=^O2l<(w?|n7TD!fD)s1yDW`zQ#JsCvzI z=B)8TsrH7z4O*-9iB{Gm4x_(83sREw ziCrv+Jx(+8>H|Oc!N`XjuDT=f3Auyr29#`(?nsZ5Ojtv*79>yYX znA_IlIe4ve&?w~F4rzMybpDae=@ZFA+i#J?YMdGF(inn8jMxD3<-1GM{%;quD-#~Jl|7D}h~9W{B5GfUBD)6)bW!EG;F=LL%T0sl8d5nyXb8MT;quq$A(oFeu(o6a(zzU-ZmwUggD&5HIkJXxOB|*?T(B+L8*7mJ-r3^rv_QQM9Oc>OlF^1XqIx2&xYgFVNWc1^R53H zVy=0Ad?|(20*L~+QjOnz^KbYaJEaxHKvLXD64EkZ$dt<)Vu-ZAO3~uw?BL_)kDU1G zMDGD;H=1_QjiObz?(rR_ivwcrC?&7w++ldv)|c-pVK4L%F!!_Wv#_9Ofy6rRw&_o^ zmSjf}F?sY}v9k-O+>M=H)BNVohV<@b9`f}!SF1R;(-Ym_xN-Piof@@sb&&N${>A`j z*J5%)z8K)391R;U;E^HJD4$I3A;Aw4!hR?vD{+6q&NBJ#z@spsM|-8L2A?$z$Dh+B z@sBRCK6t(}uf(d(xT&Idbf(tjeH+SKT>;aKbk~kInjN3a4^pvLJV^s?)8y_{<}LBN zWlmZe_;qQT+}1YeU7H=1OJW=Hu%1(2EylH|<&$(Va#lP>)FIi1jrH%M?W}iAOlgKx zw_Qnm#Xg$vRb5@7zFs13;y}E~1ry9mTcaPS*SEaQqUATOjFTG+oUm9Mx6T4bRsnlx zzAcv4B8i>6(8~UdsU*H`@}@YamCrRcX?jRSl+t-A@Fqu_L*YS{UuGqbooUGzp{}8M?;x7{-M7!Q?lRn3R^$>>rQjNsh9z)mg_m% zqb~HP4azvKE%Wt9-e1b{c5k?-$2Zwo+CX_d?%Pf2wbX8i65rBQ>^xPU8bsuV7O-;u z`!sxiphob}bst(!UD0{qyIhuIJXx!E(hFr*bQCk@NiTeg1*LP6X>`U#)}+>MN9Xkj z3I4*gRFQkBlYpA~dDe_?$nTqO0g`W43Wx}71lR&N>2J8DpUhbdDK)GEc7Kn^{AnSt z^Vf8^t3#4yBZj^j{xb34I1S}%i-aabCGMcj9Os?x?rv3}cVg#1QDs6N2;klzfk2sLvcC}X1+=hcQr;RFa|OJ2)DG`Z8P$j?66G>I9$-LZ!~$5y zEX_?q5)+|1BHF=QMXq0o+nNZothMhEa~|B z>AU%sPZEfF>vq5UkSi}KDi>nnbmk8&L<=ZAo=JuR_K@SBG46v||J=G#A#3T1H1Gw7I z`#}(X4u%c@y6F8RXEPs#i%8BDH0*q1@9NrF>#%J#@GHC^!8H*P&WEnxGoz2*T?y@)=uwfT6~Tn^_+r_(%kdd%~{LFK1I?oN+1~4La8u1Z!gtG ztr5v8ZRiWX5fkpbMdj4?f6X?AR>nU3>2?muD(*a+%2i90W#o=r^wrRLK^@mSCvZ)) zGP65RgvN0{T{5G^Od&d>Kd>LFJW%P13G$8r$%l-52fz&HYv_eDSK%%}cJM^3|R$Bi$Gr7{P2 zW^Oq|SV&N5j-BDYa{y(Httu7``Hl4g%0CyJ`wBYT?_97huu{IL!s4>=UM%^CkkoK*kKKW>Kbf^c|%C^L1ShoLPG+~ zN`8Gdd#TE@abaNl zK}GN{3ehi`EUYapchW17Ngf{*>#O=6uiYVVJ&5epWw;a@Xjc#N3K1_u*Q zs&9L8LWTi|i9>Q3&b>F+u5~nWXJ%JX@gSqM&VGbAGu+q&2s?v|28QOuBC%58F#M^1 zJO}tqXgJt`Um?grzBB0kYMdLWNQC+ccmsHBRG6fU)F$hin4pHhA6FlpT_|&#&kElq zlUaiC1`MP&u1TsN zC*~gBurrmi~USGyfCe*r^xkeRAFa^~qeU%tzYf)`wV70z0=iu-;{ zTuf>);~x497LQnTfYt+fF$PEs!0fN+6L*Y1{pVNl=na}Tr|N{s0R@ssiG&}7B~$*M z3U3?84rrC0?&F%`cRgF7w^Og@SNk_dT8S}vBVQi_6LWrd;;&72UVGDA_HH=6E&h5d z^~2Gm^_#l7W0h0#sH5vJ7YTFq+z*<=+++KUA2|H0i=1am+Zz-C|6U4`4nu0i6)$QMPf?V!CgJZ4h3 zB*R0|bl|ov+&i<8WmaN*v6PhAY5HtUJJnYE9Ie59+>S`S23~H*FZf93dRj&N;^U4t z*}B`_Uym6YOif*};Oai{tsqC*_GAdhdULvep9f#}XvW=(X1MY(F6LMBu%CNxEW_kj z&g<7D&9B)_3@e|nDL&*Y-=Q1*L9k|iShgg&X`f$FL(E#LgDsCQI}F-Mc4I#&P0Edv zBj)kB=0xs!TQezmQpU1Xlbw9TJ)J3k%x*?wET>6%LcQ^5r)fYC$7vY%6K=ImO(dTj zjo7u@@7K8Oj`ZD?g=NJjNeOhhD(0PvCOUQ+6BIl;IQl3~chPu1PmP{F7;s(Zsz!Ry zr1;WwlL~2|WjuHRh!0Fr;iU7IpUU1Hcg6}>%M+}Fg~TJb^dq#)AHe(#a3Q+9p*6<- zsEz`bzRz4|$J&!vIJu(#(HaEkqtLRX7`PgBbj(@(uyMmwqOv5Wq^Og2|Io>cS{LZH zUM8o8gneb}4)J4mxC8hww0LyPx8^f9M8cC3vz&oRrqQk`r*J2G+3;!~U-lRJlH z`koY~O`SAHV@pN)H#sjkspe0VI%dVUVsV5SPhVF~=6#CzieBBbS3gpQ6z=7{*h%Y{Nu+7LnvLo-sIl|GwheOYxsU0WujWj<@5M&YIU+Xr zfUMaHz|1Oo>f{rp_QQeg!hQb1H|;kN!Z@?9#5}+=I{87{MBNo4qV?5{d+2`so>=xs zZl%FAImr4z-y5+9k&cEQ(|&tJcRL1h5WPa>w~o#}-_W*r&)r_U-~EnjnVk}bduN!L z$G&U!DDy&rjZ|AhN^0SV<{6hgE%e?>RBUru(c(#hmZf@tXFLH5T&1+MrJkinjs)YY*SkCs+(R`g7dJs zBsh1>{xkat^vX#~@uT%zGS?e@<*u@S_xYGMdS0#!TqLG8V}9tuQKF$l0Du-Wt~ve) zxP3T_&bXcPb7lll_k&edx_oBPw3w-E|tnWaVHS5<872jsJJ*uaNr;fyFhAsO1i>IbL&nr zTj>nX&#Ip~b2wft241&7MG zPVQq{V}=r{B$PIh*mfO!wfn5D8yyh<-48jDisBhD$;CDvZL0UTP%jB}*Gk>BVoWD> zITRcdlu6?|sf7jCU(FTN-j24_lpK|S7Ed%fAe`Afmd+_U4$VNmq4bH6lYkG1nAbmi z@x=mD%RGxu&e_%L_6cqY51qW}PnhdydA;XRb5k-(eXTvFBExCJ&L6aPb7PuC^k*6l`9_`5)m6}yP&>)b&q-m5Kldw| zvm(E7yIirOg`>MN9rq;GU%z+oai>GXi|InPitVVzn1Q2q`bqos=|Zzdqh%L79!FGY zX1<%$LkE#=U($?MVQ-oGZLq|uU`yhZwA}T6? zZ3SJBkXF(7f0UV^d5|9BkAjP>yFg7g8zj9*ZCcs6@>uX0*alAZvH3qC`ha%_n&~$6I+$j z^ZFf@bf2c?-g2GdAG+vb=3aUvdSR&|XzkxK%Hlb-4WHMZe(~uw5~<`pMWe^iC_6|G zWXD7Kv=;>Jx^2iFMN=db7&e_PBs!BmvBE2Y((T~t0W#2FCG1(DfBP07GYx#Fd#&h zcr+99yjQg4&C@L ziD6gvc>3IRMrooeE@;49N%U~Z<3JA}N#FVA2MB(;TSUI>Tf$wdV!e=-*YlP@wuwg^ zs+O?=#8Vy)CP=rbz*E?b1ezKYepP>Fdp~*%hrP(P2S$tf2WDlHSGnqkVc6;c+~RLQ z#35QCGz>u2q3(sf38$m}AHgv_uwr~?5YIq^b$AVhsoLT2#DDsx$db6Z>nso8FadxY zsYN^?c!@*4P*^???saQ&E2B`1lpjIR`QC6PqNYHoz-Ra+1B*};4v*vS0n^`?5UL9u zEZ*$(=Os_QJT$pB@}{n;)GicCS8Yxg@r%FpxB6{t`y%IWCi;U5OCHHmq!FLTTxaez z3j~WsC^K)rMIZaMOZ>Sil@@I7Rjz+nkv=l3>Y8UrM}E59SVXkrZYBEioI?ghV_73_ zeFf6Z-_*1J;W`rff<<2lX)eAV*NbI-u)npnRrzgh^Jp~Z?~%;+#ozLcThy4e9h4mw zWdgtEJ~x-~+ZID9o$b2OVzTC1g_f(7_n{O$(L)Te-cO*`T4$x@7ODX!8+uaLF=)mF z9W1@d_v8J_{z57ncp-daKnPBZ_Yg*FROkPMnGk{&_Lp5}(Zv%~1j7>=^YO1?#TNTA zdm-2=-p1}KO+Ci+<%;fS!UWE+Y~=tYvl>&~!?1L! zGWk-d(79K;w|F7+Pk`b(5P|EDB#`ZqO#TA{82s<&v?GN4^XuEH(WX0BJzf^CDV&%o zVU(sv0d(ti@-0hW6xn+9GbL6=li#SV+Hc+KzlSdIYh(6B**5FlQISu}H~Nh{jmLZ) zuSMyke@?BE)U!$8&24C6w`*lF>{4Fa+*0P2k=Z2Bd4}TOd1a&Oa!%#7-B(-NAc;Ia zbM%&~gxb}|E#_a&RIsc24if=e7Zd1PGdm43tJlekZTD;aN@;4A-JrLx>F5Ue1a7*V2CC?E(`|t*pL+b zH$NLgOP|Uf=QHiTnifJY9>nnmqBF~jyuAc`tV(rmxGkG-y)Wd%*zE6+-)o#dolS>0 z{`QcwcmK^1qad{uqo^j^w5WdBHF~RMGI^6mBpU1zPljT^Rm%)`AE5AY?pD|GtY}eV zIrEqQUqe!)|F7foUTxJ>v1-S4x~kJ_yLJo%v8`32f0o5&>e$_**%#)mTIfmd;#7Uy5ts()(JF^>{bTZ5thn@^1Q!+xQ?7OCHu#}8wj9q=PC>0MqMCJ3` zflRFVd5`w2F3e3G+pV5Fkt#C48m>pbLi(ni&u8Uqt-MG<&({+BdDpGPBOGBMDp`;* zhHX`kMIege3i272TDKBC;`UJQ#KuI&`kHwJi*qi>#m>4E&1Ok*CA~yrd;I>H@FP^M zZ=@R0kpd@)y;%!~w5rt>KADRE`#DN~-o01Yjy);D@B^j>hWekb~^ zf9oCg;e_G8)Pb`;Jj^CBtLlPh)%>=x3wi%EFWNujkei~oaT`PAucxCrcP{9%^)RI)AmO3qcFAYT;q5TsaHa%pVeG&!7 zfurzT{J_9K^RJ5**&mZ`_@xK=@r1^C-}_Ny?rEl-u0Y!YTe2{zW2IprhcT}iMJu^m zEhSiMqs(nSDy+K%qqs*ChiQrG{+02+m{;GXxBWBJ9Dkb-e-VNAN%`^7pqG#;^J#j( zdCwnt?302Ugv`5YP7b>%5_Q6NmFR)QImtDb<(Mevzfk5_6zw8pI+VoJYebVx2t1kB zZ6zk{;3_c_Q8epaGQ`QJvr04X#ZXo!jrFn)`DUx-C<|iFfNwxlH)z|yME{T$ddP6E z&()5qV1?)FTuDo28hVsGi)KADX3h zj@>;bfA*^w%_4|}W}mF-y-Nk1;o^#MUjZmh-&v5cM;pr)lICq%yzAb!EFX9zeh2GG z9Ad`L2D}&lCMfDM{nD;3M{$mxp?~* z3$6{!{Za9YZ-scRb_)1VZ6PWH_G7-Fj_&-TDzz%!D$S9tCR;kgC+dJ8GSCGKdfVCr z?7*-RG&7FffAHZTorA0bwqHhS9!Dc2Nomi_agECWVs24%O{#mj?8`- zupJ4<4>(AT7v|i1i+L{Pj63a_ZM!us!8IDidAMlY$Xz_easH;b@n5>CucvLK#(Aie zK1RkbGUSgsIy%v!An-Op&2DSgF~c!X#6$n~%EXnTpYgn616ljFNaEr*y4MIQGhcZz zYFXH4JCjskSFJN}tj67};cQHQLqJWiqgckQmF{L`UdQ#hK|5Zn(k_QCipemLUkJ-- ze^?kxt~(sd`P;FGCU2h7U8ZSjt;0@n^eD7BIbwMsA^L|KQ{Tv%L~2>nFw4PINBU6_ zg8Mpe1E^^D;|i89Kf0ZI*VqUfL5d|;U`)wBXgTbNvdUccv$DCM?}Uz~rVMSB>Ddk> zJ_Eyra0DU(t&+Y=!7TBLuWGa7D|4wbjaTKCK_#Qj8MxKjaHJ$=)+4y&d3392bl#W& zy`qs@x@vFXZd19zw~qZA`Gm8r8XUw&#Y)uDUAq;Vcuz#usTR{EcD17sN$MClwpaQu z+3dRu5j+Rgdgf1gL|_4#MVDjW=fM6SUY?{hUS8hkf7lH8aTI*m2w~bv3kZ$SA{ri( zDG;n|IXEufdD-mImD0TKEa(30M}BuNdCt1`wkICh(pi$a+u_H_22GllR8dKBM||H~ zO6RA55Bt{HcGvM~Pesj0+)5G*i6Ece_BCMZJ4c?PfMJsF@n$Qz+0>{bi<+ye05r-M z+_J3Bs8JB#Nb~+@+{e67r$~?F&{=OmJH}kiZR5oIW84p@HGD56C6*nK)^)wWGF91p zXcf^pK;QwLX8Dr?7hr^d<`bhBI?w-58;H#V;crFqS%w~~YDtQ13pU9FH){ZlBf>r) zJwLz#=gPiy{_n1$?*#pT=@Q5=eub3u+Y$Ngy3PYT zvU3q>g_3}7XfR=`GwF0aiB=@;RhWLD2a`41J3IMt1qpT0t9Kl0KWO=MYOL09=P!!c z*%(u@%<<2n_ELNO^=Hv_KWdqsJYkaQ=}|n{Y_vzGArnKfLIUI7EnfD2;Vaqiwy({u zR|;HB06Ntc)Xkk&_e zpX{{BkQx>}Fy`Px>EKq+;SbFgOkpB>#})3T71rD4)caXUrC4P+>d0B#(J3lempw>j z%8lPk`}nktQciW`>g?Y>W?$kcKD+0Kd)ce<%OB_bQ}mMNBE3rXbQm461gR%FDgmS= zauJkvAMD&e!9F|^2_PZj;GVw8I7vnyi|71L@!WZl9_xl98$@GJAqyRm2BxxD0A3o- z6_p0&`I1j2EP0^(&+o$&XG}BXaoKt?!f0nF!Rl=Z^HUuy!#`%6(hI+69cpdc$;836#Ph!MYPXfsNNK}| z#An?fl_R@)I;Xl8*TOS9T>t3V&FN1UHVR+-HzMD*?Nhnp+2rN0jM1@?2`s$>R|##5 z*hH~Gg}?K?8#Lp{gFTv5x!UZ$aN(Y{pC0fAbXYQ3_B!+|)n*(KwERTsSaONU8(N5$ zuG%YoS=J&*Qu;B^hoy?7@Eb~Bqs<%ob!U;SA?Nb~G5Z26B6Ihx^cEZ?4xsmjfAQgV z)z#Xh4&Qz2iFh>3^@a4_m|N@o*4yfCTTSG800oBCE5tVqCFSOfsGoW3Z;4H3A*s{N z7-F2x9=u$Y;yJ?D4!Q)yhfJkpie*97c=?XIwb70idIh#?5bKW|lB4|g-zYYfS)n() z9(oL}%AVLr-9yrOp?3#}?u$?BN+%*qv2?Ds?JqOKkLQUm%|AG54NJYPCT-eBW6arY zt-O^vfANAlNf-FQsy-pcU}QbNv@V}g8yiBhSqoyRG5cV3EP zBJZnOGwarw+@Oq?w+@^MOMLlLOzv}?-A|+ER8cwcz@?$W^K;Snd)CfsJ*w`n?Wojr z-?76}C!n`Pl$FNJdSZ5AhdceLxeV$5$JKX7!@0HXBa#q_9)u_%K@bx}Zy|)}BFZQu zdMCQUAc-!Bh~5qfqD1dz^xh_-_ZGbyz5e!`bKdXwe&1S_KV}WHo@e&6_kCaYRn%V1 zC9z#vv)RO|)gY0!ec-WOZNZY7u{uBS!ek|A1_8|t<95eJy{V5)$fJX;|%1&UN2 z=>yj}KtTlRtAVsC*FxY?3{*mZqzLdCHrJVPw76p}Xzd^G9)W2yKYw>CKSa79xQQ3- zHjFE7xQ)c9SZ|d*_&?A7NyF=wYR#6ZTUD|wWQ5deyh~5hvsn$Q*{z(&4QF(?j^)!^_KET&DfdTVPfzKwq+73 zEsW$(>MaE1bJ3X-mATpfJ%dcUTPpJ$jRA9T+)3vNLS`y3;AU}AVx?$tw7op$PFp0| z|9eJy2M80&SgbVp3rrfOBzHielA{AibKvh%7NSP6gs!5ZxB9N9`t*_ebJB(umFdeH zAg>dPX0i>qDMhMO{%xTvtnpyFsLIgOE*XR)ffSL)H`y%pm|6s8^NBInS2u6~i7vSn2nM7}^V_!qW`<<<=@tBnj6)sWtwMy zUcMyXeK{H9w3V-$i4jtgRqDzs6;`c1(vah~;SR0gD(!Gmu9@$lHHmVa2`klZn|ESC z^SPHEK9B9#N{mB^bR0?d3nvZL4|Z@XXnDDby>1pP>|4(t1)D7hcUgA&(rvMsU$IVP zK^Vy$R46XF$A$NMHQV*hTVZtFi1{Wo1ijedx(V4-x!Vq`_CQjef_1*^(O(hJ)1(9M z0Y@w9iqscL@S{m&)%|&lJ`t1qG~ifg{qJt1<17|R{Q5*9lvx9!kp}#FumnU-mD*AL zzA`R%oi7i;?ZJ7wrUC<@YM@fo%Dd;Dwkc6I72u?=Z&nit@Gda!6K!90@~cS>o(CQ* z){h(C#(E7($cgflPWA{CxRy+%@LE(%2zSrrrhI^!I0{Q#M{RMNPPf404p2m7$)NIi z>Z%eOHnP}I-fmf#ZL?*tX~R~#Uz#>wh+EwQK*;-AOpRg z%TQvo+CnhQJ9SRk7Rf4%`HI5%6s941!hf22?QNsrQdK*xR4eCYY#3B^e@htt*;!XyIjeW zga*v|%(!JN_L;8|T!juV%>KZ2;&R6d51ASVi+%z`ZKu zD{#gfcqM_lbrJ98*3^jSWvGzf)l3iH|2oz`U$K}EZ4J#R8gxIs9loxi@6Oz08Ct~! zbaGu$k9_0fY-*ym851l}-o!XH&lp4k!`g*zZpo9v#N$u#iw(uL+XFqvksN461IleDc@m)Ar z?tt3JHv%tLJ)i}Qi31c$dqbQZ?^|2lOY16yB&QTqYysukspy&48H~()$fTG2WHEcN z?)vYeh=@jpQX(%2voydvQ^{VK9GPGGIkJvTH3u~>P!NJ~k@DmhbDefhyA%=Eu9jSb z?bp#&uXEz5weWLD@<&=248J_|SO^ztm1Cm*KFbFoBXjOkL0a zA9V`irP&wh^e&zUUwI-@TygjdKtYo~?xlN&03316K zSQ;Ta*-*iv&i>j)bFvUjtvnTJ2buZJT_xR8ej}YTArnL9?IL+s%=1=S^ovN(68Hu1 zk^rPIms|;3^#>yoXgBlPKHShD6{`L`OD?xG&pJD~T+Wy>&|2Il4r1*sDoD56PGIJ# zg=LWn=45r$^;c~@qE8#Fuh^y!7t;eY1nh`DRBBjxX~1pe+E!xK9+Z~~x&K?yTmm%2 z#U824`A{wli`}af{i!XmzIpBwV`m6JeFWHF13{@by_64lL>1rXm+y0Oo1dtT_xBzB zo16^J17M(kv;%B|f0yO7TEdBM0aI2mhs~+!nExXVHdn{fzHvP_T^lH4NFlJ+GBSFw zI9qX~GrSDMVgQ%!?d{F++#X-tNSpz#c;I;m)iBJa-}paUCVVEH-n?R>r@;3|WEh=_ z=+pPL8Q9EYz{Mrz(!1ZE)>=*Zm5K17K?8YzsAB&wqo|wJaW>wkUsMN@xxrS&7$2tduqB zj*{a_x1hv!*|+0Axr;Gm%RHtol@Za??_Haq>UNp%OK(%i11(FdJNnE@u9kbbm0!+_ekNb2 zG-9l{s?8$IT6Vs>*4+S-6&%bZorRiqN)gN3M~0aQN0&sJY#izz zeoN`}MDn^fOf3%pAytpiANb<<&C)}U;iH%m}(81Ha}95Fus}4RYRyTV|@0QWDnsJkQ!D@zJdDtBx!!Ec(X$; zj*Bc0SUv%)uOB!5a-ser2$5rzGvRz8!R6T5uj_t2qCXF8l^q@i{E{22G$$PEl#!XIuSbR}3lK zDxq>Vs|S@R_Ws&-cs`IC2j&eqD3h?!L$NUgo_k8gcxPTK25AwdXgQLReTf2iESQA! z!AW<8|1M#d8A`X4kcgDZ%hJP_QPecg3VeM_WZu!8$;Jck^m}p7asQT*Gt!uc7)mNO zmIpWRuip=~`Xlw)r5??aFBu$1wRh+~><&F5-oA^SR(!tM4f7}8lpkn%-~BjtQNP>y zlUYde;So@CxLJa#5uCU$zx6AnqZbv*uP0|nL&>yv@~cOf6=U^EEcGyl24$!Vw^{2$ zjpU)t%}fJCxZAsN%7jWdeg>+=qaLF*hzplwp7=N_D7zJ%zfh7jo>Lol_M#0Nbpa-g zfZRz0Mp0rUiz0f1L&jNDn&mtBXyEs+p@Q%d1M;|>;tn)dlo&cd6s=#Qzk_85^BT^+ z3#qNJ(Luk8jR%-AUswj(sq+Jfzp<~tI}s%B@W~?jht#>p$EJAf7@`DSHm6T}v_(ng z8yZ|d8AWh1#)IZF8Ro}Gh_XNZn=(b&u2Q>39*&JA0EEcC$HV5CJ3VV`+vgb>I?=BK6Afa$aRepKscoM<|>;m-34#1L|!ysOfLMcSik-N40pNXdTA9TzliAj zZ-P0nsQVU((MwEhuivGs=P7mgTf5L9_w|Y>eb_Zwn&`nFsRd813&UGI&riqNm+7$& z+4Odg0^e<=k-o2z$rjbdVZ%o~3TC&yUyr-UZLVRg`b~0e0Iwg3H|!I>>oXZIdpb(e zZXWAAtm*E-Q1+H}V}xNevU&pT3ZWekGp=PtPa$V`sI0C%pF?o3pg4?wP*Fd+e!)ei z!?$imeW5hCX@!f>LfN1q4eSjz8HP8ljD%JH8peDCvSPp|ca8+_5IQjj)$NkMhPTD65c&Ka$uZWBg;Ay9=|r5ns|BDu?u zJX>;z$uq2ru^lj&F@8$(Cv@Pn)MmS;glyD#$>|yzbGuKv9_RB=#CLZ< ztb6qZ$dE7&&{Svrr8k%28Gn~U8`nsr8_Fdykvm{nA5xsnq@#j6Fg2e``~E&m&WPd& z9*jPIg8RMY+C|Ex3IAuR_n2h8nzW1@3yTY~Y5R66t7ozS!c$vfO$M<#8f96#Tq8fl z+n~-5HgU#spkaMSK0?+OnJQD9n86L#R=z?%q_)K-?D{JFb<}ekj`vNXSl0-*8yIs2_{lHFm@>l5$v(t39>bZL~up}AtE!&wrZAM6-qE&|#W*lAR#8GEh(ewFA$H zhqyewwQ8oJJrwO1LaJeH+WWG>7fx$SDAT9g$r8a|$Guv8I-4{tM$BPBC7W;E#YvV! z_|~g99~BA7mB;7F&UTs_r>@G{m`$LIpb%B8We(PGYWEf|#HoG-5j8Xn0L4h><-P<* z;OzKSA#;*)Kz8l6MRoamV@Mw*d`_+}AsdCNIV+tP_Pz98;>Wv=wKv%I+PlP2K6(Pa z<-N;CkeKpIl`EBg?6H{;DTd3o9yyS@d@ty=mbjuL4%*41I)a+a-=bWdQd?mOH3;dY zxN8xzDvM8lHlD%!=OW91JMmN$k_A5-RaGzgk@qw#pQm>L51FQe>FZ9)zEChU7;Mz> zM@{QtN=Eoo4h*6&oBWRAhB!h2v-#ALCHM{bIWBkriS+$xS1e{@0Zh~xWTGM`)S zD&Ud+vkMB)x#+a>?Ou~?XIw~KompR<MW=0qTe2 z9`FybN#xNRfO2Be08umZ_3Ik^2#^SQR!4RxuzBul2e3O-QUbKXQ?gw^&{n-jpNwE5 zS*->3dNwxQWk6GsoKdM#NjQ1&@e=rGq-8pYa^nCOyd`&W`!iipiOrXwGd76eX6jeQsa~WakpB@5!mmQvlrXA32D$# zn>&-PnMaV~V@z+?{a;lX_G4$jg&wxg5zd1DS%xcyqyKA%0n5Bn`=fm6cL z{joI1``I$0;*}!Y!g7@$H4tzVti^#3G4OJ;P2K$`m>LIYRp0&TAOrXaAVb4eqSj?} zfUo(&?&##qZ(*97-~Yn}NDJ-+3Z|T5Q0jt`)42yD1~O=y%OEyjAcIYM9v9R-A2Jy@ z%ABSkkG!0AEkvEJ3Oi$dOPNs=)$&%9jeClD6ZWy=U+ zGqYD66VwIcb#9WfCAg-UTyDMf7w6zW0F|Z2y+8d=RaSrV?vQa0=F)_~zC&bXg zuLPfroYhG#3JoKI6}9ovfSy0$mObF;W0>;>h?AWR>Y+IenfbZb0^i{-bECUA5&zKu~u1M&LvG>Pc%>ePTsbs$| zvQMEu=j!<9x>OhA=T>pED>Bjbswv6Oh7OKYm{5>rv$coZ53X8C zZ0DLYiY0)4ufO@|HT7ma0ery)A;`&J_^$r3*3k=mw-9SgR#tC~>Y?+KutBRQ(or^; zt#%|e*WpKas!1t~xoYNkpRZ(>)72~;@alJhQtK~kiAcDwWgmrZNl}Vv%>`02 zqSk+mxv4~d{q&=lU-jjW)R84vOBdX~^`>lWhmq)*%&5W_(*k~XLgKTz4c8Py7s-uG z^qE2Q*%(Cj$U$BID1mBVL*htR@EPPXqiX96D1^nN->TzE6f!sh4kVc6K%og^5z6Z6 zy1v7G6VL;r)UDyWM7IWJ@Ttr zf)(`7+#O?qA1TD1As9kM0>L!Mvhm2>_sD%0gv!@rF~=Q{|3u@vFX!tY2lIUF>JvrV zfbB;9Ac$M_|8BTQSh*WV7rFbKs5IDF!EPuCeQe+w+5_#Y${$3Z>ZZ7zNM&;Qe8$V! z6uXvnovgNQ{$h~h$rt9~R%}+>>Auyn`x%eqktjElp8wvS`zw+D(=3+pdy*pBy>pOP3Z?RINGp@cX(mG<;?XH(nO6F7c44i4K0sQ|3P zxFHk-vJ*JZ?+Q^p(e;-NqcUm@y&K%VU}8{7*nFBE9 z$H6jn!O`S#g#zYgGz<)FJ3CK7UX1ruF|US(M%@+mUw&W;-fQ%6-mM=S-R3*2we#>8 z3DO zcbbxa`}S?xm!6)!ZW{{j(87c_Fg1+v)XsYSc>n0gYjL#gXl3QcNUX9X^j@9hiFe(1 z2B_hf#TbvKUe8Odh;0zd7gy0d0^*6kkG!xAs!WJkZjX>mE05_kefsR#pS-XXFW^0$ zM!!K@yxs*;<>eoezdk#@46_4vxikUNQe$jnV>BS}^C5Z27f+@2m~ioL#l`(}%|%Tn z5^0cP(WKsaG>9TX)_+`!L!dXv+nWdbOnFy(iQH0cZOwu&$hIF%+q)^b`*t87j)^Ux z%M&=I>=N_`Yz6Y}?wC63X=f|Qm|#9th8^&4AQwhHg6qG$^qE2Q9i{z*oO{onwGoA3 zql;3-y}l#J3jw1=8YCA1ZT(#7&u`zZg~&8AU-Rm&)*t}*- zD=R5Y&AV8qUVvxKv`jeEhi7H6ZcJ8F09zVak(4&(LxK9wT%XHgP!9kZYyG1%M3E+g14tWumV#lekS*5S_i=GeIVNrMwuEbrnvYfA z9)o91XLFdk-U!HzML=F^%dCDkm`rblA<3cfWGOttlM4 zW!{ntcHy1`*7pXAzGYC+dE}Dozrc?7Zt!!8_nC-j#*)At6FLm+wuUbyoqp(d){Zvu z(6>1h50wi?^dqHoa5?iw@0ZilDM?Sul|Qn)LuTj+?#bg_OJK`*fGSHTXVt`La$P%a zrkL1&m7JX9|KNAzlYH0|{{n`s+m=Q*eG)s9dfdOO;*T_suUJQ3yua}WCJ9^r zu^lQw2iJ^8I5SI?))df3G+~>(>QX&yoidy;L0JlZ;a^77%8d%TIyuL`pY{z$tGeHD zZ7L1<%anz9m4JNm!zp(j$**N}8ClPgLK*TG^EajYxP9kNOmJOE1@6~v=CacfA+{2JvuLK=B*B+(5 zN_gPPIIelS-tygiPy4Z#FFs$;oBI9&M&O~GPbDNG_-%&&Dl8-cVJA3h%*TMrVEpbK zDbBB`uf;P3N8Xl#yPiy1dG|eosu*ZW7(lrV{(e3PJ{%V@cWd1L zn&&as6fk{aoNC;qu0-16&Gt#Harv;@loz{Vo%Z*HuR-mf*NJrxbiA#`JKCIJ>ow^F z8=l8}2;2AhTWMa}lMUw8$e&K7&sRIQT{yrb16les1OS;i^G)6heD z2a3q9RDJFs?8V={{nfjD8Toany&%0Oj5`jqtZzQ2uZ)T5vR!T$is9(p&h1veoty@l z*9mnCskpuQo&X zEc|K=ej6%bs8wi-A}kS)lK-o=cEY`2&5U>m!Pdm+3(O|UHg7hL#Gsdd7Tgq-jPCSs zexc9l;+j)u;;d335b&OHVs6d|IQ`zdxVZT3#hRi5a?55r+0ynSc1@U*Ol%FP(jGjw zVz3+2?V9LJmCb)b<)(Y+-D%2OxBMaBUK8dtU}Ia7wL8KQCI1$kDn5=ebw(8zlTB1Q z91Wkp;aH?2x*^(T811?~Y;<*bVQFL2JUU7PQYwhv9=7Hq&JJHKN5^BJ8>Jgi?pnd) zZB<}_19m|!aJF>EK4}I4bdDhBWP5VvBxOd*&h97MWr1NmgXC#{Bn}P*1)Jm1)Qnoh zJy01Eeuy9G*jo#2XD{Ub`?1HD>LGcPo~`k4rzeZ*!+b z55AOn_TZCtIw3cz0a|Y-7X0xYPwe>t?glJb9j+X^KwG=>N#!BAJZM)V^^?{c`pk~< zt%Ph6DvRX+4DqM%U6V_OWVZ@6d;_FNEixX67;yo&3N5*My&@o^`$jHjN z(U3o~4G3D{ro16`6BRLEAyg(feygjr+Za8Ei=<(DKm4~Jn7BzPKP3FSM@Xc$EbKN+ zwg3*pH?;w9!|oXetN1i)v3al7g)#Rf{2_T$?l4fmMVY_)vO?k0oi6yQv?;%oAaQPT zl)y@pQ5=h$7zPo=u?dYh%L>#=o-5UQm;GQ%y9wgpQvb8~M2`2kOEZY~ZEFkq&}##i79ZLiX~AqK=XTp-t0 zw{if>!FySBrtzr$3IR^d`{K8}x167hman^7o#^BT7kZmLaog~?<#mXpwB#dfz?af_ z5L(MyXs|c>=$|@+AR}4rht&tBH~4li4D+pthMNlF)U~y>D7AzPYAQ4~2^+BMJr`SQ z;>D#NxFoD_opD=I2!9Gn>0wA=OYGyOvlaJi9?ahB3l9x%FYilwqF`yQ&Co7ZATDio zP$UtQ6Me+t0v9(3Qi=3b?Le*>1fS${GwGOe$qB)eDwJM)yGgdc7jaATtiz?el@=P~=~|hE2G^}fLz6679|_SKGL`Z;(;)`8`R(Tp6>SS1H|#Wl_|}$xS^1 z>JRzvnrfn-2pE1~R>M#CObv0(vo$~L=(?Fs9_|YHwBzf$<($^6=YR^x&E=T%#`I#{ zZn1S$Sy|a^j5dsr67#W5ntE75!Dn|UZ(_&yYTG70A*aPca^gdr;dI!V_1m$Mv2CL3 z;5lNpw$8#$ruH+7Cuk_1o}NDYa0@%+HXo+I=Wz%DolBV|nO45edk?V)&>7|H6ytGf zc&VbfSxd2?Kw!G0*v)2^fJN>1j*t2g+kF|%l<;2L&!|5f~C>HUeaYo z%Bsuwh!4<}@0}psKaJfwZvS|t4{Yv?DL7efVf!ptQqG&)@7q#E&dP=18#Ox!-hiRz zjm34WSzrImjG=mfqVge>&Y(9_GRs*>EeaRVp0K9B=9gitB>q`e?}w4w)gZ$p3S zj{TY}Yixh7@Y`X&*GTH)-Pi}iESJ5$Dy-2_PIs?0U|EU2m&?9~^rbn@plx|{VRZB& zU2SLWb$Ef`R}IeKVp)Nwb2ML4jih@^Y?oGNXSaK~71{inp5F3Oc}my1OEKbo zIjx#KP_-DVw*xTZ{FXlHbU$wih=H?h`*STha5H6P16-7jYetiMmoatx-G44|%|}9k zJpd?n*hg4)k%m{NBgbpn^`S`)b@xDB0hF;^w*v4Ew`U@;N^DSVcwAi^A(nFsp3wOU z6t+12`1$i-O5ADbuulGj|E(l6^ zKjDC8O7kVc`87ViCd+A*4~ha{r>ZsHz(n%)!|~^D-Id+GRO0TBAM*WM43PS#{-rix z9B;M9#46GCRrJ}95Vm+OZwx?K`=_SDQ$*cwgqqjR&uFt2j73G~S(WrMZ7!hCA*BZvq$L$KIeq;u^+L+MXcyx}`*$&)tj2oxTx$ z=WuQ683=<<{#ZGl!iWwJvcl>QiNU?0}_-!8*kU)HkNBJu9rFU{LvkqP<-5Nj`5C}xwsf?ov z^@oAM8!1eW@(j!2_BDk06Oea(9@I3Dx!$(@_eD zSznYKHbp!Ut-mjvaL-73Ch?YOg`Mo?x881&ii02T?!m;Yg&bdwij|0XdU}E`9q)|R z1=4xiQTPCK?i9~)eYs~rB@K|Dx;lxpUmdX5>IaIftP_*kQf9wb%i<*CA$i?aNxkO% zfXa#}ymcL-Cpk*9V>@0(Sgqejmo#GNOAp#E8d_S8&Q%-fuW{VRJHyW9!>r_l-aCyq zf8^)4@Q>(!G^lkusRNcjt+TU#ZPS3$k0&xD(Lwt>_1{W~;6uD*@N}~=u`zj22nnB& zQ^B4;nYv5TR>i0%UQ*d2?@X4Rgc_aWJpwlN>O;SZ-J)modIt3_hk0#!wt|+EN~q3n zlag5#iR1SxxO|Cc+f2srr!kY7(?%LnQb;ydT{@G);iz6$qYrGe)V^agJ={1F695++SE@l$Z2j_-pxwtipj zgYFUAEaOXgm-WL*G%T&=zlBy=(Nm@lwR~jj3FKos`q2fzAJ*u)ca5ymNk&brT`h!k zs){keQ{&^-^jqwS@BL8DWo5c;SI$|GTXCJIqIo3eL8bpI_1vCSr zmbNDZG*TG_`9A@OK!oN>ZJ%LL7psAaZty{_T$i1yiDJ_XjwYkvBcZ83ORDp7H6Bgwxps~VRA*J#2yVyFX+4Y`vg1JV z3fPVR3HU;s=wQ2H22qw#uKml4HNmr>)QO0S>p8%f{9Z%evYu0g$$~0x4~I3lX!I76 zGWI_;KUm3}9bWPAs`vpxO4$Qo=Z*0cTy>(^qgxb^4&hYgr-sF*PGeUi$Ic-w844Zl8Zkz%mp#<$X{%r&H5yG}NAQXtk1e5O9#p%aj= zC*orSg&_}s4^8b}JtVgToervu?0VcZ>RfztP50lzwNgU$z#CvO#Qbhqb6Fq#B@d;^ z43`>jGPVFg0%CFW!iMA58qEF{5hO7;)n*yYsGEGVR5Xqf=`H!${}iwQ2?WgVVQ9-~XY&)Q1_x_BxLcw0Mj6yQb9r{l zNFfOj;hI|M02&y3)PWYrguI5$KL)kNE=bcmO06uE2iNZD<#lc1A#VJ!yfhxi+I=+pVjSDDK z-)>K%jxmx~&Q@Pe4OYjr0)Sn3ovcz?#>u@nsg~2OOAS%5MQ(IG0 zWH%wO?EoGEiIN}qF!f2Zv{(PN7zo6r(lcM(cWVzIu^hE0%uW?fDKl~Tmz<>i-!Earf)qDEtA3bh-}Zu$MAurOqm zp8>3|Xk{s_GmKj5uqrXTf}tuaKJ={!ojy^2O@(cD2SJHompIwb#N;!G^C+NE{374q z3+lXJI830}_ntNM##2BAjyXqDUwrdi&aD#+8BX_fWa=Wq%in%pmOL`QeSM6`NF>rm zE67$H3T75=8>8yXeJZM|UKtx7t`mWcPF-DnF2x-KI0kTEX(9FJ zyndK!#7I8$BQU}}T_cq>ycB}tP%!HL_ahQ~at%VfE*A8PrtaOSEzP<>{)w^!Z0FAS z^JR22T(r|RW=y>RS($H7=b)!;2ZRVO`_2+nvcc!R2S@a}vjIUKcR{ze=k5a~U;O|F zVvWe3sNB7RJ!Gy-<_~9(n3!H%tiCQzW6qH9DXjpOvSQ_F_ko$Fhx+(3m?2ty&2(Xz zd9eC8C2u)!lSoSHDB60u$Wi$r`83bcnEh#qx=y-Y&rn`dnLa45PtVT6QJKnyv0vZ{ z>pr3@YT-mgja;Fn;4%4K)ct9ASPKAzo=s0a5;lX)vEg9EFcN@E8&kC-6kkAHFWyfr z1UauLD?5(31_nnh0EHciy$zPj(vycf|Dwm>Ol%2agz8xB(WV*(&)=T-95MgX`giP> z4s%okK=?WDFxi@AhC+(oN5$LgQDP*O?sKn05YgQ*Y zgt`pZw~{eg8aoEfW3%EXWEAO1l7{Y(AJR`%!55!q#!#6-khj;x|A;Eg>iW`OZfk36 z?*^0w=SZ%0NUp6j;l{HQvBCpr{=FnQzPC&N;R5`{})%Bix<%r&dKLxW^Xg5B~ZtAkgvd-tZ7>vg=^)S@rEk@AM5a z^#HOv0~MTJn#>_#_kT%Ee_bTqFktc=s@Z#Ub3;tiwd(NPRs71JPDq`2cj`cqOhkQr zILV+a9IbAL*_d6vpB5Lp_~-5f`GhM!o2g9-$4vQJX;}HxGX?2i-oU_}{`B z5u65)9ke@C=)+%RNA4G*=6}~?)pzCJP9Aid^9y$tX;bM;AAJ0_SGz+8ghr!ZK)BM6+va^=Jc!W!ZH!>9eGx6u!R|j%^OKb)D$n7T&MAlzV z4lmYMv@VuwhJ538Qcnuhr$U=J`$HhNkj&h$jn89Dfm&48cmJaP@#dnx{7InG@ECPw z{i+LX8ldXzd}KVwX*ju$#2PYVo6a83lW~H&EVC0QE-n{6JvxB6hBY=ysqSyCt$}HS z{M!^)SJ&hHY{~HTg4#YkMK(6JV&m3Z;Bhf_aw1n1KX~((0T?ML0A{4Gq98+Lbc5nQ zE@YLTdts zcH&MSkr}qKIO_6u79QMx7`$Q|XT(XMZ|UKsnNb-WPD-vtFhIB|)fAG8h?!DH@+mLN z4w7c)CwC%wc6DNV&zwTvl^hxbND2fTj2)mXqOXm%VFfRg8USh}rafVB=zOiaXS!0e|aC$|8r zs;9!jA*ZLF`CxBFOI~4*50ta(XPk2$Io7=|)ce^W6lL%|> z=P|Py!R-unoZjag+YV?4{``v;-$p|}$;<}1wMdH7*3V_TK|Vn}LALpZutUlY6{r8}qGIDbIEm~MwN&#*SvXC2WsyOi>$ge^FnNNYoE|`Rck-E?bsxt(F zpK)LvhDq-}Ig`DNGva9K5UBmPn4~GEC?o7OS&;3b;AiBDR1tGtd}Pbh#xioZBLyE{c^H4R_()a54`bNg{n`|pO13G&ZcD9jWto~#ZVi&x9P10i=R`s zjfxHSH9jddti^~|Dj9wy&=qX4p!1W*@XOEghg>$E{@mL`ZB|Saxvp#doF(cBt?e{@ zz1GM{fq;{|rRqzFx!Ve3CC3;Sukk(QJS~8h-T*5D77_#?-AZv&w{2s{Z0el%DI z?@7?M9D6?TS3w|T;eX&PW&*GnRDJfMAHnXjR#EzyHa)68u_=k_W?WxgZT$7?bKEx) zzh{PwSCu*0QCp&MbQmebn;61e&QJ17U5X9`;<}LUH#Y-p^{9r&S{NuEJd&R!oN$;B zruxeGEH}l-@bgotC8-}xZekyumd68KDjQ9EZ)x0&T)R%GE&P|k&lw|Wk!ySWuvin} z+dbevj<7_O31P4;)?Ci`3K$e?t zwf3*iUfjU}q#_zdMo3N){%j=a!@d81%;HN`NiFmDY-jr)&}!Ma+z6p4DXFmYFOD(N zF!b^g1!uit#Ja!-Uj%TivZweKcu4Oyv9#tl25dcs4m}!u2I_!Daq?c*n|Ynu&4la0@PKHjCqhF4_CJdTOBgX`zC97zRO1~y zW;;w>cki=T>uyr6#>2D@th>a zaR)VfK5mHc?)RHS5&}`&GPZ3}hrH@)1?~o3tke4?lN%fQK6hLZj0vOWiQOYFXBV9} z_OMtSiR5_^I~!n%<|Q0G zrR+PQc6-9YADen}yZi}5IEX4msjHO@)cT65)iG}p{RQ0?hrAvXg#08}7-uQJ4^gVB z(74+s@aYbB>%0^Bq3rvo71iWg27l>6Y`36GjX%TuNM+RQ7oS!sk-dE_NUHLNc%6qU z6uD8ixK32Mw9=wG#Qz13zuvbXe%ZR6&{1nYB_ejVQHs+ShMYNH5-bMlFY*Z`X~FI; zAl}##bXY<`-d%xTcTD)x{j{TKyk+k<-^pHok7hCo-W07^h6#_(|>;H>|bRUq6fMoqC zfXkoq@Vp1*5)rUUo%W@mpomXQY#JOK4A>(6|9v89OZ$znz%>B3fM)?ZRq&Pn)_#lkz!H0LYsC zo1SFoM4V@s5A@T+XAy;p`Pv(TjMGpvPKThXT?r8p4thn_m0W>>lZ60jTu{J(-&k0E zCjY0mL?lSW0mA^rb;`}xjgdcd^KH-XfkCi_4>f+C_E3SfnDPdmAIRw0_VR%hix>pD zXpP-7{brSvyUX)9O(FApdUtbK?~xob&E;@y=>cY#lk!$nTWF;nnAxptZ_7!fRZ@L= zBk(CA!t)?dmVd@)!p94 zChsT#(M}Q8`cyz*2~LTPlf*H<4mD>HO*=YXoG?y1sqh<{vBg%%?-d~^O0a%@6c)DE zxUTPjLE-|KcQ%4=n>4cB5ip6d_-LxOgR^t#@>I9)lDH4aeId2q)OF{_$5q-9=xbtt zoFTeZ^}>^z1dbCVv(%Z_-QLZ}_WuvM4@`qSY=tTsg^XGeBrJDuu%U@=+tcA@-LY^6 zHpA23ab<8PT*Rmh*#PMmqo(1&J8;`;rS;j_Hvu~<3N_oc$zw~W!2jdEq`5i@N0Y(A zXfKdgl{>|K*1KBOU~$RRznWNJdDPQo-RWIlt7|-wgTZW5@8e9t20% z>DTebR~B?lXdj_GJ_STlHA`s_tPt$XB`C|n$UO-EYcH1&!4HsB&U}45HFIHLJ6Waf zDZv>h{}5}rVo0+JrY2)-x4|IH2plPO7mwWPxIg9CE@;Ko-z}QhAYq}++c17A?GiD(-3#~elU`KJeZht6XhD7T z13wW{j6(x#y$yOEvp$rq7Bmx%IXgXN4mTP6wN?U1CHk|pwj~mMce!6^C*`kZ33M)n zTH7{#rwUdWJ(G@!ePAo(BXNLpmGok%v!{+kx6s1eJYZsNZEOKpvK+Vjp3C8sW~^g7 zZE>$docOy4_^#{bc=>U*?uzJAKo1yfH@33m8%%cSAz!}7m!FH7j4e{P{iZk**2^K7UtHI1P z!AaBV;?-SGm|xyC>%QAHE;G8!^Vq^VvX_X4yD&1ppy>aR^%hW3u3i7|pdckB0xAfK z64D`Ef?$%;(ydYwLx+k8hyscTNGU2vNDK|bfP^S1A{|2rL)Xydx9{gX?|IJoe`~px zYpDz2p6kB$-oM)GMT(yuXWEM0WqV>GQR>0u?wbeQ1@#xD)(T0-n|ciG>#_|NT?i>i zLnFho9U@ZE0WwvgxmPJ1>r$%6cWrAb;k}9Om!mYI#iaz+2sThig%c+mfIfa}UH=dm2 ze_GReIYB9JXRq+sgX_Qlhy22|q%O5+ETijcbW(ZSKx6J_=$j+$u7`q=y$RI9Sd^ug z2N9OHpzJp*`pgYaxLS=&iKwnzNr@cF;O0zk?YBuh z)*lX=G?%2RMbzrh+7dOoy*n9=uJldQ3N5+?slQj0)6F^#K_L?A8v0gkZ0Wi?gl_^?|)aC|GYI@)*17&Rd4v?w=x^A-!|d2EhIpIF0=DfX4UuA$9D z@Rx&q|3aUYZJYP+FQL~j-n*v>G15Bs5s4*bMMy|Uc%!vqzWGLe1dHp5hJtp1cwxo> zKtSC;*78kl*;#+)+ss$bwX<_hFIXm!rF3xo`9W11plB{SL=%DiKPn8tI*1(c?@l;d zCS_U?zs^3U>YvKy!+*^3zI#IJDo$`%TGVQbnD$40e5Jfh=K@uI&ALgAT{rHgs{+d- zeIpW`?oxrw3vXG()n|WDp2%oYvtrKBQgZ*O~SvJ{DpnBY4l|!_35H43$ zTQeZr+n8P5dE=KGMl;6$WF)HcU^$TTn16k)E{K|dh;6U?Rdr0R(T%_9=Hbb5Nvnc& zoLAu$HM1^~vUIVz*lbO6ZF%%Pl8lV(<>#)sUmlUwBA1K`3GeX-QBgV2bbdPS;wzdE zfkW;e*hfW@K#i+($1E*Y&IutS{1vMdw8|m?Wgqboo?c!^;rnV{nHz+{#r(i3a9bA& zTwKGlJoujUk3pW|QGs$<1>e&Ln7uIWk#cTy(g1Uht}c&ii~M7~(#TKPP?&Ilpe4Vw zAecMw;pn;2qG0ESumUSdjfETM?TM!cC`wB0>IS^d4n*x7d(t9{ChfjZ)TFv6#W2*I z7=1DP(<4kyrK$N+MeB9bC>A!Oi3A)eBslo<=Ob91 zQf*YWXaKj%AEB(Ak`kuc+{`7rc(W(4vGTo+^jOSQFqb$T@ zg%i?(aUZY=)JEJWVwzoP_Iv`%ArW8VKj&I{&J5P7MD?$X+$0_yHwsUW+-z4Ze&PFA zjk1lm-e8{MoF`d#qpF$t2^V0XL5>pvNLplmwcs~_qT(v=+Yo0E0Ij}RhoP?97h2sLS`M+`pSgVs{m z>dPajOzBH|d3izz_XOlAcr7<3=Mf0;GM$3$`8AAKCC1vw!P4M20*OKLr`p~qxf1Fv z^No6{TICAgZJY5;$%+7yE%!q?mT0l6DLoXo>pzEDin_x`@B{Wkf@bJzT%=^vk_`Ne%aSLrV>C;d1v68)U;F>~?rq9&^Y`(NtNg(5pZ^F8x zea11=t8`FVmi?zhffD`Ao4Y7ph9F}f0@BL3?><$f+zvo`bX(gG4K16<#0&6rp<}Pm zQo`pSRDINSlFpwVoAzWx{Ah_M4B89N7uvLwS*}j~t5i)<#nB@~Q&beK)=`Om3JFTx zW>?Ic@UsC`M76C1>P{HQ#dH!T>8FTP-f2#j1bVJktj4eoS?${$wYv5Y_o*imUsR7j8yB^R zGOg#6dw<6N#dZDm$;b<(&Y^)aU%QtmM)x95s;@b_90<5q7=BE}g&sm!^@-sfg*zrWDjVgS>|2 zb_V2cS-R>`jKjB2U-pz{qqlJ<+gi=3*D zGTz3YzkS(AS>l<7C*K&ZP#R5FxU1qcE9DIi(#$$ z9u3e_T#p`RRaeHJ(<5pI37wM%|{p!-w}I zZot=Ef>l*7+V<<|n~XNt7?p_AsZ!~d-#Xj|@hoDj8oT_CVKoH6!p+1ufYW!?%xZVo zm#XNs4FuP~&)x4EiSKt(EZv7~H#z?#rWJ{c$4UE_9^%o|o0#wCGxh8|Bw&2&VWiL@ zW&u=QMFv?7QOQ+BHUe+Nk@Wh6h~-_RqmC z;wdTA_fr3mlS2&yGf13PACG|K@}h*qyLazM#KpxEQd7Sk?C-8@47%EEuTFxkD2oTT z$~ph=Fgex__Mb+9`V86Gj;QkgLKozP$KmL(DFv}X>K3v?`NsUq(;OTeR{_NR+SKF* zlF=n;ypU@b@+DU1PwbiqwBTYRYM{GB_7_xERRyL?48FW zwkZ_%Kd}Ktc2$~|7XO`9d}0s3AAjIx6}}O%M)9`ftUhfo$xNTysC%Ln=j%{d@HMZl zFni}zbQ40}F)8iOXm$Shfx5JKp*7D>1dN|aaC zr@0@mI=+l@54$hukb;rVc)%JxwmstgAy*l3Sz&xWUGMwYasdAHYAT|LiED4sf?;tT2Pq;82y z|1MAS@QH%JU9WQ{{l4Sd<3$gLn~D5bqII+&kk7=zIuD>4sR+8WCC_-$}g5CUIEoKil- z9-S5cqI^bZ@LT+(LNNogYC}*#p(q2xmYD3A0|28wV9UNSAmSX>q-RMr{*~3W0ou?xnHhru$?OZC5+EI6Ufk2qjC{Fv@)Xc*sP zZoX!>9XvNX`vVR>L|7wFw6$_THC}V650Jy4o~;RjgL1-twtoLzT`}-G;ze226iZHZtZaP zv~d_l{0QiOJ9kdy?Aw2h)~HJ$S^+1?%F6&BjCSd~G>Jcikw?+c@>gAfOMH{R|;bl9;D(O@^)s}R#*%OVn z8Z32w*mMGauu)bBf-K=;A}kwSf&G_MwN43kx*g`HvCI5Vw0c5ynd>Dv6a$QAxmqJX z-+V2g?C8i34bA;VCc{za3v0o%iM*KIJk;M!Ei9sed(TRNI$Wof^!SZ^O(K#w?JR=| z2ley_i{5nSRSue5NKEDI)JJL(S9_T)F^oX-v{8v2cHP%EYdVi7uXeYky_HopX$<-#>E0-t znUR6yVje>{pb?)58l*$Awmt+~ZAei_5k`dcplqSBG!V)A^r`mOuUEbCZ~f1J-LmTK zL6Kv!I(J+ukP|OH^F;JEYiNyw`=mcDUNCu)STc6& z6D)QUPxW7vSy~EEbhV9ldLFy3Bp@rQjuxJtwVv#E2>Q&p>r_embRFYBmlNC6V2(Q~ zyjVD)JV#yA)7+fVbr+#D9(pY=+nhC@5UCOMBrLBF{&I9Q{NZtP!(VOB+2&S!-m}@D z&S67vwXQ~NT5~`dgae zh2Jilm^4%Ovqd&)gSroLe5{5m(S0?+N+`?C#bI+f5U`ue(kcozL8zlB5NQ921wdFd zShdy26>ka}IOey1H9ykszbTO5G&WgJWdGThwKdOCqimq)H&hMGoy@BJBp?!abYB5j z3{Wos)L{+wMI6zWWCJ!^y?k;*@&4$8{LeEpcTL^Da{=KM^bov2@i4hiLb~Lvmk3ha->#B-Xg^P;?;_LQ@obI zd{*nOf&jPVk^b4{bDj3pUT(q#E5|Qai|cS^dv67p22XKf9=6B!*s9wSs*02HTjJug zTkagvd4IQj)M>Z*lJi ze;bDS>Qnk=w`nD5Csu0wev8p5WU6nZ2?{c8pfAcJJKkL)%8;#b`SHNx@73CzFZh-1 zpz}f5dz^qR$;TnQK8lCx@bW5c)v@_zF7r?tXEs~izM##&yme)YODd63LYGa6bIKJv zzh~9hyTq*A^vlYRR8h<*#Gj4On2&qjZ5ry`qtK#HOepL15^%QQb|=Bp1}oSu#EZA$ z<~KWAgqPMsy^pk0*Km)e7>7?82|NL_|7no4slgKi(k?#9P<7)p$7}^OB^nwUBLv61 ziX+0<GuY?{+DfkA=XNe^JSN1|{1SNuh{umS0OsyOb!{`(M%=kgAuS`}g-;_d zWmUCQYR&!_pYRyGMy5=U% zB}_x2@%#rjy}Bo5)sP&y4ECE}JXAHii&dxx$h6N^T2jAO9=;%9_lR`VK-J!>e7V7P zJ+8~f3uhx2l|gKT{5C760yS>iD-l#@8I9_-qY9s$YBrq=HHj**C=RL7RPG>2QLsv9 zcr{lRnl;U4f4Y6r9qE!ihz>7Ws`;1#liu7eaO};!% z!Z)2_DX}mY0*_F#CSCMUDOw3<`~BFjo*ut6c+hTpTW%9>)l0bD`#>sP-#zo>ktD+d z8_1zp9gzNCn#$j=@g~gUfH>d_VR*uemRiY!GJxiKG8mgyzuW%gk8QILBs>Kg9qeLF zn^O3^dHK#Bk;hE&wi}PLB3ZD+ZTUqIUO@`>FT?nIty{8NV&moEHYY=&R|Lb_U!JuT zamfO1jWBtsoBfj9XnFZz-fg+f=EG&LrLav#mJT?(KFko0>K+C)!Z5xcQ(x^^A%B9Gz0H27OC( zRMcxzhd9A(yre+-gT+&3{tFJv#I%}+iHY}|h7uY*I`+lyIX)z#eqhazkbt5J<;=)v zw+h%Z+w1+~M-#>7OZWc$lFgkv6t(lNCCEBTA3!d_g!Kae@ep!4PT)Y{FX5m-l1OI$ zFk;(YI}Kq8QN7*W?>>K~$uan>a{2OMA>5XAYisN1fAs^)gEjkuNcjaEi+6!e7z2yX z$ARKQ{XR4gH@pCoUB8TV3LK=Lt1u=hx_Jf!u>BW601c(vWSpU&u>Fc;1Oc-In8Qt{ znDyxWYS2f0Y(oW%rEgcc4WCXmq4U-M6PRT(t4#Loc8xL&L^G36L}KV?~z?UnSSZ(pb78s zfN|7ryMcOV^(T6R`MB=0=K1jOt*x!=c&NZCYXweMl)V&|_0%bOopShT0YDqs#)#U3 zisg2+L^S`q*sI(xm+{{f5Bn(>0|DMr$oAMMIyXA^nUQ2t+o1>0VC3H|>=>_Zd_SAx zlqWujEC9w=SmmA0Ny|@4`%@V&`e^p|*wW$QKs#A-V^*Ol{+vkIJa4bSu;2pLoo*{u zNdvY`kQug2D6?=gn{0{7kjI*{n%x&o{5~w2Y?T2HqNG4Un7h zto*GecLmI}h;VPf_3qt9;b7n6;^N)XUQTS(ECz2&nc=imr%n(4@}wCF@+a-?*4=uq zRLPoOE%~6i*+a1q5uAdv9ppjz*i|Z!9)a=G;)%k|Ee}14mRb@}g=6}O@L z^)%A=M^Q)zm(nC3>3h}}pt4l@wgDZ=HZcZ+d4j^`PzYfAH(OSnmu=ReRUtvW2H>`{ zQwKrhptW3~tOM`qSGYp8b#&ex$3vj`3jDL}JQBH}7QwP>9b@mnaQP3(l}ES+#dXE9 zGaNzMOmF%m)6NV!P1VbbH*BDa?ql*)T$_F73!A{ZQmSor20g~tHFFVV)XRE&TueR1 zYT!+DIThp4^6$NOR?U84zga6SlL%rocoT#WQtC#e?9 z^0qlP-X#70ioUx976U|hwlG+BH8oRgiWBdpH^oO@kky89z--A-Da(|R?9wmkI3?xF zB&g~2MgxGdM8*aGofMEjgu#I$W6nrMQ)wq(r!iftOnih(x;w>}& zkVYolT67J15R?xg{A?-=-XGqjpwEUY34BxGnp3%!QzyGLSk}QZvJDsA7g&TV@cA-R z^P6|nO8d`U0}dnb%k!PupmPAIkb=RL#@uI&tYO0KJ&QIkl7RI0gKUsj88SVtCZ_l& z?S?9Y2WhtZK%t*UMRK8~B_=DkMdsU}bCvP@ZIQ`-T%g>+xbQ*U%+xx}q+m-sF2j;X zlRXqIG)sLsLBo^L|4}>Ln~rQ^KO6tm5o0d}pFz0p;X|gf^b+5O6SWdimwt6VO!={R zW1LZglea{Zo-lWLE0d#c{B`5r-uz^uKx;MEfbQb<>^+w&pRY=knbqd0y^0sL?bvar z80O3-Bu5Sr`P8R|TGb(p;#U@8RZGt}@+t3#;${W&`D2uT9*UzzBXCk9eb0ugJQO?Q z!zinPaf1sIISkmPm*3A{xpL)(``+r1*Pt`v4A#|UylrB#0=b;Nhd9$(de3jV#PnS_ zckLAu*{wv&0q6{&vpFoXSuVv8f)JJD905Pdg}L_~>}>6v-OrP|!F6~DB~&#p*1^98 z-P6yVfAu}%=UM{Ru0-%zAMs5)AA8-YAEQ>)>4LeQeJ?D<|7=swugl`ku366Q&)f(f zmFgfVsb#-HAJhNMKfFjrJihl=!>(a5&$pz3HQ9vM&-reJP43L)H^H|s>PrdT_6bdO z^--8v+R0Q=(+dlY;1u8(aCzbGvlGTduMb7v)6>%ufXjDt7ZY0~M;5KByM#SSQQeVO zh}~T#xna>6XOI0ZVPCVp(RYV@a`{Zus>;KhcmX}a>xq*e{4-V;3h(gj;ki3@6BBPF z%j%P%QsZ4U+P0T6GabnAWYkXqvw#?bo1_+{M@Wj&mj+54SLTa4(m~#iXapjL(=&x_ z_IK8i{aGK)aj1awdd94mYl-S*M@fJVl1w^kEEN&|a0YhCCFA+3@ef zNjetu_PHhFN}RB`VbX_;gklAb&`m_VvRr#ub5?An?#NowL8Yh|6LmA!7O9z1_aA;QS-aUJ|PuPHy0u3I8Mz5ZD8+=h6fq=3lMC2~Uu)NwLY)F+3 zOL*vxOK6apn0>Qh&=u8Z&NlW^*H3#cE=AH`{~>*i~8Z_E1M$~q3O#mny>iiQeugG768AK!A!J*9*Kis&J_FSY5tV^Y)9 zZIs`jCs9k1y|VIHgz9yRkgvavOm%YAH||+)+H=QVxXW|rC~+HG{6`Gbl?ZnRJ^Ft& zu>WPMK%HCQ)Gv1N;zi)7Y@ix{0xV|f&%x5orFu|}LRDYr>$8@7ok4U1!(vv7@pG$24tXJ5fsk* zoNI=QwoV#<(>h zlM4NKlV$wdi_ITBuj~5yc5z-n*52>dHym3i!(Y+w&fUBZ^C|F_u#;nxHLs+kn|i(V zfc@l2WizwW0|Ns{pa%%NfXPxzNK6EPLep+@bCF4yV^RNkLnwx$6qjW|Cf;*QWvs(EliPAgZdoAxcUn^v;)+0!}v z`PiTQ!AJz$@+xT&CVR!k#_6Zx)eGe$a5=35N7AC z##q3v^eFr#o<3%?Ybt<&G0Ciy@pqeJ$W2#~__{;d11u?-)iV+_r_xM?98x@P9bbRc zLwOR}#tGvCIMW{fmvl*GSq8QRVmT1PMJsrx%c#Pg3xq=X!q~Pvf(?B-xgF;V?bqnU z4)Hr?F9KoT1cYV@uZ&XN3o~HiX250%^R|Gc?vDRT%Ye- zsaYAU2`uRtjHl}YaIPR|-w$biKni=Q(5L~nba(#zIUdJE+{O^0-WNbaJmgDA0Z#T3 z92LOJmKzwgMzeGB>i!F~3z$_FtC}8NEjGgiR4lnNU#Tc6D*E6ATH{UQJ@eLct?^7_ z&ai_+xKO93^r%-VFICHc)y6j!gO;7zcAZH^17EhJ$KH}N7J-4)YvnGc5Bn8K)X7fb3}k6jmkx-2lb6>VLUecHs;gQb+TdqQOmW#6QfqUpb$rSdT+#!NTS zS!gPL_Q2s=URu_r6c81_FU?GZc!N+ign@y%iN`!}T_2Haq8@jt z1n4)fHvc+$O1Wg=I6iyHG*<4Vzf+o8AT8!Eq_%C3}z1gRPZACpEg?wUBg zNxMl~VZm=by>J2oRw6B6yShX|YMwG0P4gtoq7h?9sFxEq#vEc~R8v=PeF|ZVnalWt zK^BHcCWTIKNZkYUHT6C#V6zA$-4n9;E{wgdw)O$EdkHNp2}}W6@a}_RC2d;ne{9(m8amc(jic6N2WFMiRV{^+?w!t*FahFGEeE-a}bZQv$JntABTm7k+e=7TZGpD(sy_$YCx1c zQXxQ^b#uuw$k|$TUDIKrVH0nktM7PT3-s!2vxd1^n`JZ*Lqt%%Ff|I{k^6MiElsC> zt2sWsv2~RHSLC6}2MkrRUL=-9b;j3p0$`p$5ky8Hu6d)v_2oL4+BORXoPUDK@i zST`PSffZ~3b?B*N=|YO`ZV8A^y8)7e2)h>h77eY#SEK8QtAW$+YSaY0j{QZPG5}LU zl=lMT<5G8xO%p8`5d38VT_Jn`g{-@rkDGzbtAzklw)1RBg3JIy=a8sQh+zXx4p@s< z8@@1d;XaY3_kCaO6tgw|gq{AxDBI|P7N$Xad*7_SV}~ZE%#gM6fEnu+NpgN{N{uUC z5mCS!XWkvL#F+=F`xKUg#dc2cGe&>&^e)>k3r4;uNOKVS^n*rf$Ws5pKPP}NvJsn` zlXt(VuqU}piN9;pyU$p^eWbsk%b!ve!YRyAT~v=)dWLgk<$q`%A$b0RQ_`Xl!ai!m{FE zA7wcW3;XX$7FEe4eZSRs;+u-Rn&b_8vBYE1+PbP$&Fk}>-TYUEf0PL4U1#z8Onc8F zU?lq4vsZm-*UsN)xWC~IkdIj6#o71G%-srlLV61;`MII?^&IV&2`dy^jOc*z?8ZAWxTM35DjA>#1-?q z8YX!))+7oB__Ip6G(eQwo#7{2`A1nM{y>r(+3Wx3VwIOwj-GtZdiwObvvl)gL1TsS zLf)hfD^-D>pcs0Bbx5z*<=2#Q;OWUtY7vs!s_(HY`W}3i(x1k;L#O&0L#UHvBt!+| z_%7bg<;(oR#+;=1b;1ow!f_O|6eyIUj*p+8toDy+Kf!wJ#ryA;IJ!0nx39&5smfmd zU~A$9sdBfskOhi@it+S@-yrtl$JuihQNoO91)UTn3-f7=aIdqp8(#V8V-Hl?-5ncjO4lg4V*);2YWAyEip^lfn>0cJ%P!!>Op; zV*w{2{RnZ|AlY!ppp`Dn=nH)Cao(*r;Uxhl3j?73h!u;RVNpQWeR_WFf};r!McBTk zLzS~k?21U?_pecBbOyf~{QI){W?khbczKAo*Z2C2e9R+K8WWTHa0)BcxVIXFw{FG5 z#Zj}NIra9f>doy0nr#vD8Cg@Gm3A@@H;v{C7cr)Ifq8$uJ|9)47O=umSsJiKH33?Q zFu(}Iia2-n)-C>^ZB1GrR``lo;7&L1HXlBg1}6!-jq{qDyrH<|egBt31Jk2W_9 z0v+6Od02j(N5hdA#Y8`i*&ollA@x?^X5KSwdTVc^!dhXX5RezP|Y#?k&%T=gM~qv=J|_-(O-Jc zMU`E!>Sa!SE79g96oD?d-zG2Cd0Q3xWW4-p#n)1qU-}gpQqBV(Ji#G{X=&4-ueG4ei6O${G9@``6-eE{h2|kgjnbPoxj3=-n;2}}Q7jd=&yz~xK z&VVtX0=5G>l4W!`4-N$_S-x&5gV=1C^dO&r{J+W=goid4!hin`3r_RZ_sB*gYOFQ! zkoI_F>gA*Y`eg11AZd5mE!n+rx$JK*vWN&LV?6X^?%MgrY|Cy}Zh7gA3oMZczOSe- zek0Bj6CK^k-S1}XU%9IME$@OW2)k3#;!hxe#TA+j_U*MCqUlwG%Z8$+6xf zWAcMF<GDP;_n4sQ9B}wAajVf@F!0v0D_}x$ zbxlq~TzTxKn6CY`uNrd%I&O=O39k%xG0oNU+Z%=AnrT}sCo(lYEeyOPeHIf^@bVP7 z0Lkl^Evvf>FJp@N6@r~QX6O4o78M919)|n`VzW=o;s}wL>Tf8sw0jWH+|q(1?LhE; zvIF@atlMQa;hadNk%56Xx|w*1pYS_ZZpAR2OZdJ_;7+k8yXUR|Yg*ofKDO5`yn{Bj z!c#83#2K@gypth|UkmEP`g&xf>gO122Yn6StZeswJ%|@7wc6J$c?WBL{r!u2UUcDg zF*Q7TgaX+{hbtfs-6jSmBn#9n-@nkFQuPdWq_ie7UO9j3agL#|^>C%1Y59GIkdWFf zA1cS5UlVnqbe$tXq+DE#6rmXfL4ooFuKZ1WFb4`zQ@?z9ELka-{hju7&7eG_N_xha z8n{5qgQO7_dJr^$aGuCWa;XDxK_N^yh{IND*pm@31|(>9cJ^MfwA&%D4hhyU5_rw9hNP}+%=hOK`yA%+$OQb;*XiE9=Iwb{Dhp;5nRN)Lmn3e|hpdOJ zM`l8u&cw1}Zxi_bSNCC+kMf4*>##1i~9P^`F??-SwDd z7<5=h7h$aZ$FT)L%~O%W{5|KYj;McI1aIs4V_)EkqNfTi@SM4Yj9;jqd8>>(nwE1t zpPNNRc}XE6{_i`KEK=ZT`t@r!GTYo)D^x&R5ee!y2R0?lk3=V8x0jKz@V;H%t-@r1 zc`hYyjA$QK^~}YnMB4h+vW{f4pk14DPD|?bVT)_0qTURj)AYD^j_wXUu@x`8ZT?>Q z_m%ZJpbJS*@Zgo83+e3XdHwy|P{6k^C_lE4oO!PqWGd{O^xA{E z#pxxn_jrx(Q#6rwt~7^lj;l;=celZy{a!x0u%I0!RuN!q-NqfEI9(|ZV*)Pn%L|5r+S0&ffw&R{b}b~1qV!DUaWuLh1?>_7uQG;b@DUh zXJMQ@nLx|m9(MfCT+M-F@4xZVI=+mg2bHYD{+o-96VXa8=jW%LaLuGLI$Ol5v20nx zI9Ba47q3(folb*Pi+=Q<&gh`WS2+TId2?VlF5rC@;<4SyvzXGMWMSiq>@3{SMks1U^ilT7G#QUO{#y6SVF${RgQ95r$t(_SC(Ec3ICRsylE6E`JGIS#42L zHa@9+`;Fj^;&Lss{N|8ylPQkR=#GOqa6h1m0co$QCNx~eb*#}h?n``k%{eBb0Z#u( z6o^x__z6NWaCIJr)OH zx)TuI-z>u(p}HIvycIS*JKM|<2t`S_ZT%(^vitWjO*2ZCWEqxxXvdmdDRes1OYPB6 zAG0VEgaBV!Kg1e|7e%69ZQ;W>7dZJNHP6kp7uN=aD9g}$wGa1##7N_`*j=%BV)f19)xJ{zAyA)?5HcN z{N1*eSDv*h*^?J&u?9a)!QItMyTdd zcw-VLU>gNwzQM*uz1P$HvX=T=3@-Yb`l(Q>5qHIR8TR6HWdKq`b8&l8&tsIkr&-b4 zU1E^=j<1v1)iZ+kmG+kFjqAi2{Q&S!SP$ft4Lpe{!~yt_xBssmUhzxc(Io;?riQZl z3CQd<4n*^@JbrMuK9GPW>X#^|=HE{;Zy6lG_9`?jp*uGBEya(DT7+5jmQJ%7TDfaY zKP5BISB?=DTz+Is&-uAs{D))p12Zeu7(7o9p{AnZBp|0g5Q~E32B2zdYf%tMBu`zZ zJk-IxnRqu)LP7#j+LgdtZ5pal<9u9Y_K?2CUgbbFMG=baz02`Bys6~!?tY6Y?)`hN z#Dey@p6-d?-#1!iY;3x$Qb;OV;#q=`)eZlNT*w%%{`m1D;$!c8f3>K2g|MpnUIz&_ zhRpAinfXaAEZ>;%fZ@6im1KL^rKiN+xxnb1lbx-tuRl4EdgE=+Oh{grp}^tamG;BU zB<<;W>X*>RnvBiNNlh5ZrK%P$EheBZUl;H6hVH~z6Axto@yRu>XU?)fisb(eYb&qp zJFy8^6(el^3=sRPIyby8-#YH$^rSI`QoU||m5|+><<61hVoJ_+aAfjj@r5Xn&ZzFY z6O$xQJ{L4|Z_&gJbamNW49a(r?-q@fbdI#e(x1mQSTpvwkd~6&Fqs^7e=2UoZpAG5 zhO+LGtW&Z2+ry)B-dXM5>StR&UyFH{;`{|qm(fASl-}n&$G(w-mjcQ=n$OTzTeu78 z8yZOB$-fmZ9K#$?=G6a)kfxLn2dq)CIAajWolq}(&Lx;~=$~IH^jf%`Ebl8efgv5` ztNgC2VmxAK7AA7p@Zv89Nwvj5dBpx1598A?hsvl_UvIaN@>C;U zJO4;GQ`0U22T&IvfZu#)YE>JM$l3orDx=FoBA$N!Y47HO)?#gXo_7RHiG#|o#w%@j zRH}^RcQ~W$_DTar(%qxkl4#czI-98^uk3V53gp-i9IG<|OD`-=C8;oq4rzzFd7tA| zK4(-5VDD0&M>S_@N*5;nzWSoV>9ap`MnA`&p=h@)lOt+H#8#I80!1p6rJSC3E~ z#Lkd>P{T_&&bn>gm)*l8wHVrhc4%v(tR{tP2g7pYq_qzLGNUMfe?`SG1mZz}i0Tr; z2ZYgj9ota%=<{={^b(s3xx8>QuH_Dh`q7xy_3&YB*ydhcnwMZZ12uy(d-<(@sJxgt9xV(ub)^n`fY z_Ors67p{a^2Ss9{KyPtU*KHP)x=@#sDI3X>b9R#&s$|0}1IHijKM|kotT-aslcCH!CLF#T$J$HhG~{GfC|{>e9|TIRWn@?H zrGc|-q@kQYnZ{dK(`%Q!{>-(1)Qz&t?>(3HE`hi|ymXNVBV(NfHz!Y}prs+GB zs8PCuGf^8G8_$+o+_$5mGea##CabJ22Wrxqziuoo@YC>lV_;AVtkdt^HGKQe$V^a=x~$jjI*g4m#;<6k5sclgxM>ePW*>w zvD0(KN6>ZJIa9CxrGk4_SVEFFC%<0g+f2~=g??}()QK^P#Y}xl;!~SrP!v{rPknS) zwN&z3$iSVlINe?Ye?G+v+gv1@G6kXrI!6nAPw(e8z9pU{A6p~ele2HcRZxbHZ>!TE ziTQqRZ!C=C(1VN71q&4vvaM2%^$k|DPZpMl{fCrXh8-fx+4pguY))AZbP(Zs^{Qlv z{jU9WlKRrA0pB|mkjPK%voquRu3Y*f*Or*4id>|S#TmgJmwpTx;wlKhK|fay@ngl0 zHNB!V^NbnwoLi#&8FC*mi1&=2>q<)u4d)}Ep>ij70(`OGs zee}xygc=??Q0R9L-)9MQR{mGb&GYG(K03ffl@KWYA+@e|OuM{1gQdQB`M3oM?U_61A85zQ>h;}bNk4;yV4S__ zt4ehsJODe;!)Isa9iI1j&PAdjhz7NM@bjgU;Oe4hKCLOMkayhNFGqHpvZcc{n?Kd7 zP0!bF>`#5f^6uoBR!|t`o3{qEt6F55;slC|)Uh;S^@#TY!i@?*xc{rS*9KBmjNd(M zbcbRK;d9`(yV+CX)l8U^`c-sy8_9!h)IKd$FrWOF{Bqdvn=Sj)lgX^?Y!x%Jl$^dq zI@^U64?adaUr|G@dCWv^kiNNts6)Zg#4f|Qu3qYF^qIMTUHGDrD}3pq*vE`Cby*h% zTQ4%?*|Jt;w4WLzJ-yTOIPreyfD1A9jGy=;pU$@clp^Zkz)3@%dg{$?jUR#&}OJ+Ah4YPSg& zhMh{K<=m^u)$EpbxaG-QQ$IJyy4)_u&5@oQ0u=3M8S6I(lOx-bq$XgIDsFZH24l~5 zan+4sr&}C}@By6$Ll$8f*meZgi*yIN!bdV#A_z z1l^;=PuMVx>F&UVr0igTR-2J|22W;hIZR1a>}1_48(%EFieaFWty3;c=${^c=3Wqu~M}WlUQ7~ix z_)QV2@>k}QiadKqay_xnCi)#f?nZbtX9srGyMs+i2X%n#_Cd+sn0S9Xx>~tsq zquSn1Z;cldh27YTZQ^#?wueojQP0vm0W<{3kVMej-Y3glM zRD#t2AiX+^c<|FbIpjj4rj!_W^Z7C>X*JO+u+W#kz3QI)QQ?WWwgrq`3ksFC^D7ha zF}-^IIvqX(XqXXv7D@)|-fDbJLtkG4Mi}GBH7ATGXLtL&q69HI?{GNte#sEFe>7{N zk;}6uR+1(>GiHA_J~`(DNfZX8XNFgjq%*MXS@H5Uxq|sZ;weLUph-@>%rfYuyN!NN z{vv0i?D^Z%3FeFE%zUm|)6|+bMoh5DqCF%vZCYRoSUNEy$w6GkQ z;eX;~fQ$u5eH@JU-iF0wd~kJ_}JUGSFahZMgU@Bhd7eX9nGHpli6h zi$Q<5*TsDN(3`&rwKGA~W0!x-hVvoQEZA_18FI6rN7NqAg)k#dul zKX$1tm}m7xm-x38!0=JC>vJC!2h$%$QH)EtW^N_Mi{y!6!!v{OJa8Unm0y%%AK@%E z=ler=(gJ?2%MXi+kz*I=e<@EkmOSi|co|p|?)&)RU1cA@Wd4d08VS`&+TV<9o3me4 zAe00Lk@_%Nv3}bhSx%~~JCaQ(pZ9OLi%XoQKEpU-%)Jw|=s{;4z&1T67q+qS{^wBj zvnF=`qaBL7xl2FVq2Vg`SxLW$E#lo-9dkvi%dQi^*D;Y4^J|3**Jw@+I+GCPMs3#bS|(+|c*Bv<-+4y#(QkIb|X)&%+Z>Y&{qKV!JI?yix% zbNA^y*P+uS(zZj#{@3;&=T#Tr*K=Bn#*5gludItbOgQWE6SE4B#F&6#^ToK2b8`(o z&~`@k{`zI>&iAx}No`9poUl^UBDtbL=(@m@DztsuCP~WmNKC3t>~k;4v~gKWX*0tz zS@c+_BP)E#H?O+eisnj`vL(@qbeu;EErxbz)i+JL|GP=6SMo1-euo)b{4LC<+5(QW*E=Io?&Re!=e$*{i<23Ta}9P|zd zxbKQxIRX&VVU!UrKxV2VExKw6#|n^n6KFt9cc*?|VLqL`SCO$vYLZ{OCfl{YDA71Y zef?+;$BNwT^*Ra*O$UXF;UdiTkCbzn8~O{`QF8~+IUOOL((2Bqqp&$v%f>19=!QyfU9s@81zM_o^!%pIB+Sb)~ z(JF-KnBUPY&4tTftdj!##U5hd`XD42rG~L6>K}R+d;im^SfeN2k}b1_ZR8vyuz2HC zY?qOKU~K4h`@B00ujN>-MaOr4eDfZ70nTF)qc5(qe*ueKq2KyF0h7|BFe6US&#O8( z@EkylJ0rM0P4>|Dv;>ws6_uE~-E{W!&3G98N%N?(Cq(>s*qTNDNlHh9IJ>fVTzK0q zrG0Gpp)7Gy%J4JGYX56IHcWHfS4~Rw^Mz72JF%v;g}o1ahF0{8_uQV7Gu=y4!hd#B zTup!Ts>AS(IghQ!G20Oyn#a;1} zM6w5eww3-ILM|Me;b^4;>5awVB&Gph1Y!nN`zyPxn9j~S$02zKR@n)HoD-!k$LE`w z&(V~XG@6RRrkp^MN_nQ4Y&wu+KhadKbEqfo#J@<8; z>s;%%6yIh`l!HADP%06r{qVHS*KXv;aCuNeHFH8z_)^cY8s(lfa3w|q@|}V+3pR6mDitXys>m$^eh8$ckF%@ zr*9&;`z&v~RoQ^GGV46x`kR_ZbM|4Ul#hHV(yRh?sL|Yx!+p-xCfO&}WM35fi4Kjn zZW)mp0Yo?aAd}$=4zQ7xLqG6`A2bbeF*vnyz!6oBd#moZ;!;$lr2JDl(XxBOrK%sbq5#28|RA3oGxU{B@;j?AlF zlwMA!=!ePZU#soc#@ug|PTc-mz2PJJCH&a8?|SYCURA%=g~L?V+o+`UJcQf3XaZfM zy$2rcqwSA4dhum6i?y`GNu7+fj~3Vu+#wkcly z;596s9?UBkdP;63Jk4HUC&TSZ1*PZExp4+#xJ~uqLEp{@Rlbf3 zBqh~_NeuEre~IVU?`p?mk^D>4B@AcV zd6KB|8LMAR&hr3MTMrkhgy*1Y_8^7rc5_eLax`Wy!gjn`&nj7(@} zE0N(YGnnpoxh=7@VTU7Y6+7ftCy6S@y%&_U2 z%-ixzI)I*Wm+(1{pntLUG{tb}U)`#v|5zs z(;(}8HPshD0tYJJ;0ibnPq*@)Sy*_iC719S_b0m3NhTB5^oe_6)CTzDM}TL+d=JBI zRImF=q3^JFwgGr?nn5+e+A&Z7c9ueUUSk)RQLS)WhyEU!<2RLAW~cHl>NS;JqEZ!nPt?nNF=cA7_Hg6i5xzx5cx`)$I{w>#^@*rota$lJ zwjDN1Vyi3m=tx+qVwL1N-H{R_zM}sSp2jiSgsC#8&{WM$WN!M9XojMS>ua8j9dcQ+ zcsO8Yzg0Uzm(@}BXK4u@^OxYwDMC@pI&X;6RE{`wvC0=;&`MzTu_|M|+Oprf7dUzs zzd!{d=;`t9Y-)OH)M>fjPDg856?IXmzPjm52<^uO3$+Xz`Ri)hLWYBrG()51*QG9Y z;W$wNE^AZ3HwuWSf!Ns`gb{VY_>HxpJt`N#F?Y2{85+pr?O56tTZ}j-j5q4(Jy||5 z{GA;sB(IRd+gDrdU-?I)iW}%)pvuxQcD)V=`t|33X0Sg6glYWy+#i$WI^q7g-wxHf z)J@8={{NB-v9>eyUkF@lX;UFfY41(v|8x{YD@|EK^h+Y8MS3QWtyZ_ko@~X)^m=e+ z4qc}dCd|DQ*n}V_^wSByvrOLgP3j#|m}9S3AY%LGw5cFzkSJ7`GO$1Sm|6sioNw^h zJzkEqjL~2u_q$@YhnF<2r^us}fH*U~MthXKaROl(k>Mc+?43&E%L`x8jP0QzM@c9S z*p;pSy#4{CmX<+)uuTWCNBMiEibv_dyruZ&+Pw&cOz_19a=OgpyYk>>1u#V5CQEJADF!B7Zcr<~Ky{lW-N-6L_>MdDRv|rMv{3PNv&J9rO(F zDzDq6oH*hd_gwim&e3;Q({0XiFJF`qH~}jjgcLKe@9MB_=V=t`Yva*Am~nKR_FQoo zp0Zud5$ZBGU5X6$`qKXil5#Wq%nL3Y30^SY(2Bx5#oUfFF>oVOYXoe`K&MVMy0RSMpa)r$oM!*1K!fEt9DBLaqq-;@ojKUa(M56clIYt z0Vrh#FTiRbohUpUmmb5*mJBv^s*9+di0O|3MH440qdHZU*0X7)$y={M+*M7;o#;$m}w_^M(k0z~hny}b!R!ip=4~~tEP2NQrWCF`Y z!2*Ua*Zv&UWPeiXi2yM?g@?DLfydIq!eXrv#MPg-L+yxCN4{ z`YcnuK(CBtUm(g^1GFP$#eQjx_ZbC+MXo^!DN&?oi)MIr8f1qG;}QY+A{j*L(gK)xTN(zyCYSe zejydZ3J6?X{mm7Pa_x%z(2;mwLc8;sfPvc5M_*?M)nPwl7sTS#gl5LWg1=hqc@o&) z!veYhK7QnV3Z{qLD)hd_wH4YqiC;pge5G;y@%IgYnC+t7_gWkro(DF1$*NG^( zL(=vr!BT~T`{DyIEjyOul1R;lou85bE6*G>zw@jXfZo;pF}oZ^or#e<(lS_ASk;cboNZDb#pMseME{1n$6p9@Egz` zvt&QXlXJ-Cb9*w#1BNd!zA9L|5ioGo-TVK38$UjZD(LA-N=l@$Km6MFoufs@v&W!i zDZmVH9gyMR9zUN9ul0|F!C=n6%L;B$)|!-?r<172*w*=5m^q=>gq`yv8}H@u&WkOw zH~y(8x-vvEg*K-b37=B(I;(CwqM_|}ko==Ze(A4U z;61#F_yG#Q-;ANl6*LENKUG!=eLqG!ZN|s$yCWu{*=RNg{XA0W+3-f_mPKVdwCPNb zv5wm63G1xPwa#U`&TZxt52$vwYrj>%Lzk2J#hEcm?}h+XfIoRUPyz1XPl2;|9zdc& zyp;A1^$v*eVfp*BUPp6S@dFs6GRFdb-}~$pH|dTLJ#2jx9zYv7|sX$8TP{`_NW;5~n6ICIZ-L;vLfwhMW z18~}90x>g3MCx;CIg#S_|5|+B(C^Pc=e8w^jzYK`lhas&yhbrbeCMYMEUx)${;Py< zh!;tu&Pe}hoB+W72ieIRNB4nKxg0SwnG8(p-g&tT4Bc3 zYGkT=c~#XlFhym(eB}A3jAXItV_a!6_Lq@BhhVB7i6dx$AotS*A3y#zAimuOw&M=T z2-u?I99^mee_%!uI!2V&N%m&Gq{iV$+s7W1aax@ycZy`(A*&*F5pda@mZKif#~;Q1NpWIWQr~fO8?BQlFStB zy-c(;T=`ddjc;GCC9@z*5NHi8Q{-GO$8-(=r%{pf9AwLcY|H|}Z3q{rs;JOH&3;nX z&{*!S>F&u%wmhRbMg%1dz`QhTK<8HwZLt9JMaX_vo63C;qqCsKQcH6buGZX4sTr{9lTPs-!{!_mxQKs5f^@|L(hW>y&Ck$3gMJe zo)s^5W9Va={vQF4cPtF?VZKmrmIZ$paPhy$ROHc+O=Z9J7zaq8;yiqOrZW z_eGw~WI_&kntBN#E1CmO#}`Y8pixY8O3^a|o2Afqp6B3P|Ig8W418Btz`+h#@F)5R z{#+h5B7&f28T2}ZIOpfNVIwYEvt;#urXw9%B=%o(lY4?y@;q49CnHMt;9hFm`FLMAUUQxaob3# zOE>H6A~qENC!@A*6Ew@kRbDD@t%;azTJMMvx{_15&Q)<|)0;Y{g&E5h^zj0`c&l+e z>HsP4-%g~iXAnGA^`j%JPI%G#Y~!*i?R+EcUAX`M_w{UQ3nurIjVBT4IbjmhKVLa@ zbXZ#DID)1BdOWY%Vh}I#WC|%QwxEI%6HP7)mnToO7DMEe%!GE6344 zs)If8|KnM*>R9oFdw5L$?S7W;`zJ{e?VER};%T*L!815s7!h4nQzQC74QnsO0m~w) z7t=g>e3SO4s9!6`<`~Z__bCX|Gnl+0IJ0?rk*7PYY0V$6@t8|mET+g`0pGZP%}y1k z^?;{_4dUUH+Mj^KJ|i2T{OuphOQ@@y>>KR<7MZq!|xCjLuT^Ruvm4PXdr z(4!<%Zx|fL6DzC!D>C-f&h6YadTEhrZgL;ok3sMwYRsZ>MPo>S?CzW-$qTtfZ=Ns3 zXngz{tfQwQ-u2rIWpcwjuF75;bA;=*45`;$8*egrLWBcnZz(iy@Dt`Nl0 zoKEDxz@I*(ii*DN&aY<9Vd|$5t#QqPiRKV6gSdI7$Vdpp5A}v3njA$8V}2!VRT(@a zzs_~x!qbvV3}FmNndT*vcJf;UTLK_~7N`yJAG_`F5q4BFdw5s zihesh<$3I&mQgZrh{1BZFV7n$aG6`~ za0ff&O;O->**x$%Uc}o)<@4O9gS=Z^1zB})320gTCteFY`R|TI?}lU3`mCy{k8gYJ z$N0u}hBjrN^aY5I=0|I?;=zD38#H}|b*>&t6uDA{>EWA}*g!@ zob{*4a!FS3Re7V*GalUS>SJI5F&)nnXT0;`_3)B>eA~l3@9eu(oHf^}Pq{N1GU<^#sdzYY zu<&2`QfGOVGoY99|Gb0>$DqcNk{?(@*xA{4){<;a-a|V8>(rt|{f~@Wj`G(0;A-C)Hm<6u@>Zk|v$;@M44$iYD?+ zOGy2uJqgN7spaa+txxrSyl>5#6i(v3lfOko3r~A4<|ME;96(UJg-+;mv);3pR#6Fe z;+xy7Ca%BF>42ASbbELIiQBZm7Dl2G|Hd`N{>1S&Bs&$-5^PL}9NBB6QKLMfn4wnA@++UF|57 zMm63RS^`5aKt|sGq=sh{B9eR^iV>t13PbsM{DMEZIblE_Advubb5Lz2CbV&NX z*RmwXk!&ph`5N+;xF@TJH`|pMM!4YTmhPs=6ih0EPwCIgC;0Kx3VuLGU=*jylKZgJ zO=^F@zkqgKH;+S3(isG)1jJHU&mtV_to%wcJ-ds>#h>1WLCOc#?iHM z8N)Y@I7n=z||%mEhu1RY6VWc=~YZs5WOnfb6K-vrie(3d8_ARjG{9~r1lR;XC#B^zDM2fxO=%3PgX9fl^Ku*+P(QRr7_{0+c_ zqfPHD9!)1(;>Y;&TW{buF-{2lUyv+FkHA4EerS3crK|0nY+cwpV0w8^#P(?ohWj)j z7$*$y#4>k-kg)lBy}AMsyh@>0TIX@Wf=dP%GH;CA=*QIya*OxvAscSyl66j|PEHoewGL{8neO=fzNpYDde7z7zEV5s1EpRPG)voaoh%nJJ^!W3;TPzlABOhx9q^I-CW%iN= z`;mqR6x*7-I_Ba~3Pt=gB0K{0v9DlwcR*%c5(R2tfozD2!y;t)5h}mvDwYXKe4p!X zkzw7q;#s&tCg{79b8`~~s~ECyg-@XB46J{!^)d_>iwsy#!h>=*GGg#T9pKY@QlhKu z&aDa}1mlC?L6XxpEU3>*t9SUR!W-?yJ&siZ+g_I>J0uLDG~;@@`#QP;KaD@iK2iQ% zClU}FOZ85C$pAZXsyKxw7!LrW0co(@(9BHeSia6OAQs5{M915v z5lKPWp1Qlh^YBCLc(5&M_@?@qQ!TX|o-Gubrc^W%Hb>LC^WB7##_&VCe5l*=gLuLFHArY-H=dio*AK;<`oL^;$ z7HX`c>&l|`7Cjj9HrIW@K!4Oz0cM7M^XY(Ycg_{`ua(qWwF^RpmcYIa(AGABvvqL} zD(GeJKX-*(EBynA^SsOYF`Ea%0b363;|3?e7sj;NCCJk|dFa<`r@#LkeJ&uLrw7_w zLN`5Ut#5QUslqd*DCGdab36objz4s9JiOp)b})7;tN#nxFb{Qxzz@ zK$XOH4Op~@18_2!MXphE8{ps+=vNJB;V-8I2(^$U)jo1+6&Dv(ZxFL-xL?^$*JaeA z+1qAawckMar*_q`mAtnD?8~qQzp$_{Hir{#{Yp;Ws!{@@mcSXpgdaVY);)mBmqDpM z8auHx9XL_!-2JMc)|@iqyZX1Rmu$d=MDdf~%AP$Kt9YEpoqS4sVPgOOw&^0D!QC1^ zgeF5FPj$p%hRN(9p37px(Sn0joXpezyH0q@>@b~O{}ed>Ei7*kE>Fdi{?SRul}PXF z5(vp)U6Vi=rnD1VSf(oSXHXYkN0gm7t&Lhj6O)nzxM#omaY#ZdxYA{rSEdSQ)@s7O z%FD2tI0&h&FSg&29{ABu*Uj&P@?cyuiW~di7?g@0C8$dtJe?(~JY_|bIH2;T`7q-B z6e-)ZdZz%d(geUU8rVrOSCi}l-N=1E;pXBQ1~%&geIh14BY+Ia05f8*F;gKYEBFUs z1Bw8apc8jD#kZ8o>)1AuyZ^as+~+Fh8=lZ+GgQAB8{7)VHPvT|*Bw_f%;V47#ZZ2+ z?oZP9c5Hcu25urBKq5-!e+_{Ka1NIDU*O*PGfk0=h({cMCC^I!w66MVz~5zQBwsRo zbc}*3hP%buyo%9)0*oM0i7yyMW7>ue866Lu7njo`KgkfblDAf;)FCjiVDVcI1zfw7LeS69RQQYuF;ZRa;NFcBwh26PrIJK#1)Aj}I2{#lG0;VeMAGNpAhaO6v?Z{#|jmOO- z@UOq|98UO4bSS*q)drWg>(_e?8o|%01J&G{jR{GKi9-_;NOt0DQ{JKI>bof|{NfeM z0lz(YuF~hTrZHx?HTQip8X^5DbXqVH5IhpMD74LQH~jqgV99Zu5z2Efr{!Ip*9{!t ztHQdj0I3M)*N>`snVChQvyFc55JfxO==iqWN(~V^6mE~~DrnK@=p<*bXj=##!tIbT zRs6!jE9or}Ju%TM@|OcN-k-wf>sLZ=f*g5yea7!9DI(G}_HA^XAjtkvbknCzPR{xE zO!BxNSDS5&G~wj$leOhneE~vmP&MRVd<7SH+$VMO^E^1aESFhlEA?IVQWJWhsU(_< zVRLKR77#P1>IRB*@d@b#9-+dTcRlz#GA@$#-h&4VPGUTSZq1fcKy?oeCjH#a3vSEo z>_0oVYqIZcZf=kcg792=%H{9D%B3+KXct(RB{ze8J}^);&DJ>Vg3cDK&jTDZvcMY} zhd5xyHkv4SnJy+zfHW=h@ztjP?&ZZoERE#oviI`h_~+!+h2}y;!R<|dOxMc4cYG7C_4$DzfL|GTpF3qnEkl+HZz&2VRgLp*xzHuzvkTwjQ@+1)zRZ!`qJP2jT+vbnmo+SbA3lP3dqGSwk>vR}O zAMz~}2tuwYXX(WUm){WMF<&LO3r9(qPBsEnwPf-}{r&)fpA6#}Ce5Z9w0@~;-x!?$ z(I%qFp&IwPZ_-?{L9=xgLhVES#A(9lb<5AU*z z)QCbmpOQk{i;Exw(h1eJbNqQ_lfoa8%a#&w*uV7 z3|^Kj7ScleYw=WGDxF^mhavwCByBc)dHvD}vKGKjjD;coDCd~LFK@WQaL|z*ccLOY zcH%V0`>gbqofs6Ndt)Is{FY;tTC~v&uU!`=L8>Z_{Y@GEJMt z;M?8FRrMm2I-ME>vQv~O&)x9X%N^ltTwMKh4uqM#t++JgWSoj0M;=?1#GQOJm?$EE z@1qmL+LiQ$WGy`WU9eY>o1jn0 zSAjS`*cATc2MJxA4}kv7y2i|E5h(!rr&X%2i;K9`sD2 z){>V^C;P|H5yqBu<_wW&J?KvElGlA!Evhyp>c3M@rG9SsU3O?#L3z3#uM{wTsGYWX zSWZ}?8NbAW)y=9Q0_T6mlke*sYfCC=GJ#>=aQR+a9{B_t*=hs!eKsu?=cWDF$ZwZ+x%!bCIXKpMMJ0nvGx$04jQjxk z;31N^#Pi(Vx(YZ#?!e_NrFcI5B~a`VGz|uP)vW~4s!(d40lHJ9_l3pTD)i#JdP?Oi zGwcv&Z}zj%T5A^X{d{4zkNv9jAN0D6lhB-L#MX^W-`KrbBXjHOhKe^JJYPJ^;pkf^ zy(k{_**}RCvUO{r3Gh^p?vmc4W8#9E6BG(m}At1b;xC<9#dz4m_J2veLaM6UG#& zqng1*FmmC10Pz{DKl|G^Tu@;t;(Z}O#r0}Mx9G*rXM(X0!qQzTYB7hMJnV59X(x^+ z<|FELfXf9Wf4N7n(_5dojEHE7wX`4$fT*zuhUspC?b(S53%Zv{=^S0t)hrON5=_fS zTCl&i?gU>->#MysdJ$-y!b~QEk3ib=3z5Mt)t;*pyw9^NW~sapnn!KICg`_tS+>x5 z*1lhcT9Suqt-q&dl)$$T_)FKn{RYiaFu;=f`_k3pmT+!jc0%73gCM6Frmm<=$RvK` z*-V!eZ6iZ^c)X}`(MPDs&!TEE{Vk%T#cHjEelefg4GA<{b$yh>$mRa&_k7i*^R(?a zx8(6SNMeMi@t)7kv_a~p3J2G-QV=(>Hcl$9Dw_p%N~J4UCM?bepa7eL75|R;rP%6~ zH4}{I)L@t#(?amh_g(^N2!@oj&&Hq~IlLdujpe^qHYDqeB3ng^1&Nl;GmD zrQDU6){B1(qV)eNmwcIha(`vcGmG?rOLwFDIJSWnVLd{Q=j)s!Gpc) zYOrCy+p0|XfW>;S`~$foWa;Z%&(bRb)E(iGiC~LL$xe&gbI5O-Xe%Y0-oR_43izga zN&ktM5Xs?}-w~qSksLJgd)Bz_mw9wr(51uuer{*jpMpwqeH&N(;75)kLtHRod3hsh zfIqv4(CEO)0TW_1Q;7v?ehNWgBMsmjqxTmy`l1J#Pe5O6Ao#L@=M}4%0cx&jdV0!E z5?Z^>`R!{SSF#P7TE?#_d*2g37bQ2qc+-y}FV-W$K^`Ysc-u?G;1|Eo?cq6tE~69E z)4L#pu(*18WKI!DWeS90tb9pU_>?TfR%1h@+Iq?wcr|)g4pR~nWpdd39x0o6+S8G1 zkkjb#`S@Pi@v^o#ke*lZ!T$;jP>4wTGgbsIsDQ%aR>ub-Y%Z}XRx4D=?`BUP1`wxh zT;OU61-TQ}kYMOCm3MAVha(Td+(1nf_Fn(P-3LzG-}b5uGt0h$bR0_mVJ-JA>c_}e zImzhCH$L~!ly^*vI&`o`WEGlezKP|QgLX1?o$h6 z5%sf~t^O#QE*gI~x#h5T!cKq68ei3)>`}zmjBi(a^J7h=SFg@K-e&ni74y2;nyA>e zTZSSXAKbaKc>N=};eIX7b>lqHQ+ZMt9@;h=@S^$DS z*13JC?`)9sVP*(mD)fnh8`4W;9!x6bWV?K$D5Ii6a9^OYre%VeP|DNGN&-Tg1KWRK zDG+pMQrg{{YynOQo(QOmq*?W0cR=PQ$eItF{T`nHrWKF}rm1QkELyMx)IQVMN);bl z7J>ik)P#)0RnxLXv*}C4ca7|kS@apb ziF;&_8_aywsqlgRe(7EYDe8td0tFfaKb$7#N(v`D)1!YarRztNy$`}v0RcTb{ye{1 zfHjWk6KTdUDHXReQKPx}yX@^4j;FvG2co_USYwL=G6D>f+DH*NHDE$us~I0ZHf{~L zg##q)m%zJ=CG*fQFvNv4f-lvL4|JdY6xMCY08ce&%TNcsIpDa>sH>yJwk&}4dIX)Q z4`?cScsrQ01RKrCzbCv)jRTNB0oWHG>N=LiI}0*c*qU#JUqGwxc?4LUqyX2cqr>_m zi6F1k9*5t=&wN!A$Y)`;4>{1W(ZyIW6{B>0gj-adZ^d#D1ZzNJ`QL?p|O3~$WxehC;r+47R zOV`AYX^&weidh59B*q_6v>!3(E@HuPzJyfe}P8IhgK z0AVGN>bdv4Xij5ExS%Z8LoDZ%gF$rlqwz%EW{q8bk($FX>S8mi4goyQ2{+TrHB$$v z6$4!$AYdC9&BhHeZ!=;Q<^nsorr`}VuER+P*!efq=dwSW`|ovfg)UC?xJ?Y)U^%H; zL2FA1ki)Rdk)M(|vsthj*LG*?T5hMglst(lSp0!tj%{tFVUgz)XvhPt#FuUnBh>NE z>FBistwjr?WV!(edYDVKLS=Tgbm{n6QRGs`Dy^>b2)|!Zpt_faU{*jjukd5){PCie z6!do64?K^GOCg6QwQ~eQxY|+Up(gEmxJd8WW zw_=%9`A1&E{Jarp1+aX*XhmM+iz@1OpF`wZOGNI+3>p+n9N65Os`eq~DH_2W+20$s zfEOmL(-Qjcfc{W2Y@&c(exbDV;7Zlb0Pr$_!2GlS#35PQ%E&W5oNcIj-)%e@D=G%v zx>%5wh}+)74+g_JECsIpTBtZ?rC1ysAwbjz{bWFl+fP97Yi5vqb$%6MJ{fQBl)HxQ zR27w>CC71+)j?Ng%LsE8zOQFFCR3TiHPv#pc*=F+P9NPZ@`fMD=TM7A{Q9bI5wU#q zlN45CM+Ah-zFYnB^3_)tcX_uAyjd^aPB5fbrc+s5HkP?wo^C(zBUQsyhN!%@btKJP zR6ig&FfDhbFl9E?t@V5~|KyxIAT-dN;}WThtV4UsIwL+8+oJ>F>1aDiI&S z-JPSBOOlpM+vmD_A{~a$t3RGJ5tnThKG+-j8e+aj#??L^YTRumM!o_NqG55+3xW^j zBQB?ZxI|oc?t^u?_+#8z2h}IU43eqLC$-JV2<6|P-z{G|-W*3y)bm`#t6_Hri;qAVKhG!1~<~XL*7{en}fiXJeS6v(1*5z_<0TI|8%qt2(*O6N>X{Py-j66 zt!9ph3{D5|EAce(PlpegM*S>{QL$Qz5fAxzBuF?=I>sXrD!M$E zwyQV>40RC~a#8`E0er6{LfSO1USqx%AD`INwSr&RUlXuWZ}#>4$Q=PAw*A)^-d4cM zK%00Lkev5K>z+_-zP6ue8ID`3Qno=X|8AVr!aISeK@1ytiklhcR>K;fwWXy-toddL zhOJ@6RcmZJ7CMZpZV;ba|C7BQp9Rw*cdQO}HJpY5l@7lX*FKo7_pwSzPKoJ+FRV=0 z5@^B4xug_IR526@X9Iy6a6MY|a|5EYmr-eOZmEmypw+y{?OhPyLY#PFQH4Kqq8j5aw3eFv|e*Ch3~CV_z29KBK8e zL?MxSdq0)%1Vp_$J9==wEG}H0v+7opCL|+x5U!-ax9M;~Oq^xA-Ovb9)>XVNTlg)D zj`2tkVR?=Q^k4B8N=gDPK#aytk!{e}5o$#u#8a_y2XL-|9sSVcWKbg}sZsjz-Tt10 zR{&Mpz0vzqGYA8SVyjoDFlNBNxyn```e2$7QmE-8rAh!>V5>E(#agquI9{5|!V%=>iV_p=F-T3Ǯ=8m zFxZfu_|9!`uO`gwVQ{J$$$)A~r`mgb>QL^bo->ZZC7#}8>k#(H$^i_d(@`>7`rnw( z8%mhTEnmlm5QvFZ&dW8mpK~{n=#*ROtOPd2hoqWauX&J|cQa;m{`D7cLLDO1$ju;c zlgt~&-=Qx`Hut#7-xAa=bCknFCw0>xPJLz(ugHA{8lH>{!VRnVwiCy@pY_X#Uwg_% zAtNt;BEm3VllzV+)%)UpN9V}ad}%44)dIK6@4dwYJ?@1=^aQp^7_o;bO}nG~*jy^< ztG&8=_dZJSccBJC>q5fNrFfDA0c!TLOb?bsoLZIE4YF;=^7vua9{pNKja>oH@67ebaY zUTYQ~7Qjzdp5Y&a#PL3&ZE9C&M9*#LkvmH6-cKO-=pZEF;nOv26f7lU)b%oOUCTn6e}a>pjzX>>Xp7DA>JoQBRpftf{9=tC=)ODqk1_oaP3k zO?!7yYoywStaFk<5Gz1Cz$OUAU0?%5#Fa?kl{D8!4}}gD3g8(T%t{1b;BMtL5G8rr z2q@Gl*eZ2%BVOh`yZ4cD)OE7v=;bsQ06WZs z3rRcQI!1<|EXd7P>sK%rfUdKg>t)zhL%P3|IKanqk(U~oh4H|^gG2`~7uNIjQ#nPo z)-%;4=36$=$Zx+5lDw~VpzZEu<`;fqBZ;_Ynnk%>zo%s_piLEsp&sMO0_43A0U7DF`f-g_Fu$;x%k!FRnDF`p}ri@A-IK00#=h&6i;AkC?eeeY7l3C1DF^#g1PD2a_14aw{gj^yda;On_kC*Ud~eH3Br zXiovWEHrd?+uGaYlQ%@cCF=yoD_HWT^37jMlk&-RcEp|T5sS*ZcMjw{crC)z1Z@ZnIZSH1u53 zY+o+)Zf;9}j~qa5dV7B2#ZPk7I=3eyINJnpmccdg7i9_pjKM9SzB_vP;PA7{M8BcM zUH8cq&&EY}C;Qgg!$7Zr**u7wuk~W*tqsA>;u(w)T{O@=fnca1=5;PMta6HKpF%VL zt|o?|Avd8vlD4M_V#FIkCJOBTTrZ}Oe8*mHaM| z2QP$6rxeFRXtSPH+7_Tlf?dk4ji~J0pB`@3KGvf}x^Y3-WPU`vU83A&rl6PZS9uyW z#$X12#ly2g(Nl4#-$7)wtx~mJD$`$7n3tWM-FaL$HK_Eo?0RL~1@kKo~@HRi`)9`mPosR(&U#!hHb@b)HiJ2TBq!0@>c$>L?cb;#*) zN7}`c#jT;;!37lSSfsisB1&$3HBn^oaaT0B3nbyIfffO>O@L^Csvl@E)&}TF0)C$&Kx*E`p_7LSU+Ed0%8BlrD6(B`pJIz8 zYuB!lD1x}zwmX>f^0|UiX`HW{#KdB81q))zr=4;ODoH}-+OJwENh6Gl%K=4#->|aB*?1Z*O-3oZ!FPDJI=L=FxSL$5V}2v?m}!T2{jm zdsw=$B`;Ch$?@QSUI5Bdj+w8H`4eW*ngzY+H%}#Vb90-Q+C!g+I+;5}t6G>w9d#@F z%e}$nx<^qfvKZ(oI@qwpYW3(B-EBRmRO))asxf(&n?lpS(ljb(NV1$vl1kx^Uw4~~%`ti;|n-2U=FkJ>J^ z?Lv-;tS?Q90id423j=_)Zs34=z7yvsd8G8AwMrJ2qG!R&7`bt1!B+gSi zb-Oj)=WfBJ^!n(56?0tSI9qTBvFoxKv-qtGTn!eTJB~g zxxkWqOZ%U%JznLrBilF_9$d2=^7+X2O1wfNsKz#BkAG0X3i;U?xIo)U=*<>C`F1#q zFFheEKaMKenS*x)=IcE3ES-zpa_{e)MHdS2@W}R42<+O2{it+uxL)^T*mL#9z>#~G zg@=&+^E&z}%5)!5FW>`vp;RU-J~1(o+0bCfegd0ROCxCRd(ev{Y8u<91LSmo)sV=B zu$=5+JORJU8We2*g!3l*5nZ?#PYWWMd5R+}wUGi(FK&NZ|3GzWjnbvu&qW!_TCL4B z2g@-z&?ktD4G%L?o}N`}tF$TbxOs!mtW)lwf{|)(qVsui3PJsfQY8VoSG#3f8A!8x z?lj|p$9C{G{E8RZD`AGB7eP*hx2zw~Rma6?gLTgr9&=$JwVIhdeDEzz!tL|F{(v{s zeOFeWX*$f{YmQm7&r-dF>1K;H_^Cc7)AH%@dgnXEl1L?E)FqQtHg*5Cn+Xfjt+Mtv zp|$nidPpnguJ0|A+3iqy2>N?e(RT*NtxxxjUKM-UBpZ(9qW%ce*<{zuBhB>`v|;GGoy09)Kg9mMpUsS)rID5ds$1Lm2bXr^L2AcPg0BJacwrF z@B&Y_y1qU(n8qd#HMHY}F25w`Sh5iF8r`VcJS_xU=_g2cHM&ISl?=y|PVjJnKOlTv ze|d5GQw+SQL22+M9k})m*1R#=I}jsVsSxyf*RJa4%j3C7ge{hjh=+qW(`8zNOJqc5 z?Y>vzd90Zdmq{J75>0O^&b6*m{*VNy+0^e5{_S>MQ09CoRU3h~cEnQO5(j_3RltBs7-5t^$ zD&0tTi8PyTHZ4d>OLuoS{LlXC{4;yz%$#xN9N&1}JJz}u4YltuN3#Fxt=*a#x3^`| zQI3UoD!q71XuLC6-25-oer+YVR+Sm1J3BgN*4FYJyi(i3GS4ArU;pc6t-AtZVPw&qWTF0?MV zhHDE7NTAIVfm7sv9V{2 zfkY~7+K|5KtZ`mes)7B(dgnJ{lFTPh4nS5lJmsan4;zO~0~)T9277thsnY5yr^@X_ z5CYZ%7#J940Wax&+?OdjO_$ZywEcnCB8tHegA2utUAO=K^9H5CI8PBaP@sTr2cqr* zQXpUY_UW&TQ>717X?js4hf_d;1b?xZedV&~93vZ%T7+K>J{sq%k&8s1f*pJrHIY(|RK1@RTkW5@A= zQwE82T;Gh27X{RLRJRM-&eROVsu|Ogab2a;ubTxMZ!g5&q~J^yzdCd6b^F$_!~s4YSde<5A$MZC%57^raJ9fJ*ocedCBR9xv{1f=ZCcV>Ri!0jit3=K z@?e$c6612C#?tkb_12=T&D%e2LMVo+M`F>7yl%yNtu0IbtcEuen6*fZa=WZAtoxWv z_4J-IyaX0WB1sXO%5Dj_h-a9{gT3Y@Mg|7d4A)H18#s9p6!`fwB8(8}|2*Whlm-&( z6;;ebKZkkM?V66(Pnlo7oD9(pdiKcJ)wXguKBhfgqo?fp_>r}sU|Pn9VzwWG)!0ym zUBPHmmB-E-A<7hyVj;9PK5m(b_Dh9!Obcb><-^iEt)nVM*4TF1*b3nDgA8HW3Dq9v zQDbkZKdbM;kUC}xZQ?tQmpr~g^qt(1baOkuxxPLlCMQSw%wNUbO6W!DeW?!zhXH}y zpx0abtNoc;tRdlxRQ&|#$W#%&S1>8o>-5l(Vm(HUPJ=j8-c;5ip=iVsyhQ7mi6i~+ zEqE{xKp7yZYC92t$Ly$2_Z}BWhdJW96Z6O=PN_3c!7Gz-hJ8itJ8w%pqxZOktk!n%CXs1J0c!(k-QF=gs zBf$j`Qadx*f2o1GV@*#9P3x{GDPc|cmO_6!G7I| zLMbG!S{6qQ^;H$N*1B9#3kg4o)i(1lkyR~!wJbF@($esAqJDM`o;P|~&3?9KBt+0f zPhZ&$DE~>-YyG}4oj>}U3O;rFH%+fMC2Hx`X81eRgBBlb6|Qe_%jHK3h)D>A~!i*>dYg*!ErPkX}Fvom}SiKOuH}o9{hYnea$Q6C6M-u-TNqXwnk%^;>Z6x z+5HUYt%`g6WoW>W;CADR!+34JhBk()9L6$c5ggKcTdHDrO#EUPP1J^fk2Oe;oO)a~ zU%Vp)Q@F4?a>ULwFtcFyk^EKmM!I%;%x1Zw&fDG8lMh6kQ3v}hQl?&^ z?V7oU`Q%buGKNcH?aV3XQwnkpJ9;8cMD;Hzl4brVluT;nFHAlJU+15H5TeUJRL%5s z;s*+095yVPxc6E60RqKOp#jJgKe!l;qS|`?qJV4de&ca;FznN9^!tZN%O0AWHQj36 z+#h?L6F;|~S@>yR`YxVM^bvpff7jJ)@w`irJCR_~m9S_W5!G5h-85QhOe`zLhIP6< zCck2Q?G@eiE6#^Kp$UI%@zAa0EUTg*p?snIAv~SDGy;h<_AW;&^~2R6Ug>f)A*uFe z!QkPQm7hcku4N~lxNduVf~DCV%{y_{-L3*o19&9IsZRGJy~6@EABJ5fOHFQXS}xY= zJrMvG>df_GPJwM$m2v*sQ^aZkMh?`5NWQ6~7mID*TyKxM>#yJci`~Y;!mCHGmaby6+r3N`*7B;;|kH=cLvT1~}Opc^fzx!G_j)tl&8xDSwF=3@N-- z26sTu%T>5k%ZJYMFw0Sy5iuPiM1l2vi&m_fYD`P{5#(}i^We|SLTGe34!9{8$bp=i zynV&0omYDFFPo-Ll$l%VrVL94D`f$BtaX5I0iF*5XE+<}%XcoosYYj$y2!p-BCbh~ z)IcrsuhX6p9Q7~)g}k{zS)II~sip$=rz+fRlVT`h+1rjOYI?jsev)slRpTqv=-gW~ zoRBvn(A+t3`4pRl?A1Zm=SH%x&3U_dvE+iAohe<0zh=I3sf<~Q_O-<58nSiHVE_`}Wdn$g?YV>7)iIbJPi#p`%xE{(WJ3>>P11~(((9^w zyuskHKPsICJoD2tGj;rxpZ-+%z6yLeE}C(fbjO#RMp4pq2ab8UjSgiRtN2GFh*; z{Rt)=1_>2|2!sQxKdwitQI*HOHlY9V-DqO2aiWFrw;FEI_o9#c>~F2>2vaQhsG0;Y zu&#z;oUVUHOR7;J8*{{Br-(=4Hs~~G$Rh+|@i`i97 zedst_^Ph3ZVHdkM4tV&+oo+1rU7tj`JUqX^wzrL@$^;r)c#%nqo1m9~H)b`JJ)N_0 z$V2)y(Nr^c^si0q9m^B_o&t_OxwULoB{jqJ`rY%W5xEe`-W8+3GAZU!RL(ZmLEUCU z^V&bZDmk=JmL^}=*j*;K^@7h(sLi?BU-G23Ub5kkVk#!xifCuTlO}v5ODl6jn&m4+ z)@up@NA~-zjC3vfYiFmqP!M;-ReM-UG@ta!%{=s6>iJSC2=w?)G)=;Bkd9BcZZU^d zrS)Ad$WdiGbI;PTKco%8>aEChicJG507xRh&3Y9TT<{p0*St!no16JNVnQ>~8A&db zd7ayvO88%{AT?HhzfOf#<{v6QCy>r!Qt}sVI>xdyUW-FzgTw>?yU)SQh;ud%bsNlkCjh66(Btd+01g-XI{D zLr6%5HD*>6^ZK6aM$zv68twVbd66X z4ZDvP2}mT-f}9s)XVN5EKHs>$a`SN<<(IJx#TznI$>1;1o4kwx`)_> z0}zB8{Db`sd;_Z#eBh)aHEr4?{`A8p-|I+aS+}VXnydLs|^D@_i7*5^%=|jt}5JU z5m7Bj`(YAUwV2HK^*ClXe`Z^oHp+2vw{L-adNB0QM-`O-pd%Ip}vv?C@~=watl)ndF4u>u*cKO%|jb~cjmvg`c{tVGTb<0 z*kklwZsh7DNuAs$w|(%5BgR>h2%Tx#mvG{5>h8-o)WoWE^NP#L9s(`Fb6pIT8cD`W z#v4hGtgpMKV4kviFV(m4TUy4@#^C9a60tFi>!t2^*dFCvMA3w;>-fIa0+If{s^Qx=Ln_A!P*F6{;d5mQ9 zbIlQqf_s!dG-=>;!mplyXHY?IJO@|5IPWHwSmTgPB%K>5bN?j$9Vbm$N4{VMiQwJiP1NGmTZt3NRE?4^}iYo4Y^IB@Ge7JdVMkXCk`E2N1h z6Vx#5w^kwnTT|u|8x@A>hjgFKmvC{D9{+qa>Pwk;E=L1niV(e7&PZzb74*5C)GMhY zWF>i{7P#oZ9!cNAg2{yf(%Rs(bGTbMv@W6h{i!b!j`u;`%2T0-+mrf(ICg$VCod9! zQoujoYsBl0a00=V$-@f^2{Y%p2|5Px@==Io|Ne9YODr4oh^57ZZb*sU7tG||HqJb5 z6GJalDQB8(v{sl5?z)S6VwoDEFGA|J^{ocWmK(@H?cBAF2MwpHL*o7>Z6Z=&oyOYd1Ozz-BsSh>rsK zDfu-uu>0DYub5mUL3_|HWiZL#o#5% z4;ZrX1pYpy1=6R>qFV?=z9(iTfiQr?myw9=fJai8p2f6I-8Iq&6b+^I>(7A6MzBxk z>&K1r@vrfuI$kaBaw}{WOH0`eU0un%MGsdfT{d(KENpC~fK--Ei?}T(@&oe!?t!8s z@oxtUr?!Cz&jJ%7vAy0oi&{(RA1A+mbIkeUiVFw`aBy)|P~Vu~H=Zy(L(P$$-6}Tx zgn=0Nse5i)4WB8Yfy=KdhRQY+DNhHtBF8GHd#sSd>WuDb;}Amhg)t9xFQMDhY1UND zH+PB=xaqM(?zA!L3g3cYK8MIVoWjDrj@KXz1)QM_V4#nro)714`Pus1%mlOxYGUs7 zGg~D(O(qcp{`RI8%fmf=tmVtbk!1ZXf3_*R%b0;IN9Zmm7zQe&S1$Wx4)Yr384a@A zP3`UmWhDI#J?49Kf7gy9Si3$hv%ayS55Sd26`RKvvctNi5XFAH{N+{YoExivpkR5a z1$o0mE~#pQPPpX97~pe6_$_JlQpdJSpua5~Mf;&B(rG{iFjv_i zB9Pl&Qt0XBojFK!=}SI)^#6uNXiuSd`PkXJ4XEfRo| zr~gvz|E1EKrV}Hvj?_WXprNiLEVeI3i5J2iPVk&aZgj5s79gN>3eQLZ zGu+J0QIE{XQYNh0cXQQaU8TY8`ZBa4-h=mbVdX7orJp?`{k(R~%$bqg-MxQJEb`9N zH%FdQa-~p8>5`d)pA)!2JxRrL#32wYA@FHOfDn#`zB3(3JQ{coV@lsR<(VNuw5Cw= zBJtaB$=Ms5mb;^tfD>^*gs9EJ>*u~8wRphZOGH-=q7niF>reh}Tc$N}t}SsPiuQ-w zj0g7nKA)>;FuKgjB7wrD1Jy9<4qzU3=etmVSb?@5$iu^Y8t!8LIoc}3KDW&@zb+*x$lXHcnWz@$KCyOH`Sxq(5Q2*HxzG49UW&vo7U!Y!c=%q(}w$6NT-<} z3eD2r(5t#e$v+iewI}HX_rGL2%nI!FvN=;VVH1;ZPxq-88>Y&*N56B8mbuQ)W{+|L zBrHkLIf;TehF570*M(^+k28i6Zn)zH1JA!+iti3;>Ak&(!bR zWo01QyKma&rE0#q>)g0A%J*%V)tg5KXsN$yD_6W<9g7SkWU4BWaq`2XuLd(LXi_7SKTJTet zQw+b}JKGc<4^3YY-V~jQ1SR#0lQ?}g9%RU&$8CN?A=<&iz8848T)(Cpx3iZ}R-N=( z_>6Z??xNFDL$f{%t0sYya5>3I9^qf`ThJyBHNX2YUsGLucJb8)r686)p#tt#?uwBY zNs`vglu-vU@jkJ5UUBab{?|#CqpIjA)1b$0BdIQ@Kg!%vqYX8Ya>$=1M^m5TWj-Ua z=lmNKWo<09ry=1i*5izuN1iB$ieWR*r}a)^-EW;g5@A)V&-qjT1~n>X>9{w}pn7#j z3i7ax4ENn431!~2!4m}shg|Kx{z0UiublG2LKjZ8VJ$u9(V!eSJc_IZrrL^9o$5`G zyR!k;y=oBv>Gl&-Cs1Q=I)RJ&srUhe4S&8Dm?d>9m%`Lf zV&WSAh6I`A5nIuZ)v1tZEFh>a@o~nyeqZr;2XSZd%oXQ20Q=Z)(Vyt7`pnG6Lh6Tr z$G}nRxBi2NM-?{n<%`5}ckB4TKL~*U6a~Z=j20o!vC&#Lj!5jUHMWXy`O=W9YAWot zi~Mz2hh4fO$TxR(M#CxIv4tW*KWts(DQG13ptfw^6yy8;(@MS} zY#T$Lbm!ldV3k4~4A8GhW+)?G(*EcohL5}C>BPkTlhE1kU5#SR9AfT-NYf+|AG#n| z&tMZsX8wh8JHz}8F0S^fcINUk`#+gbZA3;}CVW!hS7Wb86rN}@76v0vctRRR++NLW zv&PU{n_z5xi9glfLldpUB^HcEQXC`@`Xm>orglxKuT4(qV1?>|(_5A=GuZn;79BTj ziF$vC9P(4LRy=tjs$wDTAONzc*NQs~iSsASQY$q^jNJSS4#N`7TCVPdYD(F~Lcr>5 zZT0;*I>~r?{Ca0VJDJ#X4t&hKkJ=c)U5!qBujgdJ!*ojk+Dg409!<{Ed2BG?Qq!%Z z(5$tQbdq(lp&SBN-&cbE%Sp}#Cl~KmAK?pVvQseZi5lxrFQ=-mVZWAxTJ`~`$3Ab5 zF~X6g^#@NWgis)3314H)AMLk1cng6DR5!6BU|RyYSj6dG=iQe>4_A=;Bgzb|_!S6JqW&FNF`IS2W1%+4CI*#$SL zwnfZ;u;sNQgtCne9=n30jmG`e6=Dj`(P)1ti93#w+N5)dB}@~lud$aM3^UTdo%g6* z;t1aKSn#@7F7HlPTR%0fSMm~}1W1(#AbKy{)Kpb{JFr9ys3sE=0br>N{tf8afMq^G zP^eTL*(U2)|5@7y(%;-MJ>F%#ilQ0A#~h)Kc?}5htzBsHgU?iHPNalQoWrtol0I+} zL%^yd5|q_8(V9Ez^S%5(=3U$^p542NT72bsaTcFFrWrz73PULH#|Ku9kD8y*A@zqt zIz}BrKMtw?s|8qK;C>$#7M=-h!Rj#VPnK1#?>|2XtLy0Xzdy9)gbPPQL;7Uf*X=#uMRJ6l_S*djFW+LM!8MQVt@HX}!)&grNz zikQHB7o%i9R*lty!c5Yltcbn$=zr6%_MI}kCnFO#Cyo^f;ww5x*Q{@KF-=>w+QR>6u(qn&^Vya>$Wu=Qi z9QZTv3XIRCt0c@JG8Oqy{~=X{Bs;XeyVPx72-}tJWIaxLozg9IwykgMGXbO4Rf4l| z^Yb}apPW>Mn~LOLq$H)k`OFqn{iWIrRzqSaZuqy%`;o}RDd*Vun6Wrd$0KNWs3UzE z`k4@TtFFp z^z`}d>`^`oAJJNRJ^H|a2EGXdMFc4F936MXJ#O-ju7(x@HEqm)E$Zpo%&f1kr_Njq zJ>1-PH@6*0==k-z0RNzB!W$2!dabf^-~<<_PMNcN{9?$Xebc7BX@TOXp>n?$;m zv%2EVE;~9I+@20{HqLx3b}-7N;R<;}WuGq?9xakwzmV8WPhgR{i-LZzT6d(ldD4o~ zbS8LqYfeOYx5*2v$_93vQF!Wtf-}H2xn*c%c`f*US-R^)hS@Q16PPb z@)0MkYv%$$zE~KOtH6|sf>V;651yLAApl5ho2Bn0ZILLksbu$S1~7}O8hqNLuXnuRSi@8OuT8TTcm%Ip_E5(=Po}> zwk$FhMJJF^J8Ve)yNXi)?>m4@!u3$K81_C0QFz|w?083YUU3(%s%Iuq{$GLpA_#vt zOn`a}z5xT4O77KN+~#*%Rlc-bl$oD`Fl^1Mv}#w3>IUODbX4rFZxs$U=#Ree$rKV) zl^$h32CFJ`{tHR8PbxFdscl`#*RE?SwQV}A9wScIsFWfzo9~vKN{%@(B%M-6A5tfs zu1V;geRbWvXz1EyvA1E$$vyxS+Rs4ZT*@m+jRRo9hGu3#B-2T2*t{QrrR`svD`yjZ zN72eb{Yq;NQn4vEs*xbI9@6ZId}55&&kJg9spFget`qk40(Q5OvF6SgXMY@?oHQth zpSxICpk-ZQ*J#xvk$&LSyLnriQ}dHBcYb7+_qPo0>xsP^Fwk0_?Wv!&4VFP1{cYZV zv%#s$8!7QzKi`}APkVl)PR(LhL;|zx9IO~0@_OQI=i~~QRo^<@4EFag0v;^HSB)h| zsW-CaGSuU92j=8rk?!3yv8=vf7T;ZAHo`t4?{OPl?jd$y_6N(N8>iZT3SuM4#egQa z>~pFG5_P{y?!X*^;s8l{YZs=6Y#qV=c7gb8?ZK+D)vgM?fk(`y9M+yCr;PxZ1T5gC zLkH&gd5Xey_{fH2%B3fp2^$OAuRl z2-mC9Ho4Y6%O%RWkfvFY|7TU}k-Vv?UQZz|-g0wyU^T4DeESoy?Tq-ZZ2@nzzCT2s;x*JHT z96l)Jn^hCEL^)duw5kjz+xU#JC+9I6 zWW&9AR=MO=3qgl7!^2-dp3^#votatO#f1;-i=A{2kFJ1wObi}y0S2)k6ZX*5=iKxX z5CJx3dEr4^PsuJV!AaE-O(V*=dOp|Ug9UUsKc}AL3?Ypm{8vPB^-<4pX|}kr4?}Lv z^3k!RO08cX&m(4{Ol6g?zD9ga5zlJ@Gi{kLYt|~Q$zduY3hF%Z$twD(h!wH02sQbr zbG$y1;K_|fSHVe5qFrC8kz6XX^HDDQ9RchpJTFSd-R|M;V%cM%Pau6P`(W4V9OPSl z9ZK+9$QW_D{$7?+l^V+8DlSNh<8}5Jhc%CN=)TD*6yu<`vU$SR-HZ2Yyyi0wK5v!O zLWwFajeu*xsp|5TgjOOgE zq(AR|&O;j-k~KuFHA}7$7U2f#vzXYT*}<@=JRX(p<1sHP>Vjx4vxS0=wTj*!;qO5f zBrvJN!)Cy%liHe_I;sQZyKtEhQk?j0Z%}bvz_(E4J!uiCT(wU0<{;Jhjf9hZGsG9T znP**B!Y@IvQaFhHShc3q4ABQ8aMDMloYSHq%16p-XniQy8U05cijI<6UNHCIKImRmFU`$0o^qe)=|MTGpXonI zcKn|{hfKV$O|P?jJJ#|YNl1Ndt!kwgwf+1w30o3!a!f-anb`J`p?_J`=zE$9D`qPF zxm`lUs+;xmn$bUf3WZJ-1eKb)?>Q;>GCACI_F7r@^af1xMwnjUILTMK+wy2ck{fF< zYAQ9JilJKir>W#rWA5<{ZxNpAjpt4BDGX^jpC$k&KYcUGlP~|N#O8TFY{U#Dh`opn zzi9G#plCX5M~76PZ?AHH34%f5`OD1o(}C3st^@?s0)EvWDzCJJ12Z*bs+X4u_F~7- zi!8>{Ea_yJv8u|sx#?AY4fh;X-l$d9P>B%^46FUSMYn5d(wmslMv2{9N(&WwYDM9C zB7tZ689Z0ORD1KVaHAH)wy5>MZ-rtFQG8twC8M%Mp_|7oE>Qb6y{!?OkU*36K4-g^ zY0SE~<3{|z(A$+_v~skL!x_PFixbkSW%1NIlJZk9BUq8J{3KdpzF0axpYd;4K&`U$ z(?0pi*HS~lQhNZD>f!LDxS_owm@Pb#5q|9Z-YOw_oEsg;8hNZagZm9?!*Gy^glUnu z0if8a{G+D5dzMIN4qq`4SpR!K-BL8CrkfDWnT5^?W!*wn#Gsmlm!U~mqr~2cAQ5Eh zz<~4-4g1f(>KSuOhv6ZLQl&$^)}cJ9O?X$I)85JIsggT~5J*k${hV!Xdd2D|;6ESw zQmDIkTiUglOERu|`%%dOfZMNsl%ubdtNitgd~?r>y!9CA&?>!C0f;Rx007E|ivg^@ zou9C=x5GvFK)2Aal=hxY_gEd(ZjV2@FX1f*7xiZV2+02V^A~}e=KBS+NwsFr)a}ou z)Oz7LL9da;TJPYH|Dve12l^JfAPCf}nDE3h#U%VD3U;m@kj7UCEs}EN3<3SaVakQi zH-(26Cf_RSEAFU75$O=Ruc-^ka+*8n=Ak#XlO=+q9J$wlxxKV;D;0d>pi+Y0oAl zv-{5CJV34B zyU|FfM0=>w2r`t98B!#v`+Vngt|FI&LH=ApQa3mB1FE_&6bRlA4?oXS3t3ZAU*opH zg-l?F!v98wF~Yo=I6Llb!nz+`+=7bVVYX^OItR0&8t)9H#w*L$H;Ifp_9?zEvV~dr zauo8QGaLdNVFE{I&o|hHLJg#*lhr=xZI9rKaZ_2bOa+a@#$Q~-<$y*!(&`F@X;Nvq zx2W{-&o7Sj;a%mDu8UuYbbdttl5j+%3C2mycohluEx*6Nmx-5Ayg^?LR8y&q;iWgx z4f`}{Y9vz(3(Iq|Qr|$1!aTX1(6r_35M)NuuAXsmb#+yjKz%J(%l<{8&I~M1Y;A4j zPL9SK?zHpIlpi}ilqs;=(hLFk_oel#KrJ$q-imh zCzab(xDpZ08+vA&Gs(*BAU7t&qZqMis2Fs(D3|F(PQS7j;2i~a^NVNh4mJ!GmveykmGia{ zfd%Wps&h-aQ-?Lr7I0kwSq1c8A%Lc_ekU~>wOaY9>~S;@MK1<3q;ph7lA8s;aQ5S> zDYBLGcOjg6(%cZYZx)}goL?_H-EATIJG|JF- zv=$#MKE@S`<+k9yk;euUPN8B7#U%}rw z!YRX$r_k6q5&gMO!)u*HTmeVbb%p?lNqru?;cG0n1$h}6y}Ro(P$-z%FAR@7!Zx#6 zfOAY!>*G< zEtcxSqBh&Cj#Msd^vS$e*eWYs3**h(Uvc0Qb?mnQ z3Ls!DUjo9Snh=oOdU~?dmKdX0Fm~aHvKpS+H!%D_x#`Gfg0{!; zs2TttUOo1ZNF>&l%(F^|N@8+Sf724=bTllnI4XD#KRR#T@2>Qj>^tal*H3Y>-QV681OB6}4G-h`e_C>UGC{wmf?96QZ1)5n zFi9S%Ukf1~z3)h*W-?1Zou(=VYB@E=R1uS@WpCq=XiS=EH?<7Es50CA;kryu1pB0B zccYp0=cEvuDqJ$o(y?s_je0*nro2z~c0Zio*6-2kz-8<0>W3A$V#qs4P{RkGU>n==zTJr8M@ z;~cQE`AB0N;=D0^g^PgWUOfwQ&t{h|HP5-(vbOBD!}p)>d(?FI)B5d=ji)2oBuH38 zr$Nt`QO)kv^$%Aj#VH8Nw0EK_&96h$ajnc|ugG4!ofY!tI~VliI6(kw_>rWSCW_p3 zoAp7xkxK0?^N}BE{Z2N99<_3P840qSHcPjoVYdi+tuC_jci8^sDJJGtfUAoA;o_U7 z%jHmFQc}Zt4>11?0(v@N3qW`qaZAhI54H+>03;~|oh?(62C*f1*uZQiKD(?X(er3c%dAqts-Xsi*ajr*XUmAIeKt) zb#=h>PnOD}BI!!2*SmkGyTBJI^QsYtD#rAS$^oUQ3Xz-nP0>yj(_mp_(RIoEf#-%` zsmQsMSSIOQAW`!XPP9*)N`%?c_gbr*vkJ19#}jAWXuZd2j)O<5w(D&@{0xd1+>fA_ z(v6Yo^)*o(RmI1WI<;oj3^oeFX5AZY$ds#v9cJ|}&DJU+lJYI%hPlF7Xh&x2O%&oK zf4vvhk%~lbE9E3ajXX&YnBr78aJf9xU#|hW4EB~=`ky~P;Dq{PKlM1WeV7QZwqy@& zDJTBCrFj0ZwT17zZ{@qt;#*O%`@nLPPzRSD`xfhwMRq4GAHb#Apb-IJJ%7Rgdq0m<(X$}Q+=9g8E=~=0Mp}2ef!3!KX1|t}*i%F&g z9+loZHEUk#k4aOiwnA#`h-Kb1FK%RZL@i}N_QQVt1_fXvWdg|ugH`mE*Y&A6#?z+; zAUC_;UH$5N9AHCn_;6EO6xCK!Pt1fL&;AG(wQU*yT6^92R}mv&P*)7o;v;EcSMuqz zVyIfAyw(Hi?qvsgUCq8mF&6Y~K`lP0IZ2E-xCOtt_?)oK-wiY-hRGRFRl_xF(!tX2 zN@Wci9G}_BH;3!qt*fe4TM+o}YSn}F0tl52NEO!-zSr=gj(+0GvAsQhv)}sVk(&=t zeQDN&SIDiEqX%}tA*vZbqPGkrt8VP?0NV*ZKYC@i+{twWGN*VB4n#7rjE#*^9wWj< z@{JcSYK1>9LP0F;1ADRh36AH(O}B!|y0|r~{YC5kzSU_cx9RogEnE(M)E}efu?gMq z79>Xgo@TPe-)yr4y_~w8@j=OlH}s$0gT+t@!m%A-6bJQo80k-m^|u!h7+0Z5H2=g| z=MX}`pe5N(tDzo22^1$wUTsxuSby8x zLnx0X-)}mR1G&dx*C|s~gesq;U-adiDJv11Fp!UCQ%9(oSI%8vET6&&1b~rl<0}0f zI+^KB<*9_Gzh-|{MCBKLYcpxr?7C0AExoM(Lbt=S!hvc;?^74O7E%3E zNYvmDhlmA`q|_vOERtQRK+A;+w6`qA@z}CboH5C522<1`C_cUt&)bS4gIeI$0{EgM z#TLfTK2(C6vyqw7E?qf@$65>3aYrb5hX>k&a;o9B?oE(5DN(;F+ zwVlw2oxgV<5|c{j{P90^Vms17ia$$j$+3PM@)|X@{9G}z-r2XxbKn6AD*z)X4J4>$uLpg{*7KB`gfHC?K_3`XPSh?yyklz z8)+`~)smg0LoY!@eBwq7$&$j9>e;Eq5Wxvoe@2c!BE7lR3a}MDgWTjcKO)XHHnGo1l8N|1}r?aW%kws z4&}(oXt%fG$F^BfI`V125NEhh(&cT86@g^tAQJ0fGwed~Z51vf3M?T6N6eWO^Vd*AT9nNKNaU zX>lWkHXl8^p5Nj51e}@8~8KSzR}f_im}d{>lx}$X|E)yaWo(i+|s# zdnWvXB60uH{s8`|%}`#!HasNx&k&OnGm@BzdMJ1_f-!d|y!$t8 zFJ1SxDJOr6MA>)pI182Qa^;JmFvCGiL!}t>tt>fxRd36$Y27O7d7JL3 zo;GFZjT>Y|p3@i35<-ltuXd^jN;VovfI14me>4M*H%8Hf1Rf?ll1{K>prGEd!bI7#_}H-);a|KFM~+MiYDJM&vEIxu`(oG-vncn~-JV z6(5^hmW(C&`>WL4;%{SpE0FmA%4L3|eXYUHBSQRW3H%96oFSW%4IP14@NkNXF?t;d ze^;&d=+Vyl67O6bE+zAJvfljaF2#oVqhS_{Q0|F9&F)x!I!yhpVcKZS_dpIec;+J< z)+9mqtZ0&fp_7lHG|PSHHT3~EoH`5AHSXJ#+-$t;I^W%O;VaJnK3ee_q|Hi0FbjcY zTq_BtdpD#oURPuW!z^Oa&x#KRA;PyM1Ytp1ABNk*UYV%08r=Q7O;@Q&&&*ZM(|M2x zF&0`TH;;^SciUD-fKnhUWSfCOkEA3L_=>9rnc|qCX86L;$4apmoegv6RKz4bgeV}d zt$z^CKo=qeCuXB>Sd-oxfT91x(ZR!)qc_xp84%c5J>F!4=ud{*iguw< zMP#^t1du=AucvC_hS$x0XSv~A1N$2sxI|-p_D-9bAo^J{V`fdw#2<%3^-tdj|EbIq z#a7#i-2OOOEXj|3Esx_Yb6AS1^`ZXtrtgl$UO#=Z&1kYtV2_&Vw7qG{u-kq@kjFc_ zD^rXTxmB1=lE=njgD_io+ao@RH<2;tkHZh_>@;nMH%5axf{YTBbBBs?q@}-w%C0RP z$y|FCLSbubQ`WJev*lLTIPf0WlGBx>1a0lz*Zwri|I#5(1>N5l@tAOUay!o z3G7QEsuZio=@J*|Q=$rB3fp71hQiPKU~&zJGKL3pD|=cc&HOs_^xaIqjJ2xfEx z{)h~a$Y#4Bl8TXXfOv@CNAH{NCT7%R*iA0JAOqzwq}9M3hi9C}^H% z5+39XgHdcbYUFb#GU#&b3DFH+!oQs^>=0idAj`Nv&FhoUO^%TZOHiqy;5DzR=eVpBbX6C37gEI-d(8XBREM-;0Shj2Wm0M7O2tT0v&eu+@85b?a0)(AfkKS{>71Qb^dWZEbSVO86>| zDNDRSE@m*d=^!!NC(Hi+I*ag$B8KNvjK|4Ss>1YD*h9X=dC;kk4MHtM&*t4a?9D5$ z8Ag7~Oy?7N*V@b__k9xt-u@0BAL3AP^)|j;ESg1Bz5l4e57d1qF;Ywa^J+DKAljy&QaRb^Y`>8(qi? z#`n*$-&vxyG!4o2?xlLN5w1bbHEfdpqd)G914J~AG^Feo3`L3pdmP8jgzllSps{H% z#$FP;a^a5R8l#eT<8Z(*^HQyuE6(}!SmMs(G|&@)ii}B_TKHHv9sZ(^ID(+!K?24eYB}! z`d-X?b`w+a%T)%^P&F36&woR~uiCOQbT;dwvz;K}BhWwS$jIk$2&a7ojm+_}dTbmk z3!V>PrXy(S=wUtiR_}ifqOLTp@>u&p`UW*_upa1Uz=yZ79EeU*FG>I1&44II!_S{N z7{W*hgsVEmnxlGNPESwU>)WfhFq>Oh8QuSss%LF`=QDm|xhKfS*FE=y4jeW83u=ZX zEThGXa_6HCSWJC+;k6TqV8P%r<hUliytC^KahV4{m1=9H~w*M0S76c(~mF zcGh}M-~jzs67s(--;01a33$`kKMC{7l$!m97hibq+^~AD++a$5%c)cI#>pvq8?BKc zre_U-p;0Q|j&EbV*%6v}CT(25dIH3$pO@N^z>Z0P@9l3b`sFemaxgotFWa*iTZlfP zOOx9OZjm?@wqHe&OMUeQ^9;l2fEipje=rUy)ouh5KOZv4@&4P#%ja_qXDe!IFFM-A zNIXR-CyEhlTAE32E^0Sw!n=H>6MTQaf1W0{0$Bbn3d+?%ptL^UvqZ)$*|-O7H+VBS zYgfE%6c=vX(ly78EAN|aPf64S{;QZ1=_K~*`@@!pVq5n%z4m!%*Va%k>$w_xvq6wbMbptF&Jj6IhV&?_BGW?G`gyC<)ke!83X@ z##mcAibD@rlwpAs?mkqV@ifAvXWO%2t$U$eAw<% z!>f8Xn~5}wu05^IllRa)8|RJDRG0G7{1n5~~9#V=Tz+2~ea)@M}Lz%x8<>}?hr4{W-RR_2mzKvdg=p`#;+%|_L7 zQpTL*_M0f#@7nTSF=A-x=`>5VuH)OS?x>2keX)U+U*&174aBMAL`6fy+5RHT4)2TD ztL($Wa#Z*~ROxW7-0AGNCWWtxU5k6Ll^;_hVm7WnF47VPOHHr5pC69E0JO_6@(yck zf_mc=iLEh-O&jrN-lxAcC8*vHh`qgp$KX;PO>UgPo%wBg*kG~cg=%rc2W%%zO{p_m zMN&W1a-F-&!R*TT5G7J*@NK$%EOki(xjXgq*9SQomkJ5u4h^`czhv$N8B^9|lp?-F z8U(y za67PR$J2MT(k@`JYgXGLUPt?-d8Iwpw+c5h^PyfuFeUeA?1sa1oeM%xe-}4<^9_ybnAJN=mwd z@fbjd8gH(2#igjOPT~x{3t+K6E4&3}5Ri(C9I#7`)~j zTsx;91t{LDOKC-Im-Sd|SOX;$P*SMi?`!Y~Mc_uWMgPZ(x9!;OZy5NkGO8XS6afDS z8P@%xS5#5*5{Cum7ENeQMmFo00&1Z6W`+fEG-(%V>dotk%{qkQPgQbW+|V}oRIRWd zd#eVmWKA;UIK=Q!^uo%Ikz=fPVJ2H~2dg|WPW|dbf24l#CG}t10NTbo`ewjEf6hD` zAT~wYqQUP4j`vU^T~E%9^W6GEHFzup-S^+LaQn!=)?kq!w7Rgcz2H+`;!Ohrg(;aO zX*JDIP~TwwjRN~nfi{~u!*O8)j&Vz{ndEFJ?OR4YA*e0zpIBH}$dG$PZ<32@q`5nU zbzfPGA6csEXhD*J5+X?kb}KpE`Ro((Mu?{N2q0Ap*V_Ku)sAj)ipovz zf_-KOxuEYmS9}*Te#!FjEQRyw^xd&7C$;sTyW>eH?o_N(C57G`{ib=iDnK^C2L&xN!wF(&5*iP#`s5&mG=6}ZN$CYN(TK1% zNU->7Z9Qs2!$AhE@E3=}ZFmG{J=<~WC!43{MaqG3`~|n#+HzTg;zg5o!|ZbPTdC^< z=p|>zUsR@SHkpSiQ<5rn*~G`r{E)dBk;by2I<6b8Ld>U3U=ik9L?DIdyT06j%e|Cl z{-={{S!xu`5(G3&5KxIQb&=Dwt7M7aJd>Q$X_P1t4}1zI^J$+qPhG1~#}B&=hK_&! zqw$xO_PGDO$^#lXQ}WwOzMSEvp}NWs?g!XF{P^t!qTz)oy?uad*mr2#9{){{JO-uLo@ufw#0Y-r>!tmRHrW zRc0;p_)6VYlg1Kr+uE(>AKBKoMD<&HMTt+fP>_)b<|jW1AI`iV_4^kwR^{jW1(9T@ z@|i3Wn9K!C)zq(DhHCUUPb2L=b{~Wp*d+wvi%5(!x<}w2-!Jp_vkV6P8WiY}miE1j zs_hj>6_F3C5+|?j+&Y;t-?bMz8C!8S>rOpmFQ?aZzuFrgXW|6(?9#T@NJV6gOI>-Rr=0xBwCnIHGj3sDGnqRwV8ipl+xrhUSU; z`o8FWyjgo84Af=R$WfGvQ$3YbdkY_%_}%vWY6j{5r}u2DqoO5e7qTW8r)0KP4lI2V zADBt_hLg=e0BP@1o&RT*|Ac`~l*=a%^ZKtPb;EPcI%+sPv$zf8HWG8BsbuWw*d|gJ z39E)Kv6vG_xL(lD+!}k;JDwGar9uD4)?0=}y>{>4fS?GXl(dKlB3;r0NT+}z-Q7cX zC

l217Se4xN%C-5}jVcXz{c&EEU|{og#tF~@$fU%1`hTI*WtJU=HkDYWKxA~c@V z9Eftk2LbK%W8bN%sezf9H?AnA#$<+I)LM7I*gBm4C2`p6jyr(Hl$@g;lqMcgP@`{V zX~>Y&lW|$Fe1!EiadTtQta7&eTB>P^gnLI7DPYrjZoN_`+x8s|4anJg#P2>+#*SCH z8~R-mN{PhpPrX`Vup@G>@N@63_&!$BFK7=0vwL8L@LuhDVutQy; zl-eH*0!-$CrIwp&#dEc9B}s=2Y{K_FPV}oyWVpS&y-{ufUv=YStTA!nv9+vmLxA>> zDm(dqkEtZTlIW|%ynZXv4AsI}Sip=D|L9bMx?|}~P?J@9@4BB5>-P!H6t_M{iY`uP zoel@?Lm8I_m)hnIqOFu#D8YnO@K%{>+=%?+#vxul6-xpn>tQ5m#hQ+O%5@4uU0F;w z>1(#wB7LM}f?+=WMGOpP^?92(BC&-~s6~+ZJhaej-q(#~r&-6w7{+$hx zaYx&vq~bRwJAs!@k9n z43jss&LKZaigkXfu2K<&B0cj00UEAfrkrz-f)D8_J+*^UsqMX_f7QYL>070>9h|Bb zRNWmwpsX9I&!7@U+*PwpY-s6A_4Mi3b}hhQpZHg>_wxpVY>y2Kp8O9} z`1@65WvXS=uC(K`Qrz8DOF1OB~uSP_;@rcEp?zSGp{)@FXVBKU4zlv>f~{)?s( zFYjY_a9SI_?sNlx6L%y?Af=&tmgkxPXb`h7&O;85$d7fJ)TemArf-u zU2QRNLL?<&f-x@`@t#feN4{${_;{=3Un!D(rEfnA5Vv)!DhnO-c4_r{c^cW@R;jc- zX$Q|`|If}U*Ha^KB%X8-4L|0{BlXiLf)KDh&NPej84-kiuD4cFDp(Yuo3m{l`)!qPV4U1Lv4bFP*@K9U*U3mqLh|N_KNpf={MkLJ zAfk;63wNS95d77%ZPT(1{|WH9fDy6xk02Pt23C86IFiSJ30MrCDm1Nc9$vn;>^Og1ppgeEpZteXaTlm2Rf=Tbx4&UcLbo$To>b!Yyhfxa1hx|1w!xFf*uM zNd?CbGu3__uMe?U73Z?5eX=M=w6OiKVr^J7sr<%K;$S$WZ9A;h+;KryeeA8}+q*9T zADM(BBG8Zix6w3gyyWlv3&}4UN=K@mkZG4FzE67FIZy7rJslB`sD^n-)rVN}=BK|* z@~95Uc}R#9h(B5(DF!ME^t6J4Co+*PlsLPJfwRDJ3pt&39^MY=)?lQ8OU+(fcmaeQ zP$uPIz9tCBgSoJ7e63Q#PRn=OE^<5}2fD+YpeD>`- z;|h5%#la^U?C~Np>xgj0$2r6+li$5nps)t_af%*h1Q6fmZ7?`=1_&LO> zs1&&ZgA@CWWUy}{dz|}6r`ifF+;jA;muEEok38|v#FQWcQob)DSxO?Gq+8B%B4yPi zzb^BPvuq9e-ht3Jsl02*c}1vI-l@3=6NlA-q{ff0pVe$?dRmDmNFS zwhAMA6s?%@d)9J(IvnbG*ki)6d=K*+2h(!f`fX24uc|cAThP2JDvIYU?v8*GBWubh znT;P7cgeEQB>-*n_y#Bcq(J&Fkz@y@I9Om?{ro0&*Y6Bn zxib7WL*!4sP`dBng2$cqFB-4WW-H_zZe-}KmbbY4(Y16EPH*^YS?ycYaAECpT07fn zA$qBW;^0g~)uCMJElifc% zohnuA!Gnni{%qlY^-S#rAm7|)Srr@R^&eUOucdn!F7k?ELSJFeX%gLHC{1^jWq&~58+C7J!CIN$6HLh2))HIk5;-YzG?6Ow9GI1zo zw-?G<7 zmYHAvKtVwP<%erg4R}>bYbaNY38Y1bC7vu%> zN-WTF^ejFiI*kvRAN!(wx`8gA+aJ4jDMhN*;0eToLm3j;8X%i>C7a~~Mv-pdF<045 zHaKe{1#(Ds5FA(3gvaNDX)~riKOcNc>HeN?)cI@3sy6balG{)GXXn1XkRi+aZU48v zaKz^hC>#l5UH()YQuQ>MI6Hd0TE#9Ho4!4UKUbQ)zC5*DIhv`mH|UFi>q}~|*8txe63ksWU%hG}_O(Y`yFreJRVxGQ zmhTVPR6GnAQR!Eg6fH%lp--)ObLlLFZ;z8`ZI0W$FCN*Gj0xQ+W(J{0G%u3eMjAdsx6qTorVcz?!(!X5zL zB6wZkSMa&hGyey`=R5CzkK7cvPQLa11g311r~ZLCN0=51jKyesrD84KNJg{R83}Kn zz*~(Q+=f5=2BquaPD}m%ntVgx|4HzSr908ajZ*mRCZoG4fk$%}9S!;6*4KP0TtsH# zdRJx{h#3l^Wd0Tw6!08{o6%*({7;tW^KzcR*pvF9=V4xg=U`NWHTJEvlvw17-e)}bNLrTTXW z$(If)!hrk0QMV$#>Vb&ziD0}mMZDr&>Zp6*pLvQ*v77FUfWkFQ)pi9Ul{R)+XwPBxo5X)A{U4Bo7QDW01-4)4b2=uAkEOOf#J;)f{k5h1 z-^lkO5s909I{N_uJ^$ZJv>=$IIn2Fz^9;8(gY=-Fy!WLW+e$TKzQr>~ICec@`y?Je zx%Eh)$(rQTBnk$GeuVha{Hue5u$lP?(FbG1^`w>maw@hge=oz%2;l?Se(%;#!SI9%p4Fl!Ghuot`LZTVcilB=5= z*yPge@^4R96FECO>mEuoSF!hQ!|P5_+z%iKVgH3j;0KQ3C4Sdl=1M3=%i@4cYFB7O zI=<6~(m;clHMqWzDsl?`>z9g_R%mY`p9#=>@jESrsAxF&rS=FrhdR*S88x`OY=!tg zrBmE%$(LsI+L3Cb?jLXNWFj$=h-gDP1gDwk;@_36|8VYrfPw)HT=~~@MdnCL0{k5I^Zb_FsaP!Lq~9=(MP@AOu|jNf z28(ax{f5r#=J~k!5`a(u_l1|R6+Z;3HGL0)BTVoK1I5Pbr*nD=I!#KX31?XdAguw) zru1Uw8O<5`!m?veZ0~adS#0~V5K_f0FFC1mE#|7-f4#d8f;<~QhVS0hVgGZOe0p`Y z=LD|2BtK|-cM-SxKD*w^?{?Go&z41xryJ_}i4uA3Fwks~b>!f2ic3fsB>n`83nh`V zVPIw8=;q5EGGz)W3#@5N|yVy={L75fUKBb>S7YwoI8dQ^^{619+n zg!k41PP^j@~JDW$fr=$p*Ate1;#R5*59i1@5Ca?DcsCup1)Q;Pe4`K`doT5`R)Sa+E^zq?0PW7E%fBukn~cM zs>?cZu|bUM^+Q%8DETID0{oHo+M2@3n#VQtJseRS`6KFPw`>u5;s?frI_ma~E8lxH zgVeAu0&;ua8^5u{1KuFWo@ul2^G`rn|Ncb~pb&t^A81rp-Z=w*Vq9;JF_Ul*<1KNe zj~A}r`3n1+<9=&D=zu3Ig79JRz~tl?;Kc`74H^vxk5LeUVXo+hhT3r!+9~^p3;5;U z?CquKGuXi@6@t#Vt^O1l#*pem2)Ls*7Nlh z!DJvrk~X)nu#ddN4TW(S6l}DNl0HTTrHd2=yyQ@ z9-70|nd4Z;=5sC;9dTDHKes{of*hSPT07k9e;w99FSHLBwGXrjE z=_Bw|?nQbzUMFliR;>PWwCDOJ$w4IPnnr>4RqSr4;%MXMqchH@iS6&5aQ0mw44BF} zIh;S@8_O*yQr=K2W;3u>z`qt}yxOaa%UnG%TRu@sp+p(17o$W|YCqTk{YZ{-YM-}N z=yW?+w~f{lqfz{$@p-!7IM+sbiyh0B4B}yergtIi$~v7{HqsAPdI+C-MVVjo#>`4C*mCIrilhcL()6wsoD?esZHKnHavaS?RgWyX9h3Ek#qx ztXNAKSrY%Zh6RT_yXNcf`T{5+Y^x@PNkaNgkSqSUfAW~P_C)>~6BI8CI$WQ@Ksz=v zQq8ngPszzuC@ncF&hLvp2UNm8*>v6A-BqOwGNEEwua9oaPFETobx-Se-Lowkn;Ow{ z(FltrzmA%d(^@uv{B7xoeJ`^6vuw0w`!CGGVOT0r6U*#y*iIIdu}XfKiC(?%-Em4r zZ$pVHyF81iOpUf>duYlto068t1ak9}ld`X)OTN%>Xx?4Znthtdy|ped<6Coi#P#Pq zSCg#QCAC2LRKT}k_4JalRhh)7w@@utb*;M6yke!y_}HSNH(b}TmXW#?`!lG*q9}L= zn#N?PjP8;LL_d5R-u5NTB1boBswCkQSIBMa&q{A1Yv`)di2c?T8LtJeiTeyxS53{~ z_(@;zH-%Ld<`I$tU+(h<@6L&rlEUAMsGZ&F;>4E5ew8E)Yn194>wiu;_5rCqV=6Y; z0~O+57Mlln?Z4nyS>hX!rgdp;r)x~$2h-<9GvVupme@`4{x_9ENk>r)DU|b5Z=Z5+ zA0=#;-D|ZJXYrLLrr|p11nXzl(txu}=JWmgm>B-AX*8#{W)V+!>kcEcoV85!ixv9- zMJ9KBpi5@(xs|({TSit^kRT@NF6&2F z1&dvt`-5#SzzZXtN=mZHR-Vjb-`33u!YsI1IHIjh_SU;!kOUc|U*BWOAuO|^cw$rG zV_mguzWbQ^>nqPAzR`Q-6^844>KCyvFSs6jVtuH~O+_D< z`xHizxp+L8A|pC1-yG^~z;3r(Cvz>VAPn37nNq~>hydhW%b1C+vkRb+J2SrH5379F zmx^{`5fpzYTYWUi^W#2kEUuvyV}L0a1`Uw^fH&r20tF2*6BT>+p93eObT3B&Kxqq+ zR98`}2yoz!FjSf9llo2<*gU^*Yr#dnbm+Ns__-1#YLEo75Y#FYMJt`EvS*K}Pfte& zm!%EW&jGoY*o&@m9M*vYkh?j&3&Usw{^6B<@MSWa{Z{9;H7?d0o0NHzEaRiE?TPKR z%h@HkAr`3`tH(a8?04`37)$!;R|hr<)%2Z2`aRmDtxB=AfuP7~pWBKdv*ESMElE`S zTVQKMF`%ku+$h1^h=Y&sUK-6s12Fibl$jjB(zaQIK)%=6v*pXYfp3v+^xoOvO|N(h z8dYl>8@z7Y;f8$Bb-ukUQNLC9v#$y-pB*~1k}M@C57c&ebIkLV=2^1xbJC8-GlKmV zE8ikaOQN-#oS@`o@mf8m=6i4Vp6hlQH2I7`M1GxPD{RJo)LtyrB(R6sNhqKwLuf~- z+&>ky`w4{0FXSN9?GvBea%q^!DJ)Oo4!m7tlF(P5KWvTPnGMJcrFubbOLOsP_jSn}6Xm z+@fq1fV(oPtK%nd`fc^KYwvn$jb6-%E8^;Ns`dWdrPJ4n7PNc2BrP;KG0=ruFb;uq zt=#M8MeZof?Cg4tCg+be<0+UH%w8KiDmC|;Wr}U$*5!Y&IH0U!fV&MuQ!s2?*wQ|$>ah*!i%d%)_;2Uxi7NJbWQA_a!$3I+>Is&?z% z?N8i^^(-sP%MER9!@c|f(sH1F`widB`voL;YF2E+j%98JaivF*qkp2n@qyqYAX0!D1o zzyIDYNRZk0%&M2=lcaZ!U!>E^U^g@>e4X(Vz{U3`h@?j_=+U+=a>h%sa`)lCwaZsHIWNN$65OooIdk!IC$F$!BeX zc#r$48z*3EFAjo6O-cff2a8o1%En}hsLP#RMpX^nEibQ-H25=Veoz0am-hChUu0E} z#Q3X?BI#p|TO^<@#UMcs4TU%0q2WJjeI_RUPyk%>;%Fw#q3lmVFR zanWAWVO*`JB7+77+(85M9-VqVicoZ6-#PgxRV_JW>UH<8Q&CKm}UfgFh`QZy8Qz$f&bVpCsVa-mkMP)WQ5JD#?m^}Gh-1t9P*f)OaWbBZYo zZjkud3LhdAD7xdA@IiL${CbYTM;4iZk&z(aKH4y6N^`L_Bk+w_!9+>>j9P))Ms=JZ zHk3@UZ~(mDfdE(S&-jS@m{pZ^+gJC>cF9dTxq-xuq$t`f`;GcYp=o)aE5a#uDhsu-wE$+HcjlqTQo%j; zd5O^Y%QowqB?$O`V*OLBd#7v>Kke4G3PT~0`S9(DH-k!Sa783E3?aRp%~GYhkTUSQ zw?8lGj?qawnDzeR1*6v@XfV@Pq`@{Zu-$0l?7dRsK!~WTzQH@0nms zL?3Fw?0A)zm)F?Eg?MIWruBm)Dn1@qp-_z0&%wbZK>1`%(PCFX4j6uTQO{_zwJd3| z3D`UA&9Mlae3X@=pw$3BrkG`OPgo3$8=Q4nZ+g;3o@#cPM3cU;9ahj#PP&@=^aw>n z1N%l@-{TRffer9b0fRON%4z`0VQeTOf1zgNq-t_kYY2#G&$WDKG%wE}IcB5`O0)qePXGGm z8bQ#ojUw&hL>1!N4iFLPe#oH?jc6(_Zp_OFZ_ZP1pLCky(aAN{?mjeHY-{>G2@ZDP z*-VZ{cdDi`<|GG&Hth?-d}XlfJRIf;)7sZ4vh6zW019i+2Kn!PxV=Qf;f$%Rtwpu6 zRDv$K9!W80-GVtkLlGO!u!SNoU$J-u7belRUh@v0t(lBzum<5Bo2fwPIOjArWr7%p|yG@R$qOWOf}V zQM26K6PTA?ep^eW4P!s|8>CfnvHh$FDsiE*dplx7GK!D z54zoH-?IpK2l`@>lw@ZQksgb0z}|m;_h#pw z*(jhCJRzf?Xo_tZ28VWtcKHcjP$`Hse|UAZdJDI0SjcMUD5y)0Q?Q?^1ma#ilp7F5 zd^Kvm3q-Y(ZdzI#-1e#~%@m(Be}5$T=kt&jI_VmwVOCr-*SVqe{=D9cFpK^mE`CmJ zV}Z9Z?7(}%99r{psYKSMvd+(dY}A;i75`+4hl8-pv+d`x>dcG_>885D@;3E&Xs@XJ zE|Jpf&3?ZPcj@2Nf7?pGwJJ@iy{j#vKgzc#-%%Kql4k7*X($;d36E5I{k=3sau%p< zfvr#R)Pn;0r2%Rur3$0ZM`@E%Lfx5pXpKWANU`!{^>;c??y>E zj<#A91=8fa0C?y5Ybx$O79}>a+6g7UtsepJ%8mQ2kHwI_L#&Q1+amK>Ym3nyE9#Wm z6->+DQfCLe{A#uC6$vZF$pr`ByE}T>8QSnmjW@Gym~$u^_gkHC=y=c=)wrEz;pv}0 zXw-gZp!MoIaO@lt(xo2;A6=N z&y=(ABt{Yu`TG0z)cn-7d;c9Pen4SWy9TP1?x&x){S^9p!<7ON6E;^FvW*Fit$oMm zDBxMZT(NtGrJZW*={8>S3iz#oVMn4SgI%Tgp#FU2VR?n?oc+zpJ*k0M^JO@R?Tp** z7HMP0m$W7(sy9kXHQF-V>H&2@bj<1l<`*BI#Fjt?ocDb|#z2f#>3M4_xBZrO<0XN< zFC#uSS@!WI;`Va-B7l{X zv{n7m*3w%xIa!53kPZzkl2I^KoWab}a&kzOggCS&Kyb4uku9@krgu{9bB(VLl_ zeHX|N!1c=u;WZ`r_=zoA;-4-J{f^sWLUm}2jX?ckLSkZAY5^NWtFb48nQ;-A&)zJH zZFG7Mq?nP?b)V)aC36W2jM&_nw7)#vbuV~YGc%hU=oXPo_@U>-25$B6!Gq}OT`w{% zFD?J0N7UDnT6d3KIWIocmmf8_F9`1ciMZ@5lr=v}8mdh}OBI}a)7-m1Ab-(yAW*S3 zFXA&z#2CJ0nEe2_ScUaoL zHNZMCzjb1Q>M!Mc&D-HbyzhbE+xw?2LZih%i|wk`<$hc|`pxyM^1@OlAAT5XTK0>) z^@Z~Zi&R!^3BdhBd(E5J8jH9x)7#hZRptRF)!JH0lsyfw!on8pX}|peRa*bUwJWMh zYYBTjyV;p2%h?hVCdkgo3BI@vV{gzbryFjPz2Xs^#cBEVc9W03E=ab%hHyW~E%L1p z%3=7Ija`94I!?eqtKS0>33>n&;t6a%=oi@6ZczZI7cyw;O0C_Onk;vdW@|67Yx z3PJp2Ex+JNSBTOokh z1L|XNmil5cg(8ZAECCYM&yME)ZDHN*9r_`k0{+39#rutz_unfDax% zKwaB`>ejgAy?h9N7E>+#)&0S!0KGzj`4}<~>%T+8n~tSsMMXSn&jW2Tm%;DydP>i6 zpCY#K>CR@ZD@pUSY6ewm?<`MHs}FK5(z;aC=$N-|I>p<4s9H$#nxCAA(ySM~(l4rL zvaWe3?K@!2qFv@Yt(Z7jF*n-X9W^>1uh^&*sCj|(vbpDXnE32hmOYc}a#2cF5d|NM zFK|LxPnvOb??R2ojQhfC-G6E-B)9OwH?RQrv))#8s5n@|z4bx(fAF?26i**K#kh&~kstKd0)0wVo~? zi{$f=E)w`jGCzT@PPBGp#tw4*uB;>hNxA=oQ7uVb+5!I}>LumbC1p$dxAJf_oA`gr z={D9kCcssyc36q{!De}-?_N9ZD7M45uRllar<=6upSt5N3TwqtiZQT3|7?M9VTODf zbsmn`v}bq}(~DyYmONf$5qyv-1$Oq@`TI=Q4Q{x6tE66IbU*GJdkQ>2!@i4)Q5@sF z8iY01Cxi=S=>5_lc~-%6af95wrVeOK%U)9uNfcxJKKYm@qOXcbL36hXXs$WgWiJ~e zIBoR30&-IWy#j{J-qmISKXN;$ri7uG;J326+I=C~ziG|KN^Mp`_+vDT4C&UMFzX3nbm05wVV4>=8~ZvR^2P+1?d zm&nsE>J9RZ8eyobz2E*cm`;x0VGd2?YEJ^R9{F4R-$(!aaR)iBLuZ}Je)_am|5ede z1TL-yuU3$_z*X$+!5heaOJE~9VDF*BiObIO9@UZyZ8GK71ZO= z{=%eYgiSA3>OKy8m$CZR2{+5KndeRXV=#a36G8+6Z=^+twAmJN#_0D;HaS9+sv4*U zRiq4Jf?Qb@X2F(o5qu2k(GD|;$m>XgHL*yAZ47cY=H7=J6&y_F-3uE@8yicw%Sys1 z);$?315tmzxi3$EQLh*^^3K)F4C|e|xEEu@mN>~9*Ee5d=w#9FSG;2lz|LUO464z5 z!q#sf{o;G$Qk$G<6M63|PtD7OeVVkfr&lfp;6O4wGV+W%Dt1Pdt`Yz&;PbzKO7>5Z zzSgpx721WMY@NB;twocQ8c$}&LXV^6ZI14nqzN_w;!xA?d*ieJRXmn>QcVi@6m%S+JZ8dY& zE>J<11{gAhP*mSl)RarqIiY zA1(T;#+daw76R`A-}D~i)#>fc2df&-owc>sz|V2Bv+MV<=)*M|{pYUS=qUyU#`AUU(HnyG&uH&Xs>kv2*-w-Xkxl+=?2_!>SnByT5=!pT&dixuq_OVF>Z9J3ajE@hvtf=`{Q{|N^PIc5 zPNmfNM4(4P<>-gQ#tZX>Bz5sy13Svvq^($JB*L%amHRK>h>h~e3q}x@*lQZl+G>$@ zAUQh)t;LgxqBc|NmxF6$k)@MxY}F*X>P#E=D);;5t2s^-IqG?)KR(q614SB)*TTc2 zalBb5pC*;IWiKCsib}F6PPC^fC4tcUP~b$_YQ_7hj@HD{oFK27xKdWl4k%{kd4S}}m;xC>*OT=4mJLM@oF^g|6@u(R39g{{HAXX2$h*l~_b{s&CZ$GM^~dY9uw~+Q&=E{(tF&6+Wu$7A)ECM z{NC@M?#(w3JAwJn|6k(=#y?=91n`SpEweW_H>F2l5qPs;k<)@zp^`xo4&?s%-XdXV z3M^8|A6qWp$F{#zW=)SQ4@RDEKwwtZ*KGmF>aK&oUFOk6$xa~4D8X%eai1S}28w}q z6AWNrAy{3PG~ZmU^wDwFRoL)oc^oE=n>=hGdW2cxbjDn8F_i37xkrj zuvD!By7L*2>xi?p<|vNqzE`{qye8g;LY0_Rb3-M{CORX$wxPC-qigE65zyA`y%)p5 z8w9wmDhwk=ASZI;)A84Xr}m|t7LLz6(9eC4-$&T1KmTknZ#Ag*8uH8ZZKt@SyL($P zs6MMId6k@!(l(GO^Y2hdOciv0yJ*Di0>+Q8z{sDty&XK4Tw0$@OYZ{7mY8pS;K~ZK z3A=xIJvX<;!eyH=moaDc%Nq>aL;lI6FM-Oc5|@2z!k@0ximFigR5gbJT(eod-a6Xa zulh4#Kcudwa&d75fbJ3K?MY_Dz~UGsz>#v)oS;@JB6>;i z-$LdLztp5R^og?pK8npw0 z@1Y}3vEa*OE_Y)8rv>2l5~(%vZD)Q`u(_4J`EGP(&Tm)QI=`ia?~dG*A?ftC$9Bo9AiMgM1V)^pDo-@W=t1(ZN`fMUDPJzHhRI zetyXJiUz_8T(zT>e&NnIYq8x*@yC6~gW89{6^-iIggZfoTgewWVQBraIv~;~eA(>I z)ZK9U>rmTYrX6tLAhkv3bsX2gA91Biz3)S%lcA$RnJ?x0n|k0i@%(GD0Yl=5O^R=@ zGOV|xp0fVp59Vw|a2Z*Q%+2nuzou9>q)-?n{JTBSM+t;<3jDnj2NA0S&8dg-^WfX}(oJR}7*9bxN0x ziL`eEAgjS{tl1HfIi8NwAXFBd9{y{04583MI{o7KO&N**#z}u<_MC)Q&8Hvny$H$Q zE>+h%U7ugQ51H%bIsElzYjgx!y`9wWJuqX_*impb6H>5acD*$h%=N2#E@o4Y!G!y; z1+1vq9lBtYMK<$NmRJbA=L{UGGNRKO=7xERNV2b;#8ejp|ICemavc37i^!d=j3SCs zY-*gKzW~K((jFOK@GE1*QmUb9W5uS@pc-ANU&gQvG{0WJxpgMP-o%i3yW(n#v_E4$W zltm3tDcGx~#h=GN_8;v$FCM8*7++s!h)lVwA8jIqIOA! zz5VMa&X*Vb-%?2(5nDgEbG(~&$M^G9Lbvn%Vm3k>&Dv z#qT1BaGsCk&dt<^OI*l7$7~E0unI_|Q;Dau{DN~2yA-tiUUq~679e;De|!CKvR+J4 zzhJRZgFLX*+-R-2TlV4h##j_YdJ3`W{zgNKX*K-ct-^;epqbCjm$onui{IHjDPcNF zcoW<@QZi$c;gZ+O{01?9dU00olmFW>b;4DL?q#dOx28}(`)mZXju`gjySly#ydNtsAat{FVmvpcR=fh94dD1qAVxRqaYcHpHsXo z{*ae+W0MSYMHQxOYqKR*M85hoP_3l1rKF@JNb7cddb$X%1ih7x6+;%k6t4*Ww8Q?E z#nx|I3*k07%kv-n<)RX-S+?gr`(l zL1br?U6((P7JWUbm^f}H%E!97tsCZ!^t>k%NyVv)KX>j!W5>!8Drf))!VDPKlbFqAVz2d~jh_(xP3^o?1?!_Wib?w?PxL_A zwSsJxc*k;6hq**995*c;JvR?s94jjQtC=D6q3jF)Rw)`-7cHTdnA!+V)BLM|Mkntm zfHYCB5RQF>TDZI0TljTP#RSJ;rE2DUDOcxf~)ou%PG zSoQR&-`O)TNP9*Eo0LN7_I$u+@6pgcW|oizyxsD;p}f51J#~Rec$btU%kepjD;Hr* z1xvNoAnyVY+0a|P;^8r}vg%Y%2n6yQ7%WQ7HoScig&#p7w^0p0Gcz;V$IebUI>P&? zAV8o6Yy%<`wYo=^+v!(IaOjeI8A!H_dexKWeyw$JcblyCG(Da-Eeqr`dDgkF2ruOv zV)q6+*d1xVl1bd}{H1Jc;_-YToqyw}pk&rd-UVd|}qkl*#@ZILO}i^EXR z$)mL$av%G&T1JW+#!Fbi!~_`L<`l3X2D1BO^}XcyKEyZ;t?ZhwEJ*8{M6a{4u*7MT z8dmdaxBrSyOl)px!31GCDnOD1b~Y$M8rVq!sr6^GY5=dni~3)KrunBUl9yT?i)A!N z8Zb$BhjMkHzjKcTALb=5GTkpKFsrjw%{f3;*{9Ac5Gi}KRT7-tJLVax)!5z{bXyRZ zJ1%R*&G*XY2=JJ5xJZZxF}N<50+J-Z!w*bdv!JcZHOYcPj}wvoi-qxi+it?)T`}Nj zP^XJ;@~JUkq$nnfeIOw;YgfLS)I98S3d2!F?r`>9qn_WRH^3_-%{j26A^%yjyFz*457%o zJ8wv)*2t6;mC_zR$-Q>@Lj+8TN&8bF!l9|xIjLfOogL4DAqSd0Y{pDHL0DGkAWNKk z)4~=uVguTi=k^~!e?W%n5+BbM6g|!wrMH-K8ms|*?Amj2sKQdJ;_|2OqMbR=fkVtpR9MXKx zk=g#RO#Rr#N6VRwHGliRNB&^H19k-W(ArI81+^X(1u@Vo!CIAFU2udrb9xpkD6NoI z-;a`9Qg_Us9&I|$Jb?N1Yp=^F+2IgJXS#pD2dFEM8cyPixH)ED3?jXe8mljRhY51X zyl4sDycR(be^N!ZD!VsC}W-gu*jm}FUM>0A3dxBEa2r`xCB)>MPVl5g-@Fo`Xuv)dw0O>@_R z_5lKLO%h6cD|8{7b{-gAGmtx3i870Sc2< zptwNxIY)P0*y?moAJxnTI5Y|!N4{1V>#4P(uVW_+*OkQmZ*tYQSrphJOO!*-{a5}0Zw3j$bY>aIk+R)NfM?)y}h2Did^3ep>Hx{X#`IMIlDz)sJrJO% zo#1jO{X>WbQPlH{~LHm)Er4 zb=FW{pGES|MAw8d$N)o`ogUI}aeRXHhoEHqzKvdO?xD#H%hEDc<-hw!GxbJsw0{=l zXttlqM@{9sv%aX32&p?dTO@0k8FdcfzSZoeRfQ`H*ggC8x&7E-Gof%r$_O#%c3XzA z+0DAmUt~aCK;0})5B-V%{;u}*du5f%sj7mS+(l32eHUlj)ANm!YrRerXqKman%0Gz zi;JO$2k7UkBn^azGuZt{24kgM3<*9Y5r>rjC5k-SFjIF>AM4F6RMNtpYPIqYt)%In zqWC^~(luMr!f3p%AaY1-S)h4W$d}b)xS!p%BylXFfN$Xw(bF{0YvIk~VfSH`$V~=D z98)@GTwt~}nXK*Zvg06za&jD3Lb-o?Y|y@|CN4c^S*i z<;OOed^0l!rHj?63FHu2}&i%p`f={TI9i148U?x^)%YOS52u-g8bJpKDqg`WPyyb?G&K+ z9u|E`jOTCcwx<9MprnLzWLoMY6!NW(B?RY=@mOwBnXhuxA(cJJ-o+hzNHpY(h{eYw$F-S96}7mt z7@?zX3j)14#wBX&I^z z+}nkg*iDmXzbarlT*!y_uoO#@Z*3X zR7%lExII)Zb(VoaX~BFZqGe0Ik^S11=R~L0(PflLDMSKZ@?m}6<%%)I<1sFrFc;H( zn`Qj|z+BL2G-v{WCPXdJ+cR_V>ShbRR7#{NHCtKv5DZgbnitYQ@pK#3ApIAUQN5%| zj#EKF#f*`%K$nG0c3b-ZN1l^8CgE{$C|TC(!h}M%ds*%#oa9RL(ho>l&CAL_*5|m3d#XP?$QRe7vFD zf@NE1wB)PiS(j6JOYi^3)|*E|-T!~wD5YfIiKHY9l6_a%i4ewEMr3D%>JIPkI$-Wb^Z`m2!{nqvU-RJ(}K4-3TuIoD2xjJWjeBSTZ^Ywf_o;#6Zh^F0L zg`cHT9`3&r8*e`5AqJbTH=w$AW+&6B{nsx#UULD_CHtAS<7i#ej;?`n@I--KYTm-T zoQe2dSqFyyzU5C@Go^=?!}!EuqPS`Fb{9W{#V|sW&po-GT#4T=yY!~`3t8oLRPI-Jpszs5j)Mu=>^piy;NKbrr8G!eTiq$Hze-ik$e{hh!qnqwIuZ;P<-tS}~QF(&^`m=}@XVSxGAu1CtFC3uZn5VF7 z(w#8j%|BrKUEmx23Ojy_owxJhM%5hoN|kEgZA8Z4mfykJG64a2VEoeby?o((;c!0a z0tYOW)bN5e2u9s%#~k0onfF`io4)Njh81Qe=cNzDL{dJE8H$Or2#rRUkbHA!xbn}M z8bhgFOg+-*??38c=d4Xy-()J`X~gs+ehV`2t05bZ>V7&L-IziTf;@L5f9^Qi4BU+H&QiI|ukZ2&~1fdcI-d7l_=Dn)lEjd$UiJ^U}-= zm{+?_SMJ#zq+9)3{aA-4Pgmll$lmVn(e)pmnCLPlw`|O>PFo0NIH;R$fd}|aJaA?8 z`V`gMN>j9(W?ay_+Gw?t%j%@}(y|(((x@lfY1`Ou#+|6ml*T58M);OJzDLvY{V^>m zsWz~rG?`KU|G82SRWm{)L9rpN^naE8cNJB1zTQ6ru6+XepB$p44mxc@8o4@ot<#{^ z^R{`ph+&ve5YFXAP(Kyyj$Fd|JDiMNUxeml^lS#8*(m&hRB z8(BuL#GipxV46SB3{wJ|>AsVvs0QJ#Fm*)8XW(}R29c3k4}tG9ue8%7T^BUAGA{DI zg3{7m4tt&E>1ekMQ@PUEyne>k1(A=z38}9VURSK(`uHKsSBVHswt)BOmjCg$=~@5t z75}-Z^Vb4-vMJvktmqT_5?^uqUAquCJLedGMt(X~~W%=lA)hIaE8X6jAx7wq~W;)?#lCeLTRbm6dLP+kke`;1-Mp!uT^XJdA;(n8E ztRvV}Az)h(7KYrR|Jd0A=e3Vnab@#a6YR!bx}#D+#BU zJ2&TCDA_hKT=ktl5LUOVKX7cs>0bLz^iN@HkjI53xZiBDsboDeSrz9C*W8XK=7L0q zQ2xBbDsuukBbuKV6VkRSHO-!%cR!KMI92B5oA+x)IT>=l?>)64F0u}u+R)`KsVFk_ zLNB}+;+RA*)ybPs$naX!E|~~$ZIbSlN6ah6%uCAdk65(MMWDsgDgC|n{mTn72N7PB zW6v8fGkA+RX~7p&08Yw{r|#}M z*c*n6MOYUo*)IElP!U5bJSBG%?AHK4;PSVcR!%DY0s08o@)y3|iV0%-&nJ-~R4a3a zMHGX}BTdDgz`-K%)ZVDv7S+n{5_!$kFk)p3ETvs4srC0SnXjuus6d#VFm9SbZEM&; z&V`wa7=}vd)Q@&u@nwe13h-gT3?_iw3Qw_JA1S>Ay1+p7@m0_~eqIW8bn>#X%CfQV zZzgEdU>;TRIH;ds$LRIz=@?m^cGI3uTLfOv3N$q@x>UdC%kFUlheATSdL6vrwgpG% z<}ri+7DJ82EHFoU9?id~JK26vW_T@z1elEJFgIT|aCLr@J89OAh-R3OS#*(TF@HEX z#!&T8tbYfg@C)YjGI^Dy`_10M!CXf_lrY|!7(Y|Av4_RpKXJDeb&)8kHDF%s1uARr`X6PUqRnbc!%g8jz5}ne z8+jKAhwaCCZL9leTAp5XtXb^%my=0%b*dfH6iGczTfdQ$Rkb&QrC#<2@rfJq7QnJBG zPY4a9ciF?9*ugj+nyM3cnN11DryK(PUt=r!CPP^tYzKCD{RhIvjiY_;v z+9M|5>ykSC2d|I@a3=w^zBymEy>H`dg2wqH;*TV_R{%{izQyC~b&A_vPa`@kDd`yAf|)D5vwhK|E?HLJy-`-htbxgOR4 z;Lokg{rR{5yQ6e3S^|wPik0QDZvP-7Q}yNFVX4;hN%fYU^cor(@(FKPoYufKitILR z$LAW!NU6=W!5cCQL&lwvudEU2)}nkxHLLZ?rFC~=rMv56_4|I1A2+KrHoYjrUnJYu5%I<04}W zEc@P(cp{p3{&0_XsMQ{Q*4mD^lhbxhtffMD(5rt!TIzKBM@mD+UIsJQrXuffa3X3E z7|MkvrKH=8=EXlFgG(wf@sfpeCZmdmngR@uY}PFgj%IS6Ar^ezdT({ySgAP_ybL@J zS6};Ajy3L%b%cfQXxxL&PE}`HP|R+zr=()4!k^cAu-&@4uy8%g@#$0Q(h;JwrRatN z-ZOVMH|``xl4r_EDGh8*U7mh^x0qN<&FX1p&@ujPK z=l5@RpnYG|H(u;`I2Uy;?Y654>apUycqxI4 zK}3WxkL!-c2TPC@yZ1oWl%x}|7QaZ-*Kz)z7a%Lu8hc1;oSeGkRq8@L<{M=hmA^-B z#+egL_a7rL&D+-2kgGhbu|s&RxV1=hE0OMhldtlN(HDwR!5WAk=8n0W1KWish{e?w zgjx}+9|G2fzQTJ`<_GDU)C5n0SATv`Ngw`xH_=yKRy$xj@hWCT7*%@Szw#$Y?25o~ zp03RvLnDkxGA6+!?XPK8{CgJL!ea>v4;czcxZGK9qslz$`7SkQ{SUs>GZ5yABPH5CiZ1T3nlkr;qncS~%p8~Ic z;9pr&J2rINa`?)+w$D{rGUnt}O;Bk>E)-|-kv8B*{JCCYBG@$Rb751h<>W8>S{e@0 z&$>@MVo7I-Zr=(L@cryyK~4b#o?oE)8f@B^*{1vY-s1ca3>n@l3_q+$7hBEm*ZAmX zRqPW#t2msWUtszz2VaO`>lTXdy%{Sy{jjV|FV8-I!o4~2ezalaDz!V+KijGqnT4Bj zV*eJbdv@V1B)V?*-c#wF(zluPmG$3ndk3zgCt)-KTBh;MT1T}rj?Z@6E^Tl zlO??Ki$DgYQtaAy9;6}FGS7=QEs^$5$C^5Qa9Vz2koaHGaW5Ydb9vbH8r0j|_{-oY zB`Fy;RPVjvKiDY2hfkq$^$ZC{(mr1w2+#kqY*5)Pyk@G*=C=ONy8DN1cv#?`{bKC3Gbvp2h1~-35xA^_ z)eQQ+!79XNkJByPvu$55%1Lb|@vESk7vu=iN%gY)_Jr3WAt2~!8~dNqcXesR&6m4c zUlnz*Y5Seac zL+ETJMrlBBnfUA_*7TOZs-CK&T1O%6cz43|+7|LwBh-0Y(%upIY(aJQh)Dhclrq3J z3j<*|<58TpsrWnJ^v+sxGarHj@g}{Z7us+#()Q3k+dLuiF|Z zeD&V2tDagB{Y9M*Dv&{QA!T%X=VfjVJkhsqv1#-uzb1CnF0|GDYCiEod^}waHTS?v zd&-_5ZMuTT_bD$vdO6pr?*_h`ncdQn{|>bIaFK8*+HgQ)I1DQg&De;f|9}mg2Gc!e zE~E@?yW~hPnDPW<8-5Rb(KTMMM4&DHCP`uT_UNfD{ky|PnOVN#q@m(m5vPT0)kQ>U zYhH;Hd>H4oW17=vN5Ol<*cw(&-5B#e{x0sd;p#W;3s;rxFLBZ1yxLR;Ylk4i1M7@qnr$JLq0>DyjOpwX||TO$lOvw%Of?7>5UE3u5L@J>zvxUx`$k?H|}cY#xo|ZxK_-f3vXxL zu=mLTZIj~p_zu!k;#!ZP=x%t z3ttwm_VY#51>{SdQmN>9xJ>4hZo)mjuNYt^JsfdNtlwCh%S%a{Z8MZLaxLx0_)k1& z1DJT-|MdAA&Cb^HTN_lh^I(P0J}?lM>%OOc>Qw>^%kiDOA=Yz0I9*3*rvk@PU=V%? zkpw$^*lp^NPol7JvQ<$tcU$^iU)p6~=A&0^$dFie?7|YunZzoc9&)E30yP8v z?_ki!nXF5gEMgxrxs+$Dgf7Eu=hRwOggU!|8S=j<5Izc}OUyH^tfs2iHmujw4F7Fv z?m_kKOC1*JD&=1K(Od{8-2JC@XX^KxNqfiV?idqMgR#SJb8Ncd4W-Z-pA?Xj2>NcF z>tj9S*&y$w0q2^Oa+<7(PyG$GeQsAx=(iQ5n4~>qf?`cW+?pa{D5~>zV}DG0gjV3g zmn95pq^D6IPSBHkISjli!z|AWV1B6d+|^D;2gk)cV<}J+zoo?Z0{wC5GqBymzR+(K zioboso)ZvgED6@iKjvLY*aLEZQ$G}8`tgVfeDAt3+>imtQo>IMzjWD*s}dql&eYc2QtWmfacJe%wa3`TRsQbua>WVSNg6 zN=vCcru{0dG^Y1fhlN^qi4WWHub(VEYs;7R*f3UQtuQ~@4iPA1;7Y18bLVmAvG;w! z`?tzU2~n{ZsL@vpQo0&mwuS<{z2RaV%m-u34H|vJg<`fs^~n6<%57-&{-41_&wbSd zQ8Cx9`JbIhH4lP*`H~EV4?+bn?fI*6kqIiKU-caoEvl%7g-zbsrxv#^q;!9HdF`_U z$!d;U!N(O!V2d-yIY_>|d-qNe1;=9f9kU0@ak8YUv6M&R8zAka06ri# zfxU^7J-#5zzG`Q^`u}F@LRteB79RUfzq{%a-u_Y0&nl1oEcmemxcjx4`@+XgexN+= zaJoz5{{o@nB#x7!-Xda(FK*8q8>pY3zh@v*x!b&lQTR`W^bANXKAF&L=10^9nReH9 zcy46uJehv*xGIvnwXoF}c-VmAe5G0O?i6%AA2mOkAC!pWma8P?MY}<}r-b6fCo|JX zSZ^2HIKiXM*L9I4A50>b_DCCRJch~{|L3>pe!0AQHN1TAhWdmVGmJjn-TW}t70?fW zfLQDUTKkB*{m}I2d3_juXn5EHn1K&d^^M^}qLtp=yu@xSG&8@n=zmykMDMCGyUw}( z$lo4e90}QjMz6?=%<9|}=p_zk1+k+p~OvKX_42* z13i)eg5`fe8TyriulvBl(+Z?F!nj&5@}RPUGx0nj3LB-nNF(dJ?Im5hlM!59_Krb; zr`a#|Vd#A~quT#~G9_vyynlKj4{dJzcNhF>PE;PZ_2w$uH@|~PYaSEcUwv+N+a*H` zMMWW8NIN0HFKFXkd`wmGLcyQ?vK54#NEve=L};UxNAPAK&9Y=^(ro2%i_^TeIVU+b zvxHf06y52}fk%w?y){A{-8A(rEn!^4E}`C=9P}u?%}(B#a96fhV$Yf3D(x5eAS%cr zmH1nkDlSCJ%2;}5g9Wn8G%1IuTEhBhCASua+Yh<)^}$U|m8|$LK?q`uFQ?u~)lNkz zLMWe@6p({p*4g3tk%jS~UI_8&)W^-4E*k3+P%8he{havHqnA6QZ?R7QxIWKigM|B% zB70_aepB-snDA5i@6FECM1B-Z0%3;#?(ELT>y>j|$wIBuU11G&01e^Mu)_)hLfIN~ zR{sewSv6i$<@uDW20y=lr}MzA95x`EyN=@q8Ef?W&1Ez(wTGA~b4TsaT2&}`R33A8_f-K3Q?0m#D65pf-HNYn z&5sA14zM-S?#CE-#%DxAvwf%e5Sf`(|LgM18crMDol>6QtpE=;%>$1j*&bKI@T*9l zhLqMN!z=?iOlG}1#BZ}^Ro(OK$eLiuXo32K1CJ-`j!7aT@@K;yo^| zaN8=rG#_r?)p>w%;2i?5KD1wv`CS!e6AOX4TNqC2@@s#rT%d`D@4+K&KMW`JGF9TU z(+1xC$mj3IDW;=}-|!QBJL1C4t&DJ zw<@!IEU14M%E9Dvz3xSZ)z1NzEHNf@EP_UNAneUPc+m4bk{TDp=$m ztMT<71hXK%0h6O}D?|?VvIe*wzT4^9Dz#{{*(;9BX>VY!Q}h~CI7&cHM>cUOofe7O z*ylleO?w3tgBDM0E}4I3YlphYJqDGRrwoA5i{V*A>%-xT?f)TFN zFdyz!rE&C+K3O84|DItU65e+*(bwLN{%nIWqoYAd!_`~9zqWkq(rC9*UfMm)NKb3= zb~IchM*4IACCb1x4PNPVRe*w|6;xomHFCA;e|Qq(?H$xOTt}dizSYxg5B7W|?{4Ms z`_TrwTwmedi=T9J^RD8HPur7HsZEZ&&oR%!ne%VLCdOo_Wy|VCd)|-gj_D2wG7q_u z6>>YcfL2kr?%L|=&>iHHo0+GnI3j{PEv>oS^Eu9o7xOmYSU-|XR06Oga~CS!YC6bb zf?!PMH;ug;3#*G%5m%lj;`qHC+xj*-cD$g&<~&maT?R$>^vKlSDY1@pbPc$}Y*6m^A; zUfve+av()KNq_#n8=Fei5nOWnE8+N8hbQ-GAG@iG$Q}i0aeU>|uQ(wNaMem{uIB2w z9j{I|d$JI#ve++Ak_1m~*KofgBqF5JLbEhA?O0vUGjqmiIZ(3**kP|`Tdo1ibRtRP zN-0j|a1wZ|0n4kW&Q@)Cfr;R36=+Dv!{%Gh+7F%lR*eo<8_x*cH#fe4axt|)_`|ES zRJsXfZX5YM%{@2!esB!&YrgMu8DpWuh-ki%{m? z^{U%0jTIB%X-YA?M)e5+pzUcAu6cjNrkwq*p@&fM0W7B-0=U@aP}_mK_P>&xTDY<@ zzk$Ex*K1%7lVx;~Zjl9zpV^EyM&9CCRyuoFy?sfZM3Y@$4k^jaR87CDxf8pXw!OAu zCha3i5QA87e|_$fk@21|8wo^!K+t9ZuSlns8fs7~{x2KbWC(5-&zQ*x@6#dUhk%Lj zpWwPBo`J}SA0aa`k1HNZ>+Gt*0SXIP_EhWD&KRNHo|FIkGT-V2vXIKv8GmC+Uvx)* zAG8a#=AsW9ob*AkPsG%|i(z4xk(81m{3aIOYflLCUp(si3cDgE=uPfrBFk3g_mp^H z##v?!iaD;%w8uuKKdhx%9m6?xT#xpu%n14c)^E>y4}L$wn?I0e@EZ*85~shS>DPu153M2< zQ9b&`WJcX$GMP&EsUAzyDJxrCmG#-PE=5dAI^YLDXF%`UXOO_cg~Br7HqFSHLyLCj ztv`w&Dzj|N4AL@j@b9k?%r5Z}t%Zt^K}hxNM)DA-$jaF^G|x{r4Ei68CRuG9oof9% zY)O4WdfLrEAo#tOg_Tv-8Wj82NH1PVJguDXL^5dlhHJ$_I%HlrrM#@c;(ov2xU5y= zy~{lu|I)+1Z(xWauo}(UXQI09f}R+%7PtN2!GR4^qu2OezQT`HCIY5@gN2=c1{dg! zBNI#2ZEHuos`}l9*rX{oZy^2j#ZCAVo|>3eLov@IGH#nXDpkx`DmyN-L}nc({sJ!R z{7hN9u|5O7%j0x@s^0nva7>VDKD20$I?jCXds2v|LID0`Q7$?Wj$|Szab47`+wR~^ zDDv~Fo?3{Brm`Bt6^<5t6;Nf ztyvw8XO$Bb4z|#`**x-#5fp`gD1Z32i5>XL0PH#8tvUcKCPjDY2EiLE6Juq3_J4z} z`TIwjw#hf6+ttnOczetDEw8!CE5Hdf=I*QNt}l$*`NHKK&F7OblO76~A>`BGLpGd983HPouQWnk!3e#9u#i5&x^D3*0Zu zeM>$)F@4K~qW(2>#d<%bmtC-OciV~%AAzsdm((;?uRr^lk~tiH8@6sM%9c1fZ5XIh zWdGCK3F>vPOxnJCDiskKs)SQd5FO@44SN5=$C?@n{eS1t8&^tSTq<$4Sbkgb5BPTe zmqJ-kNEhlr{?A(TO!p&b+YL=s`woUOBV%-w0>=e}Lo`*9Cq9cG1}J;B3Dsaq1;y-D z07U+4a?*s>pXMKV;=k}OFvDojmFuHa3M-z?5tgpZD*|s@_EA|{JIZm*tn!A^Y;FxJ z(5``fCG0$e@?^VHfMGLH`IcXWXXA&RZsV&7J{_9U1_{E@PSh}R#r_G+?a1xXQVV56 ziSDpu#6dsE|93y^xW*)+Cvw@I}8-2{9Y*KPkUCnoIBh z=CKdYrWE#23areUnjV39mE$IPVmgN2|CZOEnAm9$`3G~h^Cdba<-NA21Q&;~l*d#U zP(6Y63B6&1;Ey;^+e(Z$04zN)?RU=q4HB3LlslV~yI*>kTc60%dMtvEI+1fEZ^1|9 zy4_UObwUnKOss_+cCOabRO#HZY=GI{^PZN_7JcLKpXm7@)JUodz0f~8YU`C{Zf%{E z&gw5rYQtr6Hd-BASKJt*SQUd!m=rCwADy%2)xRSa60kLkhlL&)+M@UOExe+(OFE3! z*HtX|hP<%feCkT657a+7HreG)dVUody<9a`6u&OpygPOxlv&LLZ1;IK%cQ@G{9ji8 zO@y99LzhXRu1~)N=lfXeUyz+A{LfDZrafWfWi|E0U8JfgLf$QNFDRvcnIbj=WhmwB z7daMKA+_ope*+`lW;OnH=&NRhwU3X~{^VDR?Yf8rl+iEbQ>m=(`FmN7Qm0ZU_)xgT z?tsl!ZSDlMteXF2m2Y4%0Ro>N0=#V5mdAvNdIPK)ti}ez?5$)-U)A#eSZ~?qv@yI` zy}khYtOG=(j27%H|5?@VU!2###{Lm2ARoPH?}7M!eA>mkc@f?R(2@X)850}VSCtFX z=obZ-r*0d|Ux4ziSaDrZ(;f^Zeq4F=8P_b{J5(332gaPjYVy_A>rMHPsl1|gF8yYZA%A(o@4_X>A>ap&B%#N zf&+iC-*Is%<4}ZWFjl9y>0B1NV=AdfZvI(JLc&mEy71V%_JgliXibHvE>fAMG|in9 zyq>fT4Bi8H_C5Kd<%}6;vIt}Po$vOa$JEZ;Ei@`CD?wkzEijeW*hVx+gbklBt{(nA zyqeV6bvs!d$T7E>R5)m_-=@57CQ%uo@PJT)>kcDn0!gDLwn)E56S4H{dgK3kC&L;` zuQ$T}ljN|FPL1zQP0hi9!=_S33kyde1p`vd7T`PftQ+fg{kKX}D%U_+M*WHZWm}Q( zMej=a`o@stzMa4I?wx;Uw*7UvHQ61W28O0Di8iI|wiHFk88`pZccZKDpKf~l=W508 z=_b;?`J58X>zL-NAC2VckCfA22O)hzeV;;ApL^vw^Dx5;vs{+GKTm?zTL($Weo zS-KnVaLq2zBwS1eik2tb(eJLqyfNQK^To#hGkmgB-Y2QOc%xV+-hOYXGD!XBlLmHwPq%)M z(Q$(vaH4J}Yoq|~MCht|ly=*}Q>u@~w4zW@qGg+biP${GV)o3vy^USV4S4hz58mj2 zwVBu0B?{?)#SEV)Z*+g^i*>}18!2Y7PJgO%Xbf+_`R~~NEon+&qxtvO6N(vdPZD$^ z@9u`+zHWJIJByfGKKwI$R?H<#IMps)@fZkK;8x@}H`|LDp5j9f`SaDw-;{8<3Z=N0O0)!L>;A8xxo^Sb_yQvLsV0sMCRDp!?85TmCMoh^`J ztxznR7A(X}PDdIu9e=I|hO6-J7`8>t^kzA^Go0t~?zjz!2mt|oc{o9U8_Vzu2lpF5 zUe`ghL$72%GCIiYt%gj|5j61c{M<8l+d)sU=PGQ9)eGuroy583Mv^JqL7j<%L)XAWj~dcjzY=(q2Sm8tWMQ_R^-URzTSWfs;3i}i zU!Fj3SOoik&J`^bu1hjT$6xD)tsL0Tr%(^U{D^yIt(^mdQ&XWoTnA849qCt3gcpdT zojX@caiROKSK0P-;h$c-zQr6rttKT|$`m}jCtQe$$rX6Sho5rAiEWKoP+*vQhaGtg z*XBd}i;KOkS*krk0POdLg_O%3Q-dv5lB=sWQinD<|piLYK|jEmSECMfn7J{=;T z`nkNk|3RZ#t6lxTP;cGm_)c7Ss#UMOhZOEgeZxwNn~ud-xfuHz<_&>_{k-AeW2p8vBREC5vd8g|Qt)jI4f# znJ~TQskHWY3(eI$bsJ{Ly6wKCT~PF|<_^D^=kVWdn~e2W8RIi^SqCi#cXGZHt^2|x zJWVj*@jcJ1_n?THlf>0!CTEadVSkXLLd5fQS;@&t7+uB0_hEFN1-G%IBbWM)XnrE*d)byjEgFG_44_jCn1pL$;&bznp` z-U?^9q@M8nEM(S6)ab}{{`#vuo(D1}3hW=0EG(G0wAeW5{fQsR-={6S-dJr+UJBLN z$(Wj&k~l{=I<^8A>)!!gtrr0B;o33{aP1&z2I7jeV9}DG0O`edBK{10bZKF%f-U7@ zi;BAYHY5862lY;$gk|JnnFuxT$U6u2xkfy3>9T$>gA+PTf1$Drl`7_DE>7P^OPIN} z#%;9(FoVwJ*M?kI$!FObvpDwNL04t)0){wW7f~UjR)7LeH0?cvq(&tPz;n1~qD9u#+Ir<7g{0-*Wa*Tcz)% z`{{UpzYwNNGfn(+6?sB2ab)qF7Wn)7XDjnX8Nwm3cSZ!R;%PNX%a=du=BLD=nbu0a z{jJF@f@)fUOe%k5mE6n8w{17D$PQf3iETBxON~Z%+py)Nh&SK9L~TKS)ufeKE?hE5 zA6W#Ik#ZC?AzhElVI5(WirhW$?ZV!|dTW;zPE>6H$j=6Mb3#Lwk2OIs+HdmfE|yoe zXmI3H#Va1xyF&{rctt6Rxvy z^_l*zHT7)~zx8h>@~+}H7ao)~+3A8OuM#Gsv) zDUOBACgF{)-|!c2S9=I`E9adoePw0kyU-NWoH}koCLEDrQOXF4L1bvd6`y{F`YM&)XHO-= zIq#rf|3z(2%t(CSd`E!*Ea>)vS}!Zx$glRp{EE@q2$q&5za6_G!d8*8QQr@3_lDHu z-aA$ibj`eyem8a5VlXyp|FV_d2P{v@z+B*3o(Lxcm(%0b0c)9O(We9V>mn*%3_cz} z{Rr~q>KIn@y~n)yny7Z#fYxc~nHhh1Ypi6ECsixH_Ail>pfT9gcT16=;CiE$^p-gC@4MT9 zkH6iCZUGFrziB>rJif&LoYKlFp#9cnGdN*HiQaH<#1Ltpr7P4lOaqw>jC^}eTIKrR zIPOll5X=?F3}zVFPrtfp{hR2)`{u2??oPX2O*J~G8w2-j>wg;Y`a|X?pVpNTl)3zE z;`Q3)aTiz^%)kuZL)RGzCqbyLWd7FGO1b^9^LNa*Hk zwTT_IX^YJ)HHR8&@iQ%yrk3jx(hOG@1j4z{eySL4Ua8nc#&uU0DtOVk<46f1_@xwnxsD37StlhJb@(dT$YXd# zor#h0+u7;W66ZO6@aCqLw`66n@ktO8(mlGgRO^*DFKf67OBu?8tsVkQ{UgD=qCOuq z<1NCT)~4LOQzMkm?X=Wagh|cdTjl8(wR}-fdGvUkXLw1$-lGmy4xKb!ASL$@95066 z^p6{(R+TKe&Vab~5)#UVeaWOe7FEX{;Y}!zkUhdS5hk;#XtR(y|M2x#N&;=sSG5$Y zgwAwgo4C@c%C{z27;3<%2a}WhAoaBp?==o_Q1$!b&Lq^YE z{V4T$r@MKiiD2vhs)ou%>N|~$Zmj!$O&m|tsUD%b)fduQz*54KlH5vGT24Rbc(A+s z2}~7wz1kQ@PzB8}eX=0tsP*1(^%~}8$uA!3*sms?vlTE6c=gipRsWJp(?>m>fXCf| zeY>6|5Si2fX$}i0AP%1`X3b(Rs$mZuhn!a$#^@m&tGxH@K!%X80H7l2A?A}U2z5*F zts!c}5@+?tAFRw8@^63(EC{{YH#FNY22D+wg7y^i^Rr8ZTYk5^mu>?#ca?W^?BCC7 zO;Q0;UKlhI=RiLe{y2XMH}h(wSPkhsP6e$PC~=CiKnI_y#~0fA0bP;2=~rR?yv^X?b8kv@`Z^zbVVyBf3=^O@>k4a zy^HGVAyz4mx-c2xi{Og#@}VuySEr(IcT@X0_uG6|xhADkx&7&ntK&x+U@Fb`?^kE;?wt^3u?@WgegH zp0({+T$@3WV31N0VV}pB7uKgqp&xUCrPGx%igt}-eKW7(vs`+fg`kKL6KzRh>b)(e%JoMZB_4(GVVkYseG=Gfga@}x#{(7U}Y@?a($?n^z4 zQU1^!Jaced>M2!Zn zVqx(eW5H#}92QOE`9O}Uy$od?`;NyY4qrVcewX#uE<0;yi?Cw0_QjuO zREbC*z6wzP7uUnOGyEz*6@6G{Yy^a4z3l4Ol9AwJUK;Y|&6^bwr-q|@vs;JKTOM<5 zMc}>|qbc^7@-oEq#_nEgp*@lINqq6OVpC$ZTb z&&+??$V!!@M_(pb?CiFSFvAR#v#4|i&%5-gvvk@rlxClM|NO2&mg3gl!Dvg5$)CP% zy40-n*9B>lH_0znThVDyv?(#lwa$i%{L}hn-+o@kbi*RYQ!v_lUBgL(az|sl&wwIj zBfYgz-T8aH5MQTYZc>E))Qfz&ER$tHyfJ;ze#NI5os^uLSYtPy_~Z<%fI5F4b{iKq zUzA#!XM3Bk^TPTkjwD)EV2(Ufy1et~vM(X{D4YPQ_csQ4eyH|4p{Go=kBNcgnT0~B z4~}`5n-hW4D@R8kJs@*U3IBU#5akT2{=g~ef?@m&*IL^J)kwq&(gJm;SUCO(sFX-=s%Wgh5<+SAwe zFS)aR_|{>3J7e4WHXnK>$o+2Ca7J3xQ%6qOwAiKN-F`oD&sR26GCIAWjw({ztE}uz zHYdJAEKyYfUQcFA-D_|nkwtXDlf8l@OW>fMWY%h zj58oqX=7{qNSJvq@UJ>e?PRh~ZjpV=&zB#x7C`OX)1Z68*PfCb5|JD|rt~EuY9P1_ zZ#4pSbb%+gX*(6~23{U=FnxzP8OGed-k24>=u)lmTuHd2FA6#({9tv~kk-BRoQIVy zw#MtCmJF!p(zx#O6PSb@*pCHHyRDjw`+8O}Pgj1v9j%h{V38TMns;`FbO7xXz#oNP z5%Eqk5m?ThT*40)zpH`W&+RP+!Hp~6sU$Wde{aEfboa3&({gL7$lIZopDDz-EG&a) zhZp|``6mqB~)e8 zH5qJ2c}*6d!)!D09v%JRiJ}2@arzRlJ>C0&0(pu2-KR0BvS#a$FJl}c1B z_re`G!c_#{D*4~}e)iyd!-L0X9ST&t#J#_r2%b?PdCw1S)2Y1h+H{fLI@Yqe-e|Xx zKDnZ$`Bkp8I1>ERPFBJ&iF1!1emQ?j>wH&h2Pxo}x4T*Ev8nXsPkVzO<`a~b^19v- zad)>og#HP5&j$x1*vM0pznl=Rg>R~d#k)zZ+ee_ITkDl#oixg?K&*(Z%jci19uwYN z{dcRNd{o19M^hT&bQUg1w)QGpyYp|*mG;i6-sr(8+e%L9PR8y#s`X5K)>49FJrP~; zv*nXEortuQVv)L+&Q8iK7BaZK>yb|-^jC*^j)HebP2Dzc6ofYrB$epoIP$IN*+41n zLzy+@pHTLp{PV}(XDp=xa+1b9lTGEc>I-Tfc!8Fm%8Y8ze_5twzD@>ZghER<_^w^l z0Utg75zlLtPTEXb>N2WU@fB+hrb25>M(g^)R1_ET{Mv;3rsGZqiVH6pGO{5n&rJ(`Zc7akQAn!)JVGMjh!haZ4PV)TzPCE+MI^fKYu~XI`A9BCUuU=ZoW&nHA#d;m23Nut z^h(DLr1rXeeXAoCf7WFqb=>38@MK`$$J@IQ=bp{C8rrCddsFd?S=}buqi=udIotr2 zA0uD3A$WaV+I}#4)R*^#$GE%QI_ipQ{gTO(?Hgj-wu`>mduxxIqLY&!6vLyzMAy7| zV6kOx_A|EQ*75>El+?JIC?fh206kw&%WWJqvP%WY9^D6L#f1j5`Qc(_2z-2-YazoV(#llMnzo|Bq19!ul1_&lS50H^)LGL@-l3PUE@Acb$(Ph zakRJZhwv6n6OLJ$wWXKctj8PR>!qLCc~N5eJMTQBN(W7<@7-31x>*hY*M0j)8XVrq z;tHRG^-Y$smaz{xyrS50HU+~bXPsm}wrAxjszh=1KIjj~bD&WZ;tbS%q41EZ;tGta zC$Lnwk#>~<(;i05`@q%qO1qq7)aba?R{Qjk#mVyY`LguZL1J^`1s(E2urc3C)HmVz zJe056Zd)Yy;?=8HQ@9-4`28ju;V?25(dYhRA|gS6MLz?Qmw@XvNb3*g&gcGIJ+*)e zrUW*HK(a}5jn63cKPSxTj|4|BioS7{`4RtFn0=t*IQ~PYUf{Gcn_=|Af`dq#zyps+ z%Xa1|h?0V`prhLHb(lSW{i6CoZe+1yw{NXVf42ShcQ1fI9K46P%&nr&!ah*%oF(kljy!c!TOj_29m9(uW$aXM%Bqlpl`Y21p`j) zNW}hVNu;s|_Nybj-!f~jLF3-LzCCK4P}&Ws@71uM94SFofhV5}JFOdW(MBmwkCc6` z(u)eTSX*Syd_3W@neK~fKhJDmtoAy4c}R1zbjv?bD_E}SC~xP-mGb9176XM-c0ONc zyV;o|K?Nx>uR-zilX`t$xCj7X0O*6nVnBrW!9|~`xcget#%Z6IZ+~7lpcVG(g-<(< zn~S^IRn=&Mj1j8FJE52cUFDTfY-scTfnazHb^^qX0zfy})B>$x^V(RPf4Os7@P#fW z5@DoItj6-f9Hyd~{-s)J@X0E3>{CvuPcQ0Max8-e?AliDrBadJ%op7q7z+_DGR3~^ zZ|)(^tLvJW`ji_9GfFs+${&mB{aC91jKwG|4G!Hek$1uLUedP0M>91+*Qc$nT z8M5}UT&Gef8io%WYS4*mfj^>rb+kPX$}0F1%U>=Z1F^LGq8$pmd%9oQ7zyN3#omq( zksLN}dK9PXUVnc-0@P{lvnYl898~`41)v#n z4M?MuH?Ay(HtL|fuuo{!jySn5<(@E6Nv;@#@vR@C;#ud~on-d{E8&y|79;rr5Jq*j0N|?>H z5SYQ8@8cFj8Z*iL!#+1Mf1mbS-~7838tp7A4nNUDS=^bo0gr)$4}HI#(n&n*xT6)` zJ9ZJ8ZwET6aO?C%+;a!%4z6o;M+>QxmkGfN3a}n8KTGye+%nime}eRH?RF&*66!u| zJU_4?c^l9g{w9k2H$x+1M!6DC^w8aL=#)5sNSAb(Agg)Nba4 zOQA&T?#DQcY>Up*0#?nHoOh7O%0VjXt2f@O8J?I|HgR{HTxydDV%mbTRkSL^ zbBQRDxg*q6Sg=oeRIh<1;SE1OYU_gQZ&u_CD-V-}QYO zVt3U29J*&TQMYd8z5dAI1upveO*#53T4qjvYPm{F0!4dGe9&vCLWE)EM5BAp3jF$o zU=}RoYefLOlpd-9-1Z<#X2%9PSn(_j`3*n;(gnna2gaKP#HwOL8ZVvKOk~KCSABFk%cous*c?Vh*J))G#Pn zSKIUD-H~Ox76FOGd_I?N{L?soe*JBxe)(FVIJ0jS>?a_)MJ?=PmrH8?Ii$^GQAJLT z=c}ZRK#*>4jo2?#EN7&|;KXcgE2$~M;J>(7$02_vMuG>;GY;EAiheWdp&GP>FB+=A z92iaMyB#+LLmbz~h*m#)BH$lg=-d-q5L?FB^{NWmK2}5msoLzz_++;yWp0<^@~5x) zZC}4W-3c>bx&_8XO7br|A_XQ#kPnvwYfKOJR=;Rou`r^wNWE{XS@fMfJUezk$f@v_ zo%=A_*_#Ud4W)-HCH12g#$iN zv%eaUX9VV^_XGXtyGlbMxT{CI&fIUO&r-gt=2rO+z|FJz)f2@NQ9eNa52=mRz85B| zIC^RzU7!yYiU?u`x?qLLG#Wzd*eafC5nd^B*;2J=vt4w<){y8eskDJW0I2=^9*CnV zjy7#XaOF&1WP--o{z5g15l>1kyz! zkTVC`q$De}xM)c&fsq$5j(pCm@%fvN(QA_iB;q^};pVb=1~M6ZeXP-$q+F-kMK*S) zT!@!7f6A5AFwonpM%OHH`1AMw)o9eoDQCFXVHAw3t#j{M%jQpsZC;egEa_HK4kxkU zd6qJ-kumZ>+*YJTtz+%NB*K7R@oC`Ht$6Facgpsu^`b^!*03|DDMsEYdBaS~@W!@& z886*dRF;%U;Ang4&+%gKk(auuzjk_};StH~oG!0r?}`)B5^xt)SIx~dZu2;#Y=kA4 zg>xZK@&r`9==Yr3F~^Qe)D^3EmBx-0W`=Uj9jfnQblgKf>feqt(-%ASe+uuDYB0HG zqC!Cu|BmJK!4Mv0#gSijSpbK_neOFQVr;so)!SvUr7?6W z#?KULSNu~(A?N47WGLa6<*|%Xo=UxrxUIsAzK*`(7zZ&1qW0xh z6W3tDVeI|Z-~^Jx*7=uztD|Qfq1ys%=}rFAV=VcfM_*lre6k_(xnJ5CyOy8(UoF7L zyOyTthcm+m!a;E4*)m4-<@MFBw*+ssyRIpj5&sU7Wm;yBI#R!WQOuE)S9sPjUaVQ% zeJ<>}`KNKCuxk^)%g~AZnLqEs$0u8^^#afPHuSD4uWz!%1m;6iQY==TjeQQ=inde1 zSZP0n)sev5x;46zoTBpOfO)yw<0t8BhxZ`tE_mXr*JNDjWQi~O@5vaO9n+%?;I0ja zc;&$hGbh0&eb2w8d1J3}T^$pWhcsnHl0FmkIO~wNm89{^XdqV2RgH+elO$oC3?_{p z)!HL;*P8u(;6@|j3=l*wFRx^w#*QM4ZDUMF&Mz$eR|bWq1iiB81gvXtBQO^(1>K8< zW6S@~7M~oRcQDy}&h2wEyU4S*aJ3Xd5xi)~U%>8h#G*s@h&23)rKulMt<0YNkI=GY zg32YsF>4zqWamXZqXQzKXV2XlaLn#D99 z)27@m5JhKLCLD4ey>zP-!M ze(6%}5kU@uG`ABLOHiT(V7L6`1CWrQHxOdA$1IKKoq%c3WugnB8&JX}5nFB=pdWW& zRM~D%-b^khjh)2ADnsS8<}E8sn$Y?Q9Wqe1);ftZtLe$_=i4es_K{LMK=n_>jEqwU zH|O5(2;>@H_YNJAlKh@6Ut`M>!Ga34a#u*B2{e7I{dZO6pZi9XC}$ea;IuO}`G5#= z9Z$ENR$`1*YmaP2>(wC;sEhV>*+P#cZX?VEoq45s{M?F*Le8aFZExKEV(>W166azN z*kP)(;c$Eq@)e%Vj<8LQ|2w!vpTkf)K!aE|@J$mW9m{W*AY3*`&ogDzo>@v?NPbai zN9+lP(^x-eBSY_YLLIKDEV!<$^8>9o!lk}rLlR-{j-7EnsUqBKizZ4YEoH7i_Ci1Zls-gPIv z>xg^SX}Kc9o&WdcSN`=}?5tVa2d=)aN+MyLmV;Pf%~C5@a@bE1mmFUOiN7124JJ16 zS)|YWNGf{yPV&^wUZYu~-W}zs94N*MeUDaMdN)3y>;-YTf@(}2YXmBe9IMn1M&F4w zbYMI2DL#TnCu7@xzDJWmRH5_r($ z_u7l9rtZj#Hqpg6rLxpGpt4v&3&8X!NOw)#1rd*%4d6syGgoh{;#4f3e-9?2zqItR zGNAi~GUbE7NP$eRT4R2qi8IM34L@#GUz-CxuRc{hp!>92;&}>v2QW?Ww?wNN3B4D+ zyvm$WgS$kWC!=dEtS`BaLk%A)Nl?WuR!b9EfosYTkIs-7!H^S4(nXTYI7k_UH}Z)q zUt;tZ_gZL>p=$c8hpG|>Nsyu91Y|KCfFB%swvN^{ay4aTYp8O{3TD<>T1bc%OYp@a zMK!pvGIr?V+<4_fobxV-vCFML(#Iu!K0UB8jh+;ucCvX6rh{$FV%&rTTorq*SFbz^ z^hs9iZEH`$Mg<*<1w5Qa<-(ukhFEBQ>UujSZjkAY&LJgE#HXKVKS8#$^PKn~=j=mS z6e?{@sj&9XR`vF<`toDUvZx{ZrStmCs?0eYC?KqXr=gVTdVisbC|eyyXKSYgg#4qlXv;~oKk?E#EyK7wDLkHY>~T7H5Mio@ohP@A`(XM=EkdJo-Eq( z>*7N>^IjxYvvys{Z^Sa?$FSu&jeFpy2gE%1e{%pp0myo(D>Mhx zD*;OisC0sZgWcWqi_G)$1U~O`Gy#FcmG&Tclpz1MHW5&gDshr|w3!110p3)SyhEy; zmlZ5TGv$Z#t-wh4b)f*^zNyXW@k#SxijN+M?i@M6sE0yQd^{^ywB`$|T_naM&Q^IW zR-m)U#e0b>taJA$_&3T;)s{0M@3hEfttZMz?7HlZ6t*mL-4u$y%n}hsj=Mt$OD@cF z4yu{1fsl?+9kE<3!zwR{>{*ophRI|(=3WP{)AFLwb7mI(@pJK#` zGmyR}t(m8vo#x3snDBmyp*gOR^^W?wR0rOB!qz{}$7Q7193`Te=^=Q%xZ9=8g39); zlcFtOJ?-&89z0j%x+FnB`1fUpO&QUrvBg?YAc;>>EkEP|JPd?o*~ zNb>NJZ{=OMtjO+iU?J!@Jajx0*&;?#CiI1W!DC_T4Z!_~u8))~uv zBDCNUXNG8*PR)ly5LNGDRqzkWBXSl2|`z@C)sEHjeBWd`J`Zl;j z`}TL%Zf690vrN2{(`SAx6e}G9Srr$4Mtta6jMlYHTlS6q#2cnJBUt)Yos+b(HIv&} zTXPz3Chr{IXuIF|7a6L6hNQ))hpH{n?@cf=g$xC) ziG~-GqK(lneUIP0c92Ba>J{#C#>V!`#hE1J-3XZ;VHxS-itD0%+x)^JkSLc}4TS{_ zD=&!a!NjvTp`p<({DB)MOJ~dD_y&$?gisjX%oVt(%3l#njZOBH^#bc?C;@&?!Dt&f^^jD>PBu0LYd9&}>X)xdUaL)5b>WmO+Qwq#K zgPhSwy=PG(=v8ONaF6;u;xVH?>7J!yKFs-St5$dC?nC%^b9X&=w(i!6PKgHnd_ZNj zyD6)%hLh=@?ZgOSE#q~n(}C^#Q}qtTVM0nmZfjIEE*8}$ivg*C49}T57kUG)t=D}+ z#uak|)$%!PnHh>%#EKx*zSxCkO(C@gRJV4De$l*-MUHubw1g1Q9FFY3|Bn>aKdsrn zs9oo0g7#|cdPeZ&hi68^^9Sh=T0!Ia{qn;dddX0U^mo0&S}(T5C1wph-sjMFxz3E> zF3gRv?!UI6dir#=m!DP~Rd@NO{*!7--%a*dPEZ{D0PytqFOA&(CC`hS)5bvZ+Q~rY z#p{Z5^DQxR;lCREVQ2mAOS+gLPaj{~cuF^ITi1Z?tt~`^{N+PWr|e~P21v5g+2%9% zusQp%4fjNN(t9-GyUD)ilvcSJK^)4(`%zj`vc^<~_7XD%R#{TjkQW@@%KqlYIOXmL z0X~*P713N- zTqU8_OQ+tePSEkWUOF7q{|$_1E^ExbvYjY#ozG6}qXKsOto|JEo)#V91vFDW%~HmP z9?X8Ekdl%@K!Dl7LZx!78ekYZ4U;(=pU49RnQ#ZdvowI7joYL>L`^S>seQK|Y;eva zwa0V#XI}V;SbqFFRhbD}5P=6VROKC_bt&QF6$NpR0QPD5(OP_d3of(nj+YKSUwlsw z5XL5PK)Vq5Z@+$~S#ti-%9$MDeH*15=HA{?#Ao1-4iMN=UTLiqA($eI4jbQGFAcN# z4qb`E;P^~HaL?f1v9~3WMJ2f%7&dnOtBzJiJcB7I+;Lwgy6lG+7rz`GIZ0SM_hks8 z+MMlHJwi6RZ-j(wi}MbGF-Q&v1rHu;tP#F3-pX}x*I8-xnMA2nJ1jov92aDl}$gEnmK2+HrlEa=#mS@_kOBcg82yXgNL#9@0O1hgkmy6>^1&R|xDCuFffCMAbFIhAQTf-D@lMLAVcx55 zw-HI+y#E>zw~~*D<{$K$>&j8j{0ybU>(H;Yu@1}!x$tv1^Jz$m0^N-DA(FfA6Cx;GqTcCO#g)NUcBAi(Qdl6I08whD(=7$j^=7n(bBx=7)jnqLrU;$l|-o zAlw3OM_`@y$A-e@N=A_$AZQf~xC!cj zobIxfX}*G|C#boY$=IZkQu;a)nDms}XuY>3F(1?Acz%AXCSxI31Ok{6XIK z=P_w2L5M}BIZrnu#?n78Q7NZT@XP@;`8FI<6b_a z*BKg;i_a-`+e0YGX?zz!k6Hx~Vci~vh>qby$MsZ@5-vecIQheOs;8%kIx59RBLd#@qC9BV1N-LeCT%ku=fM6J3s%hlh=q&CHtBJH9kPgS!H_viFNPHaj0^c9fb9jArg;?RSq)3s##` zy~~#!nE;c$;yEY4y}J7M0FIi0+^=}fqO{FL@J7*|!OQ$)M4r$5`{1&*CT0(6qlmpH z>s^)p1tImgm@~$LZjqW?%9^x#UO&~zi#;s@m$g-hZaz) zw{v+t*`gS4-%!FeAku@r2v-aXl3HAe=d)cEruC$(%Ln;CkC}g5#2G7!1cj%t|Ab;Y z-_eTiR2vtqE2g6_QtTjAvsH;6pPZ{BecpaC5(#CWyFvDOdyNX@0pKzuzQq8-3yrF> zRzR3m0AK^W$kH^4=PaN|z>oWu`Cs;|+lNL<@e3t+IL&-A-C#t@KTW!-lBV_8 zQQ|Zj?7C5_31*U)XMm?Q-|H){@TQrWo#mD^M7VUlRJ+{~y=V62xJ8dwkt&Vv$UA(! zn)*xsWrJ|3c3yEY`o>UJ&!d|ORA+1h2}`+`Sf7=T;nt_O!!wiiOOpy5@%eq`%(b4c zR1W6lc8uZ<*w|rb{G{06p|KcW#7e*<%x zaW#f>q*?^Y6g5kftYWQmeptqVtHiGHch>TlXWYBQ&*L+9#*$agDh8q@h^r1$YcOk! zpm)D)$jYbI6BzJrFEbXehCq)H1tR5aGIBcj_#f}!si{}7n|;UmEt>NWHf^dpRo|#0 zhkq4cz7Xt<>WtIfYjUssSV}Lmt+qw{+DWU3TzlUVoU5FpoSS0L2~g0nj-;`$sj(=H z#(%1B?(a(hF85ZXCI8U-e8ci+>#*PweDiN`vp~HGZTK2B+XlO7zLS*7Eqs<~h7sNQ z>g22h`u~?;eTd=JJB+-~By#qd9-tA1(9p+e0V;QqhV7f>Y4QAi-N8Tu&sVmk$?)S6 z@?$aViLX5^DOoW@p5~)DnGL@EpY|edAT&3|Y`8oBYE&bSQbVthxO`Y~tA}}0-h7z7 zl%2V1gdQc*dJ|h?bk+Km;B0Den`20>R@lJ1j=VoHV*zTwhKpS@i*E-CCpbhz_J2PK zvX~QmVjJ2l)&)M85lx5B%^J&5aV7;uX8+)Qk4^M)QQHfIShL2WBJ9`iuK~ zNGu8l8v0zKKc>AgYh@@~$=@~e6%*^Qd55Hwal-QKGb^WA9<%5b zB7Cnn0mhidV+T6jGijJ`g-c=~eCsOAh6R1| zdtUp%cJ1xmz}TkE^cH5&L~LqmI=)D>WvWR2Lz&6p>IOct;ts8d$Bg3way=yfeDCA$ zPb6B^jbt5B37!+I?5}y`G&GO^W4+if3M2$BS1wB8i0tn<#)EeozP^}Qcek8A0=JAJ zH&>RmXVtn#eM)|)VB5}@w>Cq1Ty7bHO9mJfzx|V+>t+XR0`>{TA&H0b+w0o*k@xrX zhu1rzRMqDLYxbp_V<3PTK6tTw5vcYHqxA6wn16!jURy;sJ$Y)wK#nQ>C_s+xIJT&m zeDikc$XT;M!=z|LD?OPJy@5coB;Kis{d(6%b2(sk-z#6=&mEmwvC13f@vAQ)!S@%E zlq4>(xn;o(W6nwwArD@kDHc`Js_W#Eet*9Fh{)ECF z&da*{^IToR^~47>jVyzZ_|(a8m#VS(%4u*JYp`_W$sheVWX8XgnUs{8P-5A~O;Pwd zen3Kisn5KoZ;*BCov2p!s48O_`INFsD~K@p+_}kB&TojG{H+I>yM6DGz#C~;f-bB5 zZ7;`HX_!|joJSemD#HjCa_#)~i+v=K+=1D&3$opAi6P8#R=XQM#}28m+aA|souoG^ z+bkwfQzoXzLJ055w!eMHots^jil2Sy(Yi3;na7t75118?$8L+Vh}3^Avz;QPJJk#o zq@$zLt0DLTHp+ihk8U6nl|3(^Ff}qD_wtBzms~25cq=!N6{DBp(5^xgbB2+G(8e zqQ~8|phrRHVw$Wuwxb9ioOVT?ow8!qZ_D4ldo@3oy>=drUomUFo7unf?rAP^RFpme zq0MsGJNlUbG7fJ~l63}^z7VT)pBCIw$b9C;<*V#3!)mJso`_v+Kemu z4enIrUy2i5SSBJmLZnG6Pm$v#4OIcxinI>H+F|WxM|DU4K|2|CCVosxu>FUzO^>0RU$FP#fVNGSkE$C9b;tsM!L^MR``hX4oA}Dtc zz&7^TT}>SwvE&I^C67C3Q`t04uGjlK=YDP_^0$}$bD9tb@Kf+(-#|o2QGGUfH>skf zoJ?~&(oe6jN^n4HCt0Kv{yYnWi2ut`h_Rmtc7!ZZgm4hvy^`;^yZY|w z%mU+Fu*M?%n)K>Us<+?zV$dI`L!%k4!~K%7>92p{OsfC>8PQ-^{hXCqK=^x5zW;6_ zf>k1zaMA@m6je^=%Z;BbfF{}5mzr7w>`}+Z+1xE(pL4H1g3`FwT<8M~77>rK$4jJ8 z6l{dnH9>!1xr3Tk@Q9Py|FWmAx#!PezFwnCBaLc(iL-dCL ziuiW25^kYl^>m~$4Vy6!DP?p&Wv_dXt9~h1BV0#6R_8`Q#ji?_wgCe@anl`0nZY7b zk?n#^=ga?z?mH@YDZvkHd&P;c_JrS{5f)wn|9Ja_yk}-gr@zw@>wz-5n6PZQ_l!B2 zvERu1;QYs-_x-A8`qkl!g}bZ+lWMLA=ekG$OzZK7V-~#1rM$ z|DjUHyi}X$)PK<_S6@>7MQ?phL3|elmK*z)3wIyuo}_Y~YJ#GVXoMoQ{wW{L+Zhw& ztu}4N`Z8FxD(x{u1dgy5e6Q@%@2;k=4p__)5GGG1m(XwC=%xn!VfjbWu*u!%DZzVh zn6Ip0wFCHPe1P*C`QinLG49}PKEmj-w5s#m2MJSu{wSZdAe0+Rya2U!<)%kaL@$U@ zDrD<%7cV5b=&2gXJ}0%`?OZDC09Z7uDIPd>L-We;hc(~hdBK;jM{u&Wrv8>$rej&iX10YV6r~m$H*uxNKGqyy zlJfb3X7oq0u$8tO3wiULTeu{?;j4WkqN(-S_B%Z83jY6q)bD@%&pb+criTWpS6>=` zD*wiGjRY(Zt=9@WN3(vHv$ewRU@pa1GCuC4RXxH(_@>PEO^eOMdPucorV)*XhUT$3 z_ULH%3-;;rrM_$BUj&W-A8B*MLQqCa_`w0)b3Q5wX;h5rq@^cug^%xo}TrJM5mGS zpY_TNyb11Zi1b|4i#XKwR4 z>pzHz2R0ojZ<>U4h>Ud}f_)@SDds=4A@Lu^BrJUKcUaU1uV&s`_w4@n%GYE8jv&x7 z4bEpo1ZpyDV3H8IKQtx1oJORj-q%X1>spj$_5Hssh+CC#z-vEs&E+Fl z8-*1Uh%2+)27NR^vs(PVFD=e)17$ z+Z9xal-s~srasN@XYU4gojcSpFL`wgVlham%*;^|S!(gM(gk_rz74K|7KJt29G&_1 zuJ5dTxmYs1Ut^sG#fs?E9HnLRiOnSvkPPdZm~}H!1$wZWcS%p+URft%%j(OQ4M$Mf z^iZL5v@HA06L@L+cfZ3Tj+u}IvTlGei5rM{7m`sKqJR_G*zeW7;RE~T%jHaki@$?Y z8Cos}slbE0hMVNH)`<_uSH0B6K)|~I%!z7CX*q+U<@2L(INkwmGG`KhadCVc86kCT zCE>u8yR&&3q&LBv2~$#kgs$s=;O}gLMa}TkkGDXtwZwkET&B!`@@tK02y2pDNo1P$ z;IGUYS#LXl=Q)@{`u6lZbW!zlEkEthYP56O?EN17MHt21IJ?%jRQ{CEf9GivE@u_5 zOnm0XIbEdwXFt}S1y>qY`;DwTtx@}=ApMX03*@YGTF$3OJq7Mi-n>QP*hN;sZ^9w>%U6PpF zyYjDO`Z_Ud+MOHO`d^s?RO#bZUXq@|=f-|`;381_-JTYRp7m3q3(kBcg!##i+U7ML zrwASY77A?i2Y6k#GYvqJ7_vhJH5bB|ziR$r;98#WcIe9SyJWC$x|rassDM}jYyFDUEJpUNPSp1S9sT070icx!HPWB+S8jfgHODo0 zPKe7QB=%fDw~Itbh4^x7??LFvqrKLJ0UA$B8SJshQ0!X|#c`hX4-s>?8}SsaohPS4ip z{wL1IN?(n6?b~w*$tK)iud3YT*67G6NuMF?oq;<)cH#(iHhf_+ ze7s-B0O)J1ym1$$`J|K)!%0ext8W zW0j@}sG4cYz1Ui7L$yLx_VRRUpP58c)V8fWx1CV#+leaXjY*X=Ha4P4r5QjmXX5bf zxCf3NEP#^=dLMLt7NmGTxn9bDF&I6xd>qy{&esB1Zop)}65);nPZvmF;#In%mNDiS z7Fu0hy%bptYx)*{@FL)_BR)b+*JnE_Y(tB_S*fY*Kh66NhaPT+QV%pM|0G1TNJ((V zptR6Z(aFpSeO-2aMaW!UEyaUmJp-yZ;FK66#w_D~0PyD;VV8Mt$Wfh1C~2tj@hy$`R$XE~ z^*dbMmVd>2+aK zcOL>xCB3fQOI!6-vaDBSXf5ajEUi%_yfKXCF)XyPn7Ofbz1dhy$^#L&6T=oG*&YlM z#EVIIusY@Rq5sK1n7`87(w??O=`ulhSn<1MyuTfKcs4MQ01r(){MQ5Rcc#hy!8chvv-btGakTU`ko-WRpMP_HCN^D3vyufI~HFHGXD!|vC* zwqINbnKYzO#fP4Cs?vbnwk!7Z0stk|q0Q-NQY+0iZS@S25qq;WrY0r8K2l1lP zRWo_|`!?+(z{|+-_H6(<(Ca!b)GuIKRofA}+2ygpJE>tj@|AaB$1uayejknGh)p?GjH-g+3`@F zX1&xSD0y@6GNR~gnJ#H{>}50MEe~aH=0PxHB*_q zuH$j=qQ6FHZ03W9Ts+q@W->nEkRn>OV!gaYo=?Vykn#EwZo(mZI3mrK*;#9#N^u8p z^y$3~=@zGR~#YW!v$y)choqQ&1!#f!=UI+a16|<%y9rp(1&Xy?eg@ZCqLwG@L!rQ?0h0 z4v3A#rsf@zE3EVMT~B#z?MT|t7k!LX_ya;ao((kF3sUO)F~Q8?`|6caJWMf9l0BMm zzkj^+pa@wZ*F!kxV^MIHE3dBG3ReGw>$aLW>qM+2`=pP67jE0uo(&-{a1`JvOaLjb zSDylP_N7Vfc6T)u;mkERl&}l$3JT(s0xd1{-`Jx{%$Ni)fm0LRKk}6cLc{igfPyN> z^uiOpUD5>$2TQNGJ3Z`3zrQC08W_9I%bw*$4h}Uae6?I8X z;3ULfryGzFSwFasd%)^NHQS?H!`#w`R%6o@v+J~+4oDA?{aOBKS#@qtjMqBdJxhHu z09NAK$_quI@)JbYZh;M9hwFZ>!4@d_sAawrwEQ8g<0i?fIWW(fLz%9FaFp&u*8{|wd0h*`=YY+ zr_Ow9PV%1bY@Og(NUF2jcaOAgsbv`uIW&c8_9o(cD6>fDB%Nsl+jm1RoV9m?7>;_U zz6Yz$|M|hLG5O4(jFTp2!rX8X!N7a3C;0th5PH&5K z&o*Z|6R!1rMwQ+~fW?A#%{ji4S~BOceX9M~fWZOn)d%v*Fl``%2jX`fBvzE`0F(rA zEDK~nlvX{}Dd($w_0ne#(e^%PAbdzRUDjxKk3&z?g)A)PDP5_e(e^f;+!{{lRThr1mj?*tsr!`A%m@4HpVN^WdeWrETE~t+hqKP7$(4uZ-l?+7Yz4FHh9qz~J?o z6BD#I83yDH04GjBj@DkiauH}@ zu_LaWV1u=a&#mY%DG`skc$O!62#$8>7&HZ@Top`gSQSsHi6*9z>c0<+ zsaz}9a$WQju*$jj#kN-HS{j)SYveh6RA@xdkW+!0nMwwRM}!)feX}mSX|mbnp(CYL zp#;lPPemH~9!Vh(R9M=*GDv^IFc1&e5-?hs#FnFg&=fGzej-6+dBO7jV%^?n31ZlK ztk8#_#c^Nhq$lWv0bbVF+St~*BNv$kne2Z`Q5pe>db!(cnQ)Q7Owg=(tQqri9Ux); zqPqo|>~Y7=CLcIf)~5>(nP20fA^LC6m2SMPZ-Txa%xnrUQE5$N#dk`gZ7wV1;N@Dy zev!D2+H!mrd;11HENno-@p*iN@?jq2tGkXGtwKv+JsH7yP46*7IKc(M89qXr!<#%q zjsZCPgb6!LxIxz>Owt5)NPbJjMkd+z8~ zvakUozz|MUy|EFC)$Gl$skV)>5$aX$HQ?NiiMmU&pb zv0i5|F=3&M+ip#{*igwCT{hArb#i>U@?`~9v+(xJ7Z}em*bux?H0ac?D3zFA5v7n? zttKQKFP9@m9DQ#JoDO1w1pLJDvX|m_EevwzPJK?_o#2(VW3|>oFhj4fT_Gg1&OCEB zuzRu_&e>fgR-8FsehSlL2N(vzn4S_wjOlHfIV{7l=7Cl;mZ)~H~#b)aGf(HlhsD* zNQW}aOL!lyej1Nj!G{piI|(Ylsokg4qusSc>hw3b97m!WWmw}$Fy{6vfz<(|yL(iz z&GlE}Qq)N`eU>TXoMG2GkcO|bem*;{Mv5B1;jHC&7TX@~k)_lAV-rNm=!2d`-1_XY znS93zt@psvy5RQ!ov*S1M+ZO$!V-;SW_y$WNjH0)2vfItO<@rm@nPhezT!M@{2+I4 z%0BjM?oiC>6JqF)O}{4Z@jF-5&@du@eU^-Z#{^BUg=X+L~ENZLc_2h;7~ zt@E>^nw8|MwHJ@N_z!HKzYIaaMeh&5L-1<)@V_+d41ruhk_Q!Nuw^Mp`r8SQzeCM$ z(tX(`%BG!785JGD6$L2gZ=2yz8ymDokt`Wm-np+ZkV$~v5hDg`y|0dM+ibh>#x0Q=8B(O zn+Oj$S270|Ymn~>M2b;c%#zgz@@Kr?ltKZvE^ywKvoyXa<|%D=cvx~UwX=mS3#S~t zD7{@qqf`1oeb$FpI-u9lB~R#Nw@&;BbphD%cufeHK5)98I%DvE;Qf&EigD&qFMRdN zqAKcD-9llSr7CbayBy;x34O`}dhF0HlaGM^`rvtjH7}%z8H}MhNq@0uSaF!}Z=%&d z?-#|sg@XKw1A&Gp!$_Z@lrRjIp8lI%v8`!)(#-RA55kZR4k-n+R(A{yi>zYT@L#{4 z()h7cM8b?Uuf}(}DIC6#zMk8DsTeMLHnWitY`(*f1Db+W+DqNbPVc=?hLx45--@p3 ze{v`8a?aClHeirvJ?)h^xUgR{WYo{ze9Zl`R69$tbpN}SWSDvJqHeRna>%b^@!_r} z1q`&wgwQBebbAd5q9C#{du_`AMpwYF%xk9A(a46vGbVvxM>EzV(c3T^QJZIE8)l#qd@pg4HAEI1& zYrFvDezp`zk!0QkDPgT-+)l1gsCrS$f>RIK<-SLY{OWp2r+#Hznk7!Ii3<;jc*Uzi zom(E>ob7$>=vonLh;A_0R#bq7FvOB6XKT2Aq4a+F0D_A`S;XXL zxlg{0qecZOD2q(Ze*Q{dHdi7svA8EiVLH$|3UN|ukm;npyh^|nU@UcHQP(%+H z2J9#F#vR~zL^y9ClJTUZq@6&Uhu_v|lfq~230XDZHlE$Oo^&}%|2M(HX%Tv%?T&81 zY&W}8Yiv%Din6qj>3wAAeot7kqh0VZis3qc#Tr3uSqcffP2_9_^`RzpDBo!*f!fk= zkVgN*6GX~CuUf}f)qxL*fpsGKNne0JB=6-W*$5@*53@mL5&mo5HKVz`?s>34cDZn| zP9gV1jC3)n`hvVhVq;iONp}EUq3k19pE|R?ms5CNwzIT!NI|ncSeUwTk;)Sg>p|o{ zAnAiy`B&-P8-H$5Q=~W9PaC_P#G5yclCa{{SPOp@fPmc$jcqf17r#H-`;uBXVJr&uTWDI z02nmbn=ehy1V*CPbO@k(fx-Uk)hMbjslTatj^Q4UZR;q>yd8PyUmp*LvsjaqhE&r9 z!L_O%1Gj*f1Xxmr=jUNw`W8Z;w_X;+HYRs=u0B3f-c|S~upxX7%*};}7F{&R@ z5Hj**$Gzv-{C~#RY@Wa8wS_?{yh9qm7rtc3&XDWUL@YWr&#vOYY}Tbd zqhY>`Z-4om3bRZ?N2(;@b<}B0XmiEXz@;b9QfGZ!Mg^Lu0bJ++b$Ijg;@V?iUs>aE zI3%0B56OR&5C8d8xY))iZ|nc$9I8O+tnU+g8(=Vu`T6x*bq|3?2`3kx^~v5_3}Hhu+Wcn&k%E}ggoK5i6iYxj$=n92>nPUUBvlrE#zEuY&rytRikTM z2DrHpGJ;twNI;nG-XI$~C;J5r!7KzOQQTCk;=yueN581vclX}9qqEOchjk_Q6|6dT zjYpByxC$!j42s3^AxPDuYadb{ydV;wivzUx z{R4WKP)tjVdfE_Q_o;dE$JSC^2zUVloLNt0GI^#Hc)0+i5g8eYfUt~v6s~KDz#Gns zfB;4yaJ-qv#{&2WFYZ_3&qMB;zvwqF3WjW^i{~9qWBfIAA64nr)@{8B%=iZhAZ7f> z8{X(7<5#e;u02#7GB)GU6>grK-uS*z1JVCE#a!rD`Y&5(E$%+N^-bj5sTNIcv|9^t z!#%*-s<`&j1#KH0<>w3;~=Okz9#$t0)C zsqQ1B61W=84i=5IC2N+H@#{N_Nh<#eh37g4Jlcg=yWO2Rq8uPFLllI$}`#1Lv+NU629Ck3jFoka1#E4QQF z*N8RbG1U^hJHff4p(bED_P%O2|BLs=-T6h2B6&w==TihDK!*Y@6fmNC{F+U^)m-QZ zDD0RtwQoWz)hvOkZh{3K75&-^s(}ZM(z^XI@DM=xx6knYEugc$32f}Z$biO4w(+R@ zi~76}=wEnDy!W~b#^3;Wb_W=2@^%=DA;mg^Mh?#vlR~uUs{+kN92gA_NHJ%Dj_Fy^ zxB^{6z>FZGyxYisWV1Z=x9Qt*(y!5Z0zcFvbzWCs<$UdCRLtASAXwgGkY^8dKRcxo zKQUc^{Bcc#ov{$CqY{jKlm0JGKtZ=rXCP-9_uha}m$+gozI_ykGNk8+n3p=I%%x7} zo10#iwTS$K@71wXQk)G)M)vORZiLMU@XbcGb`_=ZQ7Qk_Sa4sRW+a?cq*N$Q42=gj z!+-Hcf9ADFbFyVq#3O;!}nxBuG~X0GdbemyvjSWkmicxlirtX14{} zT}csll=Cpi=P=|hp9MN@WM}(iF6@B0 z-jiShD$H!i2&_)hJma8r=6Dlh!l+?mf|pent~Ee+8GXKs9=6)e6!da@SMEt{7W` z;m{VQmI*s%VGa6s%ww~`d&)%wkHdE7bJt}#94KxuM!KSDaIErDIin`N3 zx0k1jHa4lkU3Az&tmCPQ;0L2hq6)&n9IUJ6?{oAb$2bRgjJvwHWCdh;gSj;JKt$kU zf(4-IR-Xc+Bo|uLVcYXIddk1(|CAB>AWd{nnEd_n%yB5+JM@?nJX%ddC_bP)4>xYX z59RtZKuBbA?a9T#6GjRCjO7zR)ixR3{NeaR6GW!haJSN?{a~+VG1~7k#E(**%YVMX zW2KAG@SocZN|Y%;l1GyX=JOvElacQLpfi@H07L>2Fn(7yZyK5NIY}iG{C7&zh&*71 zpXVVCIJn0_o<9dAkaQ`S4V^O=f!KHc@G1~MYhcGa>w5B;v`cw@1+cT8as4*iWoJCk|eJZ3RassAsc=NDP@vk>-aB; z@^)hLZu-E~y#PWsaI@J_A5XwZJ)v3bMK$y?ZN?FqvRKPaZH5t+7LZbba2PN1AwVNt znHy2IZ$O}EoI!pfPHJ@dl+WlX?@Z!pM#_h0b?-4_O>(Jkvw?*TB>ilX0A}KMGngUp(G6*ipg=ff|96!EHtn#Yx1sjT$>L&eaOM*+eNj@Q zx0}9=g<3EtVN-p9cB!-c|D)@z!lI1UKhO~cq)WO(Kmh@zLmCMwm2Qxd25DyKk_G|k z4yC&pq$MPz2N(hA?uN72d;ib5I?uxm+|BTPYrXF;kzzN0?k6b&*SE(vV@Yj+{7CQW zRT;xqBNcyNI;E3ltIJY3eeKt~)&{+Wzca<`S?kIt+_v-!U7~sBU9mFk;GH;~itvE{ z(*p3X$o?{~Vr9Y#eZm0f3h{jm@Xq3&1}&alEJ}4B@&Wo{8!z|2*S4j#JqXeRq$V(b z{G9cx{W6>cVs4B##DiuRA+uIrF?&4i{^K7N68dpY#j8T~NvxjX`pfWKjnylsM*Mr# zNc*%OFXX&m6Ndi&J?VW|s&iSj^-k&O+`X8=0h%eXwNIzG zJAp=D$iH(DM%uJ5-znJj`hyBL-@IN+Wu3z@p=(5S%j-|H2EE%-&O@@*Z9~BqMmY8Q zLR<6pE;eq6`R1fq6pPocpas zk6oTbdCoFXaE~Sa2w&99KIAhA3QA`czP+LiT(u+YJf=VZvbmtWkFkFR&NhFbC(~MJqq_Iffo4NbI4$fe>;}I1 zO7R{bk5GwN9^u4WjQ_`C_i;!gf@*ifX}IlPs^C?E2_F+ouS>NM_qrJa2_`pJAzZH> z0-I;c-EGC%ya=WKAIce(Ngb?IZI(Zmw?+qu44+gdfs+t6lnR0KSBchTwZ1*#y;l-=U5Mb;$Q%glv~`4b`o{#$HSYJ{es&SA2-L}rZ6$8m2yd#E?!5qtmp_003}V8;!0CQ> zb6>}R1?m`%MD9Gk3%__IQPqwjAu&1Y)b~V!{1KBbW612b`5P5V|Cx8zJy8>#Z{2xE zv6b!ZrwwF6m~(3JzElX!5&W^1MU>7Yle$DO^Kj@A&hO~&u*xQ;=Dfuuq3@{Lrv5b^ zl!Wq(0Cl|eunI4q{Rw7r0?R8E^Nc|uF;q#q=WIuFM`=f5$TJQ>*CQ&k#i^~9+21c` zhR&??wulp_C`-yl!FBEh!i7gqzo>jmO=WEQO(y4Anrtann5jOxGLWRk`Xn?HqlW*j zR<;)x?Dk@fgCq8Vh1u5X<-*>mdsxs#6?d^ky%`~zY^!shvDK2<;^Iz277*b|A($M+6jhG2PF zJR1T+7G0K)LDqMQ99%%K%;uT*dUi+=@(l+v&E-7b2;1k}>06V<9epGn7_n!Koz9g|Sg_)GQd0D3USNZ!A zJqv{Xav~5I4zx8lHGQ$jgp#O;-SFI-mlY4(V6cT#dw?41u0ELfL=1j@{78Y(T6z&| zv=;tQDAK3~KdR~&ii(P4wCJ}JaGmLwA<60Ks6c30ZixQ+vWVlh;15Sc(tLU-2D7&mcJ?gE%>UvFn1Xf?RBjxtJc+Y69b9ede}q5;pyt;(C>J)ol* znOS#P8f&EN93!=~56u+wfeoywMQ#YQV#g(vXdCR5oXVZa`?L4LhAF72yZ3H)_m(!* zofQ>w#qKB0E`MSiYek*OSXW0ItJeeNLN1<2uB-Kv;;Blhc|Xx#qA{rCb%|Jpanq4LIE{)IAA2-vEyPqN|Ae+%+HNex9$Z{spWt5zkQ4?KDC*wmN= zSP(Cxc7j|*AE}ocpXC;f?`7eiTvjOhjO?aIQws;v-mJfY@RdTFWei!4?Vh`Zx0%1l zz={2JKL0F$NulYd`~`LsmSJL-c*;&nS9kRT#SpHNe!BJ7$UTpF+XBtO>gI*r1!c!i zMaC|z@jNu3eRl14hLmk>@IjY=>_38tK1R967;-UOwQiW1nHM5-5c}2(5{>X;YBoc4 z%}N${p((X4JIO)#5xl*djWl~h-_hrUL_q;Vz4VK0*<$hefY8n5-tjTd?+j7v=htze zt@B5aEciact8}6@t?SHI4838ePWyV>LJ=|;gshl)c$1aPCu|?bG<@h4Y0jHu))*xK zZg#pV6o+ws$?Yuq(5}`9fzh0LQKu~xm{T;dR(S3%YO|x50@hc76FiOn^v?#WtWQ9k z-Y@Bt=4}0_66A2X7cPY(g<^?OcDjJR+vo5$5UJk@M#~IrrUK5t`o}xn_@1SpeT^8} zoK1{O`j;Yc7AO6(9x>O)i7rJ@Sy7j8W`VSzMO~KdF zG_(d6_!K-fH6*@u`?_jumKz*j^IuXlqK)UBeLFHXoh;j)P0_vsp;W59;lcEmO_6&D zr8DpL9liGN`=BL>-2mnhmeRd9H%EmTBx%zsBA9F#_d7&h^x@@7H&0)yXWL%?q64Jo zkrBlU<{a!DQe81O5?4+eLQOI|Lmik+L)=^UC7Ye?C$m-&TgDHYon9_EbaC%FGGgA0 zMX?@NbCHrsB&xW1Q9N=C<1@I*McxSFE_Y}Be3u?1su4e^Uoy7lCg@pv+`3iP30!S| z&O1oWshiDQ87^nFuOPcJNY*fFrWmaU!B9i7pwg`Q>$th_6~0xASrA;xJBt>1x)wsY zR`fUT`kJINpN+8U9m(>cfE~h((%jsf4ucR@eVF>&y_N-z-c)8!4*$GvX~j`z3G%%-p%;=op1I%wOJV8a2F{{qJg3ZS!&Zp{bNpHvwoTzZI=! zLyJ~&Vl9?Ev9MFdc+*x@W>mx%nEajG+v9Y=7gEyF=zn6prCauDPH<}kp#k?qG--BE zx@jp|8%xcL>lf!{^H$K?ij%*iE09*X_#7U8)$DjTzjp)zbb#@Wwp~Nf5WLu4py)VF z#Dmbc5wW%aC%4PMqkSFmr%;7R`}+6r@I&#n*FT;cJ08G9ZjM#Bcxy@Twlk@F!Z|Z$ zUlwX>X|;o>`-6Y+DmkMNJ9w+@0agqa{AN|hU^S-)n*Mu*#^WCW$VDcqJ9FvJ>OOb* zLOVH3g=@ieFpu(W(pTA(EBD3;qklrytx0><{ZJT9a=PqgTDxK0V*5ZVjyzldb}ay4 z+TMWyi)*S}ORW^ojaSAxO*$CTFgQ_%=bE%Ue)!9h-_Kf%CIFS9iL3h=>x}_B^ubz= zJ-;%$m)w2d&u-%y4O9Ft+f1dmZ~sogZ(R&W`TI#y?TmgdB_>>fs4!7P4!fV|?=>55?7sbC?n@G2!eI)k@PR#!~04SG&#Bw38^lK*+4uG+xFc z3}Q66VRyHCh7MH7dM^Xhr`Kcn&O@P1g-tLI#`*aDs=b4Wav1Tj=vms9#kqPpz|WTx zRrSS>{Dx?BC|$i@HR7<@{+1VVpRYAGI}&1_$}OqU$4%Wol|W-#=~58F)>2fVI#?oR z`E)*!p_Pn2!ldkoD3wN{(`el{RM+Vb1ER~8qXuL+D*~g9ms=H&9woxI!;4_6flfM# zHm4G~!?-PU{Ap(^B;10<%H-(_J~oX(rWJ`z*t8O&o(;YD_!$nWg1+C#69^z;Y>A7!E!Yv79VDH*!~djFF=FpwtGom=(YFve_2}_Ng)-8+-t5J%|Mblr+#h< zl9t38oOo4CL%Cd0DBr0YXNX*J5TFtU1Nf&`agx~;E6Di(1VF7G)S!!&k2IjO#n^m~ z{g?F5452Hgyu0^k8D>0AWTl5jGG>gwDjgQo_A!sXZ#v^<-|L;Zi%%j;fNbVLajQUM zd8RGj`t9G3>?Vy+fuDOXnYC+BA6TDs>v(!%EVaHRs&@UT-qX5df96)YY6cUp-ifa( zgbi<(9yK-!zAxue>$S6!%4Kh@VQhBIW@P|#c7r2hKxE_-X|=9%0j}4$+p`l3bUP$I zlsJDcUH%@L{mqS@b#$+uc^(|XA2Xyu9R`nM0{xH-sY57`lp*FH6F*qOk)Wz?31t7B z&rY?0+Jq<@A|J(kLJbWK2T<=U2@3{a7hr&rl zx5;Rgjod(qq38wutr)+u3#vcPM!`^QGrq1tr}iaikuJAc9mY)b&K6Biy3beDq2FvH|N|^ z&x-*(@=*M}_0sZW@A*UsyklZj-Mhp)B5^?yoM+R|mrjbymoNKVScUmZVe=7;t!9h- z28hPd=yJWrs#4nWva+T8B!dnBY3^uU^Xl>|@ZfZI;($3l<`*l7DqLDJK?){TitRp0 zu@+)Et4igZ-LaB2R#tgOBg@JI-$mk)oZ1OeDc3lDe6YRpQDqv09c8MRSmEu$4;oeM1D$u^GFJl>um^U0@5kvqlhZ;JE z)5Kk&8gEcC!L(h_$de{FT#Siag|0+1d2Ee!AD(r7ueJZ?fsvaTbKeY_t;J55q&RJx zLL#d@wdGPXscSi*OBUZ76Ym5j^LV0oGIENaS8yn;eD=YA4G$8>=Jv&SH9IgAVF@Fz>EFY2YTe45(oT9V6>MXshe9yNuct{ znVG#~V}u~-*4)D4V6(WKQ1|ed$lofgE$@Y*Hp%SLVvyUnM z5$3&i1#j6`w7e{EFWjJ@@O%hy$b~)RsI*-Xejd$0&r~N0FPL!1b$KYMAg)v_L1EX7 zv&(WRTS>D$ySTn?**j59&eTz^ueU(NqWt&YuXwP+$C#17diCmFy>bsX5gr-jg1!#C>nnl(zyuvifSZ=CQict z_gs80J!>E)!S#tN;^5L-qn}&hTLQUaqKU*ye*O^2?Dl`>NtO6z@qufzvveJ+hF_+&=U6HKo$3?RA3ubgkd{xcPl=#~g@s@xr25g& zmGZb<$5Sr!O9D3s0q3^&@e-fmyoNu3iW=MxmJ)|?7SBNT6VsQc*6lhM(vi7uq8T!W zi5fj{uVNH)7sQ=g!y@7&blyt&`qq4tRUVWeWP0omd4Td!LRLY}*vX`7$4Lj0n3UvL z>W&jf=dugF=O_9SGQ|)}tmf{6Q)Al7XAGrzqa(8&74I}1u1M{A8>fcp)9rc*GN#2O zy654v=h~V#>@ZDDO*M8B{YLj)Xd%MmA^pK4lhC#^o`f>}xW9tG6vy zBGFQK%c8V(`3G4<|CTD64I7~^_EHbpt(#44=Zv87-O*tr5GDf;t_{+r_8G@xpXfnefG zR=0Zj25)XN`%eFaJZx%elAcfI-#FDv6SOKiMvj75;%a<)*Rpt2a;s;Nzry6Vf7K(= z?b+cE9!Toa$s#2A`M*l#>q#iuON&}*G&R(EF1ipmhaBd4tE6On zcY9NiIqGm^(=sLBAwE6di4VKm9=?49JOwJQtAeg}8933*!KrILXM4A9-fP0h8COxP z3@U9HE(Yv3ytA(`{<`7=9u+Q&K_EzvJsBddZ-~s6ue#{&N1LH*M2o@^m9MdBV2yZqB7OvAf37d`_zpBdKFv*j_h&Vgz!Y>+#aF?~kRVLa82g z)Wv*!Ahlgf2m_ZnXq%dxn!1<2sFBipVHDG*o{)=4Pc^)}y3lSpkLF~UQD6vX|EL~Z z6oyZ4qD2#&rvP@*Q2bcsJT)@Tzmsdhf*p_oJv|k*!Um44dvtLagtODcO|^Q=mPGH~9Hcbs*31&NTn+_FNg|2$f=oz&B!9Aau}v zdu3pZnQnj!@eC@!;+s7`cw1ODgN7kvr7Jt}DJ%-`A@;$S#v4}&<=&|GjYf=EG;C?1 zZEg!5g)3-H?+8hojBMjDW)PCEIN5P^TZZ_%=^{cE;)1A23(agkc9kK|+g#RdXhAWYj*G>(D! zu5Y(|HQ^#Sv-DNn-7;Woc)3^^jK*`Bi$rJI83Wwv`5SkDJX3|WwXe#8a*C;Qcv9q? z9d`EA^RjY!=1Mwt8EqyUp&h2-Efx(ArE+8lq=m5SC@s-%=A=enj;yHW8^$Rvr9VFd&>yr{VP7T;SDN;|<@iua zSE^WSG4_M4`MfQ7U2(It6O$9X*VxubpPTYKi|dfP{Tdb^0{7-*-*$N$vn9Q(4O^Yr zU9iL5Lo?$cKI0V*=?p_3#B5L7_qaaj1re~(!RZkr8)uRh-PCR$FifhRoc| zjbEf2_;%(Yv>)`2(g62gg@Hy%;V?GE@(dk(d9cD7-C$r~<7^&8*XbSOP>kWgc9~s; z&CNPewB+8wCAyYza`dhvb`Ush7iJiR9XX_)1Czg|rQdNzdOkeyq}Gvv z{{ue1H+bNpOsWWHTlXfiq1-JkCcO!J*64oiE2ql>I5tBi8mEEr{SI?;O*X>sqWrV*|_^ z2T=^JNI6E&qHouW!6RltE!qs~a(!oJX4+DJx~6u!=5V&__qj?TB*zDCmgw3?*@qVn zjq<%)R=HV6r#K@#*EMkio$X(nDgSmO)3up-O-B@i^0YTzN02I;^zQb`cfuNtj;qQ8MTiE;b;wtdnc(>oXwt) z9VIMW(iPY2qVtFv$)BJgq4orE-lpM-%%u&I%sy&Xzqy!a(eBwWcXvZn{*cny_1&iX&c93n zN2Jc*bbd1JF#%ujww^@e&uyLQdWj1GF?5gKaLo`F!c2L={L`cwNhqBqB-0M?T@}`pH0Ek zE@Mcwy_1XEl)Fw~`c71g2Ube+-p#4sgngSwKs@jW5IFxKbB63;&Z+0R&l4)Ds{8>8 zWNK!H3QkxSM^7u01{5>Y*F2vxx;dLx!ysbMXnf%H- z$LB-ImxuGg^#fHn+_#p}vYza0OVggoML}n8ehRqjbxy4yz+jJZPyMtUk11w!BX>Qd zYISzlZcz|xn6{(*VUdx>ABwfXhI!zar3!)FomnWYiBM9uuMD(@bJleuz4p?7PHWw- zl7^+Q8v{d~QeDekthh3C?5P3shWRb7)oycHWsTvDI@Y?*@(bwn76~9992K_p#VHGu zfoM4gN36SxrbM@=V$NKvmd>^X`yC>G z!rrZ;grNR?M7veJlM5zlLuU_qTV86TDXXZMdU(tv)Rrf`rs@?KWQs{7A39z=@&E1^{Y-5n#p06Z*?^T#3(OJ91`+-gUF+QDS zAZsZ2FZ{UubtR`cI;IN%;`I@=sZCZ)8ElJS@Q0!zVt^QL>QE=xp!UZs338UyVDXbd zFAGxbIzXUO;;@FMW+kX=y`D$jr0+m4wKo7fX=-JK5yvEvXf}KR9V&s+!p@CFF8;;q zmhEMniJbpMft`1*ag;*WR#ySVU{k8px@}rnhpzD-x`F)s8qt45D&D3kX+4iWNrPi} z<{*$pXFP_=GvdSbQUCLD48fV_@lutrrB-UFQ(cE748`v+dz=HiT_iH@Kmt0VkA5_X+Qu$XU-x?d*ANxZ;M!@d>7)Kh1Xs@ueS$ zE?Upsbh@}z=0*0~AG%-d)PHYqXC}axN4R~xdZ0LB3AfwKX8@9MK`Hg-O*bVBRQ zT1_vsJZF#g?f~k(7<9KOf6UA7x@~e9XB66YPYPTdt<^(+dk(6?jV9iG`zNGfk|*>` zN`s?Sn}E-&6bdG;ntV9L%`tdROf(?%KjJHvxU1jQ!%SEXw{WP3wuYkiQwd&?*4@TU$sXurdb}mhY?jgJ^2RDUR%QAi~U-412 zkLF^zUv9jIT=t&v>OKB*DEaS^FqSFHM$Unr#w5D=LaY|zZWnfXpRx|R7dj4SC1%l= z90Y8LQXqr(@tOkFx2yGPz3Bb~3Dz_9XDTQjH z5a|+#jQD2N?5**JiwTEbET#7&j1c4yH)ym3>(mA-G@{7I&|#YBZU-%pc(_piC}T)a z%Kq@e1=M0S`CFG-vlg3K#-WMk=KfGuBUEg|fEzD<99*BO|L@Wa07uEE`t$S*bAz<2 zYirq73?Ll`{O5#4<}%P-hW+lZkIfId>+{o=cVu~gI6l5y(D#a8T6^GCec=P=^+Ph0 zBTgOzT}G_8QGzkoRLs=Q?!&znjp+GzQ_R@~*yAS>aC$jKJ1fwZ9!X!X-o zM2@rIIk8=yNNY>LpJ zx?mCHZ98SaGUIb-3IH)4DoUWC`ye z54WlckdFCGSv+~3q2DM#uny3LSaz05wn{AFf7IZ;j@TpbjoQX#+Qhi$bem#(BCYwe zq(b(8`G_M@rn0{C3i~Lojh(ySm;%y<`1xdl%ZD0F9{tXyny7aLfx(l$Tj}_n;nnlIQo>8m6yiy6{Uw?roK7$gj9C8M^W+*+XW%BR=Z(d#@Hw%XP7&a%QXWr zdDwCTVYQclhzLLh-=AJ(3VtAYa}*J7jh++*_GOoeD*N$}!}~MGPn;za9%=oFGFruZ zT-i4?7?=xh(*Ed1!^W+(P6+=wx7vO3NG=~98d@Ao&L81`dYK-^+D)e{emKS<Dg?aeZI3BUpMI5p4*r zSFZxThdtBtzG7JLS%&7NZYYZwD%tmfL`El8&34o zh>j-~7@~1(vc5jc<{dlKKgOA*7O+az1vZflE4>!?(WLWx)aX9lh?<&C*m3ERa)!tZ z0c;O`SM0u;{9caPFN8+NmpylRwlQ^~aiku81OJOICSb*O9ZZiYRqy%2 zdV|}6VPCLTp#Z~najG=PN~=pP)GYm@VA#i}VX0XB%WmdA==`L1vW(AI4x8ns()hSeFQ%5vRqMo<&bihF8BXaaiJzK;O9`gScr!Xy%JCMF z9Y;xNo5k_Y!Y%YZ=P}tLqmmekBT+}&(~Jz=!-6Q8`X6H44`ca?Ne-vm+V4q+(SAH% zj1t}rE(jBFHV-?;pWEJM|DC4o&u-mtwm{C#k&L9JORc8Zs^BtN9)s0s`YVLQLx(E{ zn77w}wi#E6ff3T2&u>>wJfB(tv+t9gc-M<(ndxe}_>{V~iIL+KiGKUJ{Ptpjm%OH!Vz9=4E{hEx1 zb53OBX-nTo@}CV7LJW=?GPs0PRa6C*;~%B7+2LQe0?+Jl>nN-kJPh_`(^iG7@lQVs zQ2jO{`U0`xZ#eupWf*aIVtvFPMH!lAbkK}*z}-W`5{{uWY`Q`xIkMAfpFR4+CZM0i zdM|L{*qsA?th+J(rBUgiC4Syigg_`l%_3%t&ITYVKB{2VZHswg(LoZsouR@AZJl&5 z{_-!cQl;}p5|ESuW6U?5hZOs_6k;7T=-5CwanHmo4vMAyEF8;}v=a>hixxWkmKGk& z8Y+jGx>Qd07z`nwq)(P$jw1eh z6V?lCBK`wtvm*lvCHgOr^nOp{H>bQW`te96mP`0b=B*O({+x56&6@Pk>T1jSZnIc) zetsrnyxJffpI%EBDSCUp?0!7@rc*hX@%p*c|6L6SM*N5UX0$`W;^Oqz;f`EmT%$-KFqoUODPUM|%Q4XgqK@hPT z^JA?6wlKN3Y(vWP;#bCgWKXRPCuhIt<|N_?lm3&1$<11xNq~wsav&ze2T4>=TMwZmu>k0)K6)V6haXhyzJ2p4FCI6J~uZUz#bN|7||G; zoVxb5V5M(%O2uBlxcsaG2IFVX4)d)~XQ|T>F}nkJ!9nI%7~0{=RN~y&Jf|6F6D` z%3{q|2Cf3c$o_+cLVUs7C~`9X-hFwFavEMqoB0b?@IFNL+8~SL8pSt}k3K$;3( z^9C8-_`qjd(1bpH!g*R77(7P;4f+b1+;6reC%L&g+vC3hHh`&TXGkA0*kOF8xZ0C@ z-W0lwqC527b6y0jzU-i$;`-w0pDQwF#?B$<@_j^e$X_$ux0m{3Q0wBWAcEK54HvZV zl1+ovsYjIG&rN**po=NKE|yW^U&oszRO|Rhu)iJD<|{;JFP+C+wXN5f0;#t~+igZk z&+5#2=vI@LX(clIqC15S_V~C5pq&(nVSG zZijVwE82Y~Ks?}N=G|y{>zix%hqS+J_03=wFQwAjG8dg!lxSV`R3c;RrUX{gAF++r zHxG6dgsP~&Mum_i$kKDt<6svtDZL@_71*3l=|V#bGM(c&!jc7+ROHWB9t_ z(SD$=p-s4Y%i;Nl7^kHrTG6>Xts^ zNP5}rx#CEt;A)&Yf)kyktV;ueyE#t0mFibx;Gjm5pzZa`O9^kw7WXk{WZur#TE3sp zYc@yA4?2gS^W)I3y<)h%cym!WFngM5f}l34;0XwZM0(d*>Mq|%Doe2s_|Ws`^p_Nr z)#4R7_TLiQjC(vHU*(|$6J-aW8Z#GJjJTIMwx&PzID?ixqVL4n20`aQIG4$7pFaG> zq5q3&pMuBqDBJaG@bG9E7}T*#HL^>+7=Qp-ZF^CReqTuuv7CP(WvT01L;7dpZ^PPj zFRQlYvorUFMMWd4Ervbo&UxA0A{&F)2g>F|D0wL4i+;>io>SAFMiGxI$hV!yo^5k*`zY>rf`$+CN-;Mc9SCCzC6$==b1&dO$#-FeWACT75=W9!^P$G0&DL_V`HQEnDK;0OBc-P(CuOFaB|~m zT~p%M3X&XH>z{divxBL!wo+WK<106+P?L=R4^jM&V5P!Z^Quty+LmWlY^wYrE%Z@I z>GyA`%@1d6h{4bI4*)du+MebfSW}D({P;4=h7Sv3$(IV9=gtst?BG-R|I>&#U`r zJ>>0aJx6Btmgib8UFNWq;wLbhlvqq=<9=5S`S4NpRm>l!wO$U5n<=_Jn2kuWu#)Q@ zRcyfYZvc6$^*k5_xkAw2{Hat*mHI{L`H z*9NDWX(cO`d&}qC$WykOC~}^$JJ6k*ye{S|A(o(kf=) z=NDL_u3F9J7n2lirpMOZ66M7e?2H*6(=29AEM6^o!_rDKX zZcY((j?hS?;Og{*m0nLG?80Uo@#2}?ER<;BVnP@nl|Y+290>Gf2O*ZtW{H7yCk2oP zSEsw3w&?a!uQT5$+8ayFwr|n4*dfGVduOodSz)Hvd&k14BoEGU5^wix#^B zK8?e(=G`VNIN)9Ds9A+wx5*B?I|rBC+{xVk`k{idC(QqH-J5#$Ae=^()yT=o32_}e zd6{%NS91k3==|Gd8@b0U#&q(>E7I{?q(3BB5S+(vQQRIVT?M@X6$<=mI|fDu%yf>a zbXq@C6sNPYWA9l1{o!!@O=)|rw;!nVp|`WBz$+%~U3&M%&Bm&StD{~(yH(T83(dqH z+eEH@8MWEpk)LWG5#`v6orUL7*4$rR3*q!+jV=d+ajL5%lSkqMH!p^~X+%ArTzF@E zVI^`q>u6nBD5sG#xuTeEH0NiVS|IDR8{2yX4-_Ub6+(2|;)Z*+Mwx%d$j>$kX?X~6 z!jBTckZi`&e*ZZFsF}n)-nE7Yr3ngCve)Z2Ay8aP+Mf)uH@5Aih?%=Bv12p*?OHM` z>t+Z)TktwK9N@IS@OE*TaP~&p#r?`#J8zrs*duKlA@Pu3Q-DP8ZLvg)96rtfR(r&j zyE{8Lq8A||Xk2SV{@%ahU$YhQT->A;b@B1cl?!lSiJ6$-KKHH~QYNp6!-a>&wQmqt zbAOw-G~?ArYu#`@f`u1Vna)WY!m#Q|YNy`4BV_5;RWI#;H z)6bCjqCR*=kE%WWxmJXm+Ybzk+v(F-4}c|~0jNHJWFvbW^9c}oKY1@R?tJq5tb-7C zW7phjYH@aCIgT73e*&y^_Ls?&qf?=s*1@TbJzx+72Ekt(KGr;Os_Gu8-S*E>+1YDK zVf6-hbFiy>tvAO1bTk*!kKrZdLuq67du4_Ok;9g|wke{~ls$mpjRMs%zS?tIn^1{H zCDX5l40>71*c58JbeVPAJVY(k3lNtWN$gM)~Py zG-ZymU83mna}TYPK;ipA+G(O*lhy0RtO`i2HsyW982^_To00g(kJ&@Ns1dbUVZ36p zt0*-ZBCMu-1w>?L|6SxA2Tov*;dug;Myr7Vqmz^;XenDtAHQOcNm4)n?FNvQx5{sq zW;b~uwrqw{*F$SZ_hUA2t3P@S-rEEx)bh5==Vf}WC^!_GI<1VilQk3?Zlyi_v;2L0 zwr+g^(&x2Dkg=OaqQ&~NwjTJ~Fz>}Px8vrB$)wi{~d|rgB>?)Dz=%8ZC z1}5>!Fz@Wk@?|{OK3XJ|Ah-8s>eqcuMydwNYM`>7VHX{}rKXcrdA!pm8dejQwMF-Q zr-@YK54CHP7HI-@THY&6J6}Ov@~;=FT)OAJ6qytYoglF#8z3}Vj}4cV}$ zz=W6C9Yq~HV%>FeA|-Ih(0;;b>G*pG&F6_}{}?NRZnHPKDl$%BV{#UlFjH%`Zz$dm zhQ9OKm;5hTSrR9sF(~;&`ePUN%Xerm`8d46o2H|X%ca(yaZLj>bN31t#;Gq;4nSEn zVE@9cZ0bJ@xQyn=m~O*plV9y1MWFG|q$;yoTS|99Y;JIfeX8A*KX>sbcn4IUJxo3H z;Kd8Td-1n%P1!d2RczN;f*EmggvkZ=tTj`$N6y5n?OU3)6Wu*;ks_Bwq@&-mp2fXb zn6%R2!H^*&O@diDb(JS@253^BUu2Usok3C)gd69?$f3*P!o_-GhW;I5rMYJp z_?B?A{=;))kN{%De&ThIn|?a^RMD}vbuPC>Be*Hs2PJBP3t>aWqEtb8r}VoHNyDe!Ss&ru;G)mij8zCL92MR`e44l zH!-%JTfHT1XtlVFF@0f->^h>&)TV=ngfjL-HDv#|iw!B?J&FCYZr$MN>Tm4GC{Oq* zr<~FI0LJ3*LIjsqC_?l?bYyg) ziH#(@VSg1>kIi6f?tKU@&{J$a2Y6k|g6jlgJOu#lPyWd09`Gxi>{whIvDjs#yFb`y zojk8kJ#RC&%PS2;a>5*o^UM8`_bCC2SF#kcQZ}D5IB?6%5dj^On9l_?1eI7=8Y)*Y z=R-oZ=-~aek0|(E!Sq8GfvrEuPmcttUgdl?qT4=byt;s$tyLWL6Dkk*o6iLC+J%gA z2E3>*syl#f?7C2sOo;Sg6uO8j9=lj?SYKxXPqR(W368>XB%$l10St>EkHlIcJW@ki z{+lssxqp@}$Ok=m-$(I5tD2d2)}(kr(zzAm`%`0Sik}rc*#A*Rf+vZgE9&WfTNo6a zLlQ6sWaBWfjT|7{e8Sz39&U(N*lxoBmAlZ@=EyBcR2!Zc?c=S3vg``f8Wj*Ar!elt zkS%{t-Qrc%fp}oSd6<2{)7om_`a5FYdGC5d(Xi>Eeak^g>He0v9rYyra8_y9a@{Un zt^2M4e{U)F{c`qPS{Z^HCxGd%tO7d;aJ{H_N&Z-vI&V1I^y*(srwP?^#Z?sYJXUNW zdL}?aRCp)1q&}#qAX*k0HwU8B4zL)Ju&6sbP|DTnxFLJY%lE!i+K|vX14dZ|{%A+t zERUZUEAf>->~VJ-8=@kM069}aHUGHS6$KxE;b$c4lp|TiXG=-@^$|XvJ`Qs2@6>Dj zfF>mQbMO1|4+N@FhA!J2`%0~@pcSl`M;PF`|Iu~=ow7bC-h57>^AIox1q(IAJ|4|Z zpe;oK?jh;sj==(Oqcs-u1L*tjr&RsEOaRLP36fh(V;;OaTO~%ev~+{t+U!o*I&mZK zcas2IA`~v#hR&cQv0h9uL~yEC$czTMi*x3y=|FPI&@(|?#h5l9xgej(RRi`ehOJ=m zug_wK#1L15&w1}bV14`K-aDuph@4n@ z4!c<8tkju%E=1u7^$Ie~qCPt-7@iNTwoeO+QyuB!&0fsp;BRCj6mTgX8~-s`?~MhJ@Qra9+^WWbQ!{qf>|Ge-jmZHDOFgqqMw%)#kW~;WpR}nS)e?6Bo1!uJEf-eTx7sALD<5m^oIQYHzEl4Z5?6PLsIw74d%PTH}&S zM88s_oyy6$Eh1Ps#8o)1^(P*k3imawkEMR3%zmy#Qe4s>Q>&HTTES%5{Xpt?gT%L> zu+Z^fsrxstM3Xzs@g)x1U7l$I;I(6nrwx(%K|c_K@M{|{4t9ToNW zeh;7{N=tW#(v5Tq0uoY+bax}t-~iGcqJT7r2ogg#1JVdcO2ZJ+-3|B5`}6(Xd)H#Q z^gmyRbDr4G-unsv{1ld-hu7z!Nk-Qsj{w#+sZr8^v1d3FPoztTr$^mEd5XsFKmve% zOHH(&fte^ryy`Fs*0I68#~ zrA=t5?t9(vcv_)@2Y_*zU9viP{Ex9&MNy9;UI_-2oI{(Wl+1U5`WKAbmu=xAcuJq% zO&WPE)l3>!5kvh@*A{Hf^{-KOFF*7B;O~g;g7NXhM76!#zBF6!c&wk?Vx6#uQ?APm zB3wrW%MocCXIIeU8N%+sr=|X_g~0=U!%1=FB|R&Qx`#^3%*~urj2lv<+PBv}sUM&I ziBJFV((Y#Eb|$MZS(A8lw;%xh3(P+c_SGZGBpF`G=~r34*{ud<0$q9O&W(|2_&u&_ zy2~LZvRWEtuRE9vZ``A$TlO*^hym~&g}B&5VRqSjxVuiF<)gy)2c@|(Wqk>P6cl_9 z3!m%10$m_IJELW90==1tWXw{o*$%MJYXZB#TENbB7&Id0Gf?%~M!SXe7H`@2Z0U^D zb?-TCa{X`Y`5%Wy**;SDf~kmOw1O+*Y4J5`(ZRBul2Sa zdVb4y*B@{huD&;o@WUF;Ql~I`1_>~~@%^=bN?TNDCzRs3bw*C_O&b;-2$imO*v4~y38uTWG0Hb<$?lBJnR&Rq`v=GQ z$_9To{d`VHuqKeJi*#7aICo+_wxc&89IgxBTVec|$eM6st zi)2E*H}@B1T@#b|(qhkvZVZ-9Gp=2T2A58*u)DwnmEuGad2$#71`1%O0@UCU2H;r& zww8mFrpT99W{%#Ei!8B#%b3D0nrE;0@XtDp*UH0HVz1x-Txpz+ICaR`V%IX7XS|}E z^Sv&;*!-#8TFL`u>PZ=y zv8Iz8%kTmumi2;qkBj zQQjZSbU2F_0_|q197#}Zj=&uT}ysH66czy$<-P8A59c&=Xo&I zeH!cb%7nBl*;toEVr3EcLjCTa`T?-Jk>0UP9pz{DquiX`n}52XZNd| z3j9yV`(qf`p5|5)m$;OCTPU$m)qD7q{;Q&Fa2Wef#eakan|AhtwTh2hp4?2-hyf~y zY6GU3ZeRl82QH$CZsDdg8|2vS;t=SLDWxxd;T2-E20}l83Ue7*RKV`9u4#0JknqHM zmUt*E0Q!IjK1J#Y3M4?V{#bepty@UvHi1)9!Gc>(%EITOet2FqcoB3{hQOWxC@dTY z?KQ;O<2bg8MtUo1GT?;aEBUc+feLZ|vt9u|y%PBf$H52{DUn}o!jG;xd>=o1J>q3% z_TYzFjWEamVKBel?@PyWlegQ-=Tp~-=^Itpf;vfuSwsymUZXD6=t zckl2+U(l4ihD~Z-7ly^w;Qae8p|Gk6i24BA(PP8bOW=EoD?>P=oyI5^5fqWQM6ffs zFTbjQibNFCo_~KWQ#>vE!l8OzY+Fny1SjJCHB>*5U9lhuG84oD`TUnZ&6lXb5SMBd z2ME+5rsp=EE2Za%poBT@8{Z-qN++Iy!@1aW8<_i$N?NyEc;LdNGLp{UAeva|cDnNx zD4K}~lDlehb#iC>kDHf;TAblFHFdwtGXdm^+e5qd$W&YS(KjK{#S6Ubn|JMDb-zq8 z-C}T?$}<0Ddg^!lY04(|iEjGtE4^&k>TjX#>FZKqh_Zvfir}^Eeg> zZ{t7GVkh}zL zs=5?vvt}*p5X?ET`aibs!7So#;>0bjeIID)xs4h_{;?!6@Pv=}u7Cv7@Wr+KPfSjz z$xK2CSJUK6Gm0>8sB^+Ky7B1NM4nH=WH~ZOGJPNm)SI7LF?TpIt8tnpKqYI}VUA$gL9BP@_33=bU88{qpIpZ(vsL>W#!8n8=|&42ayig%{>DGgYuc6`Bby~{{AV# zF4stFC@`B5m`n$O5^ykcAm5Hyk@qiz7!Vm4K0QE6!bdN;;6wjcEu#BI{?<;H0{1^UZ z>_hde#`w%r2d9KuCfo6?4m{mLi#od;%>d4S*(4>)Dtb_751JnFr%vKgD`ZM(e)0$d z=jmt=GYAX6!wv)V`Jf-~@_5SG2q{{tP$It=5kE?oAz<{4l%1C&_r2xAdX=(GFv{ zaCUUOt)|0&lZCia>?k28*9$<9@47c9YCZW=V7=RTLeO}0>8#D071V94Zu!d zkODA;TxR+o>qvAZ+U{wnWzXPofe;pq{w2VU0aDY5a zUPr9m<%L5Iu$BViXT2N-0nk$y?i4;(9Th$K7gkv9BTu03I{x`=x$-}$9{iJgfk|L^mI3zXZZ1K`-G{puk* zM8S=H6sQBtyfTw1CV2((&<^4^mz{~X{N!3AQJyX3`f>gZ8H|@|sTT1mhnc5RRK#li zA5+o=&4%!Ba_h8J>PewE$YFr9qWPAGOCid}4dRcLxwIlD^kXT|FxKSKxDspY{xC86 z3SB$7sweWy%9KF7+WDH5weY_13C7YSmrOj~Q>*@!Bp0k!-#0zw0x>`nw(%3Uh}lez zR_3)Ln2{#}*Iz);#EZAs?=(ibap6A#Bx{=N`H!QsOdx6Ne-A@KciYcSNC7;hS{mud z9sT}$Oy$g-rW`6$(Ia^+jpX0M-N6JWxX9d=NPQgR+7^AV{m3GYv7cY_gGq6N3M}0w zM{<&qR;YCdkmrn{9(`IDE%$e*_HHjp*EVj~+N<%z#aez4>9VRIq2G6k5wVZ~6Zp<@ zfwN+3$2K&nT=+{zVE$dO^AokLkE?Hrsw4HU^BHuH4%x^Re}DB*N2#7w1{kBc_&+zu zd&S>v(MZ`c<8>tbX*uJSSZHUgE%l--8$~l`?F$3ejO^@}HTvJJcl);oBt1R0!xdkx zWNDZEOW#(trJ^i2SF>1|L8~+;9keHUafOexE(5Mjk!&&XF&4l-qhhJzk5`YBcvyO? z?=#O2p6HOp6!jZIhgM^-C9zw4zj@5{v_v-ar^_9=cB^1%m_ptIrrgD__Yb$!{?_~j zz7;dx>!Dw8SF)Z?zybKj!ND<}IM{zHu{h(hI}ObSvLi$Ihv_4D{`sNoKGb$+R<4u_iO|fM=|ikfzyJD_ z@Js*0uku`vw0HPsM)Z-CYW-t&0fIBnV09N3e}#O>;$0~b%b)4Ax!SJ@>Mnz`C-zH5 zxvuU;=(qqcQtfLLe7<5Wh!ENWsQ%si*5!^Qw)h3CR_Bh~sZKpgUr(@fwS!1ECDC)G z6b&U(fVmtDwgQCSmapBZ zl#Li6b27**pXkkYsw`6VGuo$YdTQsZPCPL=0vb@>>Kqo|A99p9mDFU1p4IBTa4%?KKjjD=ArB|eMv(#rE*c?KdInK(+^&3#x4-b_BbUal4^3Lh&W|Y zPW_eF+KyuO{~|*@`)1Cx;r3@S9&^uylO5I**2N5>p+ zDaO0wfV-Dq4i8CC7L)*n17$=_74PY2$VMjF^7DutP|UQJ4=SIJkEtU!&GUuOu6RA$ zxvKf{-3EUcKUQgv;8e)`IR~BE@7sx?xv1kGLr;n=>o8gY-t~$jIA-)t5>Wf^+WnF5 zG$8Ik7`%}B3tYigTzSr78+?!Jg zLK=UP84BcvtneSn)HN9|)lJSfF(6x_hk;gwn4frw(Yil?#gc;s-}XIMv@UjQ&QJq^ ztII2e3aIvZM#8^9UK?>^)WICo5&A5fy7jhMV(?t$vWHPkNh6k-{Sv%0-48Ik7TZcS zJ3iJVef{u?#t>~}^b--SSw{~WVNIBQTYNdnUF&GCNc>tY=|MiuN_yioH@wRwMLl_MB z6yx&`@2;+gKT(1nOwq!^d{>BlU+Iuu+0N10px7iC)OYu;cxED|JB_? zu`~tgcje}mw<>pW3tYO8Y13q0Vs=nQX>HhlcMO$JI_{zKglIlu$-x!GG73&}76{(Y zRB|nNgO$d?z~Er62CEz>XaD8%_j)G=^Xk!tNHj9-xY{OcGw)RXkT*Qy+eqg(`^K7Q zF+w&q_u=u_=p@#Qjhg6f6-Hcn*Rc$u0EWMq&Lsx()qXH5wWC`wxcaa{g=hl|I%^+Q z05uN^BbvE{3bG%Y`yF!(nKk(c*^X1$me%q9j5F7z+{0*v0Hb$u)mU?LN0c|;-jFB0 zOrRMwzhCy>xjix-yEZazjHwFnBLxI=Jd^u($D+Oukz8}Dhd8AVNZ5h=)#~$zqJRd; z&)E=@R=zEvi1X|e&(5FeHo?Y+_16esN9B1IeF0YTdP&jII^XM#a3R-}|EKjjJcZr6 zWr(fbyvs20&K#rK=ST}5ZJ}j9qZFU)_Z=McogX^Qr8}qnCy5D;E|Rf=C{WaK)MZqL z-zQ@G(GzZ22&QXk2kQ&p`nHli-72v-ENAlzk=*MhwVo6i%J^pdlRPP03li81oZ{khrw%9RI`dE>JDZQ^C2{afHs*QosxM{p-&CK6G0ODfnvS_l&4 zXys`~i`aHMj06;LNN)Mm;4w&#$;rvJ4Ze4yDSK^HF3oG{T|7Oa)^5(yoZpnr4Kpwf zKR6+0Jk%_pE<-UEvKcf!l5sxkHnW(U&dBCu2;0mk*qI>clf^ zIW6I(2l}|q!mdHxcInkb(AZdohlC@OnB8kdd8`_51xfQjPcVDsm@|ieo#cO=gAB2JGvJ`qo)4d%dbNgjl4LJDORUNi&YD1|3%&~XBz&N{qK`JOFM|Hu4`B;9!|Qf z5%3Qx64dh&s_lK2~` zlbuysZG@{YY;Svht!wiNp*k2A8f~-8e!y6$3?baM#DvG%MR$VM~cS~N=GqDdj zV~EV!W~&8dz6{dW_s5I*>(V^NvcB!Ljn;JI>ZX*5L-^}n>6_Jl+zS5>^Q!>|j6jc+ zArZc1#9H0dvPHkbHkVm%5a;@j39CSj=TZOhZ*55L?k&$BC-(*eHIkT}p{S0|%?43(b5xp^*#EW|`+mq^=a-|@R{ws_(Tsbntd_@vHz z4gdBZK5|&Jtn%0B?|sbudbXp#S5hKQ!l=3aX3cTgW;!vBObzV#nw`T=LwfFHF)6hh zdCiBqt^bjE`*seXBn8QW*1AslKqI=c+!dXi_kR;dbZsEw7nf&S_6drpJlRt-vTu0r+v+nE1)(8HLXs%j;7LE`p4J_ zm4tO?g1LxP-v9Ap#cI!XB?~96T{wh?kUiFO0d)Q~zE}l9K+x}u*18Z}Gpj6-Nq%d| zAGKNqmVvoSTy16b%s_RXD_)JOP_ zo~~MgX6j#htns`!)qP!MvMb?}sld)rvcM+}&pCeC4ojky+pBJnsdchUg#0YeF~YS* z8OnVT{_gJP@=xnv2;zU^$>p;xp?S4OJLL!cG|fqe^jNEwFTahq!E>P(nd-N=6R^^U z5TJtK732#|ggz-~-*0O5Cfjd0qrJO6zXw~@Symws&`;q|3Vp@_*gRx03?z!&&?rM0 z2ODgJ_XX93dcb)$%77V_zEfxa^$~J87yNpDU*BKt8Jwp`kXPx0NtNH}9|zx3C>X5` zq{e$#kRT?D(rt=Q=~b3tCVs>~6>3|S{jHqz{K+fcN%^uuWotOP` zHC)d;Z{>08imjFlLV1+hDERc~wPG#pLoP zH}aYrU!)wBT{3iPj|+D6XF2+lEiNiY^r_gQUKtR|$%c59ZYb!ZDQV>O{qiXIVPh>F z<2Ow1K9sR1_2b(8{P;}~?<3#Fq0**ox4U&8+A3#8>CZi@Nh#u3t?JNCw&u&x^issz z;Js9bNst$as9UKuJ#i94!3+f=8qH!*oO)QS+#l zNT|yfZvw}NnEKxL&dGyY^NhG*k}tnFwS>@P1SLG& zlng92dKXA7zBH=%ItF7TD_O~oMcDFO3um^z)&%wjk;K~-PQP19z?lC3xB$H?3y=N0 z_z7a1p-X~t62tRo1etE^efz2T`#b8z8`v5PL!P6ILZ0m|ROL}5yXHBpJcl`X78-|L z`{zwxX79X`@rNLEF8-Pa_3Jz9IesFIH~>Og0lV6<*a=s5laNYY?MsR%le4mtrn$t#K@^i~w%WFRnQF6-2 zZ-n#}<1OKA1>9@QcG2^HGyf4FU4M5cH`5>MtTpWov~ z&Zz!L;)gtjfTnk?Cm_m;?zv_;CFQ%43ze)$DN-4ZRS!;k1O39ob@2FjAj+y|qj8UNt$|9L z+*Ww0ZcIU?O{;f=P`8HIY_;+TxN$kDic8C>Hh_w-4MR*+PFgk#fMMpWi#Y8Q0OW~0 zk=0m>e7rmhgb$v(GbHxneaxm}k>X8W``y4X6C$vG2$n;yOxtARxMvn(I>bazWe`+n zuPnDT1MUdG1Z$h2tw&#ArjCw}f#lczw(NaDrToS1bhLCw-F>Ue%J|_M*2(_#y8>3M z->3WwLJJDa*)sC5=Y4E&c@u&mF1@VKU5n26gZ{LhI+}jJ6sA_#t+%kfAWlKiFJ7T; ztmp%Wx_$_KHY`tr_d#z3o3W)kBgNzkJxsB6oUN%2UnoIh*D^nX1tW+)kKvHEO#-L- zX(;Q{eeH$>Ge#N5?_=cZZrRf;VXj$EeHr$Kn(9-e%ko$66rZW(@hm#Ij;NmO)|T6u zou8nl(ROhnkOl!res52!ULNdpI+9loQIA1t*RGUryU(I28%8(sxjR9;()apxHtNc= z?90c%11z^NdI`I!Zoi+WwORhcWBDI8%i$D4I;<|P6*Y%qSu|W`lJsLZ;FY+V&N^;95GLkq7X z7o$^L9V6irHm!L)fzN%Qf~p;vUJJnY&pW922lzHj7CuEZ7!%K`;?H&MsRQCo@Ab_u zxzc$Uh=KODHptcWH6JhUFkc-{^u}ya=IlLlaN%r`y7#){s{HtF_wiNcACHaU+zEtk z2m%1^AAp^LU1%s8qzh1tJdJ9xPzi3=PBZ*}FLuqQcqCC`C#yb$gw3DU;ILu1;-XH7})zmeK}dPVNUA$xMHzgOP5<=h_U5pdi*c^k3F zA8{Tce6v8cy8xfyGY&S8f6xlY5!y(LBjKHxA^BJfR|qk`Nh>5Y|x$=C83g<7Fc z)7K&cM-h#r@sS#%SwwQ)y`JhUvGp}BbvBVEBVI#Um^T|Qt9T!Kj!Zf&jmK|XAI1kz zo7^3x7=e9EV7&p-WjRXH@67S=1gsF^0W*^kuy*hriT@aT>Wn;Boe(|~H8YcoE%7Qj z6;%hI0}HD!(0kx74Wie(94zjB86=vhJ>Wl6^2Wu3A!DAQ$^}l4pmWff$EWV!{}b~Y z-E*@K9KV#l(nNa7ZQ4(|E5CixrRwCK5>F(jd?m?kMOMIxE=WDv-Vk4 zOlFdt^^^=io{5%(Jdh;5&uZT1O))F1C5GHG3G#(26=QD&_>P%yoUZ>-tF%g6K31pOZoLnCMG`qS@Sq zG&~p56$;bMgE8Gy{+r)LQ}H(;{eK}RhQBG(vx`J$ac8;;BGfKb2Oj3K+fCz=b=6Uv z_g{Y+o@1$P-7Kmzp8=+z&rb##S{}Q-4g!h1oJi$?Zg=P#-#+mtDoqib;V~IfYQpJQwbiV7s)!zxIZ}X5k6Uh2=k9v7H^; zYrcr^gz>>QtlS}7B~iaQ*qWX*27C8a#p<>|5yx5Qi-$dQ>+e+=MM~PObkB*lJ#_nN zv@TRpnzIG{dx8+WLo)AgktX?w%RgTFXR&YmO}6KEJ!!Vj!Hs@CrnbH9)(U@ERD&;TbN~b^CU9wo<`7x=EdR*X;oBZfdntdkJ2joDwIhDFwq4i>UjSO4CxZ zR$?&OxKw(g$7pJSjgGDbKh8o&NdzlLJg=itNDbVTQaW=(3oluobWFeop5ir$h`0w-6HJ z70#cBl#`xhs#?3UL!}#sqv)>n0nPAmu3Rsu06ca9K(7akOwL*fq}XKJW0UCgaY|)!4R)W z>WSRy`6|I0#R2yX(1Vldq))S9j*NIwdj-Joc>Ya67$*(4S4c~1GHA+!)`=9 z!fJy>TX!~jPYJHu4vd4BlRZ^~4yXiJ>NfVLD_n40eH9>sH*in}4y;>7N)diPz!uo8 zQU1<`LMJZN|93?vnbo*?=l1CzDqG|KqJ3tfEM)CLG=m$Eib3dC+R*kBxa4l|DM(qk zdZjiM4YK?AHP3@5E5~m8(X-CWcZPylF^iqrNuik-Z%&*{{>{Uo;>d-?Y;uTvEH0&D zoeVknQ$T?C0VbLked_+BBS}N*wEGnmd|>?xho;384uM7bdiTfr(Y{&X65b)t5~-!X z2v@)E>%o00VwR;z^*@XHs=;>lyfHXWN|WY=Kp)#fmpyG+^1=|k~&+(k))@z-DV@wzt2crou<3vb(YF*y=fWx zcFq3)7kby_&Pc8v-SZnD+;d*qB}+!P)Hj>QZ;R^niwZxW>XO_)zwJJ5Wc&j?T$Tsh zp1nztR0(oc1WYnB)J(@TK)wlMhZzeQ=2V-w(mm?t&-Sysby~%$lr9F>i&=>WxO%R> zlF9LzD0ff~$|k!DXbZ4uy7kn@NP?)xNP|HXxVg$ir^y{N=56}IQoLg4-HDh&P_l3- zLweFX>8b6-I=YtH7ipa>ITlYbEjaDGH}{;-NGp0KJfDe>5dn8&_kW|Q|G40 zqcf{m&fYP#`2J?D!k(RncoKov`>nuFHgm@A{d>aaZjy|#P(W6a!RLJ1{%~rjU$3C+ zuK)!Ze~lmU(<0c|aEi=U>SyX&{&Tladn`eC{PB~liMPgwjX9QS?853M+it>0Cj#Vx zx>J{?4eY?^15jtgQn~70u!ya^yjk6Sz!sIW>Q0H6moo_*g7PSTUSB%Qc-sDx1$MWi zwczPu!s6n^vLwvi0JZvNkX;$#V{B;XxO$$MmWBcuT1uUD?caAeXLPPhoI6ND2y-s! zXj|4T-L_YLoFnwQosd?X^|}J&RnQL=l zC+|ur>@J1xo(OZ=AX4_k=|}oTe2w1LQ#U}O~I zG*-f!4l@W>>4w9y60?k<(h{!xzA|9`(vK(aPHxH8G1 zb_vbgsR!$pfbU%GT}$)a4PqI(--Ox|f1g@>Ky`j80^|KVAD3vw-9yysM&4=>Hi3o- zzKen$&lGQ%@%=@Fz#pq!^{lY7|I0;e+jcCGN!YT^mM!;IfjYAxBi$!E5$ML@?>4QaLno^mE4IF*;hSz1ZdPOW^0{*KIHI&YT^OufF+576<3Om zSR|g=-^59euk9j2&z zoi91(pdx)fJ6{zYdR}{86#^6gfLpwXn7h^Qjmn^aU>l zTX^53f2B)6b=~c6Iknqi14B1z7LkGj$Ka42uAexuqz`(| z9avAR&gcE8_Pe1K6NudpK+MNIOsk!%b<$ZpogAw5PZ`qDWKGT5CMa;)6BOP>Zb%Lb z6Z)cF+n_mo)T>Pgt1o>xk`a&ma+KFtZTysY{K=71QLk>FzR?>EGHT1kp;5IRZC7~R z8K60onO_}0(7BtrbP{vAwRzpAPTL)D$zuXpoF5~5M+VjFnsLs9nUpkxp&mRhQY_nA zYeDakbTfwDd|XX;{G?%dv%IECCj}iHVtLhpKt95z^_-*s+>%IfEJlwnmqV-@@hr|l zS_%zPDD;!H5Eata+w_uGNGj~uVcp<%>x8q$@5Yl5np9mx&%QK82)$i9KUEn9=}^4b z=t9-p--J=jGL=rxDj}B>M8-!;=xnH_vbc&O=1)q)O!c?tG3|+DJ>?`O^|~eF{hs`+ zB)Y+%T$pbEy*=AEHi^U0oLgX52LAsp2xRwda&g$mo0%_v>1j#eZ-w2kJ-%MDUIpL& z?xfd~I?4Y?QeCUu`?}kw107FJI%WA{&Z1>KBkmao^8|OP%o~9=$dNs5W8RZ*mip4q zl+ipKNyfFSNwj#1oiA^ZpzOvl10=l#DnB1EFND|YkGTFmc5Dt7ii@}|%jqoD8L(pu zi($6DdGiL+wqs^kWT{!aS=J8V@{?qDQccWOrSkI*{d6LaOjZfUq~U$!=l*)gfb#CT zf4)CjcmOQj0=T-d{BI$N2)sRm5EuRs#Ny5a(d2kka z69g!K#r(o`u|wLdT}%@5V03ZRqCsRPA2cI2X4Qz76^NtvCARxiJ`k(EmdB-y*h{BR z=a`YFR;jO8IlqhdeWf5jx`$fle=^nz#HWyQZT%MojSNSmf;vKL+B5@BlO#Oe$gf0z`-b|^XBG5&bCOX{X(6KNq_WgaS!bF zgQp7udd>W9XNohaXaDFZ%n1E}#DArno4zteX6Hhr#49rOM`!NBe`i2+1R?GHzgT4* z+!fEjIO@&NQ5cEwZERcAt_o!&vJf@jvz=9)m;wIHm-$Fn0Hb)PlC!;hLZ{X*Tv#(! z5A+26T>D+EciXOzkqG$UzQY`lIcLF}Q8Ve6+*UX%56&QQZUzUPF5-`9CY$%M7jCDG z;U7OfI5|J}dOSU&dh$hc?(_|_<~c6xSbyQW@sO~PP*_)2m+H{h!Yj~VcCb=u;E+gK z;}Oft#Lqlb9m(Mk6R_1Fskzj%b9Nskp#iIj+b_G0he@FQqQ$Z7+787Uo@^J<==XUJ zsWuA{ln!~>@-lhE@JJbwt7A`h+Ni^e0Kluuk;?_ zj^x`te6GvjDE}$hl|p#bosKCp;HD>_lkWbI?xj)8@WGX#`_akmv2-gsaLV|W7zu~e zW3)1Mh(|NOT4Gdccy2`;wz52uA*U;G?k)Auk~%=COT{3%xo&5jJEfmj87-=YG0MJz z>Efq`0YlbXd3o(V*|*~pqQvqKAcYzRLFJjsEkQKF;=EE)aYf=kG}u4O68UFhi2adY zU@^XKY~h@+P6Q+H$^8go|Eg(DcccA{T|eOMumsenJKnTEZr}}b3RgfDNMZ_L3a}Ih8Qs-Ks_|x#h3ErTx>)-IR|EeihS$jNF9v&!R@-%%SD|sbFo@?d~ zexE|^b%?P4g0MS`kiTsf?SN{5VrqwkQTfCJE4cSJ&@dkY*ygcI>uv2eUu6`Wk%Efq zA!JS7i?Fi!*9%kS*Xb|yQh@w~_H=uV#HCdsb(d{S(VPZemy(Y#ENXs=G} zatcRlXI6!ztpKIB^%+I;jJMzxyB8Dg?Sxw0dN;@whd0MVUcd#NRw4pvYB^RTzIu*2 z<&;-c#6~SH)FgkgOS&fd6SSa*;wD6VLvHEnEUsC*-_<4z6~b7d$QwdHmQNbEf<=Mr z*vlB95fCYpe8<#C)Fp}kz6;LGal2*!(_1f;M>x}R8-o_1bV#lD z>6OB&E7kb3-`j{JIqKQ=qF1hLHa`$eBdTrx%Y9(W!KYvn6-%@)5dGd;awpHOxn|AX@_hg3r=T7!f{lqozT?S;Z%&WJ7dFU!vb zItOQWySm1DVVW**Eh^hZ_e%k^IvmFAK9|PsxL-8&u0yefg7#oDYR9yjO@*$}9OGS7 zn?pXvgxl|_brmic&Nr;-=q;!0OD>Jyjqhk#n!OFYu=}=C3VSpO%MsYgrelM% z!jAFx`ExM-*vazu=bm|n+!nU8_-cchL9cbnpHw~c5yUeZ(bT{mCTTg{j~ShNXSI6t zml)@^UTEm(6;A6y8KQm#r_?iWH}N$@TF-k|z50vo zP?7l4#6$uB$|Q5S-re{RW1)UHZ$jXFDD|Z3&N^dMJV|m!reXmwCWSzVh=@`%Gv&XJ zR_`aLr1yXjBmh4x4Y0>-)pR`ie%XgMKSAzY_eIeLPx!`H5D9n4r7bZ-?k}_NeHe`^ zlPmDQk1U?gSZ?H_vsk2G1#DX<3Sg8PZ*6$A|Esypn=9#XxbbsRhZJG)k)pc#*UFRR zO>$^cT_2vH*7|+~DBS+31}1z+@cuF%$$_y7L}TQuMJWO zRe2rR%6PCWxljtr%xd5q!qud0<+S7B%&j*_UH4oPP6s?lD0FYqrS2HwPurTe7SBIK zmzP=>C4r8uo!Mj*zt)Y6IKQ%Wy&**NiPLSdL4}Wdz*enA;Aal`*PHpta#Y(Sh>l;4 z)5_ntcgomvLvImR1=08P%3j}%?^6okVT5?^0jXpHGt7nf0RL+qafKd?>-8(_uo z>u?&ZG*n|NLZ+)q!tSXgO-@|>g7WRoZC_Bg^rs|OTvyKPni#%pdHu2=>z5}~-1pQN z_-<$wf+GZrEn%}8w&SLcj9K`om~Dg|{m&Ceh7-*`JwJHDmg{ZVtfL$8 zVzwKV)``M1V5)~JHuTR^uKQ{PzrO7Ll`nJoMzI~Ud&`;u7(3+>BYd|@hviJ@(}v3! zG2VE8(KOvcgEd#XetQFL9v6&*I`_bUWx)oHv02|B`;~D*u9JN1wsJ$zUzOsGqEplK zN}O2bhhKfsp!#&a)mh2C#j+sR=e^vP(H_kE@dI6jLuF%kw`=q_Au%f`f;O*<1tbHh zV$nbz{29wW5EcnyIrd*{UVgNz=vzpd=*LNW2d<^bfmCpi8vRE;byrMfLpl^k*C+;| zCNM2_J@W1_*LCat=@(MrUl77Y5w9jK>TXwfb(WM2C+z{=fWc_bND$aW!EX1=vc22k z`nRR+$dsaxW^7GikN2k@k5AhQ&Z-T+^ZBuhHQ`nq z$bb)Y)@|~^&C%qvQql&8IHSb-6?S^L$U?(Tf6QV$dGG7r^!f@ibyCsSXb+6F`rnqM zOyugET6^16LFR`w$D?|SFRc}A1o24N-`nHL*I*cp^-l^#w*FNhVX6u_y%GcCN_I&SR%rSV4ur~L3IE-*iOxRCp=|uX( zM`Y8_NZI=^H6lcW%1fpT1Li?Ct1I+x^m1P<@0lGTddKgI0kLlRJ!f@(GpQFr z-dB6m&p!UhcIL*{m*pwm*bV{nkaDGq-EmzZvj4{gNQV81Rm%g7&3{l}nJgYA`R0p! z{J!luCDLa3zoqH67ONNB#8?;S0ry_qllkl6jP!q6x|JX*~2CAjVK z*P?n`GNEmd^()0BK-Ay&>__jvXNKFG-_>_|x{G*T{wELIy7Fo|*sg9E-1I8(o+h8% z6x%h+dLY!~;?r>1D$f#+$Z><6?fbP%ZR#b#_k?t5UFfrW=TcB{7jy);~qO=w$fep8hP(jP~0rh zsR7HiOc|5x<3o_>fIP=qcpCcLJvS>!1c5E9o9^GVWOe6>gu(G=;sw-@&#Rp-k~Gln z*H=@f-xZ9k`=aF!_G_=L=h_C1&+ly_*}xV(*3d}!^EVf( z3|B|G!`0=W9;zZr?zMo%J$wr34laCTnK)U~ZA{&>`2U;yj?4b*-gJRx|peY^437u*%bVoSbZ;lR5E{}Nc41&G<~Y5SXCpUKZcjoiG2 z!f$5RcvJZPgN>1Bl)RK^F^wO;&k(YoV*OU8P}a1=Z2jVkTHN(EwWR=d)pg9;eQ-02Wbtxa^ zQRYiP#@d`)DUEY?Zp;rdpu-6;g6a;{%PYd)PZ z=uJ7^7`q<+c4q2lE$-{Stm4(VY+_&N!vuxaQ0ITK|lu zcV$di28IGW<_)zmUuLj0Aoi`k>N;B_oDTiGeyW9{f8C5e9n75uXWzh$N44CshUSzm zPL;oZ3N>>i_w(OrJ#X13mAJn-W+lFHqNNw>5aUVUW6yNlma8oLZ^9yH81WswJSG}p z`5E7MLmQ*#n|XY^s_E$}#fi(_&3n%XE( zQzqN1=ytL5OHv37KmTql<60jP`URDFDaAvgPwY<HgZwl87+aHgE^IFiKW{l&$cgk!W8y2e;O zZE%e(Zg0fOUc=f0r2?f&@n-F3hYhy7Oz-KP1BP~|+~#RZ%1ZJYwdKFf4Pa-yahvj( z<}TC_j%>vdNXv6^qH(AZ1c?FsyT8UN0XkoWQPI$-Ay@Rg-2PSJoni7ekOHl&H~To=MosHxAG z|M9~beHRc zZZ-RZov~)tJPG$66!$5y@Q!7iu*02R@GQydnSW=`)4H9NSw=Q_$_e6ZkRsu0AIJ|U z8+rn23Qx8$BeX{Kj9gDU+1+6pp7WB&L*$Hx?HkARS@5>7AL#K1ePum*(kgcj0shn>N8|$o`l-_bGi00U22w)G0UurW1qO z_3OSCFFrimLW>Fe$mE9Ua4HC*h}ITKi7BdneAw&KkV@mQnIBhJr_|`)@tfPQR@!Mt zQlxn(a$BtTE8%z(9<%J-n3$Nw_E2m{+K47_wfs}Ij+~kt92_LC%m8kSs`zjvYUaDB zi}tY34Be1G=9TZ5DpM)-wQmjkxuWW^+{fb|ReXIq zPvktr^h4}-`2oW-XD14+lgv~M(uHZ+vFZu+uW}}g6af6NB57^sPHDlhaw5`h#BBZk z8Wa2gA#<)2Sy0qsH3I{=rZYYTHFf7#ogwIg7vR7M%F|BD+{Y~DOogIt*@|Ohiyur9TuOi}o3mZL%p@xozol)?hVrMv( zOI84pvfA|fh3ZkR&!YXzgen&;fJQ(as@K{MljQ0~m%fkzl263R2i$1Sr4+$d&;ueF z1=ADz86hTF$ArnJQS_5;Vy%xIp1NkwPR}OPaG$;Vn<=YfupaG4MF37mZZskkLXBEU z!DZ|gav)pl8G%BTv2rLzryWyE_a~@4Kn!isbct*Q^ZQWW+M{c2N)oN@ zzsUzp{~xa2Ix5Qciy9tKky2>{B&Ad76iG!&3_7KxMWmTQk#0n~Bm@+2=w?8=k&vNB zKyrW?y7j#VpWpYr>s{;l!}YjadSBf4Ip^AYpS_FuFEza#DTu|Q@c>#3{LYiJvQ}VD z4OpWu&+sR;5+2b6mu2si6E|-%H6Qy?2L-JC;b17C@ma$U4mZkUCkSz+x+9oqe)Y#XzsX1pmzfGh3omP>rx_mJ$&z1BnY%RHThl&?6Iy|w> zh~4H_pFKFj4a?k%mu8I|#>AISuDso!k_LAo@Fm$d;o1)PHRKbxLfJmDeO2v2qYB4! zN(o-D$WNcx_Z$5z%+!cVa2Zk0(r zC6WBr+9Sr@d{idkpscW*#q-|yRU4v46Xe)%mVUxD(D{w@hg=19Y9LvT+Nhh*S6hu_ zC;lgU*3@<-i~Pg15D6DlhK%P6Q1@@%y0yW5;*3Ht3N@bz6Umya(yW&=(kV0UIBIas zDvQU>A#_+Q|2WL8#O&rrv$!)eGj{~A_)G9XQ zxcgP<1nHp2{_<=8vd<;1u*k7WEY&q~2t$Ax!&gOJ{DPYAg!n7wt0JF0_C3<4_s+7{ zM+?wL&d<+pGBUc$1s7nawZzkczM`<^p=4^HyykR3v4J7-YAl`N)k~ZyN zq`R#7Lc~NtzSe=C2H$uj`{C-CO0Eg9Z z1kdG49f{H>)7{$+0ER#!!Tz&_fsrc5(|7fn`-}@xcC3F5wm+bfYOsAk5eyZ{jGuk; ztK|W<3Vv=L-{oRvw(Ac`&dluW?;qb|22E=~Lc6m4MFY04oF`?OW-v4vO<*t-h7Q&@ z6v4ecgmvU>ka)cNmleh?t1O3U8*kB>;#c)Uadr4I5RjCLrDt*M5e%UF_#`qICxKd> zTQX3sM&-1!CWbN2X?Sx+ID)Tnm3;(f4^*I)@xn(uR-#Vd%8wIUE8ibZRN>fKoD7CF z5OrCfqonud8T$F}pML7yO>5O@*kNrLRn07HI^WH269LSDP)NhYA;CX}h1AplGY_`A zU*rHfd%)Ks{gRT_LI#ktB33otzhA`P_9N=Y?n&>DF4-;18r$A~*Ht3OFiG?M!-xEv z*_l9?=A7fwU_uzUxc#3dpc3s`jK-HmN-3-S3hy(FWE65@ZB3Kz_Qah+03j`)+3zkRq`I%czS{e4 zAmLF!(Op>pI+Ox2qYpPqWUTGjFCfYq8^3 z8eeZvHy$iIOt_B<@|zmByZQgURsFL%+YECRGB!*#HI7E#&t3c3U}_eEe`U#s4r%Om z&D8&VKgtq<)6`2n4IW2QohlPGyVk~>WhQkj9)d7yP?m4_o#R5PfSmW`d0GME^DkBw zHyMIIF;A00{#}mr=8?|mo%CF+WYYO9VbzBb(!HO|SksqtF1|Ufyc>9$s^K&2QoqR@ z>b$jI=g2;w_~h~HMp(v%*B8%QSy9gWyXBJcA5}<%a{eQ{?*7v}k#nA;=JyB`2(e@p zz=H@`i=eC-?iO;<0WqP%4_H6OOENR+G7SQ{PVZg*Gu~`qlM3XFGaT9rs=sLSi}1H znK#^q9AH|S!-n%231;VdW8sh=6#nq6TBgxMjm48NG~OqUGeH4<3&3Di0DsGfie?BT zeJJa}=Yo;?e8i0GgTemnLh+%7Cr01xovMxx8>7Qb?V!tQQ{pxH4392WT3jh%=iyBr zU<|1@w|Q zoaStStGT6hmjv<_6!!kiGe_@i}_HS!nUm)M{8K&qPxe-W48dGN#}mM zu>$|f1xwY2d(OXm1%HWy+Z`X$&`yLM zr{H2&7zjAQh23QKy7)inR5&`{u$7M(0%;hGLq7!p=t9|sJxb`Qu2DkszKE+r;cm~M z1XH}FRHag_Bn`GU$8^kOy1X?h9*B#jzE~YbwhvOX8zva zui@bOA*2TWU$2&OC7kc&t)Gfnp7LAzr=5qB1>5}oYi0&^^FT<;Wg2(uj>1<)Z>{q=J+>!!j20OMMqpwQD8huML zI`$pl~6 z_u!fSO6gXZGcxYWkoC@K!G_u0wzfqN^3kNk0u_QFp+Gj~}|tsMBnk@PHy=+Kv= zrKe$C$&0MrH6$XsFKuN$P9y2Y?^0ITHXzGr#+x4V=#{>)VDPU}Sl4%r#)) zsCjWLz9{`QKx;cE*WyWN%)CAKulMge)}_(KcGjRE5HPCXwv=oKGZdoyW`9UClb3$t^*-Q$P)9 zX#|G#kozsBJRZelL(Z89h`$0C5y?-5Z1L5|qytyVPXS(U9tgC0XE&92#gvpP$#z|t zDki`F^EEa4v-`{EC3Ncs1Hjn<07}C4B3W?!E8#gTxmJ%KlhkgFqp>pnCo;9m;||s7 zF76gUD1a5m-3K=6DkSfE;)DB6;dl`cMx{lY0C3xB(di~eSdrSl%}2f)%k+PX|6D0x z4U<~`NTgLCNAa{xd%dy=yW&<%yYeXIM62N0+15I=iggnHKKtHo=t+g}|#sErGXP#SU_4XcwoPUBA1Wa*AE1QupnC=2==K}m~b*{C@RGaK>^3@(u z`0jiD;n18GjC8`eZ^j8~^9+~AJe>PL&MXP{I)(m@^}*9uU5uSzu~*Pb6z(RhQh&AZ zBiPmKrFqcYm7aEDpqL#-Zk^*}LD~a3K@MAg$N8s)xQE+4eUhOLOy=a!fe{*=h+u#c z=^GiL*KsDG4LZlSWXh1>i8rF26Y1ZzH3xt_~C}Qwu%#hsAvr+1cd`Z z1VlO<@fKWx0n+dE%t-!SJ{C01cf)tgZ8VCV%od*>CzEx`WOC%Zjqeh=p-lMyLHjlh z!*|3TAGF9d!=Z?{M5#nttE?FJ9m2$>4QHUhzxa`t#)Iec=w?ypVhj9U8OafsW1s3N zup3}I+sL1et#$rz%0Z|w-2oe_&xqKk2eG3^$3sJ|)ZiWrdzf0_Qls+QgEjK`&4;gV zqAG7cN)ERlRh($`jP>cgwNRIKRc3Z^m}MR2^o;%`zr-g!cd9BjFs%ZrBl3fS=|D{* z%w47HXN~Es&XI{s#W?AHV`;tGQOS7G9fq{suc_B40c;0IRS4v>BGIF)#$#A+Oa02( z-Z{V#x8t+U^3ZO}U={_QVpsnxnf>X|qnq8q^DQf@5Ayx?to%;oEmhTTEk-UG?p2In zy3g1-1;7q0tj)&aqM#BgIzJHt*xJfx{&+$r#c+OiRzd@y`Oe6;?Iy^XVk_QWSYE^F zT@$;4<(@HX4+H9L%wB8@$Ho(>_m|x($f)!cFL%wtlNE5d8N^zD!SBjghp%m-^ zoW6q(-c-JH^mB?Az|D6UIB{}9A6~#_A<(zpog@ZWM{K2-7&%>)wF7Ntbf#bdwKz$^5UGurBhM7Ua%z(ekm*mB{Mr;Ka>E(%}P+iqo>my zJHpsCZPfb^X4uCxKp+oXY3EipgBZ8p8paPR#@CooEGyn@Nvj+ijb^@K(VXddaF-!r zmBE@hVuyleUv_m&mrbrOcRd#{$5S$58~t0#;867T5|J*dJuF2wt^*~=U-Ey}{M*H9 zOh>nkX-#Y2k_eeXAi!E>{%FSaBiee5!KkAe9MAZ=gXVnAI2Ei5bMtV9K*u}#DxH50 z%33GHdtCHd{Ws6O19!@p|Kw2k;N$UK{c(Y5A%!K0{zHyVGFb8kbiPM9ySW=6C#(!_ zltwhddO4n&T-@!j*NIw``OWVRE{dzY$av+IlH5H*U_spAO5R}Iiuq;%1ox;0wrwA{ zVJ6scgy+D4J{IC;YF2PXMIHN7bO2Bl*k1~emjaLQ85CU#$cAK9%mS{B2kn=(ClIBGxYp@Ij2#(*sGu$wrn#W_lZ~Wq%*Ly13XuBYHH0uki0qfL`)G+P- zjJF07I$f$TK!%Ec1-IL3nBEt?S85HHmxQ7~+Ce9)8qx+*>!-0n+FoyI+8j9$}NZgt?=WRAxR;$l|{XGj>-CbClMwGrJYS{#fosV};fB=n_ODo-+ z=Jg2MFLs{xib&{km4>W}9o@8&Xt6uf&6_P;_qK`7j=JPM~J_&AQ4nHHIj(@Di(%o;Y4*lgc>zYUJ$?s?u4%J8y_sBx*%ai@YM zRaqxDagL?;)_JVmwvRCzKSRvEq=gAE?2Kk1t^!N*LiAx`(z_e5SM)J*<9o!_B+Xj8 z)WaS%kq$Ruee9Md0c^r~Rqk7P{hR+T@<|VY&C#Xc#*q*2ahs+;YEC(rG6c1^EX85lkf_v%b7m*<<^vWxrfJjhu&hFPv z{}Q-BME-v8YQIEp(evK645QoWRNc{nim}%`KFy$jIhdzNY-t~N=?eAP=Z32Wd^KF%@)gJQGLf3gEb4`U1d%H@~CxRc8PgRk9tkMEV#&i zDCYvVHg!t)Eq;S!Tzqe*cyClFF+^W<op!?Yl%VRJz{1 zz3dwxuEfM=IEf{lkd604=rSWy9kgjLCDhV-`tto&NqJtZaVBKr4kNG@);8n&{c9=7EIRA&*-GZn{70eM*-<3%nq!yXLY~4WGLA<<3N<_J z9VF8BXT+_IUGE(iBSKcw*k?M!9M2P#rK`&JYu2AoPa|s2uVO?&*K!p$>35@f}QB~*tk8>%mH-#*m?^vuwFa$fdaNY19iN`in zmj-9S4htj?-dh^2zwkb;jz9qT39#`?8g!~Lcwz;e<0K{ot%Dc`S|@{zZ*3tr7J*m% znvbda5m-TLEwikEq#jtAnXO=+^S1n3L`*}GZ*Ha~R&mzUnH6|{K6kMgsIrTGbWz|^ zS@3E}gh}oxY}+4k)(I?xFWpV5gvCLNbygQvA3javDEa0Lb^`cumT8OIUAE>o2ZHKx z@2}8D++V$$^|$fyFxU-K_RSpRHa8HBc~8d1pfFuLJ9@YKxbScNZ6$_Dm1M93y$E73 zjiS}!Yg}f?#Dc9*KSY4O8Mor$=QlHYIOn&f+3)Yky#v^S*mx@qY_rt4)@=vtR4}`kWPO|U$IQc*H9Wb*yBbID-JRKe zEJgdIQ)!2r&(ADWXV@-&u*dAC5YD#Hhxnq=i{Jm#$*=RVRaFXwN`?W+bf-2KZ^E*+ z@56gE+9+p|;PKYniv?gn{z}Ao1BAa87&LtPYX4xE_P)JJdabWbXB2yN2|v@c?4Z=0 zJ8%E|fq~J!UA$k!;b@CJT16<744cyq$NHWe*~#vA6kt!(;VvglI6&IS4(5FG<)?Q( zxmyN%pG!}-^cM#yU|n5Zj1sAktyZB3mT98qINd3@QIXvp&1=DB7Wb!uP{07SzrWv6 zY6!$uN5TE9ZJs8t$ZXY83pM-o>l|q|cor7#*Cg?Ull{=zRCM#dm}nLt5_m^$S*PhA zgL52XV{54A;z^sG(%TWBc`pPP$G>EH^VMj~GUm0CN(k_7_Zn)m!8sGiUnYmjcvBlG z3OR(Xc;I!ZZ#~tSQ(@~M%v`ZCm^hqLb-i|#H=;Z4GOIef^CDj_XkGgTQ=O{D>*&3W zJA9mPR322Bs#F=PRF%)W`z|%W+X1TqdE4}N$P|@>`I4kHzqdUq2|W`9BDbn3;B)=Y zu|ygM#07xq0oZGy&DSSBr#pdN6Rt8L=ZCj%-v*3^)A<0;NDGh)f?z7 zEp9SKZ)gB53fNn~=~3O!GM~awG0=@eEco8~lDdTYW;g}Fpo5Zhs(u ztTW>^9hLdb9rp(9ezwK-Zty`;Tb=7nRda`5Q9*?+kW_B8week_D}!bW3?7o)u6}Tz zYrC>yVpkw(jy$?>)WN`O(UY5&;P&1e;-LUl<}})mG46yQHnEG|JUJSkl)r!-2@TIWroHkXhW1vikzPewBX!@ z|4_$R?x-yvNV-cZgH=Dj0~&4x0o>U8iv&W)F)EFSu6G$e1fCtP;PKD)I?akDY-w7Tu-%UvS^k`!4NZ_9)vJ!e#*qAaB{80>V!Khg8{hlc_Eh5<)JWa>NO zswTata1>6E- zd#pi0`Tof1iXP(hQ99xkh{@}*txr#g`nN;fH|iUBxU1H_J2=#Emv|o8>H;(4nv#PV zh*OKhNj6aOQE+HU%HO1<8lmA7ZlL;KsGV*c-aNGMUaGF49B}yuC#LBWx47Q6V>JVE znme+xw^HU)-{elBt$M%6HAYLBI;B=3z$B0oC=%T#(7c?TABVJQd4){50 zW!{ukK^-Cvo4mH_R%(~`!6J3ZP@q>Me`%lKy&di>=DQNT9%}Dty(PA-fh-<~^GQsO zqI}|2Zdo{qq-2UMy`}@$x=%k7_v0VA`{2e{_}KNl3b{CjE{J_zAux<2KKDCs-%m!^ z(j&EvF~_MOkK(9T4-o)>)o<=`c+F6Tj&siUScgNC;f$^R#{D2^D@yPrPyJ5kz z@br-FxAX=v$z3X`g_&=~a|k^XcWNM}ug@GRdc0M$xiGWr8tnNJ{ko1c*Xq+_KClCm4V-lg z0cviQz)!{fgX$WPr#JfH-46*lo>n_m-%2e?-TxPDgX> z?d(ld1SYZI(}zjyCAPMg? zNAz^?x*;`S4#57{eV}IS=8*zu>)U0?x^`!AekT$UcN(v1A54KKn_tO;<6s7l8gMQ!BKusv2IxUYq|Mcmd>L^;TM?vomsujam0sqzP|EGD; zEc%>ekF{yBOu;R3m;Kw}6RwS+tR~+>;3Pn46ivj}3<$qK+wBPu2wISz|7t^jG#9{k zc5da$iDe|s52DYA{%m3X2qs9uGQ^vEYX@13=sDujY}>d=F5YBivWF1PCrVTeX1U6N zo>sS}S+8Fn7~&-!M}PiFDKVIwA6`}l1s`Yf;}@>0|GkQyKZrGlObbDg zqWZ}OaGu<W2r+Ew5QtZ6* z{OXpPr9g$aXULB;2OtB}-6ygkolu0w0{=<*g6DUWylw@y`)|5`f94WVXoA{Bx~N+D zvb$Rywzpl4tACG0NCT=lvT$GE@z}kxN*VCzRH8 z?&18^Nv~fPHqgz5Ru<5zPzpCSayb*SJ4!1R?XC zm*5vFko11q!}hv|^My)KVVNcEYwxNmjssvlHs`&PfoK<^!xZF2>*-_`YGEDQ?CZk8 z)%9BLJJ9AYHu%5-#|~tWcc7H;7>5e@{8h6fJec@t z#W;o^ZkB6N8{Vw;cEyX(M-Y7qI>tZs*CAAnOFGEgBj@R=Z3DK!1$8-^G0nPM#s%Sx zuPrav$A8udb?$WgwsdG*K6q#)K z1Me!n;VJ}>+5mc5@Wi9<)P~kYO!Ixdow4kr4Xw1o{Vz(p7e7%mL+ucC9Uzs zaf^UeI1NjYe&52i^=Aj{K5-||xtOS^`7ZghyOm#q!3zNdf%y(DtzRUx6rQKDW<4(i z`u$J$6;yl7Um?w(9x*x+H_LE(ezL7CKv$WjL9hK?B>8)3{|Tc@;~#>rQR_DIHKwYY zCSqgdXCrsnGgvU*z*VFxn(^oa+00}QGlNeAp_-2(e6iTJm>f_F{e5O%9hJqLGl5aV z#dZJ4I^|N;5Oc!-m%&P!MSt_cox^LEO3;zzde>FGi_=&DOF}$cj+aF22&BKO(sK$o z(vW@_*R`10b!NiT0eBj+N>MffSi-X??#bai=zO=NfB_XS7Ys5}FN{;E+{O>Ystpu=OE1XW)KQRS+u5|4Ua(_=Na^MQ-(y%EmdpP4} zqjW=bR8*(v=dDfAM2E8FL-!Znb#@_!2L<1d+la%>j_pPHd1*6JHzxMB^q|kAu-=}X zjM^cof56^IU?l+ma}5dJXI!=NqV!OXMCZla^-b%@{>J{bAmre5a$uAeOJg&HQ#-;~ z0A5GP^oG*=EcAZyMc(De2u0FLsF9RGA9I!7-B{W01B1Z35%P+f>HJpB8#|(oDz@si zX>lT8Mh;XEUk7eAD>Vea>YFn%oI`ZXvw;#IP23FN56(X;w12r^2Ma@wyKG!c8?Yo0 zoYs#F!2uel z&O734gOH5fQy*5IW0yAWm<@Li-mKAdKhQDa`=L+HdI|Qjt1CdwZDKbk#W>_s8oLY$ag16!x8TCAZGlM$*|FU zCRnmOpQ&=7b*5{+qPI~WFgbm=pJdt;)Z{5=gz z=IApPaul+IJo(Ik7KiCiadihf(sc^`YnV!gH-1Sf1gGEfTDw|f8DE~OAFRfS5k8V* z9x5GoRSmwYAZh6j3nhc9_?|G`^ScS+<{u(=C$B6yUo3cS_lpd9Q8-wUs}gQ|QNNq+ zB8Z~imJGWKyG$R)nrV0IvQoPZSsYtt(%E#Qetl)&#v>XTVVPLuj=(%E1jt}+>qS<+ zK3xxwem9Tj*zDx1=YnE}ZHIV)X#s39?JHfn)_A(^xtM@7on$)`bm&W-k`H1Y`jh-+ zrabhEj>S(@pNOI|SafS7Y@SuN0kjTydfXP1RYl7wN*?%#8z3=KONZ9mM^W}Lw&|IS zRV^wvA9}8fpF2Aq#ap5PGU6Zs8tpMQPeZP*Mw$|Sfa#GQ?Uq9VR`#uXs8?voGZ8sz zr)-knY3a4+UfIKej!Z*Sa~{+}qrk*}GpbGUler;^xEFW(YJa(Fq{sa{ML9Vpt8lNXRHKdy^n0{;;}|w6U+~i zf1K_^#NKobLBCrrw&1j~wY4{oGJm@cy`hA80w=naEdP72=W8f&aZ13cD%?=h#rw>r zLX%eT{y=nW>=kq+ekJu?-~r?v-2`yw&q34g_%OUKKmU7h_`?jkMZ zLPk^Z(9()O5cyFf|BfZ)$7OT6Yp;O)YkP>+B3FMI^-^Gmwwy}kHFyskW!WYzKhHdV za2*X>;5nId?Ggagf)s#CA>X{AU;zhR@lctB(3B=#e*cU1JPsx;EhqaEtEr5BmU%~3 z- zze9E=Jf^Gf0|9)$Ta(TM#{I-D_@sm4z!wuVKSN{h%JY{8KC`8=|2YGdu6cSi43shi zVrf*TT!2MJk=$3bJAk8t0(#zTYL!kbm@ey>I{M1*LTK<#=X^08t*rs2QmW5(AEk)< zMCjijdrolCBt!48-Y}2N=9C$epI4MIuc7cju+w9 z{Bi6<5jM@kYu54~K)C4@34Ut?xUXW0?C9^E&EHsL05)SZX#<%yxeSR|8PPW!b3SN( zh^OzH7ccNDDj2e}l9D7GpS%_57n#42>86-!MgW4HaP2Qt^0o#fI!!O<;ls!31Umbc z`bfPe% zwahXF9zGN>yiaq5ZH}UHyqh_26#)8u(NzQny_-*!C}E=%A7*^AJbXC~=2x`;$)~W?--q1WY1jSN1hq zb6!nZY_{Pr&WAydSuW{R-j4CheA}?v;Ctu{AP-`Q%JonZh0bhJi^}uF=K5zULxwl5 z&%wy_u9*ZCxirzsDaozUIsZY0dCVhojD;+ls-x|5*SXK=>+!0zgFZa1MRt)CBY*8T zt`Z2{ctbOP*u#}YdTV*I=Nl!*nc)#R41@5cN1cqz$91^`2ByR#!?fH=4t71#l6t7_ z8IF6)UljMtHz@cZr|(FcvE;MM!bFO)uN;I5W|W+}RPPS1&9RNV1^!)LM&@ACOLQRc z8xntI-zhUI3;e%6v=MJYGHq~^;6$fb`^#I|ejVH2*AQgha4+(t^j>lmXB11oO*zlT zxWoe=y?K+`?XL{mT@rupj+yYzxlcFvMIcmX-wxk-we(zX;cw%C|6>=?AaP)W-G3Qs zQ~TX*_r5+bDf?y7Y!LAJ-+thyNyky9D#xcJzR4^95Ju99E*Im_QDadp>rK^DLyZXs z5j7){3q~UVdx@xps5O-w17xcxu;fZvNXGt~KHVz|$S+}hrehZxWgiXAde3ft4dZ&6B z>MUO{T6Y8Z?EO74lgIQ;(?b4V^TP3F>#FmHgg(0pQF85c*$`{Sq<>S0FxG$4clwv) zx81=*l+bQ?5*|mm5(V4kroL*@5qfe%-p>;bTvJEOt-|Bsypzg*UTqdqnCLpKb2gmB z3e8RRUgb(Ks%vNrFJZ5ucBn~zZfxWD(PezHq3Y2afhTMhacm1e4a+ZwpH<--^W{mJ^@pWC>s8lLKV)pK>)kik@7GTGXN<@R#-k>oV8`D=i zVDJ?{1NyQI&W0lNeJqG*&FVr2PB`fY2*lB8wa4RW+skP#)u@`;iB1nFgW;n#4@-vL zWPGXHrzaW_!p^iJz`z5T?ONK~_wF64()-A>!GMiL4tI6+>MB=4M!q+JA#^kq5%>0C^z6yF234&^unyO9=_ ziOs#IJb|it#yj6ZYgRd%g#Ot2z8&-a#@1FEeX@YY-qW+!{3B7b+YM>Q-z-+j4QZNJ zX3kPaOGgeS?%|&2!(~P47A<*N+!A+Bp)BPMW_(#KE*St+X7r~O$Yq>V3vFgiLKx-`ST9{0ON$Xq}_)-B`Q{_Uo9%i z!k%&dOl($I?1GAfwz7Rz7~+y2mAy1e-Yg;_A_+aIT(q<^r2o0D6(XA9yszEW84Ueq zbjBp3+nOR`8yt?x6O_EZTmSx+-l=PbN3_&xlfw9=6=Cq|kx|&PG2(4pweSph&mB{E zG`US<{c2u9$3-Y(iFVs?qner={%)g_tSN&hv*eN4Ctt;ZSVX5o19$kyA3MDhCVAK` zpu$-_J%yegSb&vjuV3%3mR42$JcKp{1XIM4`G>Z7_QmpM{n;y+wp;KevcIcF#ZE=e zz%`6m8OrLa7`hh$(h^Sfg6CalV59H>GX870fxV|+L3<>Y;G~{A-UcdTf_l%rqz4+Hz z7az`bBd%{Vn@^xtR^K6RGS2$pPnE0{G9K>o{(MuHjtXs1y!?2Us!0!4w zF9^1}mDNQGKXC^R%SVHr2n_en3PQWgHm2NKI_*8ahM%@3D=Q@*+XiOTZ|*vIU`mX_ zhNM(*|8z1JA`bkCA}y20JQ0ln83q`OjO(3!Cq%yH7;00q2Op=+Kla@tHA%WF;zlZe zG8}_f$@v3f8~@TH4^C&Qc^&ud)5GH*QRQ6;s`OIMo_({B@Ufh7(_y8Kg2T?Hpx6V^ zkn{81%cbpz(h*tDaX9rb&!g~H!`^4xT{vNs{N6eA-FIjM&Z&X=9gJ zvS)zzw;fZu?Km<0TT*4uwVt8B6Q{>Y!xZ=^03HKw4n)@U31I5qv#5tdE^`;J!vy-qwluHrGvonh3wKw!%zbYc#pULzW&B8K~3x^_E zQjxnW+D7-9sU?@!wP%*^NgtYSc@Fvd+loh5HVn|-&bav80@`Tt`W4o0FfRV}&JWZSGf@9R+ z8dCqdFmj)%CgM@LtS`Z5b?R#kI^`DfyXoO_&3#TQNAKqvKvW1-gi1K-x-?q-S(!{I zP_W(G;_8F4UI0MwPg@wiUJ$(iSnFt!ZUn~B9o_Z}Mj3(wlXE!7q zg1If<6)vcp8_=mwH(?s#7carKN+F^7aQovYGOap^139ft1q0-pGTJkXc})i1%Qtgs zL^^hx{~)!03H@0}$sVCyjZVfj;VHrJoclV4lwO@ypY#@xWKFt<`__3vMDe9TG-VI6 zAGZJt65^l$F5gpCCx0uxTDwslDn|>;n!*0Lp_gWV2`e;>qK=wg&Etbzc`a?)Xs^1c zt~=Xcj0f1k#C{53EX}=-XO*`w3@QOkL!HpGjs2V}|GgO>Ap~dWAD!O*NQ=ule=JtW zvahRfzfWr4^f|FOl#YKQq_AL}F-6|)=C&*8z2j>#g0xGORoat|IuHwl;}Ye5jzXdF zY|!_yDpYrdyEIzrs0TV%GMKp5bEd-|-pv&1M8hP%kO(y=>6}N0n7FvI6E7g)wjmFl z+R)`kP0g5356y)-;Q60*N<2JuyE+a3-uN@4^>^RX|B&cxn_1pc?JQjSPuU0tBhWDF zK<>(<_ALFOZp}Vfmk&Gc%){_oiOhv>>PQc=JxB;w)j#Y)R!P3Cwhj zWP_$TgJ<_(Q|4{f*>8|{i*zQwFT{1p_wEzfE`yW$?{Fe#IOp$N!7GdS9jQ{fxho3? zkzqTB!oAj*_91jEI}zyRnGt4OLxJqF4+7e~OpiHWS1qdG67upf2?+^^^M|*m4%N+0 z*fM>;{giO8XvQ?3=rxDA_$?~4vB6YQ7O}#VhEz1&5rGNywiy?bEb*V-SomywkvG0Qc`x8^`&F~bKfC@3gvY@FH8 z1kvH(zx{ppN2uhd{4`+SpWfr{3ni+c#984RzWz^gp}E0XPCvKYICxJbuEs4-4k~7G z-*X{V=Jicpkmx>#UM(vdULW!}u&$V-e=RlZ>P_exp0eR7?EeEJk`w*?qF{Wu|KdvN z!&Vhhsiewo6(MtIEQ|O0mjdiQ+<&%W@yaA@7B>}{nTf19hz(Q_#vvg5M07HgH99F1 zHyCQxWSWvSYK#bEFf~)xl|SIOGdY987P~WEv|AQ+_~4^xXT}hp+6OFfXa+{lory>1 z<28sNJu|3S={a;UdRV;C@wRRU=HD#-yGQC8!T#}v^NkmwsL4r#bm=NW^O~d0nVj~P z2+^Vb4@&~hXrAu7R4WX)9;X;e8A#P~t2CB-vEx_&#!X!W?b()BNW$sO{dZoEmoN!n zpdciY8A0-PUjFnAz1brVZ-?WG@%bx;pp_1*V!bs6wHtXB}$=G)1b@QjM~9$)c^%mZu|bz{W#^vX;p$@?Tl2^#A&G-L4XYfSv;A{2r*gW}o4N zwNd=}k{V1}QyL$p!hSl4{SMovU(I@Cnzuqan!$Co=y0ldAVdH*yRag{SGba`x3VS| z%?iCLpijpRi(!_J2L6!~yzj{e&VU&FaoA#21$G(8^Lbb*rGKS^N`1eZt`aqcRs0hID2*c!lW1D^W-fl`sAPRcxlfM z%g1NOyH49^F@?Vj;t_(Jb#y-8JwIEq-^491NS>|2i^l){kf^qZ6+3QU*=DVzNqv@q}hbUFi0ZgpHB z{f~<$)2Qo)tr@CT%}gkC*Q$m=Uub^8I`FH}JFAZ!UuEk6X^V46w;dqcfOTykWu0k_icU@`EV+)N2 zM>z<_dNzq*HIxE5Q`25PL*;Go@&>+P3;+GOuw3irVZT--JYhwHB9JnS-~&4#o;l+d zkS;iP&6fC;1dy%!|9@GPUilLyd$wW=$QBUjW0||(tPnel&|#FP^V0cK8`*KjvcCEL z;>JC*1Z}gQNbCj&N&XPkDu5rs8ll3x~JH~?28uK!;kjMFIiXfPGa1rHpv>X!B+sSTlEZ-Ok-rb@4}WQ~bUu z+&gXKt%6~5$8}vY3TR*qB--A}>hYz}!d@iz!t(~=dZ@Hq79r~PiyQJ=DJgqbf*&X! z@j#=XvkQ81h$g_lC@Lk#S8xg$}$V)k30x}YKsdbeOT zlqu&mA4KctJAO1d?u{w2SYh(oZ@j)x$9yO{q;pm?s+MvJT?Tm9#a+puXu)#=hG_EQ zfi+E_ke{BO(c=#cxjrLX{971(>AlwO%nc!o&NEC9-b&F$?P^u=!qW(4lx$(qY0;9o zmaEy2fVh8%KsbMfZ;#$sn-&^5#HlO6qBErIa6f86xzdQ+E<>ca=`y((jc88y!y=wc zJlhBjWf)Cz!oZOXyiee@oN|WY=ka|?$dgGb$ge+Fx30d`k3g}DtRDZIG$R&SK*sjG z&nu4?9Rm6`Ai*T$SU_r=g>hfHnxNLcW5`7KWG&pIezIWK^1m) z&PS)qG)XAhsgBvz*xcOsDSYor@g@`qS$pm*a+TuVOfBH`2?ns|KeKh1JlGzRt~oSr zg>;WdJlr6@uVcj!cF*;tx@o@G!3W7Pr<%!$+E+}`AO>t4B$M@a zx_hJ`Enpk%F4UZU^iXS&7Pe3OIGy*p+`Z2(Z%R){clj11GPD+lA24@#B6b;{$qew- zAMP@G%)k}^#Or@;NbYd+opmW6Op1vqa@y7MR@V!Q`3EMPcBXGHDg*Bw{G;0&q~qxx zj#B1o1Uc9JCjLAWa?TU_A;-F$u(xk%1|pCRCy_}b5|RNQc-Yh#7Mde(Q9;*fb#tLY zCiP=50XBuu7jbNF`tEqD-}nDRNds9KS=l1lNkaBkWMm$D zNA~I*G;K0cS=rkmGvgd&rpP?@(UHWlH^=zhhxh0E^LRZT=U?~zdfoSRUC-|EDcxuWc<;;ycn?{x!@^F&wgXD?xF@2 z;)FLXUAY&&CowuY+U;z!1|~tz02#ceS^5nspZgkZGllu-t!OY-qdZdn^vfX*A^t#? zi-CxCg>oAe1d=L0`yxU>pvq+#N0>;g!YshW7TraT$VE_*C@e6^DbajYPgJ&|daXZ{ zrGoDWx2^~q9yaKU6&SBuz^>w^ljOj^tY2Es-XvIEy{Wc-`YhOFRdo3*v7X!oK_JM); z{P`WvV5qs#Ban+a6LQhrSzu|=j5^uvJD>jdqkm7!OHz;h4LeMXyWeqhtVivbNK-0W zZISsjBT+NEWDXJ2re^256))O6?88|7iOk%{OcUCi0)rieZISq{;-mq$Xl`z1h9F*<2t zsuEWsHb@}K&dQqhe@0M)k4f{^3OO?rDxS3M{khA-_5u9tHG2gK!e098n997x*j<{% zFDSb#xUs1Al>-}4t!KjlxCPzR=3O9#dKAHz8TJ8os&H!x<9NN zi-p{Xuv^LTdo-T|i?ATIg3rgW%3OvhpdZGa7BiI>2aM1@LpUEzn&*bQ5x69zeVul# zhI(BJ-xbv7wW65OK z_f53=i%dT#)P|aj0f|6hKy=N=ADDn#(VExtK%4UFr@MJ2(Y%d_7F|AC zf-}8B<_)bX1Wmu~wwTU1-Gt4aKL0hxiR(Er~_Hsu18!X zPEu2J&1npH{Iu7J44)R=v(0moS7lbeip{UFooogxRgP`tk}Fj_eO-b2daacfRasg2 z1Ps>MB`;1(>m}OKfIc`3!}PA3Gt+s$m9kjo#T>6Ry>h#LTn@}O03b_NK!=T3TnHv0}dKbP7EsF8Q zzW_(^<2SKoN6fiOQsH}2_tsKRyw-!U1Q1vU<$Zn5jB(?GYhj7X1kFMK*FB3{lWUI; zb#!#B?d)<_SFb5o3<*`m@7u-g!PZ)+>FDY4@S0i-Aqhn^dR{No=iHKkzhr1&kqM+F zy~qZJhKa_1ulqRdX@$g_tY!+p|&OqF(-bX4xd&sdYg7jkh_fTgcLZ_($p1 zQ3n9n0|7r5(s#Gp(H`!Amdp8?frV7s`%-F=>MN~N*$$^zx9rAuGZjH7p0sxs=-h;QkH-Kr0@ zTx~GyFGto)$L#$4ZVY)~qQN=ndX#cYULn`8#n*=k@@Tl2&-U_Y%G4D|SCs8q4{EQ6 zk1q1Aa1eyl;VOm9>ecjpB8!uCoIh;crv!(4QdsujdcrN$ihX95zZ zJAu6lb^<=TyZEz?tV)UJVj)`xEXrl*7K-MtzaWfgDPpIZW?2N-x9nnqPqMxI1zN{2|v7 z!*)1!b?pF)gM{eIz8>Bn%=C!)gJ3y)UKZrz+E1tO`YQ^|du>Cg;qe_lOLLOU6V+kk zJ5L(jPrvYW1%D#uBnn6U?+fQ8oswG_+QR&WvJ&h0FNX==-Jv-xv*u}_M>zMTd7){ka%O}OGA85paaG#ivCrcLgtatIN*Z|;-VkP#I+TxD{1b%0$6~Sj!w;>tc%I@?fQDn zL)qg!=HnfA`U|W*v0)hav%_nGhYYy4{TD`8&X55n5P;>W?8bPnGr!_0mKkdrxjUr& z2yGcQ-AmhNr3szQFDgPV;iSQhcaeKsQVr`XV@0Jeqqm~Uq!`D5AP*!_*MEHfDxNiL zt5JR2uiI(L{i)mU@kI$WQ))M@sW6#E)`Iv5T{~J)+XuuHEO%dBHIxgv)!o$-&=nt5 zmDus`A0Ne%Tu4Q~$kNfM#iUHIg1aq&45uP#C`WSqZZ~R@0gtU zZ7`wM0}f|MF+TdN0zlJU?)BV0IYQQ=ukcySX(jyX!|y^!%*#FY{+8Gs9t|eCTxKim zT-zJ9Z7DTy-JinLH8H<`+FA%1<_J-i_%Ecz(W}Q$ijtuwTvD?%N-xI4BX#0qF7~za ztw*h?hc77Z{h+y1+GEel#y2Md1#@p`igKy9f-$oZ?Hmya z%33nQuM7LMt!zDQXQWQnbA#K0Pp+P@03*xj9n69@i?;YW;DOZa4L`oOGu=S%j%Zx& zuI8aajQ<0yEnx`>i8UDuW&F-%%SvR{m?7J@niI;W!I%Qhh>JT4vTtq*D;IX^@OhtR zj$!m%Jj4u^y!C7x-6HS4Q{T~?A{q|Jjzr^G955d5g3pZaA4Ogg}*vq$g(c&b3(iF33Wvhwv-n-AB6j1>c9CT zWe<0PL+EM_3%_T>9l(qMX9YRUZ#tXp-Dk5hAd@mxSvRFBClXZlF}HkI;AbV83I%2a z(XUT>l~(oAqOjO`2E80LXH?9!p;Q%WF`rWelrm_KKjfwvXs&s_&G;hf%rR6<#6tRJ zgmLFcA_0K>-DUD;feRFt^=!J@6&k)XIWT{JgWW8a&PXqClSL08v28(0#^N~!;)#f) zP<~+xHr1N<${ITCyz|0EQQ(dyR5o0>Ec+>sO@fYyo59x&-Yu{b^Y|tsIn%o@P533d zKX2+V-5MNpfchPsjA?#*@U|d-@#(&)%Sicro{T?ks`j&_kL!qJMWL(0^@OGO1=>1&ocMF^8*RfT=R(&eY(~sQ+t7 zz4<4R1q<386#vHylWNfnRM$(PR8~^{sIxG!x_@r3cCBq$MoTY}Wf1`7u21hy(rW9;dFjOts5g>Iy2~Zxq{3^do)SSKGzt*AFvfV*vr1 zoLqd(ZQEQt@xo5bs&c9Ex9tO;p-&Q!2iarIZ#UllQmH~>jl7p?h-#m9e4k&I6)3S6 zT{|ss6%7nPxOC1Bs164}Bcd3Y6G$gw?oMI+QSN_SfXVg1!?d>b=c^J|ulMoVxoV&8 z$06?kAX{9euwN3<+EVdYV{R9{nr#HoB;K!N{nEGEH*ZLRy3-szLB(XDgx}G?z=a1S z;g6mKlHvxW&f33xw3k79=4ZOR{IJ}r*ZqHuu{x`ThW(FB5$uRsy}Rh@d!p53Dv4B4 z#j{;%jJAIa9a`d0DzxS2FL7pbjv7tAJ#=IRISe*NXjT3HLCpzFX z)4>$_k~Fj_2>;OA>H0JLGPfC$?D-neTDwrMyzXMxeC_zj)yTbN?Nz^}QIVWMC-Cq^ z5Ni)UDmBzapz%6?e)jg7)QV{2$tWn?)BKGx=ukE7PDcWPEIqI`f|01tdlg{Bx-^c0JXV$K`gA6c*Rqc9 zSDPI7;zxrXMz&+icKt>IO7*_IHIh9)P3q=6`O1~^iqqp(xczPQ)e1dxqJfZ4MiqI8>N$5~q1olX6Qj4>R8)>tnwGac!B{>pZ{_6P z3RnQLucp`tVQph`4rm^0CpP@x@agTZ*OcXDGgNsJLi3zP$HzUnf>CR)RV%8KI!6qV zg2B@GwzMl8V5r@AhCq_WFY%e9-O!$7Q{p;(et82X|HVSY%{!lBL9Dj1GnYuHldcC30 znzTd>A%VXznOiBQcfUb>)%8%{U^p2Dd#ijv`~W0eJwm9Z?trFN=Nv;y-N0D6*Pe8GsJbN2VKgF4o_E*;veFda80hw9MK2b zr7xaz<38jxADRn9BdStWOf*2!d-4VoxLNuHYX0`H|I-A)oNwm%<%c>4;#%1Hou#i1 zea)MK8O9x$lLgEyb}Z677-fuUt4C6lX8x`ZY)Tt3c5y5a=O5LV%#6AjCssCc5cmT6 z^kJ1lrTnNxNpBVj^qL^N}8x<)k;o8Uz0REJGpg z6cN(ghKlIGnwaIkcRp9OxdTqBpurV`!#77wR}#wG5EW0urjBh;%PRNUS67c$X#CgP zm4V%z-r?ma7J1jGrqq}gfSN=QPV*hO7iVpg2{ZGKf8y!+r_6r@xuS(?(MdGg^IZEw zuIqM=L%4+HdRDC$6ytr}|8QOE@F(WhjRdFMa?>YI{vDWsggR2_c8AUZv9%0o zHXHV>Ip*`W>6dVxbr9VQjf@nf{7Ur{pEg~{&AS02VOG=)!Q4!jz#t63k2;WBvcPfM zu$P0=E-qe=fsv&p^avF3_aa)SNSFiv{CcpC?;Z17!%AATfv~7>PS7|{a@(+e{#1m5 z#-UAvPVzzn>ti&ssq6OUtY5fg(XC5MOS^m;Qyv^BKo9@ofR{!EWACVJNH@HLa;;kg zkj!hI1-#_F+aW>HJD{j|ADI{6aa#fZGjV1g$@3DAqC93;biJUrQ5f@qXF&3I>0Qm+pR*C`B${Vwr*kcEt z5(I*G$C%6d`o7iE%vzRqgNttFQ_hi?#&}hW-g6Kx?N)yqW@@gb8vhq3sH zq?xLR_3Vp%C&KNZ5xy*_;BBs2J=i$jeCwy!uSK@}!Kl4!Br%#X-#hryX}n zEcd$@i2eMi+>=`C87_1Bins5uUmt^nHk%PlIIr~5>me{Pc*zowM_HnQQoy)JC-rXs z@#c*Mf(tRIGblo27MReNVANzfIdl`Le*VVEM_EEYds`f#qEUR$`&@7m;&-k;T~7fo z7sUE_y)Ksk+fQuDd;FYTUD9cn4D>uc`$O7~Kz=Lw8Z7q0=|Xj2o3!uyZq;(a$QOU! z`yR;1Kw1WWb}dPT#6;uVK*-3@BbGu1R@{4}Zh2XEH-Hp)-YMnHbw#N@)Bz^b2tk+1x5qlyX^iE`pJl6G; zR!}!~hW#a#6E-a@oL%Yi>(&SBF5AX`a(<4%D7c%<-@=ZvjvF!!#Kk2)b>Ra3B;8*O zWMRDdGH<%g_bC(2_w#yzmxIKDJcNTNzf^Hr@~ZHb173*MdmfSPF51hxTPL>}s8H@1 zum+a(3CBAi0o1>K4dj5jPWlkYMD)|d6uZPE(Lar3PFgP#-*pU@((SKtKQ*ucW@|+5sp(U?-|>!8LOUfY(Iu4(GU0&bkI|ho7!|4qoGI6H>#| zAap*$EkxO3Pu%~$>hEo8q?b=ZZQgGhpnryR|7bLT-YYC}p1~hn&uaH)xntGyrr<^q z?WLD+AFIQr!TQTyLb~rfHdvw+s@y;HrE|eEvbRbkzZV&KLz)jragQVoCO_0uX()m@ zXH3AEH7YTbOP#?f=7AF*!_O#%0d7zg4LDz~o$_Yl*?nl;7b^21(DpK^Y*6#o^JIFV z*?}?5yW7!^3+^-wZjYq+xDH8{XS#nLDIs!PK5EEA{QlN|mHj4Q(Ik&{;>7y^_X`k4 za^^N8Dc6ggnmgqzz(nSyt{LIM`;qt99-OZDBD*|I0fd6{-ut+6O4tVbCC@2P_$%2! zF;)PIEq5|-AoK){q%3)Mv$(jzcF%j9Byb%x#v#8g_Bg@Do6v^6vp)E68`DeJPmPnj z#>I}0K7ZCLdw}--OkwNH7^OMe_1zd0wjOqkY2(H(&WnfGmxg=zFh>kgJDP3_MrlRO z{FRZM&5$|hdp6-dWgm#_iA-J}kc75QH~=tCTRc<3u+EyNg zomop?P4I=uiy9b;7l+5M0GMNmkdxwTsyb_}M+7gU|E~E3*ES!)@H4hilD9aA3D8yZ zfX7RQZ;WV$9sio$LyM%&zSlpk(2S=z2z%Oj{*b90toDl%jmwS6*x#KGBuZL9+y7)= zF8F+(Of4j2fS%ImAR-2n(4E-V-&SHC_Fh!NaWVobM3VkbNjt3LwfuIOfw)ugXYF_cG&7N# zX|L77F2=*lCKl3hKMmzFM@p=;p#%c@#P-vnxqEkp z$X&s>-`#>Zv5hjDH|mtj97{D0OE$6q4%ljdkUZ_j;@`bx4mTJ&hA2~i_EP3_?bs;M?D#aZN8Wivq z0S^v`d(J}=m9eal*e>bzUAIvGv`(65msil~mJcO1&@){~@ws83X+>ruxL;fYCw@Tl z({~6#b!qY!(`d$6?7My{P(n;@?3+HroOnRdQbxUHGpd+9DnmM>ajK>_Yb3v7cBY(N zt%{Mai}aNx%-ipc01)AG)Xmm#=sCo=>1aGUsyrL^auVZ5@Upvdr9pP0;n9C#L+OsG zA^{5T6K-X_@)`y&R?1Cv6K+rum|e8G(wOkb?=(St1recd=3?fX&X$kEtA2&WhO!4r z1Ns3^c}NSkHe>6jZPktoFGGSCA$!F5ZOz!h>`>q6N6tTADF-hK`-9+wIxKcEnDN9#6UC zL%)s5Nk>ZdH9DD;;kI!FYS)07rT9SU#qSaNEfPnc*04rg7i8qps)}#4t$uC~1t#JD zk&2ql-=y*>;SWTR9+lAsLtzaJ)#I{vGtT;}SYncAT49UR_oMDi$Ta^6@sd=ja?b}$ zf`^t)g0&M8p}BlMd=V4|r48}Oj)w*Yieu>Afm}@jG2HbECvW`CMNf{!IeNyCr;;AU zR~26XG*Nc*W8cjFe1`jp)W4;3@L{i1I`K9ZfnAMa$0rRnZ@{_H=>u2`A#y%{wtX%q zhju`(p4+>B(bRVP)7B!8-R+_mVt|&p%HA6HgYx#(*nNW6?;f>ht3OZDltU$EG zbiUk?69IQ!#kWT7RmU5sfb`R_LAuMZjet6XBpHYYd~Gw;tVJ%{2=dxRwf=`YDZJp; zCvtVT@gXOvR#zpb1tz4^!?PjL&X_+yKgv>V8D=2~0_=cf2@FQwV%ymk)(-ldGYn$#%K?8?xYF#I`T^Xe_bmm$c+Wqr-!E zPWR?p#__q^=}lp!2Xtln2*~B~U~4&`q6KN|uzfYI&P4Is7H^)%UtWg`5l}3fVMYMt z*?;}F2xPT}!-*c+2ORLW{tEo^YD)K#>pRh~=x9T>dZWW>I9}GQDX`l&AYOsCvlAY5 zX^K@WDllj3lm^GH{(|`K`K-H^T*vRW?6vsydqALrBc;_v+6x?q%gnV1OBvO9m= z4SQ=I-;*pNUn*Q}VXaOo`a0&S5YHw4DcU#Z8EEhWY6%gf_M~IEZr@9?w%vVBj|7Yi z2jwZYX)!2HlzJ#?{5?on`W^4wQpF$0r_z^?9<7j8pjMMnhj!0#rWnzqw29ZR&+;-` z==#J&@NM8^V`jE=uLI~Jo-GbpPRWk=+s!7lgBk{ua5cQ?QR>C2Y-!&>0|;ZIECLd_IoiHA zW|^*J={I<~vhQ6IiZ`Pvyk&phKvr_zstU0;3Ns7?_Q&`DqvD}*^XWGxk45sLz_l_S zw4FESZF;ET7;dPzXa7e_dRq+g5A8Gg5lI8Nq4?%jx1%_dV^;X28inLF_f`Pz?yyc> zanftuf4xaSt)G5u1QIa-T$+_yD05CdkgcusTLYmQQqF^rcX5pCw4K0876eO1ZGNcc zmV{9kKOJ1X!~ANGXhF; zgKJX5svt3+KKr~VKr`$%`DEQ)qiOm9S3WrI3ErQ$>w$fhEy|eS(UI-~Q5Zv`uYPTn z5uTOT=U7XJj}WbFqw`- z5x#ihYtE*Sp7_a_18w!2T5PEuZ;j;6L&Sdx)_2r)csyR@=^D^E$(b&h-I;Lj1pA?~ z%1Xi$8vOj2ZGC5~wqJ<`oD6#y4XENL;{8mgRAiGo!G55f(Kqb49E&d8yNl>nnmbk{7g+c~AX8mfdT2-_O=I{5Fqx$R5#{pWAh1C^5D$63Mo#Eu z9;H)OGgT{kq%tc}O37PSE$39PgSsBSiegLBu$#eupA&`uriT*+Z}0|N1NEV*5CNCM$|pjK3zkGQ0~7GpeS0Kh9;eTt(p(!PVKA z+G(EPXXWElo%TgaFrQtqBTV!~Vqz<}G(6_MUmLVhkE_>v&||>pY0%NqDi3(LYVogj z(U{ITf#gg{za7QlltAeXze?mKWrJtNU&$u-`aN!4#P9__Y<2wROJ89O+aYq)gd*Aj zm0aZ%3@z||Gdcbl`e|OvK3`5IOlKWGYU2fbv|cy2A+9xEUwtiQIRC*wD_%HQ@eKW8 zc}~@=Zf?g!YjO3iRLE3j?d=jWj?xhfsEj<;W?G(%RI>pMm6XTs_R$|+Il$kJty{^E z;(IX=*}cs7Fph?r$75omcGK8WSytKV#LhZ4Z$!x}JKVlHyfIbPqMH-YzY@Fv<;Ga* zilxJ<1qARle*Rs_j68oSBIm(-TYv~ReI4Ze@bM#&_)N8=#kao)JbKZzJ5ehw<2%5N z6C|k;cI2kff*_4A6F_H1JF40FsWNnu=+X&3*+-6PZ{C-YnevM@=N(;e@9pcG1#a_s z!8P?L0yz_~s(e|3Y;1UgVnWT=ar&Q0MAE$jWA19m3w-?WqN68}ZvEh_;tl5rkAUdJ zf5;osrt@8?6}c-HxWxylyI!!nf=kha3bv^agc~@}kZ=my4E{ zs8{M|Z#QoLHEoDNNcw;mKdIk%X|)kgaT_`&$mIONK4d@GS7hm5(BgISgt5ovo>FAS&_?A>m- z>3#GfJxj^k5|l1kV#z(2)&j$mUpi1-z}oNDgGSB@PvMdVRO}FN)tg|jn}%&%F$(YZ zBKcbVA4z2~EDIU#<2X@-=vuWaX1hh2MO56CQY!+vd_G?efzIzKr z$7Y}Z1z_;{{x71Ox=kgB|FWuP7NEdYUbh>wJ+S z2}jSaenx~YpP|ZJNorRtsV*t#cs^vNKF^^FG`-X5-kYNBo8VIgJmL$;hdGY-I4GL* zZv4B1hwHUo5mE1-lkr`wdc{CT5h;0N8?$>6C#BB!^XV~-*!(lFgOR!kp7J}vod zApQ?`k75QwtG)m<1w#n_;^kd|cw&-L6zMOz7SMjW4pNr)Yfo1$e&PA_E9D-gvK4CA6Y`jbu%Tz=h>Z=&s5|Bp@B+)}`-^90W5o!EiR68h5?^l5xUWW|GOa zJXxD@qC2d8%j?QiMP>{-r)Q|kk}o7^=0+=<5+hf9i$AzO)4B`g2mD5n&KDxGEa7lg z%*pX?W>HaY*p=eWI~*`xUS8mjbb#y=SkR=Jy;_2{T+n)|+1OH|ll=iZcKdLp{#&;K z4HfP=>?z9v&S^;-7#4oF1cb}TDMI^0M={A{!zgqh9wifWOjw++zI*oAgC=9ubJ4fg zU4ALi;12H9TsK`_{mc$`DZHL2LgM)*=;#xblJu7YGBCbWdVOjYP7el%rl(`H^FH>9 z|8m;_Y%iEgcJR|?{XQkyI^ndlFj|obse#Pd?LDE|VZtRPTiJgPgtX8Y_XZu>-Gso>6k%0@Z zCH4fx#tD;&ZjA4YUW_KteL$mNXJsOC18>)eI)IxV6El38Hg;dk>qn+B^dmtQ%|gVS zx3^qdz_S?nG_{6}7mqhF-*X_zJ~8G`TEj*P-CGRq?d`<^Ekh?3eJgg4bQ&eOzOpu%*|{2xbQDgLszWW; z+7d@R8_a1Qzxfy4gGA~kA``E7b98&&i9xf@J7R8RXlH3G+^sPdas+*WCr!iaby8kp zZZgkYOaseMwMc>Qwc$K&P0NOj`+rj!Vunv4TSxNJ)&0Q1`;z@_z$U3n`LLr}Mv4k$ zfi+;$KPwgofcX6E`j$OdT04RfCjQ<(+8T`c&cmT=c0c8OmM;{$({x5WY!hH0N`;h= zg&oGFcu?ngH2+V0ZMmDHpPC~S(xskMPH9k1IS@J6HS&2)@1R5dVtCC5ZXF*cS|A|< zBx4qarcVv;U+TFmZwH+W9X(yg9}n-odq0r3Q7gFt)PZ7mv7NshS_|-n2d9Ys(NWYXy6#lwD)-O>tNDRj|oHzN3W` z7RX<~>RxkHzba=;!|wrf_%XZdMN7qQKZJid0;G{dqz7+7_oguKLIU4KHAxSh zb>{PiNJZZr&1!yYQtmiSR637kJ?N~U3^3tQ)*V061zq&zDO)s$Jr?a;1<03J^i2-+ z+kncWd{`ofi1``x-#Zuu@*ZlU60$Ps+|>#jZlDx%bP_E(wL_qPs)>R3Q>HP{JcWEN zD$4Iif}^mBM7|0m=B|-?x!4}FC79gv1PY};mP%4$U(8vS)=pvr;}{8R`0;}bc{nFD z+jr6@*V%WB$zX39G5MG$=_B61BoG|>zImA!RvgWL3SyUJh1*MOJmFfvT_}F4u;t)w zwzKQQ3704x?wcO{cN_%NW}y08S2BM!5vfMie?fjYE#uw9S!}0txyT!$%o5_8H(U)W z9xKv(H04_twpVIsG%&>2$_V?El7iFVUUUHd5uG$ozqNTfM9g!l#>{|GZp#?$)8O_M z?5_8vB(CpQuuI5D*^h4YH8A{>Lb1x-y=%)%wRhB0ZK_E6QE0-tW@F`IfD6Mc_`vph zY?nBN|UOmmg20rl^rk)DFQ`gX)rJ#~}Y zx7HP}Ff6(eMGnb0S|YOunB!KR^U$O{pQ1J^D9TX09KL%NHREQebRabA)pr!H%_-0w`T{PfHiOUtB5dKJ)XyQTLDfL}$$x1cF_cVOjG9&&7%djO=#+Vdusm zioyk&*tg!?3-ca44s2f~7%2eR;I-=Q>#T-sD}jW_aqftdt(IwGnGXud8}MsDk_+Zq zHB^w>X|3NHmt0w%?h7`eV7d27==tv}=8;=J2p0TnM!-N3){aPW6|?u}hD!)W1GSOY zvdUou<+5fNQ&zeE8ONRS%gZ?8yIsSX&_gW!sWU7x-R9SWn{EPDN6fV2GQO#XoItTN zyx9BjGk4%M<+nv64LJyNdED^%6vj7Ou%(Jl!mQ(6SccKf^jX<{&3I+A$K58}d{(_p zF#I51i(JnUABsLvXMUIOta*4{>#5Ff-~FAkzHOBgFuWNeSYhg<|5>8Se181Q z$s{N06`)O~zT-^6N;w`L*0%H>BRNzLKPiJop{(D%DHO*1RIBW0d|1yS<`L@lJYb`n zcO8uJxDs?22|4WGM;5=(vp{i6jl(T$>Eto3}f* zYqlidI~h=*&_3XW|WeMGq{G8=tv;RpCD2>;d z<_=c5DbUp0VUCIiCf87D1u6WH8`U2bbb8qle+P901;!5r>kPTE?dO zm*^L%t!HUT+%qbG3TnT!+uoe4}I zQz-kcrhe10aB3m_WwSHP581b}DIReJc0hG)U7D;ij4jMwWqn`*UE>}$ z%l)*I%1;5jnh4W9WdVmYR|sNO?|rFu(lb&xVWy2qiJIxv2P@uoudiku2M2+-+7UEL z@6B{FWH_LYXFZWB=1M+~?p7QC4Y_k2bQ4`2KlPv$65- zG~P1D{|+HS4_pEnU`@>I2@;w1KY5)Q8jod`S51{SX1=Xn989&d6Rnu`mfa+q&na|m zb@%gTiaKF$bGLkA_!f#w?d2ga{?C&pdltz3h(reOlgjX1^B|j4r|zssd-4^o%T<}S zT%qLtUuz}oJfWe0OK<&l!QYTHMCU@01^MkG&^&O-_rD29h(-jFZ#|o#vc_n_pI2L0 zhm@$IAB$Z4=$Yg#?F}&j{@v-T*k{YMsPpB=uIGQfM;ak4riR(P6$xtenw?1B!H2_D z;y?#MQ9BIZtFXyvX>HwXjfBQCH%{M)6iqr!iR1h^qaYM6uif;FE|B_6Wi3IkiCd^a zEmaRA_+UXIN{C@V28h^-{^ajrI$dCnz=Tmt42QGr@=;{n)LM$bkh1zW8^D5KsJ*7$ zw|8NPr4?OV?%pz5cFe7*a|OogdsS&114K+fj#o^+=tELpR@J@=%;A53ou_*R`U(xB z5*jw>oSt@Jgj`qqZ*^4P*GSedpz)#8awjhLamQ6vKAbPTlpD4gBS@_!AC?6ljvTRI~2AET;Mjv`UM7# z>*XMZ!z>X8MZnl2)DU_IJ&cqB)5OURpX=+%1ZmUKFC9qON5xz6{&%NXfuv43(N9-9 z`Vh>^BskN@T$uGGEjwB^ch%VtTa^xtpbg1d40XJ zKx@({!7_~?Aw7_#+T8_C00fCM5!p0mw}n&_fXdANC3O+dd>b$6S$64pN{_M|y>*N| zK_YU^_%phv+FqL|@rRe>SYASKJtv)@)f}^zmLe7_&QOIw7ywTJ-Aq0WJb~|?<4>o3 z@P?h3k4^1YSUKf`SEAlngX@D_YEa&=<5aJ4)-;Rc!9Mbc=B=U_AMLmNg$1RxN~_zY zI8bc^-XP?`DLS+kj+YC?v(>SoHcV00fy{ud3OHw3!E8&`4#AikZHTmEXV5MS(OY1! z@c-RdxF>Nio2wU0)L2nbxf~%MhfTII3>tkGt8UhHmdssbZ)($nB>efkdp_cS{!`pA zv5zBtR{bR48xce6k)Vy!A2F2Rr<|C;#pX zUpSoF3{Li67x<0}hf~|FPxO2ag9Yeijk9(!@&8ToOKeH(XYU1eW4_oAa0o3A+tOAa`pMV zbgLXfsbD^bBkTMS|Mi;hrjCx}wts%y?sri-$jhNUBdqm5$VTj$2RV=nq1Hq#WH$K; zj#~z>YySo_!i)EOHd(G@Mf<}jiu<|<1Wg~GYlK=ljmdG_I2vA@=TzY98}$@xc(}9E zLv$mhls$P+TP~rh!i4f>cDPu{h)DMLvkZbgO_+ETG&T<-#GC2t^xANtW$&>21REuv zqHDv_uAbd$yGuqn?zp?tO4{B7H{Swhsyl7rYW+whv#h(iI$5CwH`B?9RO8-s2p}kj2n4R#;}k^ zznr}-`?E}@d;6@{d$B@ghImvbkR261-puDb=cD)w?W_jn9H1|kt2n=;b(@jEolorT zuKf6sF;x~ezFzU89NYp_GO8CDV=zI{JR%xrU=Q)~hEO zYzl?^YTbm6_7~3@LBGd(MS`$v>Y@CF%Nc%2E3K0>UUd!LyJfS;%>n5r0RbcgJaPK# z28D$T%F7*Lk5FK8+BV>WFLMs~wL2PhczHTI7p(@xGE2Sin(tNS_*q#d0Fv3^Wh0GT zy&!qsb|H@!&{@5Af0fTbQug&%RLvqPIgVEEgbg$P%U3N`w|rIb{~@n6-_g<@7n%Y6 zwNwowd_H38l0gH6o3eVLyu$*(Guib?`^@d zXw^f>z8*b(ZwpA^sOHg4ddT1O58upl8!kj(dW>${tWR=GH*L6~R}pGPj~X&n)?E~6 zQDX4rRhN7=&^SA4rAJ!sSEfzGf5-)Pf=8Pb6~8+dqxV4mEcJZ10aGamCsjxFii`+L zF>J4Yz|8G>^&^tL@Y;p?=#?d$VLb!UAc7=%w{lI_5hV0E@gKK*UWhp5;qK`hY~O0H z3_Z2{upDA$S31AcMJ8LTmRO+A|Eoqq&EV30Agh!Vny#q>i4-+~B_^h}W*)s=n;zaB z&tRinZa{vCNlG>>2S0$A*XX%&t?_7O!hCh?EFE{290L8GPPA3cv-YyP)f>lr-$!q( zYaWib^n^hxkH8H!g{{>eXE|cp1r9N`c`PE@S+CRZ-9cwfz>6Z3DiFN(kRdeaW?Q!J zvV{!~j4iO>RmP#MN5K}!58g!D+!zeL34vY6KS`VQys6>xqNfK2ljh_j>vyq(Vl(DtZl-B9QV#rZVDZl6GUz zoOx>S_Wfz(;T`^H4K%)Nxa{{QIQhm0vH-JbA7(M7vOyiCz!(zw)ye@ioNLE_el7uw z1E)H!#qB_htg8d6ifz08h2DaE<65iEe(CMr^H?ExH-#=$iaJ}+nJfYNk3BAla!23 zmRxDASjwo^tuf9&_-v2NShOn(_YLoo5++7j;zkp?WoQh4AfR??Ag!I$%Uoq3|?*+EkXV+^Nl zo^-$ayz%-iCV~l<*S)EOwBc|r>37JpcKDxPp4vJ(*zZXKnW_iGi2x&0kH6E#2zVKw z#r}TUg$MRiFZs>(q;(KmOd5XqJp#7uvNw)K+T+B0=}r9u`hwaKRHu|%1C@90{QNYc zV8NB1bhXod0`P@m)Sqxr0%_QV6HrCLc`7>xuP{XQKpc07E%1h#@czie>-MgH| zcWwq`I;V-e+n?|RbVuc|FtBlfU2Uj*t`h^g*q| zva+(Qkpg-5Me_lAN97}ULGVS$lLYkVC4(Onn&;b#_R`YRJHY?Qd}-aZ)R)OZ8i0bZ zo#0J(IQ_{E=9o&qdPVJ!+9P}sb|rgK_mk?`2l?uiCa9l6{mD`f$FHdAN744#51<#% zQ~a6RQ6FdkUl zPQv-G{s)elsW_3o zPEZQ~%lwZVIEdZmPSXJ*Do8Jo7Caj`C6ia?4@w{HfT>;}kqbb#YFCCqd7aXKcF1}# zoZ}&q>nMfCy#8nvb@sV)aJ-{#)}{Z@ChL|9yg@>3!z^m?2mHVn6mW<6Zl;4NGUYWj z_L}Jo2?e^5hY=fThw;#)MARX!?HMjoAiqXxVhIl^kV6`0hB-|QK<@B?#p#+&B| zCIEm4sNrmSczpw?;wOW)EG7-=uhdTYrGWI4kwBDw#}X zioeUQhiWYX(xc7ihkG8WcRgB1zW%5Y6`>R5KNTP?|EzR8rydnQ(ve1w}JeOE44 zidBAKgq*X4{Mh|g>F~BetnS>EnMlkDl%+_4@6yvw`Igs=*QK>*A8KiN!`$PJVNI{T zP4zk*dA}TBID{`~cCI(Arfol8af?NHwY!_VXywZv?5nn(>=B4r-<~y*D)Ok=>Bsr( zSGYqt2!9&_HITc4^eabq3VI5Yf6+ffd9?lVE4RxOn$6LEIL_s>&+SuxxIuG}R~T>r zUqsiu%W>}F@_YeRPrh+Qw5EF^j>e0UU4c3$Z$^^$&!f1@z?5qZS8i!lT4T66PY*H7 zHE>kCp4dozO#GmnCz{3MDcb37&4JV3uM&Gc#na@ieF0BvDMw4Ol0RmW4>%Wb{RQ79 zxy&BEm57DU=Xx}%KcP?}{0%{22uNPb@Xalf#$DWm%fE>-smA>Dz{_&L1)q}~mWE!w zn~B&Aj647J-9!($^JSy!Zf$rfZ+JXw$$pwFZ&lcramj_ATQ{?w=vdTl!dEaJ?raC~ z6kcPmZgufRDAVS0*p6!7k9={_K%f0VbDa2jgGV0oFa5B+q^oW2@Hxo_iU#vF+}7&E z^+Vziw*@eW+xlw_+2`6KObJVVLP_$BScOJN{n`VG4@>eoWSXNgMCvW`ry?th2_Bib!T^sS`Ec2=2 ziyAVAN#_e$4}6PvNJ6T=N=*7MUogCl5GO_DAq#_{Z)pw}-&1@OB@9+9s=A!X2f&WsfW@^{vyDeTowJZBD3Dk!j0ZkwNmca+^FE`!u zz@7(o)f}seUorlxufo6|U&Db3(f?!WyThse|F91k*|IV+zg8%eQAR=wnc3oyRCbcx zIbs4)b8MB2GL9S^A$zZLoWb)x^n0GC>)Um8UEhB`@ALV*U*o>-*Zukd z_ZXA-{JYfQtQjT>8HN+MwxR=_^E2r+RBTgNRBdl9+oe?1VZb&}W#i_n%@E&U6P;6x zy$omHqchg=SIIn<$w+}9WXa9?vYxChhvAg0wG`L{J0pS=Uk5q=ptI0cWxejdJ%Fz4KLHz zIZj`7I8ZtpA~o;nF;!Ym?(<7Kvli~0eM#clNz319ZQiO{ z=;E7B&r0^fVdRM)FYEVyXqPba)7aE*WLo;j6aBf}E?$(6( zGQm&2qUPTk%|McDA@u%~}gJ-i+6@LuvyPN~mmZtd4y&VmN;8V?w$vMvIhQUerg zX*4M?Y^bQ}6OHt7Ue|teX=T^023bL-Iq9kqUG>OL#fg4E`&r6x*w~*r(X8^>D)b-T zV!9tLoKy8NX{HgDF0Z^DLkXvS!st(0jGJf{8;*Zc^bURbSGxMbMyDbY}cpybCLTx)?}#aig4+w%)hz z+kn=S8uA1mcv(U@M)L5|JrchJnT@j8ylALF&jNe8N+!@XUF5kZ5h)YxE}ZQ^r(K-;-vL3Bimi6+&j-om;U;F4QJLpFJgK1jhjS44x>%t ztCO2MlQq&jqCj^OGJomGern(JL}5rneA^j3Y`RqdKficAJuS$edUAL&00@AE9roD& z+Va)s=$`$??mLy|BVl7({oJA5W&;zSxivP-<6~Pzhq|6%bO&IA1AC2{aPO8iRpbT> z1uj@tYlLe)5U|3Q7-g+UjKog|U(kd7;y6M1V|sx@7((o5z97^TiM%`qhlLbwS3To| z%`;`WS0OmxFh6=QW$DVBqFuXpbL0DWmA_Jl?4qr$K1oromtCpMM?!R@hq^S!$nqI5msL-jPfXG@{m0tqf_}TTy+- zDjV~M1vfA5`FqznSS`*MYy)j;YvbkPYx(;1Mwg_1+lA=Q@(%@4A{wOIJWKDWo~dZ8 zWp2vRJ;628ev0u9RfUKy&)t~%n8pu?gPYvu;6*}e?=K3Grm+WIwQJeL`gnJkmmrfC zw3#rbcC)*EXs_6_7$%@>NmBdcZI&LqIu~)<>A0_*uMXC$Wv$8`tpJQ+Q&Uq-Ix#ma zEWTDW!LI!5@|K_50q=3D3hiKUW!<1@;r{wp{kw;sV$Qk(gic;bUGLUBQy7_GwurC0 zn6WFcG3a3a^t0Wk(cw}%u*rU88|l?m{*iV$gZUSnW3G|F@@uNV(d&IEct=4#d^#4* zJg!XOG&v$5N<75GV;(LM&Paz--#V{&mzfHpZ^j@|M{`2#lFtlh;M5>z?bg=}`>qgj z3R)4jc&fU@o66COv`>o53}A+j6L7R)$)oyWAXwH4%GYZ$zZxW~ymW)2*iKa^i5J3q z!J?U>IH@73?a{%l%?k36^l5HXrD)j_Mr3+JKmqq(Vtg^fBg?(RZ_)G(K?t&yBNe0u z0!9rSmdgrbX$zCv%ob{i1leimRxdn>4SF-=jg|O!Dvz3U&0@iG8+y56gldFT69k-5n!tbc@|5vO+t>!t$-+;azhvD4T`n7*mSnjR)rAF2}00FxsB(K^sYGL!Z82L~K3aQ0S zgs56{T^!wco|?CKLI14?#;AYgjBAS$F8$%&0!H;Y8{z`y*s=SId1i%Kwq-evT;OtV}#! za^uZJAan5WjI35J9_E776z}?lV~cJ_S#yZaL?*ud>iB%q`#LHDI@ef}G6}4#X7rvM z5Dz?Wo$tFmH;KbvzU%Pv6Prchj3>mdXh+5*^toQ) zt~i}*eVQ6V3ACq(WM^bJ)*aOtot(^lI~5gf@FJ!Bf!tKQpg<;SskdQ$x52xu@<;U$ zGOaNCj>S1)Qr=#+5UK^?nuf;!?$!{sH9Gn-U7;_;U76waYqsf6DQU!D`D7K_ZJ%k4 z$=_%3J(Mco+T_BbWGUL*iEn!^fb(uDW#JFlniBsY_Apq*{Q57Ms=RH9Ry6a+_#{o! zIAMppXoZUP4kcpJFCF+;H5jT!HAW&GykqbMkM-!|~=n}we;{M!(loiw#`@3OaTo;7Y+Nt*?K2v~8L#TPmcR&A_+haL&8@R#Pg!~hj9MPt94fi<&01&3&FFi*1yRyvk1qKQ3}Hpt zvheQR`t}5{9lissTen?-%RxRxG;j<&m|rn|g@>dz7LJv(BGNTo+up1ziL7gkKgzlK z2y^=8ncfwhrdueagADBHJaMP0iyIEOSD$;+nO5~rhWW%c?+67cdefuW9i65J&3R@BYmnwhh5?0*CDiWHh>UlX zYbtMDD2={e%ed59=iAR`tm_)X6MA8h0*LXj>W@x7E+;_cSYFvk!|6Y1p2L+{8 zr-{>XeWTyz3rvuuSv9YP8WW46MExWLsDy|H91@~M2JYJdNK8DGS}6 z7w_!CO``VEs9ui_@1(m;sZ%A;fG)l(Y&zw}hY{oF4RgrNCIj7hcV2(2Qc)h~USJI^lK8Xh&(boIC$&2rjk6gX~k z9NH`E-q2#p8hG!J=E|Gz6nqR&QGULHR@<`Do~N}f1_|Zp9zRHPI5I5O?5TN@$n2H7 zroUo(N9e!A>ouealJK)o&Y0O(bw8?a=rf@zVXv>vDk=?(k% z44HHn`##C#Vv^*Cj4ZTqmA6@IlK8HR-Wv-CuX~-!H)~8fjBmWEbmohaXK1lI6`C^K zy<{zq_)mUTQ7j<~Qd%!IN?_UFJDU_vPQx({Fv4l#A(fl@c*`GH+bWUdySC@$=Q( z$o3waW#dZxXvg-U(d(!+CB&N_AcTQq=Xh zL?I1G^GuJ(4V<9K7L%5~K?^b;gqi z_R$VwnY{h=juOaaGSSwPMYbwAn6ppEC@k**yTyr`mv#lLzqO1X&8J^8J@u@!t4mQ) z@y|ljNqL8Mu<9Z&^Ixm#= zCN%v~9l&sGGVyBA&-qAjmz$A$ue&{;thLusfdojy$U&%{#@(|@6dCbGAv3}`Cff5W zC#%ym;l;2FdYhb1&ogiv+gXR%tBCpjl*i!Y;ntT;WpudBW5TW3;2CaE3lmd-qbx(L z*;P`A{BNnKsIRoJzF-s5h@pG}3%L?<_72pLlCqMi;VQdYGbHuEIn$~l1-aZyFYQ1f zc$N0=&bgVKmjZTPmlKyE?}AUxs!Wv0uZj#IDR!y7?=NzGe|%9=Qu5(+Ckx~o8~pd+ zmxdBtk3cn?K94MgV@s9CyKB zM49ThRA#sxV4k2SAMb?;?6sY}RFN^UIJ&I;=S&I+UXQHZVjeFNTeWYfNT6a#rj8Gp~hmW~QRT;b+Cq`M+P|Q|(BHgr!-x8E!~EQrD== zHF&iV@?@TiVj}BIvCCdOz+ry)HuyqS!TyrBE|5R;l%@;lT3z4h@79H?rqOAvH;X$2 z7uG3fJ#o06?N|$!{945oQS^+?uWyw5|}J= zmeHzZpe_WlE&j^yllPKz`^1d}uKpK0`=n0rYPT_GADG7moc5C#2^v!s)yycEWH0;p zFFEUO9uwNwJ14Fd#(cJSwnlws)l1Ae&M2;3u>_BbL&C>p;2DdK`BUg{+O~5K(HQ}M z${N`~sx%`a3UtrfRT4Agg>r$`*IY)o~}ng4R4v2s(6Qzi|{@5 zAEP{*Xo|+uPID-%vncG zq(|oT@?2WmXBE0DZw{7>=3!MWaiA~*me z1~79yJt~8OTgvA!!UViyFM~L%N1wrUvQ~0)t+qz z@=aXRTxP>~hK)v~YV2j};s?!!lm37GXChBUf6NYEmu2AK(k@ip(x`T4e#R=;+FtfN zcoOpfM6+m@N#IVtli9Q}E1)2EEbp(-W4^aflSgCS*NbJD5zA8AlUMPe!4*_OpYYFa`90&T!{$v$*$_{SGbR&Tba_4Z7V z61>Fbe|m;CoQLtfX0$hy_BAkkmX&?x<=R z7)~qnoVr+|aPEi6d6sP3Q7_Ao}K?m4(BVKv6Ac{uO)JE$>$}$W5Ypp#_bYIOO21rRqGh1qmQ9b0_HLj_w!ZXPRc$+RIzSK_A|1dG4Oi~2jmYSc#|VX2UTiwO6)(#dNviZ3zf$%7^(Cy+>9bs-3ml;H#w4!* zF644~s4CL^R7k)|hpzFZ$kNOS0Fx20Wvv7}RCa(+JB8~}UH_S!Q11Kqev`$q{HTcG zesnen8vLrJ7DX@y_?|*k0H}6=fL;-J2?jn{=?!XQglGJzVS+c^<{TNAbO0Mv@SfZ| zRaX3EE5XS-LCntk6%!dppQh<(hb7hWoY?uolVe8xm@+6fOEnN6O7J#Yy(HjabJr%m z^7))mHe!H2k297c<;}#mO9dk@rX>rM*rc-M$ZhcJKW2n|0j3z94kI+d+uO16ZlA#V zgN=nkW9Qk>J`t;LPA}?daVe_^dKCB`@y{}e&uX_?)R$Ti(`2nsl+eB!Y)>uQdzvs{ z*mPRlp9!vfOShxs@)srZ8OHXcud!J6DDuO0;2;Yp)`SXxi5W{Y?%HpZcmAa6*JDXw z*P>Q)AAI+PNd&f>fQusr%lx<(nGuUFmr1kXI|ACTM8p_g4)~eSk4DrIb~GPOUMBlV zxvm{MulI|m)x+#*^q&Z7XMz{7fTm?mk%zLnsI^|Q8dl;S za@)Fk*(@Bos3q@Ii(dSlrHwpK`lx9=enB(i?JW+1#J}dhVUV`j$DUcuP=hUao=L<9 zAe|5OijrQ4v47Y9QpZ)QPz1|uUa3*lek&Z|+T72~%Y978;S9nQfgO(;=+zM<3IDc8M zV9w(G#Dg*O>n6fx>S4N^R4c9AOchA!{Qq&{%kr`@F$7MX-(F z`Ev&2wKy5PUvG+pUO3P}R{NJ=I*y`AD&c^F;*#wDlat3l;~HsDu3nv~YQDt~qwkwq zU{BsISYq#L%lqc&c6~CKrFKMt>vS2Hu4XjPe-RW%$nos*pujIb&AOpFzTgvPk)>Hdnbl2h2G5M3Y2-Qo?FAg@YHf|Br zLD#YmPVQN<=~t4zWZi#KWQOKJ9^GegNf|s#eUC&TZG1WGuPn4h7STAhKqUaF4crg| z;$)r7_;R~0*OR2T`ny%(80FTD=`J5|(u91ct%z)hEWE8938QZV0@n3Wcf_78nz{HW z$D46Lo{^O*?dHMI?d#e=AO6eh{pfvoiZ!%>la4^R>((-!Pq*x8W`y}*1k-$j1ZIl`n)c$AHC3L zb>dC%g@wpAfL2j@JJ^TEz=L#bYf|$aX-YgA#~L75!%2d#chW<`DxB7!<2q2opCZZ2 zzFFc?NWH}NXO&66e)zs`L2QLRkcw+rOF=$9m2$S{4{2|~oDRkOQ$;+;M%-mI>73vp z%yQ-K3r)x>I?Aa*AKGlUPH}?D!HUe{_{1Tou!b; z=BI=uBkL0>aJ@#SQ&sStW8W{u5sOnKKM>E%S98wzj^!nZ7VS(%B8T+3b$_u}->?I8 zKM=TD)Iqwo( z&MO*{IzI`cVP1x^I6GU}`ILyZH+KfFEEO-Rkv< z)Ph&6s*^OGn>Ec(u%;XBL?o|+oD-hb(j9nfI^!_}*xSn+2_r!5S^8>NFC7WiPQdOrQ_ zJ&)5(_2ccvW*3HK7N}?vSKYAUFYb&J1@D>R;yM@fzbjcD`hc6uT8!n5MTc95Nyh+@ z2G89a;pS{lU9_WRiqfM+n^}S1X8Y>TaR8^+L%0Wm3@Ked+XIOA3e1T4h_hviBuZ#u>B(#ou-&1D-rlot;C_)H_@V zetd5G-iPS|e!-b6xl)Td8^x~}p(9-3_PG-fb!~(lXP+JuV23W3S{mF0ol^X*H&nMc zsG0SnJ8EJlbLo(Cej_`I?;_tN>5;i)*^eK|c2iphV~4;2Wd z_3^rW>XfFN>e^VhvM!2%Te%)HtK=;Bx7O}i#$dTZ`~sm<75UT~zLoxpIix>LT% z`Y975RSauOX?J$#$Um+3-VK^9BO?FTl%0v)@mYfr3JDs_$cES~5&79A7@68%gn6VV zPWaMeUYtf?0$_5MYx<^sKu403eMe7$`umPvq>`N9-rWlXa=$KbSBsL8;7U#E9I#&z z-d}&VlS#YM`q2VW`nS@Ox?yLHX&XM?&rkYr!G{{G;zH`Qd^FFwcbfU7vqME?;}pl; zR0(C$(b@DPK(g0k11;$YXyUtHDQ_$TP;AMFz!$49^3t;ZZ+CfA@LvyI)8%Pq*lW>+ zuIJi#;-jv1!CL&*3u)e{U~Cg4i&4hh^s3RfrK4lW9ao01Zr!N?tny(T+CL44LaYl*9Y0l51C;Wl&dOR!>-3!U%y!`=fUOb|4T~%3QC@6u zz5Q1@6?e%Gykna@0JZV9Z7gRt90ojVK&C$7qZPIN^Fd)sT8c$CC#(0%Uy zvb~<^fvf;awOmk{CzsrNj(F+XN(;JsQRqp4x7A?$`}rq!D#r0- zkEG)2LYu@yC@`+Gza3T5E&c6N-agD%hxMW&y-ng$OPPyJ?NV98dP|6KEghx!55#|a z=7Ww1aC+=kxr7H<*fDpp#_hM1`DkMFqREga`=H1-VsR$D7i3TuD;*B~Us0(+iz5lE`*v+B^XTheYrfVa!be9nJ-4F_xdc>Gmq_a} z@ZB#=={iu6_i$KS$+j|cE<8e}#0}dS_8Wj|;$Jx8gHxguk}To}jkJnkb@pbz08rlj zqC3%#4>RLwa+NztL^~2_)v}K>a%n$>WEWn%f2c`Gq;b79gWImO?hLJx`G-4Jeu04Gcp_G^kPw6lLHChYB55{zrfs4|GEO z6~vu1rJVQ=o6Z>NphlYJJLrJQKT7`%eOI_5CqK6i-S5UuhVJ)42iu?)wAJ49Ua0Z? zMXr4}{)f|a3aa#Djjq_*S0DLfJCxt(ch}B+@YIY#>7NZw`=1toqL%s?92M@HTVz@6 z$rzfSmq(p&AM9H&*4Vg0E>c>Hd2Tlzr=)-SWCzSNmGNf(30bW2?kIh<_Mg z*Zqp3%s<}!eiKC-oumO{Ey3>!1G5SH^9ck^hNn?YT52tAz#r*z=)rzG)s<;QFTiFF z(%+_2R@iK~G(M48Nxo3xY=Hv5u)&srHM07plP_<`qYwpg7SM};fXkZ{ZNkoE_y+-` zf-$sjK5|5VasoJjHao>l+qoopr{tthcWrf!u_A7mvCB$s%y6bVRDgRFzu`YA8{_ZWD|~Q^c1U@fRwXUy(nAs?x-+^y9+$BYuuk&r zo6bOEeaKB-3$>rHMXI>lin8F!#e8axLz!Hu7mOh9uBEq6)?_$DVEq9seICDJ^}30C z{CY&M`|a)+Czs0FCr4#1K`IF{qR@T=VCmVoCHDk*zHE62ofxb+ERl4)nDP9}KX{g< zoYCPXI<_NwS3oCd^j?*VpSB&Go_E3P6}}yoRReN?q_f!~JSJ~q4avCg;kUgPgKqG< z2@r(9qO^cZfl~fLzxiy}8*J@5>g#|O)I?Dhya>@Zkw|kg-Jbv=ub^NDiSz`T-*RGh zcVPz~f?s#KUHh;Fz&2Js7^4PU7dNH#N;%oxy=(QKC5e!d$1d+q{$XK|IJsc z1#5hud9#+@uDHsgB-Pzet05cP?B>JW@#;?VMF~|?;cgNg%2ajhU-_x*$ZlNot!?|PT?pARg9-etVB;^7Z2Ika_~nbmUI)K)Zo(+lLof~cnL4RnCF zc7|iJy(?TKp2RlTz8m@$@rSaW6u6ZWcXyt%St%K`ZHRrvQs37E3(>yEQrn~eC`|4v z@7ri92!)gzBFw#qhYEC&*XM+GZ?6#dm)559v3sZYSLZ_KWbtPNT*f%Oow|F^AZK3_ z+@Cx-1=f>&n6LxhU7#m7-(F+7D~lK0hMf7<^6>qVypfeI<4zC90(i`dsA5TGWEWu+qdERGEeMX= z3E0p=ZfUKrZZ{}6<=h(rLJFmx1uWWimJb4Sr@y6jtsY~0G@t#v>&x3k)*c%sn-i%w z%t_RLXi;f-Ikr82=6~wF*Ybv*4`iV1sb+=X_i=sobf~??c%7D!?K-bN!&%R2-e`Sz}iF{a2W2J`|ZVMM!iDBvE)vn z&)_xv7P%-sb02goMYK<~HS_{&>8D@_MVB6}|-jzv{bSKsiz_1#Dd1yQj8eMu;)Az)>fo1_LleoeAJ z=H7?md)x+9pQ^c0M(gQAyPbcR_SA^zY%HR#}93Y#Nas~VzEPpb_l;1rK zF&=HK^m29}Fy7nhJ<3=SQk4+=`ky{8MwrC6Fgdgs1B~j*Fkx}N@yfXlIC znUe%Q$j6IMZa7!TSDoxo6z{>*2*clI0Bw0$k@S$h3C$-!+o@QQukI9-0qN|`f4psyT&sVNQsEJwJyqnVnxNDDvxgvH+qY+mc&nYao<WL^g3=FjqO-KWOjnT{w$$>6w-M*8s5eltW`!By2*krLO;~4rE+he^?SCcPFm^O z9qU#}e?#tzOL30%Jq4e6bsd;U@0b0dsAnIpj$H)C&S$sRt&+rnVIlYr(!9BOu4t%e z&3C19y~gr&d9`KxsO{&|q%+B3njv8r?=_))0BiaBHut0pfPyR?Uvsbv%`*Q*;MfP< zs@SfNTKuVtzqZGF3UB2@MBc2|3f{Ot1s>$ijEap(N2Q?dw}+3XveZ~th7rsJgy^Us8W3-TGB18qKFzJK)g)+6WE|FqRU{6n3tv2%J! z)%*2@Q1bDyR>t^XK_d?Ib&k3y79tSTKPJ5(2BN*lQi|_BI;sg~{;K={X4n-gRU$`i zS#%fKC8H%xxL)jFWy8Za#-{uSym%sv-KLl9#(AXe`JL=D;-lw;$(aDoP zM~j~MesOuV zebXJQk+S5KehXRmuLAz>8ti|A&A~O&+}Sf+9s(25*nJcn<69-)e~P5We{9ld2sN&OWUu(>Do97k)nVHIu>9>cyoSk9Bj1;T=>LPV42S8fM{6*{U|U+$lT!~ zNornUE)u4)PxO%#y|Jvq5{EKw-Ily+i4#1^yo+adAs1FD$`1xzC_k58ac|DUAQt}j z_g26{ZmxkhpEz+TyA}OoI08Wp@Y*lfCiWpgifm0exo$ugpa!@%yJ`>Z1xp6V!}LdX zw}ue6-)!K&b!`;B&TJi#>e7f?qomu3&}nksmfzH%%X@U z>m+fopY^}MzsXjMsu^xowp{{tMpZh+Mw!3se5Ee!eKXbpy%!+D)!djlqzxf!f6X-M7?J|16gyW1xuK{ zD`{RUgzI{|;KulmFI#(^`hSaTIv#oQr4=f};)jp|NrP;URkevY7zh}*`+`C~70EoR zyREq$Cx$2gN{OFF>@Rv~;x)kkOQ^Wg-|$um>`LV@mkjgJbv$n{bwQm(^b#!OKm@3zD$Z_WEP20TT<58Zb)F+ zy!89*gNFo#fD1!NP+}iLe}9UeEJ#_Ae(Bl2rZ8e&6A*pxvaGv;(y_y-0sx4IvW#Sd z!Vd!Bl$5hpQ0A;jtr?Pi%BBV9&D^`6*|JLSAHt8YJKq-%j;ilTYvG=|{j);Oy4*zN zd%-(y4@?6K8eK-u2&dnx9g)|LfNB|Ph74J+5DSfAjPfW_#hmZrKP-7UFY~&^2Bs_& z3#YFp3x%3Andi{$d5p?H$z^DV>WG5s>{>#~5gV7|aa!m_(x}Mffo1fbOFhQ(wP+-uGsl zLBnLg(r_uTiy7PA|EDKTa(zBU0z-9nGQXh?cn0{u+2>D1k7~jbEM@)FlN5shh%VNv zg3I=V>3yfDTsU#J=T4P3f7(;SHl=&7EI+3kJ2>3FW>~EKZ@?qlc^*hC?rN9OqX0g_ zPP5zylZuD^;T5{D0g3L4Zio-vjk9^OPM{Cm&}ssz$fo@*1zqe%m7WiS3$baLu~_M1 z*i$@6>Q%C^COXt%ZzJF0JzAvSHY;&FzTuauzNu2jsSb_KsGdAM*nDz6#v6HhsqKk(VMJtXH!8X}yClE9zpI_$hQ%tR)+4>yA)SR*raz zh<3Pij0vsZt;uxGm8>7G`+Sfq+U+0gLmvJki+DpG{J6DF96o?E$?xZ%RMc|Tn)z&N z7v;pK`3y<+O44AoIUbwgyxHC!nU9k?gWvhZ{J3GVCgt9Tr^`SP_4$6E5NX((Y$@5Q zjIj8w$COHp>y9|O@&t)jROOu8!7GRBA$HJQO`TyEPe0W`B)=^g>#qJ7Ef)9QGjRyn z^Q(MS`VxQ&f3VFt5r(TF)8RypeG3z~+d~IyJa`p;jArz8Eu8df(7Mnv>;WR* z^&QNUCv>M2)hd8MKE*_P7h91ne=tG-SPxby-`V{xcg3PT{Bzi%33pe#V4E?Nh(Zr$O$2nfjNz(U8C+in{Co3kL6u zMp|N3sd?E=37`^xxCSrkbdN=)tZ)*U1Xm9jej-0QC_iI z{-#aA?2ec#P;eA|{rhOAzXm-CiWNt&{j>#<0zRWOh$JS9Cd^1=DF8lD`NaC_(J0{+ z?d>M&3unj#*6%FFi*jH6*)3zvJ-|5T|9$(>vFK!zIWfT`#ul>__ z1u#ec&g633BHLj>_A+2{Kv)Ge2H@Wa+%!}dMd?k;(=B;Ksi_yKHo%2r6;g|VrjwK@ z0%!{SXN0jE@cy%RfD3BeT2!Ziwk<#m29EWPmNU(R9vLRMZ+1ZIdSYhevomEp0KV}8 zieJTom54&X6aj%G6fK1`Dm9H6Iag7{Gu4u%RJF=m%;kl17a~tw=oGZ=JfX3Be(a@h z(7E=bgq>5nBLOiom^XNHP49SFK~rrJtZjm|*4`A+NH=PGH3BSEF{kDFsMGZPzG?X} zpmqf?C>8Zx?Q0G{&{+BrL&anMBJ<2-G}PSHE85n<_v4 zr8!L29q4&Ev8c7dL32!2oq$%$+RThN@G($j$+cfk?^}}QdU<(Z=!G@|>zA_8a?uv)i;luvElfGKHhp z!ZVRp*Y*v*KI*Yr$M8}U7-(!RrpnzGUh(<;uPIBq!Vkza(BH2iVMGOWbDINAWD* zihrM|>+nODdnhjKq<^z4gBfNLH`x+_|1ozdV*FNvCOt}vu$!cKGxTl$JIwSsM2_tA+A3)K-)J9G2^t0!2KK4s*=)VYr(5!-&X7Nm;Q zIgfcRb4kVan^Q{vg1&^kIF&+rU~ie+#QS(%j<%c&`Grt0uk*Gc^WmR1HmwpZd{X<0 z_yV0%>K?=0fk!WaE+;DC;B-#-nJJ!vocaY{fIy~)_=n$N;_;7PZ3o+#AL1ecLRjH; z#V|qHD(;d&O9+H%iW;OSQK?#%oKk?@QeBo?y2HNvv>eX@wAa{=mZbU}`Q_okFPZx= zD)nu92d{k_pz2}jA<|{g*Es(2who$VXMn6L?aRq6!RKA-B$S`{&pyY{937&H(-uOp zK8QwMQA%V5l5Mt2_-5boNq^=aW-+fjgPyykW&FwWNe%papAwf!Vkz8_w#*25Pe;e$ z2bgpgd2vpzc(1aJ0p_ATG5BMPa)@;%dNA2CQyhvlYLSP4dHN#Vq2UCnG&DWr*Jjpb zYk=PasE8SIh;ki*`s#x$Hx5Ue84#J1HTDO{2-}VH!G6T++Wgd(|BfEjv?7WJamMymj$oh6}?tola@M`vDVG3AF69ABx{*JQ;e!Un$C>T!p(A z_~j$o*=MY4^Ph<1&Yji);_I=a>zkL)M=~2U%210M$TtpwAAHaZQBYMq8TiDN8H-tP zaUh)yII6XCEML(z8;$&F%=6grJ+HbTD)dSiOx27DKQI9hKA0u|6P_nr!857@nWZXX zJW@>Bzm_Tc^kgzEAMIzzi96&uqpGzGwu$FI|I7Uljt$7ewrurjCIEuCNR@AedFfZO zfnkd`xT*rbMBcXhN91zhzgr>0tsH_n0uGRR4Dhbb&WC%Of8*DD+-Lb5*O|&?ls%6y zle*v=-*>M6D>Xm#A9IwNIiCCd%%bE)`kt&_RZ}VWE|VpZBWRiiWz^wq^g}z+n(c{% zHqg!Nz(Z-Z0mMn^wx}TrPP<$rBoN2|a5J2xyWjv>RX1nh$~~G$CxLh@sB-Z3S}xix z7<7t~Am@wqPO3iOzW=sJ_4Ih{nWMSjpIH=OZCY#JIa=_Iw07EMLpR^DL1Dmn0m%c5 z4Hls?C-6AL$abs6=FO0E94FX5!mOt|BI*65&0*vz0^}JQhKB0_)1!@oji)K&mY@!d z2Q1|&*rqh=DXq!6)Vblwnpd<;FFNnsTJJ8xZf^;Y92x^p00Zn-hQ=J>Sju*Ipgl6w zB5tOD$vF5HW@i$22%Krf9ZKuNa)uD!hfAJimGB-_QDScL0M`kC&jskDW_j`6yb{q} z6=1{in9hQ02uUtE^|*6<$$xZZt0ex^&A1lu^JR-C1D3`Uhzn!?jZKsTNN0H+2hG^G z;^i0ERNBwfz;Tku+t>y=6eP<|4fIK1ya}R?x2M3}G{zPv*EicJy(S|p9v^rI6dn)@ z3(@X#Ve=7Kvv2#GIrbgisBmmK^*50g;kMQZm(wP!^_rBWVUTlQPW{U#4Q3}HoG#x$ z_MM%ZBWm)c{xX21R!V;O!kZ_g5y%ddzKaV_U(20MQ5r~j{I2_6)50v6cDX28a~f|! z%MBza&6?Yu;+LDPj6=BrHh&+3YXmUy&LlcAB=pk}Kn#H#`Za8T301xi(Vv^@S^kS9 zgWUy|ONxY}R$m8$BQn4Ndj?k6AP8wfpvU0`U}g4bS_R#y1iSU6{M7r+ns~zy@CCPB zPCa_`m?XJv(6{RUl9st0Tt}6*9V?)ZGQ!+n+D9YO_w?9K*h&D{xkh0aDWxJM5GMm#aeZvsI|gD{_KZEX!?FTgy5Qj9K1;XTnme1U%Fwzh+ojC;fnfruXb z!+)yk6ML!;4KJUc5$E^NV}YM`&=%6*pF#f0_-j$;@H9sjaO@|z-h4FE#QPzS31oYz z1KRr|q2476- z99j~U%t1gef;O)XSOGeKcs0f|{mCu|nA37i1tS@fH$fl!B~4egX42}s@|(DGkFP${ zkkkF)=k1?1)C>kZEh4-rbvqy$ES#lbD_s;#ESRgn`wD)lRUj9KC)1YI*TP%noMh0W(~H?=4kWi?=P!MI&LL z`v!hY^Z5M>6eyQ+@%QOarMx7wq;~tNv`CrX7xJFAC>|xuCI;|DlARdZy`i ziQf$2$P;zXIS!kClJy@GTY|}E(8XQ3GiS5QZJUk!q{3z=PmbK)Vah73u!@XnYQRkq zNIQhJ4E7p}hW;AUjuN1sXq{ATA(___FIpbk*j`&Q2V;5BZtmX~b3W_M`Ge}QFdxo@ zB~JV%^Z`Xk_X~jOTteuY-lRhb8|YlVF%eaTN@Fjk(YCXq=%1ikc=S{5XUE)pEP7zC0H% z#=s^@ZbIC1+reGsCOs04aR8Fv{DevAv>>`MS-8be*|z6NQn2UZ#Z0uRw1>vcmdW#K zPV#oq$=_PY(MNHmBA!ZNXIupPkj;JKOCz&-l$EwF_CnF$0Tbo-e^>I-l{Cvaq)KyI z>Rtcb2$awNpBBLX@2(-4M4es?&tShGKZDubTY6X&Iu4X?uwSLA_Xo}a-OQIM)lcu8 zt5T-@^80bA_dm1%<8{o|cDo>{+I@Df7)q8wl2^P{$sR$!SwjUPpekE8eU8g=t+-rp z(CSvmIC{Q<^K{Kuges%2g3z&d!s4q+%n;J%xZD>7Hk*5Ld_e9G{D7`~JOQRr26gT9 z5&;LvPJ80wPovLwTUP%Ys!+)ktE8(3<0$3KKowa3$r%g+G+Yb#(*tc}=ou`}lD~Yb z@+K`5GeT1z~nYxW%@ z?q7%9-<`a>Z~dDuLGJ9_|1^OoSk8jyb<9eq)7HTnKbhi8WwmO3TS*pK`eSVd_P{O{ z#hUearTBY$$;aOLydQGaBr7I%>Hc^t_FA3`;J31D_~mL*l;Osa2eUTkm5*Pf($V{R zb3L6$8`tttX=_Y67N`~7ppO6H$q`y3x5qI>_MkVhB1NC@=&9m1Z)aCYR$|d+;0G=xG6?99|XJ!u*7x1 zK^eZ=(RUpGrApfjD3l_zBU1vQ*?uj=l9(&oO>ym|4Z>%jk!F%_?B6A8M^NzWM#5t8 zhl%1MnY+KsEE8n$J7yaKR_p2ycq=3aj%q~o+P9-nA;vGAS^_a5#KFZ>eY|RbW1bR{ zIKI|-u1thZV%sn{Y^K_96Q3q{h}p091vE4Yf{_P9RNwQuU}03LZ5y_;A8j~PaqH~( zFH_~>{xh&!>r3Xu39TTldlQsI*7-C4|Frhz@le0rAMjL2B5lalB5fp+eQ%MFitMtL zB|F)&&4{81m4sx-RtzS4S!OIn*`{oR!C1;zVg@n8jPYD!#(m$v=lS>Xn%C>AzRhR7 z&biKczu)JaDl<>&zoUOIKqXmVcIx*$9iU+OhGgin^9r|}r*yyzO@*C#n*5pZs@R6C zAmo6dO71Z*aZcvc9$l_ET5F@i=wmd1Qs!D$@=j)GUj#v_N0Y5N5JiCAR`+}F7&ugT znU{VtpvcS0MvRTwZmhLU{;ZMCUdH|{=C6!uP}@^5nSLc?ztPzAhm3i$xVU9M?iX;&D@1&P&fy>iX+%6k zfAfDRC))yO`U?Vp21*iCpGBOD4jA(~)FwZ3FWu^A^5Y2v*5#v%{6~aDWgG51To`|l zKKU&aN5Yn02h{~~wsbcSj3msh&S5RU-lua*Xtey455w_2K-P5gC9DbB==hH?FSMWsLs?oc%NW) z!9pw)Z8U|yt=+^a@Rb|Y$kPmPp-k=VKJ7Ezpe)MtJ-f%e{B*}xBUo<5;@MVLeEGS= zqru7=;(z*OugyyC%CXu%|8m}i3;JkfeVyx5q{VQLz4_G^d$SG+Q&-6qH^i47pN>0C zStU=w8aFO&Dwm5!Sxg4FlY-kvm}<`*Wa6w&3LiRdNCLVpx8!~^A>lUkdmiGrlm!!|=tK>aCbMWhS?zWFRtK-Iy2PmFv?rD(EpmUFB@x2Cfz|Cax4)E3A zjpvDlOe@d(sd{Suw?1}1O+f)Ea>cj-nU~LELXh2mLH8F?dZj6~G}U>=VejRiHchT8 zcowYHBe-MqkhaC2$qJYxdfhH}j6)u=GZBez@G`C3w{lM)T~1`S@e_H{X2`4-IqfWu zh!T3cL#}FPMxWd4GL}2645RE6qU^b&{#&d7qhx4WF25k=&besIqDfT{Z(+P^=wV=2 ziVIsm$Ea~QL|f6}Z!(TbpUVvz$O#%`a_py9Wd$J4C#K$0xb;W}s-V%Ro|?>-+lQkk z{`d#s-{T*t#;Gc<*UH!XXQ!$3xw^qG;h#kwct{=&6kN-Dkujk#S~OT?cB2BUGf-=m zu|Xq*6dVpHNC4)Qt#b-=TlKq5+G_eW_eqXN$=hzfbgj(rKVJY5zlqE^%kjyj!I9bY z;L4Twc2FJs)LwtXd%){W^C*^h8RB9|ba~rnlM|#d@pk1@Uq=7G3sp0=E!8e&v~yFt zWuy+6AO?HX{#Ad8*LK+l$>g2p4!vEt@Okdv7*4m3QR1<@3HhIvgw}C{6cP1Po3=@p<_&J%(%0>`}AiOfBC?oT%Jz?D<^M=)qjyRl?XH(>0q=BXzH%z$61_Jm7 z?3i(q1phbfr^@@@W@#&ZOJ5+GDZRS0u$zq+I{Y@|2IzvtRw!YB&U}Ba$&QtH|6AM- zDa$#P{cx!k2EdJ!XFhSypWAKF*Za{h7#8v#Otf@z;s7x!N)lSOx8Bg%XZ`@x!4YS* zSHQd2dyjOV%~$rZ?HYxlPZP=$WIl9^)h&~~wQC|I2lye;Wn-L%j() zZp^Fbq`gPc(~63_w<%T<+d@_#RrnEb61mZ4p3%vUI1(cn{a*UaNcVDnj-vvNeN>XB z?lXR6bOAJbksvuosyz7pl!#$V@4PWF zH2Q{6!WTp7Q<_ajjvQ&(MDT5D0(gM%8O-vUc3hkZo3A|Jd>aFbj_0OzJ->MkC8ZX! z@#vWM_C%T|sXtxXGQZgVv~cemYHTrUx+?oHmq9u zO3JN8F80TINM<1)REZnWWYZ3NbyqrSImqco)Ol|AY(efFyH&nFRGa$A9TmaGODC_G zt2Y`rA8v=gwXnSROu}3FSlX>Ku^Y$IP4bO3zBWmVLH8{{FOHu(b75S7H&u3Rin^XB zN-shpXUE6ID%Q7Y%Zt*^y*(g!iXzp0gcDM4ZnOdW)~tYe^}D(laQsnC_8&*dfMX3N z){!Tnc(S#%_3-tF2JC1_N$K+HU{Uwu<}q4cUxMq3!6PY5w&$A{hA@62bnDpt1{-b& zHsa-Qo>_OAJuU?X26|O+rSE~YNWnEJqmkD<;4P(lV6i=u6;CO(ZB>zxk%h@GVwRVe zetdpSYGpN>mPS8A_yo+&M$PYbm({J9ak1HU8q7?7+X^Q2L zTf-N&&BN{ACi6go_gHeA+u6%$1aX7T0q)jjs-2+Kr8+gZ>QUWF4s`Ksfn|}al1TF& z=qbrWf(b2nWNP2z9{{=y2?XQ&6TR;&`r`Q8QZ(=8f&W~Ea36ff^B!s7 zTYNrE>b-QUn=B~9T)1$u%u*#nYu|6WJC?sO~u{;Mp(BI#`tWfcK8sV41+H#{-pF}`sRZ8eqp;^+rHL*OrM*>Wm2p+XY1VE ztnJEry$}07)>Z-}F-k#Eafc=vH&=k2J@GjU+d#yk>Hh1(`1SN(3K%T*#$87Dn%#A) zllrrg(AdYM&O))ri`q)e7q-~=5aRB3h=VO@SzW|=!~Qa!fXSGxLa%#FjaId9GwdVl zym9~d_-vXi8XNJ}-|P1(w4`LvOfLXMEL6bQN8+KdgY-@=&`=y1S6K1A^$<{J~QtV`R5!Yerfkyp^aPOrxq|4vp6<3md)(-J2hn3 zVBt@4df><}z)OeDelc{S^8cZ8ES{V>BHq6Um+B(8-*V}2IWiki1G>q-ToLHmS~`Iv zL8l&st9jUbLlSg}sG1_s^(z;5lp=r6@S2YHDaLIJ9(b=_4W1Kmn*NSL0ru)k&$^wr+uOSv88L*+1#wN z@$#h9R8;WY$NS`zB;>T$IJJG*Q(uQ1`y2%`Rya#qf6B;^!pCDn$ z*2`3Qaj}irI>W!h{WhQ^Q_Rf_Jq&!98zz~Qyr^aiCt!-!DwGf6aJb#Hq4e~0bG&qR zZAPLDU;onlk_@^3Y>;O3=B*wTL0D=D7`#M0jtzC!{ccqujU`v)bZXmRd~C2hDMnE- zc-^HzwGW01X;Eq&ibdF2;07?kf-iqht9|&^v;2E#b4lIO03Q3Q?4r=u#~%4_u@l_F zYap_WeOWtlMBC{y&Ox{@{O&-1|If)ur%}QITKqq1HYrerVr>!hzPH!yxSRYVOM$zPbp`(Wzic3nfkk6u0Ar!sZ>wT!L_mpY)oLggPr5QD^cSTY9A#9s@b065XK94G1|0%+7 zp04;`Z~1qk@s#H5OYOzlbc3D40H`DXTPMOaoA}r-YcV&N2+sWw^gjQIB2&p3{o^Gi zCuS%j?j9cOP@XYkjl!a${9pG!{gK8ABi^*V=_9IPft|19G?bkEyx1SegjZGp1JrL2^G`X`yYdrhu zd!pkxBHxZcsR?o-Duex$Eb-~l(Um+oV(J*28(Pn}?EuUT2kc1z4Pk& z^e|!~3qhiH^${TXJ`IzwhgNfwc4iG+HPNjg(c!2dZ!?2+~%lifGgPTH{>VJBMg* z8vN|8_Q%Qjpf?vLB_Nlxo5r)dhFWMECmMvxv;wr`c?ccmFfIyIpNuK zg=%+O>SD#rr{ zYh!FN!s-#Eb;D8B;YZa*LHWJC0*p6kDb=V~qwY1d-cfKP_nUY1$Gw|-Tc*hUZE=lU z2Pn?+xT>?T*Poc1TVe7e_BT(49lw~_XMCP(S~^Jc^zstUmr&@PRK8Ebc~<#9e0V5i z*hS3mU4m~S_iaKFgt-RTE<&E?#)#0`xj06GXQjf{rax4{g~k7MxOTeyk~E18<(&kY z4}*6T5;Mv_(quA-M%4|-*=ppV8gFz{Js-NwY0n2y+8dL@JG_2h?s@Uq2005_2|wc7 zd`aQ8VvwuT4kmM|9S+xCJB_|}{LB}KKZ%8#^z+)GDk|iMfg+LQZhNL~G_Z6Ks46YZ zx~E;aE!fcZh`k2JnntOvR|g5_6ZjBAZp;-+Yk0@S z_*0$BM``SvH&EFY#x9fO_~)Kgg;%O}zTdgUkjke?cx|=3Pm}38It^sAjA?oD_`uTf zK(z_%!P|W3b^6qK563@GOwEuyh5sr(7x}q-i#=Led$aU@^kzH<`NS=i`JsKyalKZ? zH7v|pKtMo0Be|lKZEt1!ih+?uvEv|rI`%Ztt@yUapXKU5KEvIbnvsM3{ntEDL;ywp z8*t8Ghoa^hq&?tF!wg@{WdHZt0(~VzfPQ^rF?eLD)N?tt3Otahpxxcu{f5R@fp`2V z>{a^`K{9J4Ry=n#t(g%&tAaG7f6R8r{@|aToh`BPYVwbLfPsOM(bSE1yCknuR0mo$ z?^AGd0k##v@s`WNax{NyGdSUg&pWdsc++Ea?4UkxbZ5IM2CnG39J)bY1c8ckRZy|9 zP3sa(*aPmIkDYy#@Qq_GK(%i+yIfzP_pY*6bBkz|e7Oe!Q@OnPgdyU&#(edaB_*Y8 zQF;V1GwR^O4&Kd-@Aa}Qe_*(p1#dd1$mBuK3wm zH*16B-m9O`Xk=pI0o_-`n(FH6^uHjDDQRC>sic!PG}^$@1luJjYwBxzaS)X*%{;T+ zaZ4@d`Y4DzGG%Ue+TQ2c?h$OwOVDO^o-_jtnMZj3+$)g${ZaruL%}$%)i&Ik<_6*H zsKWha_p-uCbmt(lsO-K$6lpHNDmps)YNccMYN?CV=CSK1LBEll^C*UQS7L|!21V6%&(tgtN&#Bsu%TG zO6#G*&cEM3{Ez8|A_z)+^*~QLqkBkxbw~gWaXMFZMyH`YoH2Gk07PA1xIYOx0$9<~ZQz#gSCD zdY?<2jRSY@R(i=kL?6}H{<6_}xbLk)Fbe6i6{lGW()3~_p^+SD-Kbl}?swma?aa{D zP+%Uy_TqLBBoO6p9KH2eX4`R4-Qg-HG&nqLlKsnEh*J$lzq1*0V+KiqZfJe`hN05`{d8$3@P%CF)t8YQ;%jWcb%rpZN}F5k3oXlx}>ISgvMj-WS)vJ+=lSR z;XR@}9P*4$bo^nBA^NZe!&Okpxj=34YiQ2HD*;ZVb{(NLR05_%lx`{^{U-=DKe8SQ z0{*fx-&r@^C={Tc2)iP^LGb) zP`(jp3YJoi{P4`Rqjo4#rY&mLvq@-ia&%NnM@I)qPyebs1Weoy%`c=tP-AcE+2MpUMb{j@+?GYdT+tU zV`gtZu5`fT$P548Milz=x#f`Ng31cJbQIh}d9SS$OBR4d7`BYC?M1@YXX}yEn;F}# z;u-k^4MZ_VUTB$?`8%nC*G#AMHwhf}EUqBGl=cVq>X?M`&v(FiZ+JT}+5O+)#O*E9^tftpl{YXc@u8&#b39!p_Xn z9zB<&XO*6zB{iCzyAkWF@rpBrnW%wW?G48^=H}A9^GIl>4N`}qx?_wO>Z7?k%hJ{s zy+D+~o}MD`juG7~teq22CNz9q__}&WNlD3k?VSv`oX|=A?9r<3>5tvhhjzo#IwpsR z%JJEjMR~3j5_q!wA#Sl~blJ)TwRkOzXiAw4GO9a#mbUz#?Zqp1(FjhMMT3++nxvQ+ zTz7bO*}e%?S6BC)8nZMg{`c?SoVDtlDtW2ax{DO%J7~?6;j4e@X=7q8)QhS#@yw=t zCfG$55}PcjwpLc%>8gR{U%m)FRBe-hrgh}q07Jry{Ec4mp_|@k&$%1)ML_ZszUuDtB> zTK>C*Es8ZDpRJ;Tc%VySHy?Rex^>LF+xvVoRe(51nn`88Eb^(r3=a=$Nog|N2?zvg z_%X4AIsETWNOkdv(>y9HuaaGYLoTuh!G258I%e(+is_{hJgX3(rJH#XoJ=O~(8T&% z2caeF=E&3%OZA(=EOV>?rAf1TKN$46Wsf80U3<3$x@-jpMaVoFeITL z$F#KXZ-4Rsw7^I{R(5G$c_LU#+$&%&*W8>zwT}Q`s#;nKv1W4vN=(J4?SZ1#=XBN< z67Y(BGeIC0pijVPm($Zz(}JFl&Ma4h5shUwQAvwE8meyPRm|fD)pOeo)w|=z!5YPa zNzQ$3oN?a!ubCd6q`u{Z3JC5IU8lm(2q2666NhZs1w{jXb_!@+-{%;TYV^;v0XXC+ zMEA-?KXgCkNDkpAnveCJaJ*qMxy&&CII0 ztr-c17)4&P?NfZ_PYngz1Gos!&69;Y7IKC!wN~Ep29|!h!129H|7hW9nA-Mh+2j^! zfO}|VY@o>@=nr_>q~fbCUZ`kGkjcU<03%LPPYcV4s8pi@?(RgRG=X%W1?VVljnO(jV zjh+bG{^|>PpmgpmB1JSBeGz-$1kJj9E@wnQH#B}gyail-)*wRCeeq{)U0_tT9mF4{BNo+AkRu23`fW&T(1nKH!EJX-94yK$vx)?T7I0^ z$4S32G%Fi+IMUOrZ#AK`=;&Or^BiK>6TfCDIKo8xAU?OYxj(BlrJlRz8#`QxxZt6o zs4Fq+^Wj)qh{}||b!Btu$Ps&-n*M4rg&9}ZEie0g^C}zYi9Q0aTMOPN32nPGtz<3b zYW3|r)3MlHu+*}OA3&`d_l0wPOI$v3@u(#U=#oBm|I@+)U%r$WaH9xu!tjz!b+B7DUd;y9N zBYOZK)5&xp&BR;ni*4gQ=AkmpIm4wcRY*fpUJ_dW#KrM!+9A{wa94b26miy7#YDcI zY|Rs$^fdyXlq6tjU8hiP`P%x`MbwY*k$)-%9toP4n1_;)tbjaZCSeU`Z)DOMw-toh zUwTp5tvf?yD6jzadUjx1{lTzs=ekV*2Lfq-fdkQ5%(yl#;lS%B>y8@^q_hv=!kiI5zleP9tV(@H zOv{mrz*{VZU<`_g0@g5$7gErX?+-c4vJjpWM9LaNTD+>x0(5!HnGG z4d>DvwC}@<_w6Ou)vw2&jf3&0aIvBbgL8&P0S!dIGy=mTtzkiX=P$Ta>||;Tp29h} z_-vLHe4a4}e&(I%?=$z$*Y$zeP+o{fUMQ}9DJ-N89$Ys9P#(kW$fBYmEsXwylZ9tM zFx*`EBy_hd;o-}2jYJT?OHd!JH*4+&pg;wPZ>9(hfBxjEq{pkIcQzK_KaYVm_*#69 zNYoc%NB<8neuxJaeOV{+qCw=vxvP}f>aMzwu5|{u91>#nYBCCql2#9sP!9>XKr3Qo zqM<=>uP{nYRaNrxe*RXsrzt%_AlLu#EnwnKm4%x{fCgB&SvV#Op!J~8eVYfu0<^5F zTYjSf3dB<}8HFnb)kXg1#(Hne1dGF7kgfR3Qrb?p2HjX2d>q8v9^%~M{Uhx)`}eQ=bU>aYw8a=4++VtL#Xj<@cw~!s zrFB&1!46kFK`MKIVo$hUCAD!EL zrCKs<_2>7lZP!xM<|=8TU;kb@7xvmc?z4!S*y95aDoWtsz<}`n-e(R=|9izpC)Cvm=gEWkX zcH!7msBL%iQkYxCTk(86adu`#!k7Y#H}VT!Rb4$@b%G3n+vewZ$3>ZmKv`OxY>Rw; zYU$~njke5Fe${6G)M_!8<`goKv!We4IsWv4RIIVJ&=pg1&5!lTKk7A=m3c_$GGc8R z2@|ErC-R|B4l3^Cb3%FD>Yl}v_FmY_&NsAVXw9^Z7qIehn=ByR>iSP0p_lLe=yaE1 z9@+2pD$1fVSV5F_V<`*_{RMk+Vgu0(wHOawZL>XOF7@JOUX$x~R)##@<_~#ioC`Vv zzv3s1ocPM#g*+I)pB7MKy&PP}W+sm-1$6?;3t5DY-2l2jNN?uZ%DwY!7W7S~#(jTo z;(ed}gqOBAi?JnWD@DnUs%$1g;iYX1db9Ub19I5C#ukhf`PhM5-Qm7>g>cEV7iF}_ z2L|h?fs_Ng6yfCtf;m9o`{tgGINL}mrEk-+w0E(Vk5HC24~{cTK=QVm z*=Jos?lCY6@VeeT zl-JLdwu_&O5v~;lW8NvQq#Ab=5kMuKot>Vc9;PHKX13XbQ`?dEjVEPxGh*c_{$7|_ z#DaqD5{%gELAy`m(PL+{KUc+gbAPfGYCxXhJ)+SwFpyf%JA?R%eKQ*PmY86v7R>|o zDC#TE51Z@kj0fSb{H(6t>kxn->c8rJG$VeSY{E|zw!$Nri{!K}b& zb?m#mC0(2JhyvSpe>HN7;nZVwkO2catwqiU5tCu(2Sz zK8L5v7?V`pP||#8b8&=B$=_p60}0GDGV>#sFa&2l7rWRh_FE^IGhoT_-o49dX=#r# zGO(*CW~OYhRtwUGGE23DJ`iW|9eX$IUO>MQF(>tr`9$~Hyns;R4))o%Gm%Z9xT~2Y zM&JloOz?SD6?|2r+)`=+ch-oK_I34#>VYxojD0_ZHr)GxF^SM^Y-|cPlg!6lAjx#< zaYT(P#k*DvB1|!n4M+VD1jjM(PA+f46#tVKVLZudqW=k_I!IMUL1!>ae}d>mq(En9 z9l+T?iofUVeCp@YV!H!?(;unn|MZPdBNTieLpnIu{FSXGGOxeXDU98F1QE7mte*1K zGC!U@YhZA&O8`Y;AJN?X+XaO@h#Xh^Xu*f(JrZ9K+|)_wu=?iJuh;p5AW+BU_cD{O z)mTZ!Wkx=ZXoHq)bgB}kCK5EE%U-w$+wSW-^AmAxx38r?KAV7^ zBB1WKBu8uB|Ku2Vu{f-UdR&hL{MFJSpt>*s!;MjEc#BYcZ*T9cA9<|FBaAXOFl35Z z`VHivT=rJVsi^toU~4ecV-(EtVEky=rLxz%tQ%=!-V+-d9)X@DrGR@s^ztf6WX1W) z8(?87fCFwInj1#onJL}%74_I3K?OnFFP6%ktgvqbDuPlGIObD{X&vMmb#df^?z{1h ztIGl@Z}`$x|H+BQv4nGrXP#}MDEiJ*&13&fmKkz@dvL{IHb*y7tX~RuIrBh}oTeGb z!#?Td4>*;ZV*j*l#P{tLC`yve(jT|^v_Nm24Fxf?%@dS1Coqnzv$7Hj&J#9F(FWvd z1Y5mV&Zl_c|6m%P>vv(M6e?}icR5%cd>U41 zkVgvqg?XwAcCbFg2CBB!coQ+#Rj2uH^2=Z+#bU8DWGaA3ErsYHe%2T2AX_^r`N3uVj16{*V$Iq;wc? z9XERZv?sOrrnSg3<7~SUV~KE=1#XDBxZXEF{D6!@-`iwKJDtc<7fgLwl3oAx3S%`BGnYi0X7Wdeq)s}$NIT&aPWt&{MNP9<)5 zhGqW@d{Bve?MbrwcWckD*K?@TxCQ1CK57l(GKD87`^$WmXLg#c)N=)ttU}9!JS;4k z=nt15t=Ya{T+x*zET5yNIwW?T`6wXa*!{c1K^a#`f2~$bCYR%d*#wQs%1ZHP4h(HK#m3gn$ZG&->rC}WE7|gfMD!KU^f@k&|SBR`&`IT{O0zR0s!~TpIdjY?ywWS zY+LYfDY9PhbN=@X+cv08?NX=e8f7BEcAdJoXas1BRCe@)D_F*Q`)E$*Zf=<)ASZ`NfunBH`4G?Eu2s!pcs`{`nZrU=L1%06&g<99os<80Hwr0%?{ z+3&Ar?>kMa+gj^C#93>7Q%ixs6I=EGA3GTbG=d zJFnY!umn+F6AUtLSrN9Rm|7M51|SGcl|gSJKv6~e0(-=Fw_ES9{>;Ub8Tz~;{EZDD zU$NuL#gUOaCUDQ&9AbOaWWs7)qR^FhByW!)rCN?pn^4>eJpA_IZVJfLl5DDoN6e`6 z^Ya`)Ggt)QpkX#bT_~!ROF~(b{=>|>u0Q)oA{@P3hB+J8( zfz1cp$xr8uF#ez;7bEaam~#|7l)A`iao`ACZyatqz?*EA$0*5A7DHNqd68L3cNzFup zkB1`?kl@)-XnRX_%x+lA92~Hiv^#5q*u%pVI-oJZ=){d9V_vObZSHq@^3H570QWth zOXY*^WBA2N7-DtQbNTn$+8RQ+NbB(Hx|zP_m}wB>RF($?Fa!{@ zt`F`PUqlgSW@Z9337?AKVX%X=8`5P=hP)ZbDpCBO<7Pk`1jf(7U3~TX91M9x6gkCc z+9OwZV6jHqJa1EkE5-qM?y#R8F9}8T7KGx>(D(!q#x{dlhZAdN$aPj@#KIW7cBpOe znsM;TUndHPH(wK07uE1n&+!&xUVXhq7DUa$+M=rauaq_(qnYPBExdj744_J0+9Yew z4t{cX^A~ki*FCInc&S;e^o&wRO=hBpPl@v4rcIv3M1VPY_+}loe4~ zT%U;>K;5eZDaDV;%3lgd9_Du;rF(PO{W2jGY5KVI$J!mYge)*q@^u@ZmcmX%Y^M9N zd^A~v+{XWv1wz6jWEFN$5^rjh6o+}I{>oCS74Hk4 zhKZ~jQrtpF`nOCpw7*QcL{~Fkj@A}k^ePAFm~%0LJ005&o)}8i7|Coo(v0&$dxWOt ziTl*LcxryUsj({Fr4G^#PlpX%_)e?Ng`BKVjkBdCCGUratr-B*7KF#p4eerVCyhka z|HBJ`zYW8ipouOrABQ<%46k<+>@N=~IHEp*P=#QmjNdoW2sxSu7^`k$`}pYIvG$rt z5VM~_iXT2OMl8M8iBo39kK?V5?A`|*3%J-K05|m$RFIETe^5iD+t-@fXL%&u)0}@4 z$KXFMg|&<=)+&DmNz2-=1o}mg>LvnB6aDwi!_z+!$vcQh{1J6VF&Bd@7(;9YS>Jni zJdF?>WIm_*&}Tq<9eoV+l)njAdscPn_l?8FHP7TH)yvx@JEa|W20&(t@=2IO%c5@wY;}I!VPq1t6P+vPxf8oOy%jM z0zQ{P=z`CqCJ=5g$e^#5>e3U{^P6fQ{MgT5cDHJJCxgm2yn*Zae>sQh5b~1wnAf|? zG9RnHK48E|X}30p%F&oCKvv1M|D}9JkCL|H&xCOxuT0s2I0I>)p49nDYuwj8k)kQe#y8M?xDyq?dnbSd8A$(wF zU?~*Qi2o5#9(4cPJ5%b=bUiUUL8DZKmRscgfD^`CGU4Bzv)6;LEKh;Y!UiXQQ`Vo` z$7!lLNPU|^t9U2X9ptz*H8qc%X@mP|;4PUo5PSX3cxV9=_C+g7Q$#TgSuCJ+pp>yx z@sLP-$&XtXVlx4n93716IOcxPJ`xv%;SILojA@hNh5crol=hxouJ9!xwM}cU;UsmC z;Wb|}T!XI@L=D;N+rNs+_CJZ8`7-P|3kF^-&iV*1MV6f(zM5Lu%Cb@onH`59XSGPG zw*8|F4A0rw8A%V^e*v19NPeLZ=Y4@lIQ?;}n1N*-uT2XsgnRH;iOT+Mk&lWyNuYA@ zz!E{|0Y|HP?O`xRc=BbS;b>(jXGg#uP9|cC*F>XHiDN{NTbEcA!Ck6^3`Qb5|=ogBZgi=K?+=GR)(=D86o~6}>C7(YR;Z$^L$c;IOb^5Djp{BH!r=Ca5qf6<#hRbKLhV{zog)Q0{`oc( zgO|JIsMO_IRc5nY_Qe&7J|cj5#-oQP`06dpnS`YT6*Rsp7mi|KaRc-(ymOy`_w48Z zGA&H?ILNR}5GKm;$MIx;`2j`c%=Ps!FdOx3Xs5$BA|rS^8VWl|iBAS?87jr6|0`*H z-^bgY=zn4sB$($06`A%0`EL4xYxELZy%zjeb&zser(r*+j!6fb(ow}i?FJ+vt`Ywc zpy63;Xg28TOMj*3FUvYxB8X)O5SNmI?fqBS z;ZkE>DXv|PzLr3k+ z*V#V~$9RWj9d0U>aJMtsJjs9a%_Kc-qX0hiMJu(0T#E&!BJ#d_2;`NHqdIc|$$-&z zqjxI8IlONhT0X@cbtk3yr#ZVE1n$X%C%WlMr0r(qi0ZI`Eae0(Rcdajw5rN%YPISj z<`jA2`)8w6U)E!AXer?T`Lxqde?;7h_V)gA+$bk(f)UHj&wGxVVgUR9eo##lFxp>b zZ3U}>R@82Ss{_xW#1w-f7U0RAPtbsWiv*#zmHGjhjyEeox)*41I1c5QA4^~EZ=CE5 z;csys)HxDn{F!{x1Iaw=tt-Zm6hwj|IiXAJ^MmmuM_V-uoL1bQRCV%?N5K#Mqo+(%O*zoV`++u`)IM0}~n%uQ6cU zJg}YKTMb?ZmnNxtKQNRy;lukh-v5p0{1U%p^PXqRYefT-_)OFV@c6!O3@w0`DQ8^l zaZCd;=L&%eWX&l0ve&eZ=32BBK6XD4`vMmt0kz#N)c1$)QEfV>H}kf_@7i(5?2Y_E zswymd2?DGO!yB7v%GJ?Tlo3S`4MGi{s`b0CeVDxxC9?Fv3sjrh|S zpo~m~7C=#TYxe3%P18>8wE)ErdV!wazr>YKr6@Nu7l2mKp(2Q9g=O&KZ{5GzaoVY? zdc7xa?TK~L)7c7F^WF$pz6BV$rFzK7)OiKvwm^RTk&1_KlZ6^)rq|UPV=HlNU*G3~ z)DV_wYxNl+Aqs+YJuXqYUK>Kes>rnGPv+y&;-R?e4cQ?As8>79hX%P`OG`^C$W)JL z02y-ZodqgoVItKwqxd?!kOFGr)PZ$-MWO$fQ&Ocd>K8yw8+K-iQ@tJ%FkSI$Lc$uVfAJ932kswOwGAUyD zQfYjkyof0$)Sms49`jv7WF(gb>w`*BC=`jR`xt$3vh-@|s*v-Ix!R+hzyIP22~#I? zxqSl?_sRom2u}tWQu+;@^c&7jyQ z?UUIvJ+5&r8N_e)UtL<<#V9;oZ-PN2eC8pEr5wT+C4sg>TS3Y`%M^tUN0;e4Zzfnc z*bB|v-QjIYm_Fmvf`5h#P*L6o^RDcI)@-URBM@&rm<59QrZiBr!O-@6_sK!8~=VN|KU4RcG;v(md%uygSH3k;_>Bz6~eL3P|Rdza1{dy8RE zIacRA=bI%W}@4k1N6MG z;&B_?Cr(%*z?(n-!@8!nTidw5`fUjj>??pD1iCZ;9PIahR&^cBWnfe;KKimvjcJ@C zU4#w#`sU_c&z2ukWRuo1_*O7khrF z(cTShGH#tb@z7chrzqVL?&rfIQz0_X1naMXI<<>^`dVzDOy=dBr-z5jy?e+1J!j=t z?aqvibQPr;h#~@Tu5kVNpc)f^`JbKt|72P{u(g|3j9jZ70c|SR?bO$*ykF@xbnjY- zg7no_@P>EEA+bEv(D66dx>SvYl4b2258A%2&{pRSD$41ct!BOSD+hA6r$Cf0vU2AN9$bV=_w{$#F4~&T7C&SuajvqI zhr%36WYwHh>j}LBb9Q(JCUW+$g#qEo_ znn*~k%i}vnse5}aL;k)6iQ0?woSjI(Z1)0#@{ZcRTFd5$aAK{Vvb_+(!S_<`GSZYV z(4JwrEMwh$(#?Grl(G0MEJZd;d#|E3gRdW_us7T8%{%Uf z694f_mSLf9w=}`pS{}3^GmjL zvjQ3|4D!RoxzPR~#ncPt)==pLw&T)#3P5C3)YQ0Xv>d1O!LzXiCK8UUHw;-4@7w;C zzaB`s&ro>wFLu5%C9y(}QsW|c+ad9L8dmc=BLZ2ECCF}=d$iWrVbU>OCi^;8HKBp{ zkRcu_k%T4-0-^t&bSu2R7{%JUF1}=tcFc~o)j*COp51N-X-L_VTgJKNjHWC0HxT6- zZ@(60v9=HhCqD#je^;l-wC$_Y-d}xvfb|Qv_i4hTX>I7&a$Hd1xF|qHkCOhgzn(Jf z_39yk5VF@*9(=5AZ2=(y>PyA9D&3fL$Y!w&l^hxU|IyEYVws@d1$gmDWI#=Ne`R9j zW`Ucks_NjtfUdXvwO1ZvUP9#kTX1Ul>B4+gO!qA3LB((OS1$;rm{87 zQW$QlQ2OpCN1OSaTC>T?u&tE1^$Gt^tsks1wH~+4qJ$Ap`r$Dw!rverF8k?xEi2S} zp_yM1e)VCwN3;1*h&|Bb0kqVcqFTJ7uAzb2N7wshr5G*mxqPR{^beIj!~iBPtf2UT zvbYvo1V_{U%xU4Q`WX01qwUb%JQIJRtV;gM_a}VnY(QFU;ieaoesM*Ig`q=^N&yY4 z7Q)rxOxqUv`O;=~iwn-)@!}%mIACdthM@cyU^*(+DkQ{#|Y;tmOa= z^-SU?a*Tj1l(9$fE`Vst3`nFH9O?nuTkR7pTpI#uklE4CAnL9*_9~5eA$lz-p!Jph zz4(Q-wcv5;r{RaqUjLs>IG#Z5bCuWa0=h)i2`n2vu$LGDkY;R{I$rTQ3(IV>b)ub& zBw-7cmZCh;Ox*QSCQ9u)S>iy**Nf~Vq6|jS`W^AlA{bfCfOtbr3YUNE@C6y-LMVem zVbJ<Dw9ZyC=mmE(vc)>4SjZo@8dXvc7q##dY1?xGa(o%(&zu51kHzzj_ zjmuEuF5t<4t|=pd!mlcZZ(C>PSj_6PB9db3b6b2eTq6mtUL#5`X3C@8z{X!zfLCL; zXlulSq@hdCF7~Vw=ZAH;{Z$r>1HlO*w^E`)?QPo0Evu;iHvSlsV00X~SIDn>`qC30 z04%bcj$OiaiSWcdu(E>D>y}0)O;0hu)dfDVm>8A#<5>ScL2!wr7>>w`Q!!wd6Qq1` zF`;eNwa^hUwmDuFCmef5dmNrP4aJxWHv*+Z`tp9+i@8jd8JM(tmqX^oc0jtZxG*Om zaCuIks>CM-f$IFY!}jf4rmgJ+ia?uaJ^u{(SQ19aQ;9^bQJ;#O{DL1@rnD@PS05=n z2k24xwW45~E$VfBbufQi@i{0phM(%4?W!Sq?i?8@1y!0$Ci%7HSt>uHwb>`CZDeU9=rGqJYTYKs?TL4kCZyyzV zi~up#LTbzR1Xd{)PzdY^D@!3t*6o3wmut0 zS~s*kE~5Zj4tTP9kPQ0a)G!x7&_spa1%EOGOiZs;S=fo`1p0j|1i}az$nToQsAcSU z1Jdg~FAvTaVcj(aK!(+hTz)pest|&&i1+%#U zNUs?MShd2SkQ{_%NvL}hF+dj{AW0K7qtS6ND_)UJHPiIR@hW^WsKtUV*A+@aKOjzc z?8$AsR@&&dPq^TwM^bMc_Apache License 2.0 Takagi, Isamu Takamasa Horibe + Yuhei Oshikubo ament_cmake_auto autoware_cmake diff --git a/common/tier4_localization_rviz_plugin/plugins/plugin_description.xml b/common/tier4_localization_rviz_plugin/plugins/plugin_description.xml index 2a58895354cad..01fc1a0ee488d 100644 --- a/common/tier4_localization_rviz_plugin/plugins/plugin_description.xml +++ b/common/tier4_localization_rviz_plugin/plugins/plugin_description.xml @@ -10,4 +10,9 @@ base_class_type="rviz_common::Display"> Display footprint of geometry_msgs::Pose + + Display geometry_msgs::PoseWithCovarianceStamped + diff --git a/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp b/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp new file mode 100644 index 0000000000000..7708e6efaa104 --- /dev/null +++ b/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp @@ -0,0 +1,285 @@ +// 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 "pose_with_covariance_history_display.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +namespace rviz_plugins +{ +PoseWithCovarianceHistory::PoseWithCovarianceHistory() : last_stamp_(0, 0, RCL_ROS_TIME) +{ + property_buffer_size_ = new rviz_common::properties::IntProperty("Buffer Size", 100, "", this); + + property_path_view_ = new rviz_common::properties::BoolProperty("Path", true, "", this); + property_shape_type_ = new rviz_common::properties::EnumProperty( + "Shape Type", "Line", "", property_path_view_, SLOT(updateShapeType())); + property_shape_type_->addOption("Line", 0); + property_shape_type_->addOption("Arrow", 1); + + property_line_width_ = + new rviz_common::properties::FloatProperty("Width", 0.1, "", property_shape_type_); + property_line_alpha_ = + new rviz_common::properties::FloatProperty("Alpha", 1.0, "", property_shape_type_); + property_line_alpha_->setMin(0.0); + property_line_alpha_->setMax(1.0); + property_line_color_ = + new rviz_common::properties::ColorProperty("Color", Qt::white, "", property_shape_type_); + + property_arrow_shaft_length_ = + new rviz_common::properties::FloatProperty("Shaft Length", 0.3, "", property_shape_type_); + property_arrow_shaft_diameter_ = + new rviz_common::properties::FloatProperty("Shaft diameter", 0.15, "", property_shape_type_); + property_arrow_head_length_ = + new rviz_common::properties::FloatProperty("Head Length", 0.2, "", property_shape_type_); + property_arrow_head_diameter_ = + new rviz_common::properties::FloatProperty("Head diameter", 0.3, "", property_shape_type_); + property_arrow_alpha_ = + new rviz_common::properties::FloatProperty("Alpha", 1.0, "", property_shape_type_); + property_arrow_alpha_->setMin(0.0); + property_arrow_alpha_->setMax(1.0); + property_arrow_color_ = + new rviz_common::properties::ColorProperty("Color", Qt::white, "", property_shape_type_); + + property_sphere_view_ = new rviz_common::properties::BoolProperty("Covariance", true, "", this); + property_sphere_scale_ = + new rviz_common::properties::FloatProperty("Scale", 1.0, "", property_sphere_view_); + property_sphere_alpha_ = + new rviz_common::properties::FloatProperty("Alpha", 0.5, "", property_sphere_view_); + property_sphere_alpha_->setMin(0.0); + property_sphere_alpha_->setMax(1.0); + property_sphere_color_ = new rviz_common::properties::ColorProperty( + "Color", QColor(204, 51, 204), "", property_sphere_view_); + + property_buffer_size_->setMin(0); + property_buffer_size_->setMax(10000); + property_line_width_->setMin(0.0); + property_sphere_scale_->setMin(0.0); + property_sphere_scale_->setMax(1000); + property_arrow_shaft_length_->setMin(0.0); + property_arrow_shaft_diameter_->setMin(0.0); + property_arrow_head_length_->setMin(0.0); + property_arrow_head_diameter_->setMin(0.0); +} + +PoseWithCovarianceHistory::~PoseWithCovarianceHistory() = default; // Properties are deleted by Qt + +void PoseWithCovarianceHistory::onInitialize() +{ + MFDClass::onInitialize(); + lines_ = std::make_unique(scene_manager_, scene_node_); +} + +void PoseWithCovarianceHistory::onEnable() +{ + subscribe(); +} + +void PoseWithCovarianceHistory::onDisable() +{ + unsubscribe(); +} + +void PoseWithCovarianceHistory::update(float wall_dt, float ros_dt) +{ + (void)wall_dt; + (void)ros_dt; + + if (!history_.empty()) { + lines_->clear(); + arrows_.clear(); + spheres_.clear(); + updateShapeType(); + updateShapes(); + } +} + +void PoseWithCovarianceHistory::subscribe() +{ + MFDClass::subscribe(); +} + +void PoseWithCovarianceHistory::unsubscribe() +{ + MFDClass::unsubscribe(); + + history_.clear(); + lines_->clear(); + arrows_.clear(); + spheres_.clear(); +} + +void PoseWithCovarianceHistory::updateShapeType() +{ + bool is_line = property_shape_type_->getOptionInt() == 0; + bool is_arrow = property_shape_type_->getOptionInt() == 1; + + property_line_width_->setHidden(!is_line); + property_line_alpha_->setHidden(!is_line); + property_line_color_->setHidden(!is_line); + + property_arrow_shaft_length_->setHidden(!is_arrow); + property_arrow_shaft_diameter_->setHidden(!is_arrow); + property_arrow_head_length_->setHidden(!is_arrow); + property_arrow_head_diameter_->setHidden(!is_arrow); + property_arrow_alpha_->setHidden(!is_arrow); + property_arrow_color_->setHidden(!is_arrow); +} + +void PoseWithCovarianceHistory::processMessage( + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr message) +{ + if ( + !rviz_common::validateFloats(message->pose.pose) || + !rviz_common::validateFloats(message->pose.covariance)) { + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", + "Message contained invalid floating point values (nans or infs)"); + return; + } + if (target_frame_ != message->header.frame_id) { + history_.clear(); + spheres_.clear(); + target_frame_ = message->header.frame_id; + } + history_.emplace_back(message); + last_stamp_ = message->header.stamp; + updateHistory(); +} + +void PoseWithCovarianceHistory::updateHistory() +{ + const auto buffer_size = static_cast(property_buffer_size_->getInt()); + while (buffer_size < history_.size()) { + history_.pop_front(); + } +} + +void PoseWithCovarianceHistory::updateShapes() +{ + int shape_type = property_shape_type_->getOptionInt(); + Ogre::ColourValue color_line = + rviz_common::properties::qtToOgre(property_line_color_->getColor()); + color_line.a = property_line_alpha_->getFloat(); + Ogre::ColourValue color_sphere = + rviz_common::properties::qtToOgre(property_sphere_color_->getColor()); + color_sphere.a = property_sphere_alpha_->getFloat(); + Ogre::ColourValue color_arrow = + rviz_common::properties::qtToOgre(property_arrow_color_->getColor()); + color_arrow.a = property_arrow_alpha_->getFloat(); + + Ogre::Vector3 line_position; + Ogre::Quaternion line_orientation; + + auto frame_manager = context_->getFrameManager(); + if (!frame_manager->getTransform(target_frame_, last_stamp_, line_position, line_orientation)) { + setMissingTransformToFixedFrame(target_frame_); + return; + } + + setTransformOk(); + lines_->setMaxPointsPerLine(history_.size()); + lines_->setLineWidth(property_line_width_->getFloat()); + lines_->setPosition(line_position); + lines_->setOrientation(line_orientation); + lines_->setColor(color_line.r, color_line.g, color_line.b, color_line.a); + + while (spheres_.size() < history_.size()) { + spheres_.emplace_back(std::make_unique( + rviz_rendering::Shape::Sphere, scene_manager_, scene_node_)); + } + while (arrows_.size() < history_.size()) { + arrows_.emplace_back(std::make_unique(scene_manager_, scene_node_)); + } + + for (size_t i = 0; i < history_.size(); ++i) { + const auto & message = history_[i]; + + Ogre::Vector3 position; + position.x = message->pose.pose.position.x; + position.y = message->pose.pose.position.y; + position.z = message->pose.pose.position.z; + + Ogre::Quaternion orientation; + orientation.w = message->pose.pose.orientation.w; + orientation.x = message->pose.pose.orientation.x; + orientation.y = message->pose.pose.orientation.y; + orientation.z = message->pose.pose.orientation.z; + + Eigen::Matrix3d covariance_3d_map; + covariance_3d_map(0, 0) = message->pose.covariance[0]; + covariance_3d_map(0, 1) = message->pose.covariance[1 + 6 * 0]; + covariance_3d_map(0, 2) = message->pose.covariance[2 + 6 * 0]; + covariance_3d_map(1, 0) = message->pose.covariance[1 + 6 * 0]; + covariance_3d_map(1, 1) = message->pose.covariance[1 + 6 * 1]; + covariance_3d_map(1, 2) = message->pose.covariance[2 + 6 * 1]; + covariance_3d_map(2, 0) = message->pose.covariance[0 + 6 * 2]; + covariance_3d_map(2, 1) = message->pose.covariance[1 + 6 * 2]; + covariance_3d_map(2, 2) = message->pose.covariance[2 + 6 * 2]; + + if (property_sphere_view_->getBool()) { + Eigen::Matrix3d covariance_3d_base_link; + Eigen::Translation3f translation( + message->pose.pose.position.x, message->pose.pose.position.y, + message->pose.pose.position.z); + Eigen::Quaternionf rotation( + message->pose.pose.orientation.w, message->pose.pose.orientation.x, + message->pose.pose.orientation.y, message->pose.pose.orientation.z); + Eigen::Matrix4f pose_matrix4f = (translation * rotation).matrix(); + const Eigen::Matrix3d rot = pose_matrix4f.topLeftCorner<3, 3>().cast(); + covariance_3d_base_link = rot.transpose() * covariance_3d_map * rot; + + auto & sphere = spheres_[i]; + sphere->setPosition(position); + sphere->setOrientation(orientation); + sphere->setColor(color_sphere.r, color_sphere.g, color_sphere.b, color_sphere.a); + sphere->setScale(Ogre::Vector3( + property_sphere_scale_->getFloat() * 2 * std::sqrt(covariance_3d_base_link(0, 0)), + property_sphere_scale_->getFloat() * 2 * std::sqrt(covariance_3d_base_link(1, 1)), + property_sphere_scale_->getFloat() * 2 * std::sqrt(covariance_3d_base_link(2, 2)))); + } + + if (property_path_view_->getBool()) { + if (shape_type == 0) { + lines_->addPoint(position); + } + if (shape_type == 1) { + auto & arrow = arrows_[i]; + arrow->set( + property_arrow_shaft_length_->getFloat(), property_arrow_shaft_diameter_->getFloat(), + property_arrow_head_length_->getFloat(), property_arrow_head_diameter_->getFloat()); + arrow->setPosition(position); + Ogre::Quaternion y90(Ogre::Degree(-90), Ogre::Vector3::UNIT_Y); + arrow->setOrientation(orientation * y90); + arrow->setColor(color_arrow.r, color_arrow.g, color_arrow.b, color_arrow.a); + } + } + } +} + +} // namespace rviz_plugins + +#include +PLUGINLIB_EXPORT_CLASS(rviz_plugins::PoseWithCovarianceHistory, rviz_common::Display) diff --git a/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp b/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp new file mode 100644 index 0000000000000..172124ba176ee --- /dev/null +++ b/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp @@ -0,0 +1,109 @@ +// 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 POSE_WITH_COVARIANCE_HISTORY__POSE_WITH_COVARIANCE_HISTORY_DISPLAY_HPP_ +#define POSE_WITH_COVARIANCE_HISTORY__POSE_WITH_COVARIANCE_HISTORY_DISPLAY_HPP_ + +#include +#include +#include + +#include + +#include +#include +#include +#include + +namespace rviz_rendering +{ +class Shape; +class BillboardLine; +class Arrow; +} // namespace rviz_rendering +namespace rviz_common::properties +{ +class ColorProperty; +class FloatProperty; +class IntProperty; +class BoolProperty; +class EnumProperty; +} // namespace rviz_common::properties + +namespace rviz_plugins +{ +class PoseWithCovarianceHistory +: public rviz_common::MessageFilterDisplay +{ + Q_OBJECT + +public: + PoseWithCovarianceHistory(); + ~PoseWithCovarianceHistory() override; + PoseWithCovarianceHistory(const PoseWithCovarianceHistory &) = delete; + PoseWithCovarianceHistory(const PoseWithCovarianceHistory &&) = delete; + PoseWithCovarianceHistory & operator=(const PoseWithCovarianceHistory &) = delete; + PoseWithCovarianceHistory & operator=(const PoseWithCovarianceHistory &&) = delete; + +protected: + void onInitialize() override; + void onEnable() override; + void onDisable() override; + void update(float wall_dt, float ros_dt) override; + +private Q_SLOTS: + void updateShapeType(); + +private: + void subscribe() override; + void unsubscribe() override; + void processMessage( + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr message) override; + void updateHistory(); + void updateShapes(); + + std::string target_frame_; + std::deque history_; + std::unique_ptr lines_; + std::vector> spheres_; + std::vector> arrows_; + rclcpp::Time last_stamp_; + + rviz_common::properties::BoolProperty * property_line_view_; + rviz_common::properties::FloatProperty * property_line_width_; + rviz_common::properties::FloatProperty * property_line_alpha_; + rviz_common::properties::ColorProperty * property_line_color_; + rviz_common::properties::IntProperty * property_buffer_size_; + + rviz_common::properties::BoolProperty * property_sphere_view_; + rviz_common::properties::FloatProperty * property_sphere_width_; + rviz_common::properties::FloatProperty * property_sphere_alpha_; + rviz_common::properties::ColorProperty * property_sphere_color_; + rviz_common::properties::FloatProperty * property_sphere_scale_; + + rviz_common::properties::BoolProperty * property_arrow_view_; + rviz_common::properties::FloatProperty * property_arrow_shaft_length_; + rviz_common::properties::FloatProperty * property_arrow_shaft_diameter_; + rviz_common::properties::FloatProperty * property_arrow_head_length_; + rviz_common::properties::FloatProperty * property_arrow_head_diameter_; + rviz_common::properties::FloatProperty * property_arrow_alpha_; + rviz_common::properties::ColorProperty * property_arrow_color_; + + rviz_common::properties::BoolProperty * property_path_view_; + rviz_common::properties::EnumProperty * property_shape_type_; +}; + +} // namespace rviz_plugins + +#endif // POSE_WITH_COVARIANCE_HISTORY__POSE_WITH_COVARIANCE_HISTORY_DISPLAY_HPP_ From 769d6c874c122ddec5c05c6be20d5a1664244bfe Mon Sep 17 00:00:00 2001 From: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> Date: Thu, 29 Aug 2024 16:53:18 +0900 Subject: [PATCH 056/217] chore(gnss_poser): add autoware prefix to gnss_poser (#8323) * add "autoware" prefix to gnss_poser Signed-off-by: TaikiYamada4 * Fixed typos and left overs Signed-off-by: TaikiYamada4 * Fixed directory mistake Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Removed gnss_poser line from CODEOWNERS Signed-off-by: TaikiYamada4 --------- Signed-off-by: TaikiYamada4 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yi-Hsiang Fang (Vivid) <146902905+vividf@users.noreply.github.com> --- .github/CODEOWNERS | 2 +- .../{gnss_poser => autoware_gnss_poser}/CMakeLists.txt | 6 +++--- sensing/{gnss_poser => autoware_gnss_poser}/README.md | 2 +- .../config/gnss_poser.param.yaml | 0 .../include/autoware}/gnss_poser/gnss_poser_core.hpp | 10 +++++----- .../launch/gnss_poser.launch.xml | 4 ++-- .../{gnss_poser => autoware_gnss_poser}/package.xml | 4 ++-- .../schema/gnss_poser.schema.json | 0 .../src/gnss_poser_core.cpp | 8 ++++---- 9 files changed, 18 insertions(+), 18 deletions(-) rename sensing/{gnss_poser => autoware_gnss_poser}/CMakeLists.txt (84%) rename sensing/{gnss_poser => autoware_gnss_poser}/README.md (97%) rename sensing/{gnss_poser => autoware_gnss_poser}/config/gnss_poser.param.yaml (100%) rename sensing/{gnss_poser/include => autoware_gnss_poser/include/autoware}/gnss_poser/gnss_poser_core.hpp (94%) rename sensing/{gnss_poser => autoware_gnss_poser}/launch/gnss_poser.launch.xml (79%) rename sensing/{gnss_poser => autoware_gnss_poser}/package.xml (94%) rename sensing/{gnss_poser => autoware_gnss_poser}/schema/gnss_poser.schema.json (100%) rename sensing/{gnss_poser => autoware_gnss_poser}/src/gnss_poser_core.cpp (98%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 89b9fa0eb8f38..8e285671ec21b 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -199,6 +199,7 @@ planning/sampling_based_planner/autoware_bezier_sampler/** maxime.clement@tier4. planning/sampling_based_planner/autoware_frenet_planner/** maxime.clement@tier4.jp planning/sampling_based_planner/autoware_path_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/autoware_sampler_common/** maxime.clement@tier4.jp +sensing/autoware_gnss_poser/** 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 sensing/autoware_image_diagnostics/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp sensing/autoware_imu_corrector/** taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/autoware_image_transport_decompressor/** kenzo.lobos@tier4.jp yukihiro.saito@tier4.jp @@ -208,7 +209,6 @@ sensing/autoware_radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.m sensing/autoware_radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp 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/gnss_poser/** 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 sensing/imu_corrector/** taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/livox/autoware_livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp diff --git a/sensing/gnss_poser/CMakeLists.txt b/sensing/autoware_gnss_poser/CMakeLists.txt similarity index 84% rename from sensing/gnss_poser/CMakeLists.txt rename to sensing/autoware_gnss_poser/CMakeLists.txt index 775cde514945f..6baf468e289f3 100644 --- a/sensing/gnss_poser/CMakeLists.txt +++ b/sensing/autoware_gnss_poser/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(gnss_poser) +project(autoware_gnss_poser) find_package(autoware_cmake REQUIRED) autoware_package() @@ -16,7 +16,7 @@ find_library(GeographicLib_LIBRARIES ) set(GNSS_POSER_HEADERS - include/gnss_poser/gnss_poser_core.hpp + include/autoware/gnss_poser/gnss_poser_core.hpp ) ament_auto_add_library(gnss_poser_node SHARED @@ -29,7 +29,7 @@ target_link_libraries(gnss_poser_node ) rclcpp_components_register_node(gnss_poser_node - PLUGIN "gnss_poser::GNSSPoser" + PLUGIN "autoware::gnss_poser::GNSSPoser" EXECUTABLE gnss_poser ) diff --git a/sensing/gnss_poser/README.md b/sensing/autoware_gnss_poser/README.md similarity index 97% rename from sensing/gnss_poser/README.md rename to sensing/autoware_gnss_poser/README.md index 6799a1f79ae89..9619038492af0 100644 --- a/sensing/gnss_poser/README.md +++ b/sensing/autoware_gnss_poser/README.md @@ -33,7 +33,7 @@ If the transformation from `base_link` to the antenna cannot be obtained, it out ### Core Parameters -{{ json_to_markdown("sensing/gnss_poser/schema/gnss_poser.schema.json") }} +{{ json_to_markdown("sensing/autoware_gnss_poser/schema/gnss_poser.schema.json") }} ## Assumptions / Known limits diff --git a/sensing/gnss_poser/config/gnss_poser.param.yaml b/sensing/autoware_gnss_poser/config/gnss_poser.param.yaml similarity index 100% rename from sensing/gnss_poser/config/gnss_poser.param.yaml rename to sensing/autoware_gnss_poser/config/gnss_poser.param.yaml diff --git a/sensing/gnss_poser/include/gnss_poser/gnss_poser_core.hpp b/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_core.hpp similarity index 94% rename from sensing/gnss_poser/include/gnss_poser/gnss_poser_core.hpp rename to sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_core.hpp index 033abf04f1255..88a4a87fa636e 100644 --- a/sensing/gnss_poser/include/gnss_poser/gnss_poser_core.hpp +++ b/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_core.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 GNSS_POSER__GNSS_POSER_CORE_HPP_ -#define GNSS_POSER__GNSS_POSER_CORE_HPP_ +#ifndef AUTOWARE__GNSS_POSER__GNSS_POSER_CORE_HPP_ +#define AUTOWARE__GNSS_POSER__GNSS_POSER_CORE_HPP_ #include #include @@ -39,7 +39,7 @@ #include -namespace gnss_poser +namespace autoware::gnss_poser { class GNSSPoser : public rclcpp::Node { @@ -101,6 +101,6 @@ class GNSSPoser : public rclcpp::Node msg_gnss_ins_orientation_stamped_; int gnss_pose_pub_method_; }; -} // namespace gnss_poser +} // namespace autoware::gnss_poser -#endif // GNSS_POSER__GNSS_POSER_CORE_HPP_ +#endif // AUTOWARE__GNSS_POSER__GNSS_POSER_CORE_HPP_ diff --git a/sensing/gnss_poser/launch/gnss_poser.launch.xml b/sensing/autoware_gnss_poser/launch/gnss_poser.launch.xml similarity index 79% rename from sensing/gnss_poser/launch/gnss_poser.launch.xml rename to sensing/autoware_gnss_poser/launch/gnss_poser.launch.xml index c33f9a7589812..ef2e2661a16c0 100755 --- a/sensing/gnss_poser/launch/gnss_poser.launch.xml +++ b/sensing/autoware_gnss_poser/launch/gnss_poser.launch.xml @@ -1,13 +1,13 @@ - + - + diff --git a/sensing/gnss_poser/package.xml b/sensing/autoware_gnss_poser/package.xml similarity index 94% rename from sensing/gnss_poser/package.xml rename to sensing/autoware_gnss_poser/package.xml index e43013cfc37ec..7d7fb27777fed 100644 --- a/sensing/gnss_poser/package.xml +++ b/sensing/autoware_gnss_poser/package.xml @@ -1,9 +1,9 @@ - gnss_poser + autoware_gnss_poser 1.0.0 - The ROS 2 gnss_poser package + The ROS 2 autoware_gnss_poser package Yamato Ando Masahiro Sakamoto Kento Yabuuchi diff --git a/sensing/gnss_poser/schema/gnss_poser.schema.json b/sensing/autoware_gnss_poser/schema/gnss_poser.schema.json similarity index 100% rename from sensing/gnss_poser/schema/gnss_poser.schema.json rename to sensing/autoware_gnss_poser/schema/gnss_poser.schema.json diff --git a/sensing/gnss_poser/src/gnss_poser_core.cpp b/sensing/autoware_gnss_poser/src/gnss_poser_core.cpp similarity index 98% rename from sensing/gnss_poser/src/gnss_poser_core.cpp rename to sensing/autoware_gnss_poser/src/gnss_poser_core.cpp index 4cd3661edeb50..f4047af75dada 100644 --- a/sensing/gnss_poser/src/gnss_poser_core.cpp +++ b/sensing/autoware_gnss_poser/src/gnss_poser_core.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "gnss_poser/gnss_poser_core.hpp" +#include "autoware/gnss_poser/gnss_poser_core.hpp" #include #include @@ -24,7 +24,7 @@ #include #include -namespace gnss_poser +namespace autoware::gnss_poser { GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options) : rclcpp::Node("gnss_poser", node_options), @@ -411,7 +411,7 @@ void GNSSPoser::publish_tf( tf2_broadcaster_.sendTransform(transform_stamped); } -} // namespace gnss_poser +} // namespace autoware::gnss_poser #include -RCLCPP_COMPONENTS_REGISTER_NODE(gnss_poser::GNSSPoser) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::gnss_poser::GNSSPoser) From 67d5e68e615ef882944902a907b6329820cfce57 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 29 Aug 2024 17:09:22 +0900 Subject: [PATCH 057/217] feat(raw_vehicle_cmd_converter): set convert_actuation_to_steering_status false by default (#8668) Signed-off-by: kosuke55 --- vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp index 6fb8f4dff44f6..696225db60609 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp @@ -87,7 +87,7 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( // NOTE: The steering status can be published from the vehicle side or converted in this node. convert_actuation_to_steering_status_ = - declare_parameter("convert_actuation_to_steering_status"); + declare_parameter("convert_actuation_to_steering_status", false); if (convert_actuation_to_steering_status_) { pub_steering_status_ = create_publisher("~/output/steering_status", 1); } else { From ee600a78ba4e9ff49d0969d5e4ef4f2904c3cdad Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 29 Aug 2024 17:10:55 +0900 Subject: [PATCH 058/217] chore(raw_vehicle_cmd_converter): add maintainer (#8671) Signed-off-by: kosuke55 --- vehicle/autoware_raw_vehicle_cmd_converter/package.xml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml index 973af0dc112fb..4ed4fbee7ac81 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml +++ b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml @@ -8,6 +8,9 @@ Tanaka Taiki Makoto Kurihara Sho Iwasawa + Kosuke Takeuchi + Takayuki Murooka + Kyoichi Sugahara Apache License 2.0 From 0cb309e3b6c3231ab30ba02fd1e02d2948766c56 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 29 Aug 2024 17:20:20 +0900 Subject: [PATCH 059/217] fix(autoware_behavior_velocity_virtual_traffic_light_module): fix unusedFunction (#8670) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/debug.cpp | 20 ------------------- 1 file changed, 20 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp index 1ad24cb48409d..2be77b2731fe0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp @@ -30,26 +30,6 @@ using namespace std::literals::string_literals; namespace autoware::behavior_velocity_planner { -namespace -{ -[[maybe_unused]] autoware::universe_utils::LinearRing3d createCircle( - const autoware::universe_utils::Point3d & p, const double radius, const size_t num_points = 50) -{ - autoware::universe_utils::LinearRing3d ring; // clockwise and closed - - for (size_t i = 0; i < num_points; ++i) { - const double theta = i * (2 * autoware::universe_utils::pi / num_points); - const double x = p.x() + radius * std::sin(theta); - const double y = p.y() + radius * std::cos(theta); - ring.emplace_back(x, y, p.z()); - } - - // Make closed - ring.emplace_back(p.x(), p.y() + radius, p.z()); - - return ring; -} -} // namespace autoware::motion_utils::VirtualWalls VirtualTrafficLightModule::createVirtualWalls() { From 1827117dd786938be38891f4bd3647b8d5ff32a1 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 29 Aug 2024 08:25:02 +0000 Subject: [PATCH 060/217] chore: update CODEOWNERS (#8434) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 28 ++++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 8e285671ec21b..85f0c68a35f29 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -79,30 +79,31 @@ 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_vehicle_launch/** yukihiro.saito@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 +localization/autoware_gyro_odometer/** 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_ar_tag_based_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 yamato.ando@tier4.jp 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_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 +localization/autoware_pose_estimator_arbiter/** 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_instability_detector/** 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_stop_filter/** 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_twist2accel/** 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/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 -localization/autoware_gyro_odometer/** 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_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/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/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/pose_estimator_arbiter/** 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/pose_initializer/** anh.nguyen.2@tier4.jp isamu.takagi@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_instability_detector/** 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/yabloc/yabloc_common/** 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/yabloc/yabloc_image_processing/** 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/yabloc/yabloc_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/yabloc/yabloc_particle_filter/** 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/yabloc/yabloc_pose_initializer/** 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 map/autoware_map_height_fitter/** anh.nguyen.2@tier4.jp isamu.takagi@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 -map/map_loader/** 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 map/autoware_map_projection_loader/** 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 map/autoware_map_tf_generator/** 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 +map/map_loader/** 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 map/util/lanelet2_map_preprocessor/** 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 perception/autoware_bytetrack/** manato.hirabayashi@tier4.jp yoshi.ri@tier4.jp perception/autoware_cluster_merger/** dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp @@ -134,7 +135,7 @@ perception/autoware_raindrop_cluster_filter/** dai.nguyen@tier4.jp yoshi.ri@tier perception/autoware_shape_estimation/** kcolak@leodrive.ai yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/autoware_simple_object_merger/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp perception/autoware_tensorrt_classifier/** kotaro.uetake@tier4.jp shunsuke.miura@tier4.jp -perception/autoware_tensorrt_yolox/** dan.umeda@tier4.jp manato.hirabayashi@tier4.jp kotaro.uetake@tier4.jp +perception/autoware_tensorrt_yolox/** dan.umeda@tier4.jp kotaro.uetake@tier4.jp manato.hirabayashi@tier4.jp perception/autoware_tracking_object_merger/** taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/autoware_traffic_light_arbiter/** kenzo.lobos@tier4.jp shunsuke.miura@tier4.jp perception/autoware_traffic_light_classifier/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp yukihiro.saito@tier4.jp @@ -177,7 +178,7 @@ planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_ planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yuki.takagi@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/** kyoichi.sugahara@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/** kyoichi.sugahara@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_intersection_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yukinari.hisaki.2@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp @@ -191,8 +192,8 @@ planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_modu planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp 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/** maxime.clement@tier4.jp -planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@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/** 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/** maxime.clement@tier4.jp planning/motion_velocity_planner/autoware_motion_velocity_planner_node/** maxime.clement@tier4.jp planning/sampling_based_planner/autoware_bezier_sampler/** maxime.clement@tier4.jp @@ -201,15 +202,14 @@ planning/sampling_based_planner/autoware_path_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/autoware_sampler_common/** maxime.clement@tier4.jp sensing/autoware_gnss_poser/** 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 sensing/autoware_image_diagnostics/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp -sensing/autoware_imu_corrector/** taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/autoware_image_transport_decompressor/** kenzo.lobos@tier4.jp yukihiro.saito@tier4.jp +sensing/autoware_imu_corrector/** taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/autoware_pcl_extensions/** david.wong@tier4.jp kenzo.lobos@tier4.jp ryu.yamamoto@tier4.jp sensing/autoware_pointcloud_preprocessor/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp david.wong@tier4.jp kenzo.lobos@tier4.jp kyoichi.sugahara@tier4.jp melike@leodrive.ai shunsuke.miura@tier4.jp yihsiang.fang@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp sensing/autoware_radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/autoware_radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp 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/imu_corrector/** taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/livox/autoware_livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp simulator/autoware_carla_interface/** maxime.clement@tier4.jp mradityagio@gmail.com @@ -219,10 +219,10 @@ simulator/learning_based_vehicle_model/** maxime.clement@tier4.jp nagy.tomas@tie 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/vehicle_door_simulator/** isamu.takagi@tier4.jp system/autoware_component_monitor/** memin@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/component_state_monitor/** isamu.takagi@tier4.jp -system/autoware_default_adapi/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@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 @@ -244,7 +244,7 @@ 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/** makoto.kurihara@tier4.jp sho.iwasawa.2@tier4.jp taiki.tanaka@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 vehicle/autoware_vehicle_info_utils/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp From fb6fd8d82a365ee12157670dce8db3e7ba93659f Mon Sep 17 00:00:00 2001 From: Hayate TOBA <105347690+bathteayo@users.noreply.github.com> Date: Thu, 29 Aug 2024 17:46:15 +0900 Subject: [PATCH 061/217] fix(default_ad_api): fix unusedFunction (#8581) * fix: unusedFunction Signed-off-by: bathteayo <105347690+bathteayo@users.noreply.github.com> * Revert "fix: unusedFunction" This reverts commit c70a36d4d29668f02dae9416f202ccd05abee552. Signed-off-by: bathteayo <105347690+bathteayo@users.noreply.github.com> * fix: unusedFunction Signed-off-by: bathteayo <105347690+bathteayo@users.noreply.github.com> --------- Signed-off-by: bathteayo <105347690+bathteayo@users.noreply.github.com> Co-authored-by: kobayu858 <129580202+kobayu858@users.noreply.github.com> --- system/autoware_default_adapi/src/utils/topics.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/system/autoware_default_adapi/src/utils/topics.hpp b/system/autoware_default_adapi/src/utils/topics.hpp index 6018abb877285..e0f57de89bac3 100644 --- a/system/autoware_default_adapi/src/utils/topics.hpp +++ b/system/autoware_default_adapi/src/utils/topics.hpp @@ -23,12 +23,14 @@ namespace autoware::default_adapi::utils { +// cppcheck-suppress-begin unusedFunction template MsgT ignore_stamp(MsgT msg) { msg.stamp = rclcpp::Time(0, 0); return msg; }; +// cppcheck-suppress-end unusedFunction template void notify(PubT & pub, std::optional & prev, const MsgT & curr, FuncT && ignore) From 7e4cd9d40bbd0f10a60985b3e8481e7ef04af0b2 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 29 Aug 2024 23:42:05 +0900 Subject: [PATCH 062/217] fix(raw_vehicle_cmd_converter): fix null check (#8677) Signed-off-by: kosuke55 --- vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp index 696225db60609..0530840655816 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp @@ -99,8 +99,9 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( // NOTE: some vehicles do not publish actuation status. To handle this, subscribe only when the // option is specified. - need_to_subscribe_actuation_status_ = - convert_actuation_to_steering_status_ || convert_steer_cmd_method_.value() == "vgr"; + const bool use_vgr = + convert_steer_cmd_method_.has_value() && convert_steer_cmd_method_.value() == "vgr"; + need_to_subscribe_actuation_status_ = convert_actuation_to_steering_status_ || use_vgr; if (need_to_subscribe_actuation_status_) { sub_actuation_status_ = create_subscription( "~/input/actuation_status", 1, @@ -119,7 +120,7 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( void RawVehicleCommandConverterNode::publishActuationCmd() { - if (!current_twist_ptr_ || !control_cmd_ptr_ || !current_steer_ptr_ || !actuation_status_ptr_) { + if (!current_twist_ptr_ || !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" : "", @@ -270,7 +271,7 @@ void RawVehicleCommandConverterNode::onActuationStatus( { actuation_status_ptr_ = msg; - if (!convert_actuation_to_steering_status_) { + if (!convert_actuation_to_steering_status_ || convert_steer_cmd_method_.has_value()) { return; } From 21ce55f425ebb3a03f50fd179a68f2410a45f641 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 30 Aug 2024 02:04:56 +0900 Subject: [PATCH 063/217] feat(traffic_light): add dilemma_zone_plotter.py (#8638) * feat(traffic_light): add dilemma_zone_plotter.py Signed-off-by: Takayuki Murooka * fix typo Signed-off-by: Takayuki Murooka * fix typo Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../CMakeLists.txt | 5 + .../scripts/dilemma_zone_plotter.py | 116 ++++++++++++++++++ 2 files changed, 121 insertions(+) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py 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 60cc9f93a02a5..db5b02916a103 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 @@ -12,3 +12,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) ament_auto_package(INSTALL_TO_SHARE config) + +install(PROGRAMS + scripts/dilemma_zone_plotter.py + DESTINATION lib/${PROJECT_NAME} +) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py new file mode 100644 index 0000000000000..55bfbeff893b1 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py @@ -0,0 +1,116 @@ +#!/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 argparse +import os + +from ament_index_python.packages import get_package_share_directory +import matplotlib.pyplot as plt +import numpy as np +import yaml + + +def get_params_from_yaml(): + autoware_launch_package_path = get_package_share_directory("autoware_launch") + + # get parameters from traffic light + traffic_light_yaml_file_path = os.path.join( + autoware_launch_package_path, + "config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml", + ) + with open(traffic_light_yaml_file_path, "r") as yaml_file: + params = yaml.safe_load(yaml_file) + yellow_lamp_period = params["/**"]["ros__parameters"]["traffic_light"]["yellow_lamp_period"] + + # get parameters from behavior velocity planner + behavior_vel_yaml_file_path = os.path.join( + autoware_launch_package_path, + "config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml", + ) + with open(behavior_vel_yaml_file_path, "r") as yaml_file: + params = yaml.safe_load(yaml_file) + max_accel = params["/**"]["ros__parameters"]["max_accel"] + delay_response_time = params["/**"]["ros__parameters"]["delay_response_time"] + + return yellow_lamp_period, max_accel, delay_response_time + + +def plot(max_ego_vel, params): + yellow_lamp_period, max_accel, delay_response_time = params + + # create data to plot + ego_vel = np.linspace(0, round(max_ego_vel), 100) + moving_distance_during_yellow_light = yellow_lamp_period * ego_vel + stop_distance = delay_response_time * ego_vel - ego_vel**2 / (2 * max_accel) + + # plot + fig, ax = plt.subplots() + ax.plot(moving_distance_during_yellow_light, ego_vel, color="blue") + ax.plot(stop_distance, ego_vel, color="red") + + # label for the plot + ax.set_xlabel("moving distance [m]") + ax.set_ylabel("ego velocity [m/s]") + + # colorize the regions + min_distance = np.minimum(moving_distance_during_yellow_light, stop_distance) + max_distance = np.maximum(moving_distance_during_yellow_light, stop_distance) + ax.fill_betweenx( + ego_vel, + stop_distance, + moving_distance_during_yellow_light, + where=(moving_distance_during_yellow_light >= stop_distance), + facecolor="lightgreen", + interpolate=True, + alpha=0.3, + ) + ax.fill_betweenx( + ego_vel, + stop_distance, + moving_distance_during_yellow_light, + where=(moving_distance_during_yellow_light < stop_distance), + facecolor="orange", + interpolate=True, + alpha=0.3, + ) + ax.fill_betweenx(ego_vel, min_distance, facecolor="yellow", interpolate=True, alpha=0.1) + ax.fill_between(max_distance, ego_vel, facecolor="red", interpolate=True, alpha=0.05) + + # init dot lines for the cursor + hline = ax.axhline(y=0, color="gray", linestyle="--") + vline = ax.axvline(x=0, color="gray", linestyle="--") + + # capture the cursor + def on_mouse_move(event): + if event.inaxes: + hline.set_ydata(event.ydata) + vline.set_xdata(event.xdata) + fig.canvas.draw_idle() + + fig.canvas.mpl_connect("motion_notify_event", on_mouse_move) + + plt.show() + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("-v", "--vel", default=16.7, type=float, help="maximum ego velocity [m/s]") + args = parser.parse_args() + + params = get_params_from_yaml() + + max_ego_vel = args.vel + plot(max_ego_vel, params) From 471d0796ffe2eb4d0ae300194e3ca29899740b35 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 30 Aug 2024 10:38:37 +0900 Subject: [PATCH 064/217] fix(autoware_pointcloud_preprocessor): fix unusedFunction (#8673) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/downsample_filter/robin_hood.h | 56 ------------------- 1 file changed, 56 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 51f40765e9ea1..dd5cc9d60dd76 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h @@ -340,12 +340,6 @@ using SizeT = uint64_t; using SizeT = uint32_t; #endif -template -T rotr(T x, unsigned k) -{ - return (x >> k) | (x << (8U * sizeof(T) - k)); -} - // This cast gets rid of warnings like "cast from 'uint8_t*' {aka 'unsigned char*'} to // 'uint64_t*' {aka 'long unsigned int*'} increases required alignment of target type". Use with // care! @@ -1931,13 +1925,6 @@ class Table InsertionState::key_found != idxAndState.second); } - template - iterator emplace_hint(const const_iterator & position, Args &&... args) - { - (void)position; - return emplace(std::forward(args)...).first; - } - template std::pair try_emplace(const key_type & key, Args &&... args) { @@ -2175,14 +2162,6 @@ class Table return 0; } - // reserves space for the specified number of elements. Makes sure the old data fits. - // exactly the same as reserve(c). - void rehash(size_t c) - { - // forces a reserve - reserve(c, true); - } - // reserves space for the specified number of elements. Makes sure the old data fits. // Exactly the same as rehash(c). Use rehash(0) to shrink to fit. void reserve(size_t c) @@ -2191,28 +2170,6 @@ class Table reserve(c, false); } - // If possible reallocates the map to a smaller one. This frees the underlying table. - // Does not do anything if load_factor is too large for decreasing the table's size. - void compact() - { - ROBIN_HOOD_TRACE(this) - auto newSize = InitialNumElements; - while (calcMaxNumElementsAllowed(newSize) < mNumElements && newSize != 0) { - newSize *= 2; - } - if (ROBIN_HOOD_UNLIKELY(newSize == 0)) { - throwOverflowError(); - } - - ROBIN_HOOD_LOG("newSize > mMask + 1: " << newSize << " > " << mMask << " + 1") - - // only actually do anything when the new size is bigger than the old one. This prevents to - // continuously allocate for each reserve() call. - if (newSize < mMask + 1) { - rehashPowerOfTwo(newSize, true); - } - } - size_type size() const noexcept { // NOLINT (modernize-use-nodiscard) ROBIN_HOOD_TRACE(this) @@ -2231,19 +2188,6 @@ class Table return 0 == mNumElements; } - float max_load_factor() const noexcept - { // NOLINT (modernize-use-nodiscard) - ROBIN_HOOD_TRACE(this) - return MaxLoadFactor100 / 100.0F; - } - - // Average number of elements per bucket. Since we allow only 1 per bucket - float load_factor() const noexcept - { // NOLINT (modernize-use-nodiscard) - ROBIN_HOOD_TRACE(this) - return static_cast(size()) / static_cast(mMask + 1); - } - ROBIN_HOOD(NODISCARD) size_t mask() const noexcept { ROBIN_HOOD_TRACE(this) From 6a2b0069e74b25b3bfe26f6149185a174d3fa0ec Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 30 Aug 2024 10:41:15 +0900 Subject: [PATCH 065/217] fix(autoware_behavior_path_static_obstacle_avoidance_module): fix unusedFunction (#8664) fix:unusedFunction Signed-off-by: kobayu858 --- .../debug.hpp | 5 - .../src/debug.cpp | 97 ------------------- .../src/utils.cpp | 25 ----- 3 files changed, 127 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp index b205838896038..29014105dab6e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp @@ -33,15 +33,10 @@ using autoware::behavior_path_planner::ObjectInfo; using autoware::behavior_path_planner::PathShifter; using autoware::behavior_path_planner::ShiftLineArray; -MarkerArray createEgoStatusMarkerArray( - const AvoidancePlanningData & data, const Pose & p_ego, std::string && ns); - MarkerArray createAvoidLineMarkerArray( const AvoidLineArray & shift_lines, std::string && ns, const float & r, const float & g, const float & b, const double & w); -MarkerArray createPredictedVehiclePositions(const PathWithLaneId & path, std::string && ns); - MarkerArray createTargetObjectsMarkerArray(const ObjectDataArray & objects, const std::string & ns); MarkerArray createOtherObjectsMarkerArray( diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index fb4e5c7b9a25e..536e350e50bf1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -231,41 +231,6 @@ MarkerArray unAvoidableObjectsMarkerArray(const ObjectDataArray & objects, std:: } // namespace -MarkerArray createEgoStatusMarkerArray( - const AvoidancePlanningData & data, const Pose & p_ego, std::string && ns) -{ - MarkerArray msg; - - auto marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, 0L, Marker::TEXT_VIEW_FACING, - createMarkerScale(0.5, 0.5, 0.5), createMarkerColor(1.0, 1.0, 1.0, 0.999)); - marker.pose = p_ego; - - { - std::ostringstream string_stream; - string_stream << std::fixed << std::setprecision(2) << std::boolalpha; - string_stream << "avoid_req:" << data.avoid_required << "," - << "yield_req:" << data.yield_required << "," - << "safe:" << data.safe; - marker.text = string_stream.str(); - - msg.markers.push_back(marker); - } - - { - std::ostringstream string_stream; - string_stream << "ego_state:"; - string_stream << magic_enum::enum_name(data.state); - marker.text = string_stream.str(); - marker.pose.position.z += 2.0; - marker.id++; - - msg.markers.push_back(marker); - } - - return msg; -} - MarkerArray createAvoidLineMarkerArray( const AvoidLineArray & shift_lines, std::string && ns, const float & r, const float & g, const float & b, const double & w) @@ -346,68 +311,6 @@ MarkerArray createAvoidLineMarkerArray( return msg; } -MarkerArray createPredictedVehiclePositions(const PathWithLaneId & path, std::string && ns) -{ - const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now(); - MarkerArray msg; - - auto p_marker = createDefaultMarker( - "map", current_time, ns, 0L, Marker::POINTS, createMarkerScale(0.4, 0.4, 0.0), - createMarkerColor(1.0, 0.0, 0.0, 0.999)); - - const auto pushPointMarker = [&](const Pose & p, const double t) { - const auto r = t > 10.0 ? 1.0 : t / 10.0; - p_marker.points.push_back(p.position); - p_marker.colors.push_back(createMarkerColor(r, 1.0 - r, 0.0, 0.999)); - }; - - auto t_marker = createDefaultMarker( - "map", current_time, ns + "_text", 0L, Marker::TEXT_VIEW_FACING, - createMarkerScale(0.3, 0.3, 0.3), createMarkerColor(1.0, 1.0, 0.0, 1.0)); - - const auto pushTextMarker = [&](const Pose & p, const double t, const double d, const double v) { - t_marker.id++; - t_marker.pose = p; - std::ostringstream string_stream; - string_stream << std::fixed << std::setprecision(2); - string_stream << "t[s]: " << t << "\n" - << "d[m]: " << d << "\n" - << "v[m/s]: " << v; - t_marker.text = string_stream.str(); - msg.markers.push_back(t_marker); - }; - - constexpr double dt_save = 1.0; - double t_save = 0.0; - double t_sum = 0.0; - double d_sum = 0.0; - - if (path.points.empty()) { - return msg; - } - - for (size_t i = 1; i < path.points.size(); ++i) { - const auto & p1 = path.points.at(i - 1); - const auto & p2 = path.points.at(i); - const auto ds = calcDistance2d(p1, p2); - - if (t_save < t_sum + 1e-3) { - pushPointMarker(getPose(p1), t_sum); - pushTextMarker(getPose(p1), t_sum, d_sum, p1.point.longitudinal_velocity_mps); - t_save += dt_save; - } - - const auto v = std::max(p1.point.longitudinal_velocity_mps, float{1.0}); - - t_sum += ds / v; - d_sum += ds; - } - - msg.markers.push_back(p_marker); - - return msg; -} - MarkerArray createTargetObjectsMarkerArray(const ObjectDataArray & objects, const std::string & ns) { ObjectDataArray avoidable; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index dab8eb8fb35e2..0f3e3da5b2171 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -114,31 +114,6 @@ size_t findFirstNearestSegmentIndex(const T & points, const geometry_msgs::msg:: return nearest_idx; } -template -double calcSignedArcLengthToFirstNearestPoint( - const T & points, const geometry_msgs::msg::Point & src_point, - const geometry_msgs::msg::Point & dst_point) -{ - try { - autoware::motion_utils::validateNonEmpty(points); - } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; - return 0.0; - } - - const size_t src_seg_idx = findFirstNearestSegmentIndex(points, src_point); - const size_t dst_seg_idx = findFirstNearestSegmentIndex(points, dst_point); - - const double signed_length_on_traj = - autoware::motion_utils::calcSignedArcLength(points, src_seg_idx, dst_seg_idx); - const double signed_length_src_offset = - autoware::motion_utils::calcLongitudinalOffsetToSegment(points, src_seg_idx, src_point); - const double signed_length_dst_offset = - autoware::motion_utils::calcLongitudinalOffsetToSegment(points, dst_seg_idx, dst_point); - - return signed_length_on_traj - signed_length_src_offset + signed_length_dst_offset; -} - geometry_msgs::msg::Polygon createVehiclePolygon( const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double offset) { From ee38d9541afead023b5e629a0cddd33881d70802 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Fri, 30 Aug 2024 10:42:06 +0900 Subject: [PATCH 066/217] fix(object_association_merger_node): fix the frame id of output object msg (#8674) fix: fix the object msg header Signed-off-by: vividf --- .../src/object_association_merger_node.cpp | 1 + 1 file changed, 1 insertion(+) 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 cd5e96d2374fc..663a338649d3c 100644 --- a/perception/autoware_object_merger/src/object_association_merger_node.cpp +++ b/perception/autoware_object_merger/src/object_association_merger_node.cpp @@ -152,6 +152,7 @@ void ObjectAssociationMergerNode::objectsCallback( // build output msg autoware_perception_msgs::msg::DetectedObjects output_msg; output_msg.header = input_objects0_msg->header; + output_msg.header.frame_id = base_link_frame_id_; /* global nearest neighbor */ std::unordered_map direct_assignment, reverse_assignment; From 17ad4253014bc753afcb00dbbd687181a83419b3 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 30 Aug 2024 10:45:29 +0900 Subject: [PATCH 067/217] fix(tier4_state_rviz_plugin): fix unmatchedSuppression (#8658) fix:unmatchedSuppression Signed-off-by: kobayu858 --- common/tier4_state_rviz_plugin/src/custom_container.cpp | 1 - common/tier4_state_rviz_plugin/src/custom_icon_label.cpp | 2 -- common/tier4_state_rviz_plugin/src/custom_label.cpp | 2 -- common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp | 2 -- .../src/custom_segmented_button_item.cpp | 1 - common/tier4_state_rviz_plugin/src/custom_slider.cpp | 1 - common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp | 1 - 7 files changed, 10 deletions(-) diff --git a/common/tier4_state_rviz_plugin/src/custom_container.cpp b/common/tier4_state_rviz_plugin/src/custom_container.cpp index c82ca685ca9ba..4e7bafd044897 100644 --- a/common/tier4_state_rviz_plugin/src/custom_container.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_container.cpp @@ -40,7 +40,6 @@ QSize CustomContainer::sizeHint() const return QSize(width, height); } -// cppcheck-suppress unusedFunction QSize CustomContainer::minimumSizeHint() const { return sizeHint(); diff --git a/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp b/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp index 28458d7c79d71..6e4d32d40f7fb 100644 --- a/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp @@ -50,13 +50,11 @@ QSize CustomIconLabel::sizeHint() const return QSize(size, size); } -// cppcheck-suppress unusedFunction QSize CustomIconLabel::minimumSizeHint() const { return sizeHint(); } -// cppcheck-suppress unusedFunction void CustomIconLabel::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_label.cpp b/common/tier4_state_rviz_plugin/src/custom_label.cpp index 59df84138b890..1f96fc0d45095 100644 --- a/common/tier4_state_rviz_plugin/src/custom_label.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_label.cpp @@ -46,13 +46,11 @@ QSize CustomLabel::sizeHint() const return QSize(width, height); } -// cppcheck-suppress unusedFunction QSize CustomLabel::minimumSizeHint() const { return sizeHint(); } -// cppcheck-suppress unusedFunction void CustomLabel::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp b/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp index 3f93df006415e..786b58ecf1d2e 100644 --- a/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp @@ -55,13 +55,11 @@ QSize CustomSegmentedButton::sizeHint() const // layout->itemAt(0)->widget()->height() + 10); } -// cppcheck-suppress unusedFunction QSize CustomSegmentedButton::minimumSizeHint() const { return sizeHint(); } -// cppcheck-suppress unusedFunction void CustomSegmentedButton::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp b/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp index 3c671c988f936..70f21ca1fec84 100644 --- a/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp @@ -76,7 +76,6 @@ void CustomSegmentedButtonItem::setActivated(bool activated) update(); } -// cppcheck-suppress unusedFunction void CustomSegmentedButtonItem::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_slider.cpp b/common/tier4_state_rviz_plugin/src/custom_slider.cpp index 16dfda19a87bf..cf3f7c3d4638f 100644 --- a/common/tier4_state_rviz_plugin/src/custom_slider.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_slider.cpp @@ -19,7 +19,6 @@ CustomSlider::CustomSlider(Qt::Orientation orientation, QWidget * parent) setMinimumHeight(40); // Ensure there's enough space for the custom track } -// cppcheck-suppress unusedFunction void CustomSlider::paintEvent(QPaintEvent *) { QPainter painter(this); diff --git a/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp b/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp index b171fa554cd01..3b58ded626439 100644 --- a/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp @@ -30,7 +30,6 @@ QSize CustomToggleSwitch::sizeHint() const return QSize(50, 30); // Preferred size of the toggle switch } -// cppcheck-suppress unusedFunction void CustomToggleSwitch::paintEvent(QPaintEvent *) { QPainter p(this); From 0cee96143239e16ead4a464d83662bca7a5aef1e Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Fri, 30 Aug 2024 11:59:31 +0900 Subject: [PATCH 068/217] feat(autoware_perception_rviz_plugin): rviz predicted path mark as triangle (#8536) * refactor: predicted path mark replace to triangle Signed-off-by: Taekjin LEE * chore: clean up Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../object_polygon_detail.cpp | 26 ++++++++++++++++--- 1 file changed, 22 insertions(+), 4 deletions(-) diff --git a/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp index 9c25c2dc3781e..28ff67433efe5 100644 --- a/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp +++ b/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp @@ -701,7 +701,7 @@ void calc_2d_bounding_box_bottom_direction_line_list( geometry_msgs::msg::Point point; // triangle-shaped direction indicator - const double point_list[6][3] = { + const double point_list[3][3] = { {length_half, 0, -height_half}, {length_half - triangle_size_half, width_half, -height_half}, {length_half - triangle_size_half, -width_half, -height_half}, @@ -914,9 +914,8 @@ void calc_path_line_list( const autoware_perception_msgs::msg::PredictedPath & paths, std::vector & points, const bool is_simple) { - const int circle_line_num = is_simple ? 5 : 10; - for (int i = 0; i < static_cast(paths.path.size()) - 1; ++i) { + // draw line geometry_msgs::msg::Point point; point.x = paths.path.at(i).position.x; point.y = paths.path.at(i).position.y; @@ -926,8 +925,27 @@ void calc_path_line_list( point.y = paths.path.at(i + 1).position.y; point.z = paths.path.at(i + 1).position.z; points.push_back(point); + if (!is_simple || i % 2 == 0) { - calc_circle_line_list(point, 0.25, points, circle_line_num); + // get yaw from the line + const double yaw = + std::atan2(point.y - paths.path.at(i).position.y, point.x - paths.path.at(i).position.x); + // draw triangle + constexpr double length = 0.5; + const double arrow_angle = M_PI * 5.0 / 6.0; + const double point_list[3][3] = { + {point.x, point.y, point.z}, + {point.x + length * std::cos(yaw + arrow_angle), + point.y + length * std::sin(yaw + arrow_angle), point.z}, + {point.x + length * std::cos(yaw - arrow_angle), + point.y + length * std::sin(yaw - arrow_angle), point.z}, + }; + const int point_pairs[3][2] = { + {0, 1}, + {1, 2}, + {2, 0}, + }; + calc_line_list_from_points(point_list, point_pairs, 3, points); } } } From c758c81143ea386f4bcdae56f788357f981a256b Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 30 Aug 2024 16:24:22 +0900 Subject: [PATCH 069/217] fix(simple_planning_simulator): delete velocity dead band for brake (#8685) * delete dead band Signed-off-by: Yuki Takagi --- .../sim_model_delay_steer_acc_geared_wo_fall_guard.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) 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/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp index ce962eba9275a..6b993b8b24409 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp @@ -166,10 +166,9 @@ Eigen::VectorXd SimModelDelaySteerAccGearedWoFallGuard::calcModel( return pedal_acc + input(IDX_U::SLOPE_ACCX); } } else { - constexpr double brake_dead_band = 1e-3; - if (vel > brake_dead_band) { + if (vel > 0.0) { return pedal_acc + input(IDX_U::SLOPE_ACCX); - } else if (vel < -brake_dead_band) { + } else if (vel < 0.0) { return -pedal_acc + input(IDX_U::SLOPE_ACCX); } else if (-pedal_acc >= std::abs(input(IDX_U::SLOPE_ACCX))) { return 0.0; From eac633255c7327f91d46110f67dce0ea1bf1b990 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Fri, 30 Aug 2024 16:35:47 +0900 Subject: [PATCH 070/217] feat(autoware_motion_utils): add clone function and make the constructor public (#8688) * feat(autoware_motion_utils): add interpolator Signed-off-by: Y.Hisaki * use int32_t instead of int Signed-off-by: Y.Hisaki * use int32_t instead of int Signed-off-by: Y.Hisaki * use int32_t instead of int Signed-off-by: Y.Hisaki * add const as much as possible and use `at()` in `vector` Signed-off-by: Y.Hisaki * fix directory name Signed-off-by: Y.Hisaki * refactor code and add example Signed-off-by: Y.Hisaki * update Signed-off-by: Y.Hisaki * remove unused include Signed-off-by: Y.Hisaki * refactor code Signed-off-by: Y.Hisaki * add clone function Signed-off-by: Y.Hisaki * fix stairstep Signed-off-by: Y.Hisaki * make constructor to public Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki --- .../interpolator/akima_spline.hpp | 15 +++++--- .../interpolator/cubic_spline.hpp | 14 +++++--- .../interpolator/interpolator.hpp | 6 ++++ .../interpolator/linear.hpp | 21 ++++++----- .../interpolator/nearest_neighbor.hpp | 35 ++++++++++++++----- .../interpolator/stairstep.hpp | 34 +++++++++++++----- .../interpolator/akima_spline.cpp | 6 ++++ .../interpolator/cubic_spline.cpp | 5 +++ .../interpolator/linear.cpp | 6 ++++ 9 files changed, 107 insertions(+), 35 deletions(-) diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/akima_spline.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/akima_spline.hpp index 42cd1aa6759a3..363d046534399 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/akima_spline.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/akima_spline.hpp @@ -19,6 +19,7 @@ #include +#include #include namespace autoware::motion_utils::trajectory_container::interpolator @@ -31,14 +32,9 @@ namespace autoware::motion_utils::trajectory_container::interpolator */ class AkimaSpline : public Interpolator { - template - friend class InterpolatorCreator; - private: Eigen::VectorXd a_, b_, c_, d_; ///< Coefficients for the Akima spline. - AkimaSpline() = default; - /** * @brief Compute the spline parameters. * @@ -85,12 +81,21 @@ class AkimaSpline : public Interpolator [[nodiscard]] double compute_second_derivative_impl(const double & s) const override; public: + AkimaSpline() = default; + /** * @brief Get the minimum number of required points for the interpolator. * * @return The minimum number of required points. */ [[nodiscard]] size_t minimum_required_points() const override { return 5; } + + /** + * @brief Clone the interpolator. + * + * @return A shared pointer to a new instance of the interpolator. + */ + [[nodiscard]] std::shared_ptr> clone() const override; }; } // namespace autoware::motion_utils::trajectory_container::interpolator diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/cubic_spline.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/cubic_spline.hpp index 43f1102fd0f73..50cff1dde3f35 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/cubic_spline.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/cubic_spline.hpp @@ -31,15 +31,10 @@ namespace autoware::motion_utils::trajectory_container::interpolator */ class CubicSpline : public Interpolator { - template - friend class InterpolatorCreator; - private: Eigen::VectorXd a_, b_, c_, d_; ///< Coefficients for the cubic spline. Eigen::VectorXd h_; ///< Interval sizes between axis points. - CubicSpline() = default; - /** * @brief Compute the spline parameters. * @@ -87,12 +82,21 @@ class CubicSpline : public Interpolator [[nodiscard]] double compute_second_derivative_impl(const double & s) const override; public: + CubicSpline() = default; + /** * @brief Get the minimum number of required points for the interpolator. * * @return The minimum number of required points. */ [[nodiscard]] size_t minimum_required_points() const override { return 4; } + + /** + * @brief Clone the interpolator. + * + * @return A shared pointer to a new instance of the interpolator. + */ + [[nodiscard]] std::shared_ptr> clone() const override; }; } // namespace autoware::motion_utils::trajectory_container::interpolator diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/interpolator.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/interpolator.hpp index 18dce8b46c2c7..f0b12a47819e8 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/interpolator.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/interpolator.hpp @@ -17,6 +17,8 @@ #include "autoware/motion_utils/trajectory_container/interpolator/detail/interpolator_common_impl.hpp" +#include + namespace autoware::motion_utils::trajectory_container::interpolator { /** @@ -29,6 +31,8 @@ namespace autoware::motion_utils::trajectory_container::interpolator template class Interpolator : public detail::InterpolatorCommonImpl { +public: + [[nodiscard]] virtual std::shared_ptr> clone() const = 0; }; /** @@ -84,6 +88,8 @@ class Interpolator : public detail::InterpolatorCommonImpl this->validate_compute_input(s); return compute_second_derivative_impl(s); } + + [[nodiscard]] virtual std::shared_ptr> clone() const = 0; }; } // namespace autoware::motion_utils::trajectory_container::interpolator diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/linear.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/linear.hpp index df0806f285339..9854b100f3742 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/linear.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/linear.hpp @@ -19,6 +19,7 @@ #include +#include #include namespace autoware::motion_utils::trajectory_container::interpolator @@ -31,17 +32,9 @@ namespace autoware::motion_utils::trajectory_container::interpolator */ class Linear : public Interpolator { - template - friend class InterpolatorCreator; - private: Eigen::VectorXd values_; ///< Interpolation values. - /** - * @brief Default constructor. - */ - Linear() = default; - /** * @brief Build the interpolator with the given values. * @@ -77,12 +70,24 @@ class Linear : public Interpolator [[nodiscard]] double compute_second_derivative_impl(const double &) const override; public: + /** + * @brief Default constructor. + */ + Linear() = default; + /** * @brief Get the minimum number of required points for the interpolator. * * @return The minimum number of required points. */ [[nodiscard]] size_t minimum_required_points() const override; + + /** + * @brief Clone the interpolator. + * + * @return A shared pointer to the cloned interpolator. + */ + [[nodiscard]] std::shared_ptr> clone() const override; }; } // namespace autoware::motion_utils::trajectory_container::interpolator diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/nearest_neighbor.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/nearest_neighbor.hpp index c433607902b38..32bff2d30b41d 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/nearest_neighbor.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/nearest_neighbor.hpp @@ -17,6 +17,8 @@ #include "autoware/motion_utils/trajectory_container/interpolator/detail/nearest_neighbor_common_impl.hpp" +#include + namespace autoware::motion_utils::trajectory_container::interpolator { @@ -40,11 +42,18 @@ class NearestNeighbor; template class NearestNeighbor : public detail::NearestNeighborCommonImpl { - template - friend class InterpolatorCreator; - -private: +public: NearestNeighbor() = default; + + /** + * @brief Clone the interpolator. + * + * @return A shared pointer to a new instance of the interpolator. + */ + [[nodiscard]] std::shared_ptr> clone() const override + { + return std::make_shared>(*this); + } }; /** @@ -55,12 +64,7 @@ class NearestNeighbor : public detail::NearestNeighborCommonImpl template <> class NearestNeighbor : public detail::NearestNeighborCommonImpl { - template - friend class InterpolatorCreator; - private: - NearestNeighbor() = default; - /** * @brief Compute the first derivative at the given point. * @@ -76,6 +80,19 @@ class NearestNeighbor : public detail::NearestNeighborCommonImpl * @return The second derivative. */ [[nodiscard]] double compute_second_derivative_impl(const double &) const override { return 0.0; } + +public: + NearestNeighbor() = default; + + /** + * @brief Clone the interpolator. + * + * @return A shared pointer to a new instance of the interpolator. + */ + [[nodiscard]] std::shared_ptr> clone() const override + { + return std::make_shared>(*this); + } }; } // namespace autoware::motion_utils::trajectory_container::interpolator diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/stairstep.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/stairstep.hpp index e8c8f8c015b63..21bf57b46e3b7 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/stairstep.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/stairstep.hpp @@ -17,6 +17,8 @@ #include "autoware/motion_utils/trajectory_container/interpolator/detail/stairstep_common_impl.hpp" +#include + namespace autoware::motion_utils::trajectory_container::interpolator { @@ -40,11 +42,18 @@ class Stairstep; template class Stairstep : public detail::StairstepCommonImpl { - template - friend class InterpolatorCreator; - -private: +public: Stairstep() = default; + + /** + * @brief Clone the interpolator. + * + * @return A shared pointer to a new instance of the interpolator. + */ + [[nodiscard]] std::shared_ptr> clone() const override + { + return std::make_shared>(*this); + } }; /** @@ -55,11 +64,7 @@ class Stairstep : public detail::StairstepCommonImpl template <> class Stairstep : public detail::StairstepCommonImpl { - template - friend class InterpolatorCreator; - private: - Stairstep() = default; /** * @brief Compute the first derivative at the given point. * @@ -75,6 +80,19 @@ class Stairstep : public detail::StairstepCommonImpl * @return The second derivative. */ [[nodiscard]] double compute_second_derivative_impl(const double &) const override { return 0.0; } + +public: + Stairstep() = default; + + /** + * @brief Clone the interpolator. + * + * @return A shared pointer to a new instance of the interpolator. + */ + [[nodiscard]] std::shared_ptr> clone() const override + { + return std::make_shared>(*this); + } }; } // namespace autoware::motion_utils::trajectory_container::interpolator diff --git a/common/autoware_motion_utils/src/trajectory_container/interpolator/akima_spline.cpp b/common/autoware_motion_utils/src/trajectory_container/interpolator/akima_spline.cpp index 283f46dd5d3e9..eb2fe2ab8deed 100644 --- a/common/autoware_motion_utils/src/trajectory_container/interpolator/akima_spline.cpp +++ b/common/autoware_motion_utils/src/trajectory_container/interpolator/akima_spline.cpp @@ -17,6 +17,7 @@ #include #include +#include #include namespace autoware::motion_utils::trajectory_container::interpolator @@ -90,4 +91,9 @@ double AkimaSpline::compute_second_derivative_impl(const double & s) const return 2 * c_[i] + 6 * d_[i] * dx; } +std::shared_ptr> AkimaSpline::clone() const +{ + return std::make_shared(*this); +} + } // namespace autoware::motion_utils::trajectory_container::interpolator diff --git a/common/autoware_motion_utils/src/trajectory_container/interpolator/cubic_spline.cpp b/common/autoware_motion_utils/src/trajectory_container/interpolator/cubic_spline.cpp index 9f262b6a702f9..db25816d1d457 100644 --- a/common/autoware_motion_utils/src/trajectory_container/interpolator/cubic_spline.cpp +++ b/common/autoware_motion_utils/src/trajectory_container/interpolator/cubic_spline.cpp @@ -91,4 +91,9 @@ double CubicSpline::compute_second_derivative_impl(const double & s) const return 2 * c_(i) + 6 * d_(i) * dx; } +std::shared_ptr> CubicSpline::clone() const +{ + return std::make_shared(*this); +} + } // namespace autoware::motion_utils::trajectory_container::interpolator diff --git a/common/autoware_motion_utils/src/trajectory_container/interpolator/linear.cpp b/common/autoware_motion_utils/src/trajectory_container/interpolator/linear.cpp index 4897ba4d2a56c..c3e4ec99c4357 100644 --- a/common/autoware_motion_utils/src/trajectory_container/interpolator/linear.cpp +++ b/common/autoware_motion_utils/src/trajectory_container/interpolator/linear.cpp @@ -16,6 +16,7 @@ #include +#include #include namespace autoware::motion_utils::trajectory_container::interpolator @@ -59,4 +60,9 @@ size_t Linear::minimum_required_points() const return 2; } +std::shared_ptr> Linear::clone() const +{ + return std::make_shared(*this); +} + } // namespace autoware::motion_utils::trajectory_container::interpolator From ba6f68945cd37a39408d2067f19384e27d99abb5 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> Date: Fri, 30 Aug 2024 16:55:12 +0900 Subject: [PATCH 071/217] chore(stop_filter): extract stop_filter.param.yaml to autoware_launch (#8681) Extract stop_filter.param.yaml to autoware_launch Signed-off-by: TaikiYamada4 --- launch/tier4_localization_launch/launch/localization.launch.xml | 1 + .../pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml | 1 + 2 files changed, 2 insertions(+) diff --git a/launch/tier4_localization_launch/launch/localization.launch.xml b/launch/tier4_localization_launch/launch/localization.launch.xml index dd274ce247064..45bb2d3cb38dd 100644 --- a/launch/tier4_localization_launch/launch/localization.launch.xml +++ b/launch/tier4_localization_launch/launch/localization.launch.xml @@ -14,6 +14,7 @@ + diff --git a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml index dda9c1f2c97ce..b162a3851e1b9 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml @@ -22,6 +22,7 @@ + From 5020617a55ed78936bc173cfc2320e4efb30cfc1 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 30 Aug 2024 22:13:46 +0900 Subject: [PATCH 072/217] refactor(goal_planner): move pull_over_planner directory (#8696) Signed-off-by: Mamoru Sobue --- .../CMakeLists.txt | 6 +++--- .../goal_planner_module.hpp | 6 +++--- .../{ => pull_over_planner}/freespace_pull_over.hpp | 8 ++++---- .../{ => pull_over_planner}/geometric_pull_over.hpp | 8 ++++---- .../{ => pull_over_planner}/pull_over_planner_base.hpp | 5 +---- .../{ => pull_over_planner}/shift_pull_over.hpp | 8 ++++---- .../autoware/behavior_path_goal_planner_module/util.hpp | 2 +- .../src/{ => pull_over_planner}/freespace_pull_over.cpp | 2 +- .../src/{ => pull_over_planner}/geometric_pull_over.cpp | 2 +- .../src/{ => pull_over_planner}/shift_pull_over.cpp | 2 +- 10 files changed, 23 insertions(+), 26 deletions(-) rename planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/{ => pull_over_planner}/freespace_pull_over.hpp (84%) rename planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/{ => pull_over_planner}/geometric_pull_over.hpp (88%) rename 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 (96%) rename planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/{ => pull_over_planner}/shift_pull_over.hpp (88%) rename planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/{ => pull_over_planner}/freespace_pull_over.cpp (98%) rename planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/{ => pull_over_planner}/geometric_pull_over.cpp (97%) rename planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/{ => pull_over_planner}/shift_pull_over.cpp (99%) 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 670a61479e875..5d3af19c51dbf 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 @@ -6,11 +6,11 @@ autoware_package() pluginlib_export_plugin_description_file(autoware_behavior_path_planner plugins.xml) 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/default_fixed_goal_planner.cpp - src/freespace_pull_over.cpp - src/geometric_pull_over.cpp src/goal_searcher.cpp - src/shift_pull_over.cpp src/util.cpp src/goal_planner_module.cpp src/manager.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 7462ec519b503..2dc4788be9ce2 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 @@ -16,11 +16,11 @@ #define 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/freespace_pull_over.hpp" -#include "autoware/behavior_path_goal_planner_module/geometric_pull_over.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/shift_pull_over.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/shift_pull_over.hpp" #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" #include "autoware/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include "autoware/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/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 similarity index 84% rename from planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/freespace_pull_over.hpp rename to 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 bb968fe10cba2..0b27b4adb737b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/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 @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FREESPACE_PULL_OVER_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FREESPACE_PULL_OVER_HPP_ +#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__FREESPACE_PULL_OVER_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__FREESPACE_PULL_OVER_HPP_ -#include "autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp" +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp" #include #include @@ -51,4 +51,4 @@ class FreespacePullOver : public PullOverPlannerBase }; } // namespace autoware::behavior_path_planner -#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FREESPACE_PULL_OVER_HPP_ +#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__FREESPACE_PULL_OVER_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/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 similarity index 88% rename from planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/geometric_pull_over.hpp rename to 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 589379167b80c..6a2f0a57d67cf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/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 @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ +#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__GEOMETRIC_PULL_OVER_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__GEOMETRIC_PULL_OVER_HPP_ -#include "autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp" +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp" #include "autoware/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include @@ -65,4 +65,4 @@ class GeometricPullOver : public PullOverPlannerBase }; } // namespace autoware::behavior_path_planner -#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ +#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__GEOMETRIC_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_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 similarity index 96% rename from planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp rename to 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 9899f4a5fad1e..7cdb249463e08 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/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 @@ -12,8 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER_BASE_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER_BASE_HPP_ +#pragma once #include "autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "autoware/behavior_path_planner_common/data_manager.hpp" @@ -207,5 +206,3 @@ class PullOverPlannerBase BehaviorModuleOutput previous_module_output_; }; } // namespace autoware::behavior_path_planner - -#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER_BASE_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/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 similarity index 88% rename from planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/shift_pull_over.hpp rename to 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 15b8d7ac81fae..8ebc3579a9272 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/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 @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ +#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__SHIFT_PULL_OVER_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__SHIFT_PULL_OVER_HPP_ -#include "autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp" +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp" #include @@ -59,4 +59,4 @@ class ShiftPullOver : public PullOverPlannerBase }; } // namespace autoware::behavior_path_planner -#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ +#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__SHIFT_PULL_OVER_HPP_ 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 b527fa3e1dac0..2a48db97b1977 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 @@ -16,7 +16,7 @@ #define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ #include "autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp" -#include "autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp" +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp similarity index 98% rename from planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp rename to planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp index 57c35fc4dd8ba..a49cd7a279e7e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_path_goal_planner_module/freespace_pull_over.hpp" +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_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" diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/geometric_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp similarity index 97% rename from planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/geometric_pull_over.cpp rename to planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp index 3baa603f4d00c..c5df07c0e9176 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_path_goal_planner_module/geometric_pull_over.hpp" +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_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" diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp similarity index 99% rename from planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp rename to planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index fd6b0cb639387..1e4cb0e8d84f9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_path_goal_planner_module/shift_pull_over.hpp" +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/shift_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" From 3e4a94597954d0d762f11cd77e213286bd1d925c Mon Sep 17 00:00:00 2001 From: oguzkaganozt Date: Fri, 30 Aug 2024 20:00:46 +0300 Subject: [PATCH 073/217] refactor(perception/occupancy_grid_map_outlier_filter): rework parameters (#6745) * add param and schema file, edit readme Signed-off-by: oguzkaganozt * . Signed-off-by: Oguz Ozturk * correct linter errors Signed-off-by: oguzkaganozt --------- Signed-off-by: oguzkaganozt Signed-off-by: Oguz Ozturk --- .../ground_segmentation.launch.py | 16 +++- .../CMakeLists.txt | 5 +- .../README.md | 12 +-- ...cupancy_grid_map_outlier_filter.param.yaml | 12 +++ ...upancy_grid_map_outlier_filter.schema.json | 86 +++++++++++++++++++ ...occupancy_grid_map_outlier_filter_node.cpp | 20 ++--- 6 files changed, 128 insertions(+), 23 deletions(-) create mode 100644 perception/autoware_occupancy_grid_map_outlier_filter/config/occupancy_grid_map_outlier_filter.param.yaml create mode 100644 perception/autoware_occupancy_grid_map_outlier_filter/schema/occupancy_grid_map_outlier_filter.schema.json diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 541d4e4d4c920..b25c8f3de9a5b 100644 --- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -23,6 +23,7 @@ from launch.substitutions import PathJoinSubstitution from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode +from launch_ros.parameter_descriptions import ParameterFile from launch_ros.substitutions import FindPackageShare import yaml @@ -327,7 +328,9 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp return components @staticmethod - def create_time_series_outlier_filter_components(input_topic, output_topic): + def create_time_series_outlier_filter_components( + input_topic, output_topic, ogm_outlier_filter_param + ): components = [] components.append( ComposableNode( @@ -339,6 +342,7 @@ def create_time_series_outlier_filter_components(input_topic, output_topic): ("~/input/pointcloud", input_topic), ("~/output/pointcloud", output_topic), ], + parameters=[ogm_outlier_filter_param], extra_arguments=[ {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} ], @@ -545,6 +549,9 @@ def launch_setup(context, *args, **kwargs): else pipeline.single_frame_obstacle_seg_output ), output_topic=pipeline.output_topic, + ogm_outlier_filter_param=ParameterFile( + LaunchConfiguration("ogm_outlier_filter_param_path").perform(context) + ), ) ) pointcloud_container_loader = LoadComposableNodes( @@ -565,6 +572,13 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("use_intra_process", "True") add_launch_arg("pointcloud_container_name", "pointcloud_container") add_launch_arg("input/pointcloud", "/sensing/lidar/concatenated/pointcloud") + add_launch_arg( + "ogm_outlier_filter_param_path", + [ + FindPackageShare("autoware_launch"), + "/config/perception/obstacle_segmentation/occupancy_grid_based_outlier_filter/occupancy_grid_map_outlier_filter.param.yaml", + ], + ) set_container_executable = SetLaunchConfiguration( "container_executable", diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/CMakeLists.txt b/perception/autoware_occupancy_grid_map_outlier_filter/CMakeLists.txt index 0fc73d43e54c9..29eb1bea67e73 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/CMakeLists.txt +++ b/perception/autoware_occupancy_grid_map_outlier_filter/CMakeLists.txt @@ -43,4 +43,7 @@ rclcpp_components_register_node(${PROJECT_NAME} PLUGIN "autoware::occupancy_grid_map_outlier_filter::OccupancyGridMapOutlierFilterComponent" EXECUTABLE ${PROJECT_NAME}_node) -ament_auto_package(INSTALL_TO_SHARE) +ament_auto_package( + INSTALL_TO_SHARE + config +) diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/README.md b/perception/autoware_occupancy_grid_map_outlier_filter/README.md index 28974edf65053..7de2cc1dce92c 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/README.md +++ b/perception/autoware_occupancy_grid_map_outlier_filter/README.md @@ -40,17 +40,7 @@ The following video is a sample. Yellow points are high occupancy probability, g ## Parameters -| Name | Type | Description | -| ------------------------------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| `map_frame` | string | map frame id | -| `base_link_frame` | string | base link frame id | -| `cost_threshold` | int | Cost threshold of occupancy grid map (0~100). 100 means 100% probability that there is an obstacle, close to 50 means that it is indistinguishable whether it is an obstacle or free space, 0 means that there is no obstacle. | -| `enable_debugger` | bool | Whether to output the point cloud for debugging. | -| `use_radius_search_2d_filter` | bool | Whether or not to apply density-based outlier filters to objects that are judged to have low probability of occupancy on the occupancy grid map. | -| `radius_search_2d_filter/search_radius` | float | Radius when calculating the density | -| `radius_search_2d_filter/min_points_and_distance_ratio` | float | Threshold value of the number of point clouds per radius when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink. | -| `radius_search_2d_filter/min_points` | int | Minimum number of point clouds per radius | -| `radius_search_2d_filter/max_points` | int | Maximum number of point clouds per radius | +{{ json_to_markdown("perception/occupancy_grid_map_outlier_filter/schema/occupancy_grid_map_outlier_filter.schema.json") }} ## Assumptions / Known limits diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/config/occupancy_grid_map_outlier_filter.param.yaml b/perception/autoware_occupancy_grid_map_outlier_filter/config/occupancy_grid_map_outlier_filter.param.yaml new file mode 100644 index 0000000000000..61cd3a2dc19e2 --- /dev/null +++ b/perception/autoware_occupancy_grid_map_outlier_filter/config/occupancy_grid_map_outlier_filter.param.yaml @@ -0,0 +1,12 @@ +/**: + ros__parameters: + radius_search_2d_filter.search_radius: 1.0 + radius_search_2d_filter.min_points_and_distance_ratio: 400.0 + radius_search_2d_filter.min_points: 4 + radius_search_2d_filter.max_points: 70 + radius_search_2d_filter.max_filter_points_nb: 15000 + map_frame: "map" + base_link_frame: "base_link" + cost_threshold: 45 + use_radius_search_2d_filter: true + enable_debugger: false diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/schema/occupancy_grid_map_outlier_filter.schema.json b/perception/autoware_occupancy_grid_map_outlier_filter/schema/occupancy_grid_map_outlier_filter.schema.json new file mode 100644 index 0000000000000..d31f77bf27968 --- /dev/null +++ b/perception/autoware_occupancy_grid_map_outlier_filter/schema/occupancy_grid_map_outlier_filter.schema.json @@ -0,0 +1,86 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for occupancy_grid_map_outlier", + "type": "object", + "definitions": { + "occupancy_grid_map_outlier": { + "type": "object", + "properties": { + "radius_search_2d_filter.search_radius": { + "type": "number", + "default": 1.0, + "description": "Radius when calculating the density" + }, + "radius_search_2d_filter.min_points_and_distance_ratio": { + "type": "number", + "default": 400.0, + "description": "Threshold value of the number of point clouds per radius when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink" + }, + "radius_search_2d_filter.min_points": { + "type": "number", + "default": 4, + "description": "Minimum number of point clouds per radius" + }, + "radius_search_2d_filter.max_points": { + "type": "number", + "default": 70, + "description": "Maximum number of point clouds per radius" + }, + "radius_search_2d_filter.max_filter_points_nb": { + "type": "number", + "default": 15000, + "description": "Maximum number of point clouds to be filtered" + }, + "map_frame": { + "type": "string", + "default": "map", + "description": "map frame id" + }, + "base_link_frame": { + "type": "string", + "default": "base_link", + "description": "base link frame id" + }, + "cost_threshold": { + "type": "number", + "default": 45, + "description": "Cost threshold of occupancy grid map (0~100). 100 means 100% probability that there is an obstacle, close to 50 means that it is indistinguishable whether it is an obstacle or free space, 0 means that there is no obstacle" + }, + "use_radius_search_2d_filter": { + "type": "boolean", + "default": true, + "description": "Whether or not to apply density-based outlier filters to objects that are judged to have low probability of occupancy on the occupancy grid map" + }, + "enable_debugger": { + "type": "boolean", + "default": false, + "description": "Whether to output the point cloud for debugging" + } + }, + "required": [ + "radius_search_2d_filter.search_radius", + "radius_search_2d_filter.min_points_and_distance_ratio", + "radius_search_2d_filter.min_points", + "radius_search_2d_filter.max_points", + "radius_search_2d_filter.max_filter_points_nb", + "map_frame", + "base_link_frame", + "cost_threshold", + "use_radius_search_2d_filter", + "enable_debugger" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/occupancy_grid_map_outlier" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} 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 1536db8610b76..046598e445ba8 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 @@ -106,13 +106,13 @@ namespace autoware::occupancy_grid_map_outlier_filter { RadiusSearch2dFilter::RadiusSearch2dFilter(rclcpp::Node & node) { - search_radius_ = node.declare_parameter("radius_search_2d_filter.search_radius", 1.0f); + search_radius_ = node.declare_parameter("radius_search_2d_filter.search_radius"); min_points_and_distance_ratio_ = - node.declare_parameter("radius_search_2d_filter.min_points_and_distance_ratio", 400.0f); - min_points_ = node.declare_parameter("radius_search_2d_filter.min_points", 4); - max_points_ = node.declare_parameter("radius_search_2d_filter.max_points", 70); + node.declare_parameter("radius_search_2d_filter.min_points_and_distance_ratio"); + min_points_ = node.declare_parameter("radius_search_2d_filter.min_points"); + max_points_ = node.declare_parameter("radius_search_2d_filter.max_points"); max_filter_points_nb_ = - node.declare_parameter("radius_search_2d_filter.max_filter_points_nb", 15000); + node.declare_parameter("radius_search_2d_filter.max_filter_points_nb"); kd_tree_ = pcl::make_shared>(false); } @@ -235,11 +235,11 @@ OccupancyGridMapOutlierFilterComponent::OccupancyGridMapOutlierFilterComponent( } /* params */ - map_frame_ = declare_parameter("map_frame", "map"); - base_link_frame_ = declare_parameter("base_link_frame", "base_link"); - cost_threshold_ = declare_parameter("cost_threshold", 45); - auto use_radius_search_2d_filter = declare_parameter("use_radius_search_2d_filter", true); - auto enable_debugger = declare_parameter("enable_debugger", false); + map_frame_ = declare_parameter("map_frame"); + base_link_frame_ = declare_parameter("base_link_frame"); + cost_threshold_ = declare_parameter("cost_threshold"); + auto use_radius_search_2d_filter = declare_parameter("use_radius_search_2d_filter"); + auto enable_debugger = declare_parameter("enable_debugger"); /* tf */ tf2_ = std::make_shared(get_clock()); From 5347f93903c3b3b056c68411ea73b90cd4357fd3 Mon Sep 17 00:00:00 2001 From: Rein Appeldoorn Date: Mon, 2 Sep 2024 01:18:02 +0200 Subject: [PATCH 074/217] fix(ground-segmentation): missing ament_index_cpp dependency (#8587) Signed-off-by: Rein Appeldoorn --- perception/autoware_ground_segmentation/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/perception/autoware_ground_segmentation/package.xml b/perception/autoware_ground_segmentation/package.xml index 1a2f1d481a6c8..ff61a6b600f54 100644 --- a/perception/autoware_ground_segmentation/package.xml +++ b/perception/autoware_ground_segmentation/package.xml @@ -19,6 +19,7 @@ ament_cmake_auto autoware_cmake + ament_index_cpp autoware_pointcloud_preprocessor autoware_vehicle_info_utils libopencv-dev From 544b06eea2d6f9517f3ae8005146f557d3994a70 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 2 Sep 2024 09:40:27 +0900 Subject: [PATCH 075/217] feat(autoware_multi_object_tracker): reduce trigger latency (#8657) * feat: timer-based trigger with phase compensation Signed-off-by: Taekjin LEE * chore: update comments, name of variable Signed-off-by: Taekjin LEE * chore: declare min and max publish interval ratios Signed-off-by: Taekjin LEE * style(pre-commit): autofix --------- Signed-off-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/multi_object_tracker_node.cpp | 30 +++++++++++++------ .../src/multi_object_tracker_node.hpp | 4 +++ 2 files changed, 25 insertions(+), 9 deletions(-) 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 4b3240d81e68f..ce7f8157a31b6 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 @@ -73,7 +73,8 @@ 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_published_time_(this->now()), + last_updated_time_(this->now()) { // glog for debug if (!google::IsGoogleLoggingInitialized()) { @@ -153,7 +154,9 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) // If the delay compensation is enabled, the timer is used to publish the output at the correct // time. if (enable_delay_compensation) { - const auto timer_period = rclcpp::Rate(publish_rate).period(); + publisher_period_ = 1.0 / publish_rate; // [s] + constexpr double timer_multiplier = 10.0; // 10 times frequent for publish timing check + const auto timer_period = rclcpp::Rate(publish_rate * timer_multiplier).period(); publish_timer_ = rclcpp::create_timer( this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this)); } @@ -221,21 +224,30 @@ void MultiObjectTracker::onTimer() { const rclcpp::Time current_time = this->now(); - // get objects from the input manager and run process - ObjectsList objects_list; - const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list); - if (is_objects_ready) { - onMessage(objects_list); + // ensure minimum interval: room for the next process(prediction) + const double minimum_publish_interval = publisher_period_ * minimum_publish_interval_ratio; + const auto elapsed_time = (current_time - last_published_time_).seconds(); + if (elapsed_time < minimum_publish_interval) { + return; } - // Publish with delay compensation - checkAndPublish(current_time); + // if there was update after publishing, publish new messages + bool should_publish = last_published_time_ < last_updated_time_; + + // if there was no update, publish if the elapsed time is longer than the maximum publish latency + // in this case, it will perform extrapolate/remove old objects + const double maximum_publish_interval = publisher_period_ * maximum_publish_interval_ratio; + should_publish = should_publish || elapsed_time > maximum_publish_interval; + + // Publish with delay compensation to the current time + if (should_publish) checkAndPublish(current_time); } void MultiObjectTracker::onMessage(const ObjectsList & objects_list) { const rclcpp::Time current_time = this->now(); const rclcpp::Time oldest_time(objects_list.front().second.header.stamp); + last_updated_time_ = current_time; // process start debugger_->startMeasurementTime(this->now(), oldest_time); 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 e917acbda9fcc..3c23e3f066488 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 @@ -78,6 +78,10 @@ class MultiObjectTracker : public rclcpp::Node // publish timer rclcpp::TimerBase::SharedPtr publish_timer_; rclcpp::Time last_published_time_; + rclcpp::Time last_updated_time_; + double publisher_period_; + static constexpr double minimum_publish_interval_ratio = 0.85; + static constexpr double maximum_publish_interval_ratio = 1.05; // internal states std::string world_frame_id_; // tracking frame From 0a364d21ccbde7a68d7e5cf6bf8090dc660295c2 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 2 Sep 2024 11:05:32 +0900 Subject: [PATCH 076/217] fix(out_of_lane): fix a bug with the rtree reference deleted nodes (#8679) Signed-off-by: Maxime CLEMENT --- .../src/out_of_lane_collisions.cpp | 16 +++++++--------- .../src/out_of_lane_collisions.hpp | 8 +++++--- .../src/out_of_lane_module.cpp | 14 ++++++++++++-- 3 files changed, 24 insertions(+), 14 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp index c375bcc35c1ee..aef035200b6cc 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp @@ -129,28 +129,27 @@ void calculate_collisions_to_avoid( } } -OutOfLaneData calculate_outside_points(const EgoData & ego_data) +std::vector calculate_out_of_lane_points(const EgoData & ego_data) { - OutOfLaneData out_of_lane_data; - out_of_lane::OutOfLanePoint p; + std::vector out_of_lane_points; + OutOfLanePoint p; for (auto i = 0UL; i < ego_data.trajectory_footprints.size(); ++i) { p.trajectory_index = i + ego_data.first_trajectory_idx; const auto & footprint = ego_data.trajectory_footprints[i]; - out_of_lane::Polygons out_of_lane_polygons; + Polygons out_of_lane_polygons; boost::geometry::difference(footprint, ego_data.drivable_lane_polygons, out_of_lane_polygons); for (const auto & area : out_of_lane_polygons) { if (!area.outer.empty()) { p.outside_ring = area.outer; - out_of_lane_data.outside_points.push_back(p); + out_of_lane_points.push_back(p); } } } - return out_of_lane_data; + return out_of_lane_points; } -OutOfLaneData calculate_out_of_lane_areas(const EgoData & ego_data) +void prepare_out_of_lane_areas_rtree(OutOfLaneData & out_of_lane_data) { - auto out_of_lane_data = calculate_outside_points(ego_data); std::vector rtree_nodes; for (auto i = 0UL; i < out_of_lane_data.outside_points.size(); ++i) { OutAreaNode n; @@ -160,7 +159,6 @@ OutOfLaneData calculate_out_of_lane_areas(const EgoData & ego_data) rtree_nodes.push_back(n); } out_of_lane_data.outside_areas_rtree = {rtree_nodes.begin(), rtree_nodes.end()}; - return out_of_lane_data; } } // namespace autoware::motion_velocity_planner::out_of_lane 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 b9048cc358a07..33f0842c56d36 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 @@ -47,9 +47,11 @@ void calculate_collisions_to_avoid( const std::vector & trajectory, const PlannerParam & params); -/// @brief calculate the areas where ego will drive outside of its lane -/// @details the OutOfLaneData points and rtree are filled -OutOfLaneData calculate_out_of_lane_areas(const EgoData & ego_data); +/// @brief calculate the out of lane points +std::vector calculate_out_of_lane_points(const EgoData & ego_data); + +/// @brief prepare the rtree of out of lane points for the given data +void prepare_out_of_lane_areas_rtree(OutOfLaneData & out_of_lane_data); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // OUT_OF_LANE_COLLISIONS_HPP_ 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 ca7ed3b9dc7bd..e51980d60dbba 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 @@ -25,6 +25,7 @@ #include #include #include +#include #include #include #include @@ -225,6 +226,16 @@ void prepare_stop_lines_rtree( ego_data.stop_lines_rtree = {rtree_nodes.begin(), rtree_nodes.end()}; } +out_of_lane::OutOfLaneData prepare_out_of_lane_data( + const out_of_lane::EgoData & ego_data, const route_handler::RouteHandler & route_handler) +{ + out_of_lane::OutOfLaneData out_of_lane_data; + out_of_lane_data.outside_points = out_of_lane::calculate_out_of_lane_points(ego_data); + out_of_lane::calculate_overlapped_lanelets(out_of_lane_data, route_handler); + out_of_lane::prepare_out_of_lane_areas_rtree(out_of_lane_data); + return out_of_lane_data; +} + VelocityPlanningResult OutOfLaneModule::plan( const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) @@ -253,8 +264,7 @@ VelocityPlanningResult OutOfLaneModule::plan( const auto calculate_lanelets_us = stopwatch.toc("calculate_lanelets"); stopwatch.tic("calculate_out_of_lane_areas"); - auto out_of_lane_data = calculate_out_of_lane_areas(ego_data); - out_of_lane::calculate_overlapped_lanelets(out_of_lane_data, *planner_data->route_handler); + auto out_of_lane_data = prepare_out_of_lane_data(ego_data, *planner_data->route_handler); const auto calculate_out_of_lane_areas_us = stopwatch.toc("calculate_out_of_lane_areas"); stopwatch.tic("filter_predicted_objects"); From 38c6e0e4074b51051d21ff4fc86095613bab01f1 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 2 Sep 2024 13:13:32 +0900 Subject: [PATCH 077/217] refactor(start_planner, lane_departure_checker): remove redundant calculation in fuseLaneletPolygon (#8682) * remove redundant fused lanelet calculation Signed-off-by: Go Sakayori * remove unnecessary change Signed-off-by: Go Sakayori * add new function Signed-off-by: Go Sakayori * fix spelling mistake Signed-off-by: Go Sakayori * fix spelling mistake Signed-off-by: Go Sakayori * use std::move and lambda funcion for better code Signed-off-by: Go Sakayori * add comment for better understanding Signed-off-by: Go Sakayori * fix cppcheck Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori --- .../lane_departure_checker.hpp | 13 ++ .../lane_departure_checker.cpp | 151 +++++++++++++----- .../src/shift_pull_out.cpp | 8 +- 3 files changed, 131 insertions(+), 41 deletions(-) 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 4bcc3f1b7baee..4c3c32eaa321a 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 @@ -132,9 +132,19 @@ class LaneDepartureChecker std::optional getFusedLaneletPolygonForPath( const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const; + bool updateFusedLaneletPolygonForPath( + const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, + std::vector & fused_lanelets_id, + std::optional & fused_lanelets_polygon) const; + bool checkPathWillLeaveLane( const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const; + bool checkPathWillLeaveLane( + const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, + std::vector & fused_lanelets_id, + std::optional & fused_lanelets_polygon) const; + PathWithLaneId cropPointsOutsideOfLanes( const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, const size_t end_index); @@ -177,6 +187,9 @@ class LaneDepartureChecker const std::vector & vehicle_footprints, const SegmentRtree & uncrossable_segments) const; + lanelet::BasicPolygon2d toBasicPolygon2D(const LinearRing2d & footprint_hull) const; + autoware::universe_utils::Polygon2d toPolygon2D(const lanelet::BasicPolygon2d & poly) const; + mutable std::shared_ptr time_keeper_; }; } // namespace autoware::lane_departure_checker diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp index fcb64607f6d46..ea678ec26941b 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp @@ -313,15 +313,8 @@ std::vector> LaneDepartureChecker::getLanele // Get Footprint Hull basic polygon std::vector vehicle_footprints = createVehicleFootprints(path); LinearRing2d footprint_hull = createHullFromFootprints(vehicle_footprints); - auto to_basic_polygon = [](const LinearRing2d & footprint_hull) -> lanelet::BasicPolygon2d { - lanelet::BasicPolygon2d basic_polygon; - for (const auto & point : footprint_hull) { - Eigen::Vector2d p(point.x(), point.y()); - basic_polygon.push_back(p); - } - return basic_polygon; - }; - lanelet::BasicPolygon2d footprint_hull_basic_polygon = to_basic_polygon(footprint_hull); + + lanelet::BasicPolygon2d footprint_hull_basic_polygon = toBasicPolygon2D(footprint_hull); // Find all lanelets that intersect the footprint hull return lanelet::geometry::findWithin2d( @@ -335,39 +328,63 @@ LaneDepartureChecker::getFusedLaneletPolygonForPath( universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto lanelets_distance_pair = getLaneletsFromPath(lanelet_map_ptr, path); - auto to_polygon2d = - [](const lanelet::BasicPolygon2d & poly) -> autoware::universe_utils::Polygon2d { - autoware::universe_utils::Polygon2d polygon; - auto & outer = polygon.outer(); - - for (const auto & p : poly) { - autoware::universe_utils::Point2d p2d(p.x(), p.y()); - outer.push_back(p2d); - } - boost::geometry::correct(polygon); - return polygon; - }; + if (lanelets_distance_pair.empty()) return std::nullopt; // Fuse lanelets into a single BasicPolygon2d - auto fused_lanelets = [&]() -> std::optional { - if (lanelets_distance_pair.empty()) return std::nullopt; - autoware::universe_utils::MultiPolygon2d lanelet_unions; - autoware::universe_utils::MultiPolygon2d result; - - for (size_t i = 0; i < lanelets_distance_pair.size(); ++i) { - const auto & route_lanelet = lanelets_distance_pair.at(i).second; - const auto & p = route_lanelet.polygon2d().basicPolygon(); - autoware::universe_utils::Polygon2d poly = to_polygon2d(p); - boost::geometry::union_(lanelet_unions, poly, result); - lanelet_unions = result; - result.clear(); - } + autoware::universe_utils::MultiPolygon2d lanelet_unions; + autoware::universe_utils::MultiPolygon2d result; + + for (size_t i = 0; i < lanelets_distance_pair.size(); ++i) { + const auto & route_lanelet = lanelets_distance_pair.at(i).second; + const auto & p = route_lanelet.polygon2d().basicPolygon(); + autoware::universe_utils::Polygon2d poly = toPolygon2D(p); + boost::geometry::union_(lanelet_unions, poly, result); + lanelet_unions = result; + result.clear(); + } + + if (lanelet_unions.empty()) return std::nullopt; + return lanelet_unions.front(); +} + +bool LaneDepartureChecker::updateFusedLaneletPolygonForPath( + const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, + std::vector & fused_lanelets_id, + std::optional & fused_lanelets_polygon) const +{ + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + + const auto lanelets_distance_pair = getLaneletsFromPath(lanelet_map_ptr, path); + if (lanelets_distance_pair.empty()) return false; + + autoware::universe_utils::MultiPolygon2d lanelet_unions; + autoware::universe_utils::MultiPolygon2d result; + + if (fused_lanelets_polygon) lanelet_unions.push_back(fused_lanelets_polygon.value()); + + for (size_t i = 0; i < lanelets_distance_pair.size(); ++i) { + const auto & route_lanelet = lanelets_distance_pair.at(i).second; + bool id_exist = std::any_of( + fused_lanelets_id.begin(), fused_lanelets_id.end(), + [&](const auto & id) { return id == route_lanelet.id(); }); - if (lanelet_unions.empty()) return std::nullopt; - return lanelet_unions.front(); - }(); + if (id_exist) continue; - return fused_lanelets; + const auto & p = route_lanelet.polygon2d().basicPolygon(); + autoware::universe_utils::Polygon2d poly = toPolygon2D(p); + boost::geometry::union_(lanelet_unions, poly, result); + lanelet_unions = result; + result.clear(); + fused_lanelets_id.push_back(route_lanelet.id()); + } + + if (lanelet_unions.empty()) { + fused_lanelets_polygon = std::nullopt; + return false; + } + + fused_lanelets_polygon = lanelet_unions.front(); + return true; } bool LaneDepartureChecker::checkPathWillLeaveLane( @@ -386,6 +403,37 @@ bool LaneDepartureChecker::checkPathWillLeaveLane( }); } +bool LaneDepartureChecker::checkPathWillLeaveLane( + const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, + std::vector & fused_lanelets_id, + std::optional & fused_lanelets_polygon) const +{ + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + + const std::vector vehicle_footprints = createVehicleFootprints(path); + + auto is_all_footprints_within = [&](const auto & polygon) { + return std::all_of( + vehicle_footprints.begin(), vehicle_footprints.end(), + [&polygon](const auto & footprint) { return boost::geometry::within(footprint, polygon); }); + }; + + // If lanelets polygon exists and all footprints are within it, the path doesn't leave the lane + if (fused_lanelets_polygon && is_all_footprints_within(fused_lanelets_polygon.value())) { + return false; + } + + // Update the lanelet polygon for the current path + if (!updateFusedLaneletPolygonForPath( + lanelet_map_ptr, path, fused_lanelets_id, fused_lanelets_polygon)) { + // If update fails, assume the path leaves the lane + return true; + } + + // Check if any footprint is outside the updated lanelets polygon + return !is_all_footprints_within(fused_lanelets_polygon.value()); +} + PathWithLaneId LaneDepartureChecker::cropPointsOutsideOfLanes( const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, const size_t end_index) { @@ -398,7 +446,7 @@ PathWithLaneId LaneDepartureChecker::cropPointsOutsideOfLanes( { universe_utils::ScopedTimeTrack st2( - "check if footprint is within fused_lanlets_polygon", *time_keeper_); + "check if footprint is within fused_lanelets_polygon", *time_keeper_); size_t idx = 0; std::for_each( @@ -484,4 +532,29 @@ bool LaneDepartureChecker::willCrossBoundary( return false; } +lanelet::BasicPolygon2d LaneDepartureChecker::toBasicPolygon2D( + const LinearRing2d & footprint_hull) const +{ + lanelet::BasicPolygon2d basic_polygon; + for (const auto & point : footprint_hull) { + Eigen::Vector2d p(point.x(), point.y()); + basic_polygon.push_back(p); + } + return basic_polygon; +} + +autoware::universe_utils::Polygon2d LaneDepartureChecker::toPolygon2D( + const lanelet::BasicPolygon2d & poly) const +{ + autoware::universe_utils::Polygon2d polygon; + auto & outer = polygon.outer(); + + for (const auto & p : poly) { + autoware::universe_utils::Point2d p2d(p.x(), p.y()); + outer.push_back(p2d); + } + boost::geometry::correct(polygon); + return polygon; +} + } // namespace autoware::lane_departure_checker 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 712b8c3ce265d..3f750a7f1a87b 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 @@ -63,6 +63,9 @@ std::optional ShiftPullOut::plan( 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; + // get safe path for (auto & pull_out_path : pull_out_paths) { universe_utils::ScopedTimeTrack st("get safe path", *time_keeper_); @@ -99,8 +102,9 @@ std::optional ShiftPullOut::plan( // computational cost. if ( - is_lane_departure_check_required && - lane_departure_checker_->checkPathWillLeaveLane(lanelet_map_ptr, path_shift_start_to_end)) { + is_lane_departure_check_required && lane_departure_checker_->checkPathWillLeaveLane( + lanelet_map_ptr, path_shift_start_to_end, + fused_id_start_to_end, fused_polygon_start_to_end)) { planner_debug_data.conditions_evaluation.emplace_back("lane departure"); continue; } From 482d0ffe58a7fb5f9f36a9b0c6887a740822322f Mon Sep 17 00:00:00 2001 From: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> Date: Mon, 2 Sep 2024 13:23:43 +0900 Subject: [PATCH 078/217] chore(autoware_gnss_poser): make source codes follow the coding rules (#8703) * Follow the coding rules in autoware_gnss_poser Signed-off-by: TaikiYamada4 * Edit _core to _node inside files Signed-off-by: TaikiYamada4 * Fixed AUTOWARE__GNSS_POSER__GNSS_POSER_NODE_HPP_ part Signed-off-by: TaikiYamada4 --------- Signed-off-by: TaikiYamada4 --- sensing/autoware_gnss_poser/CMakeLists.txt | 4 ++-- .../gnss_poser/{gnss_poser_core.hpp => gnss_poser_node.hpp} | 6 +++--- .../src/{gnss_poser_core.cpp => gnss_poser_node.cpp} | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) rename sensing/autoware_gnss_poser/include/autoware/gnss_poser/{gnss_poser_core.hpp => gnss_poser_node.hpp} (96%) rename sensing/autoware_gnss_poser/src/{gnss_poser_core.cpp => gnss_poser_node.cpp} (99%) diff --git a/sensing/autoware_gnss_poser/CMakeLists.txt b/sensing/autoware_gnss_poser/CMakeLists.txt index 6baf468e289f3..94317dd21a238 100644 --- a/sensing/autoware_gnss_poser/CMakeLists.txt +++ b/sensing/autoware_gnss_poser/CMakeLists.txt @@ -16,11 +16,11 @@ find_library(GeographicLib_LIBRARIES ) set(GNSS_POSER_HEADERS - include/autoware/gnss_poser/gnss_poser_core.hpp + include/autoware/gnss_poser/gnss_poser_node.hpp ) ament_auto_add_library(gnss_poser_node SHARED - src/gnss_poser_core.cpp + src/gnss_poser_node.cpp ${GNSS_POSER_HEADERS} ) diff --git a/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_core.hpp b/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.hpp similarity index 96% rename from sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_core.hpp rename to sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.hpp index 88a4a87fa636e..e551aedab8cf5 100644 --- a/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_core.hpp +++ b/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.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 AUTOWARE__GNSS_POSER__GNSS_POSER_CORE_HPP_ -#define AUTOWARE__GNSS_POSER__GNSS_POSER_CORE_HPP_ +#ifndef AUTOWARE__GNSS_POSER__GNSS_POSER_NODE_HPP_ +#define AUTOWARE__GNSS_POSER__GNSS_POSER_NODE_HPP_ #include #include @@ -103,4 +103,4 @@ class GNSSPoser : public rclcpp::Node }; } // namespace autoware::gnss_poser -#endif // AUTOWARE__GNSS_POSER__GNSS_POSER_CORE_HPP_ +#endif // AUTOWARE__GNSS_POSER__GNSS_POSER_NODE_HPP_ diff --git a/sensing/autoware_gnss_poser/src/gnss_poser_core.cpp b/sensing/autoware_gnss_poser/src/gnss_poser_node.cpp similarity index 99% rename from sensing/autoware_gnss_poser/src/gnss_poser_core.cpp rename to sensing/autoware_gnss_poser/src/gnss_poser_node.cpp index f4047af75dada..4a5ff71e3df58 100644 --- a/sensing/autoware_gnss_poser/src/gnss_poser_core.cpp +++ b/sensing/autoware_gnss_poser/src/gnss_poser_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/gnss_poser/gnss_poser_core.hpp" +#include "autoware/gnss_poser/gnss_poser_node.hpp" #include #include From d92b054c646734c70647375d754e0b96bb4d4c81 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Mon, 2 Sep 2024 15:46:37 +0900 Subject: [PATCH 079/217] refactor(ekf_localizer): add namespace "autoware::ekf_localizer::" (#8680) Added namespace "autoware::ekf_localizer::" Signed-off-by: Shintaro Sakoda --- localization/ekf_localizer/CMakeLists.txt | 2 +- .../include/ekf_localizer/aged_object_queue.hpp | 5 +++++ .../ekf_localizer/include/ekf_localizer/covariance.hpp | 5 +++++ .../ekf_localizer/include/ekf_localizer/diagnostics.hpp | 5 +++++ .../ekf_localizer/include/ekf_localizer/ekf_localizer.hpp | 6 ++++++ .../ekf_localizer/include/ekf_localizer/ekf_module.hpp | 4 ++++ .../include/ekf_localizer/hyper_parameters.hpp | 5 +++++ .../ekf_localizer/include/ekf_localizer/mahalanobis.hpp | 5 +++++ .../ekf_localizer/include/ekf_localizer/matrix_types.hpp | 5 +++++ .../ekf_localizer/include/ekf_localizer/measurement.hpp | 5 +++++ .../ekf_localizer/include/ekf_localizer/numeric.hpp | 5 +++++ .../ekf_localizer/include/ekf_localizer/state_index.hpp | 5 +++++ .../include/ekf_localizer/state_transition.hpp | 5 +++++ .../ekf_localizer/include/ekf_localizer/string.hpp | 5 +++++ .../ekf_localizer/include/ekf_localizer/warning.hpp | 5 +++++ .../include/ekf_localizer/warning_message.hpp | 5 +++++ localization/ekf_localizer/src/covariance.cpp | 5 +++++ localization/ekf_localizer/src/diagnostics.cpp | 5 +++++ localization/ekf_localizer/src/ekf_localizer.cpp | 7 ++++++- localization/ekf_localizer/src/ekf_module.cpp | 5 +++++ localization/ekf_localizer/src/mahalanobis.cpp | 5 +++++ localization/ekf_localizer/src/measurement.cpp | 5 +++++ localization/ekf_localizer/src/state_transition.cpp | 5 +++++ localization/ekf_localizer/src/warning_message.cpp | 5 +++++ localization/ekf_localizer/test/test_aged_object_queue.cpp | 5 +++++ localization/ekf_localizer/test/test_covariance.cpp | 5 +++++ localization/ekf_localizer/test/test_diagnostics.cpp | 5 +++++ localization/ekf_localizer/test/test_mahalanobis.cpp | 5 +++++ localization/ekf_localizer/test/test_measurement.cpp | 5 +++++ localization/ekf_localizer/test/test_numeric.cpp | 5 +++++ localization/ekf_localizer/test/test_state_transition.cpp | 5 +++++ localization/ekf_localizer/test/test_string.cpp | 5 +++++ localization/ekf_localizer/test/test_warning_message.cpp | 5 +++++ 33 files changed, 162 insertions(+), 2 deletions(-) diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt index 13e63ddf3c170..cf82d6f7798dc 100644 --- a/localization/ekf_localizer/CMakeLists.txt +++ b/localization/ekf_localizer/CMakeLists.txt @@ -25,7 +25,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "EKFLocalizer" + PLUGIN "autoware::ekf_localizer::EKFLocalizer" EXECUTABLE ${PROJECT_NAME}_node EXECUTOR SingleThreadedExecutor ) diff --git a/localization/ekf_localizer/include/ekf_localizer/aged_object_queue.hpp b/localization/ekf_localizer/include/ekf_localizer/aged_object_queue.hpp index 880ab82418e06..44834de01ddfc 100644 --- a/localization/ekf_localizer/include/ekf_localizer/aged_object_queue.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/aged_object_queue.hpp @@ -18,6 +18,9 @@ #include #include +namespace autoware::ekf_localizer +{ + template class AgedObjectQueue { @@ -63,4 +66,6 @@ class AgedObjectQueue std::queue ages_; }; +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__AGED_OBJECT_QUEUE_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/covariance.hpp b/localization/ekf_localizer/include/ekf_localizer/covariance.hpp index 713877c1307d2..460d38429d056 100644 --- a/localization/ekf_localizer/include/ekf_localizer/covariance.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/covariance.hpp @@ -17,7 +17,12 @@ #include "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 // EKF_LOCALIZER__COVARIANCE_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp b/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp index 8815a1758de01..c02cd6e2944d6 100644 --- a/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp @@ -20,6 +20,9 @@ #include #include +namespace autoware::ekf_localizer +{ + diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_activated); diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated( @@ -40,4 +43,6 @@ diagnostic_msgs::msg::DiagnosticStatus check_covariance_ellipse( diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( const std::vector & stat_array); +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__DIAGNOSTICS_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index d247c817874fb..d6feb17367b10 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -50,6 +50,9 @@ #include #include +namespace autoware::ekf_localizer +{ + class Simple1DFilter { public: @@ -242,4 +245,7 @@ class EKFLocalizer : public rclcpp::Node friend class EKFLocalizerTestSuite; // for test code }; + +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__EKF_LOCALIZER_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp index a127d2ae81433..5cf13dfb309b1 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp @@ -34,6 +34,8 @@ #include #include +namespace autoware::ekf_localizer +{ using autoware::kalman_filter::TimeDelayKalmanFilter; struct EKFDiagnosticInfo @@ -93,4 +95,6 @@ class EKFModule const HyperParameters params_; }; +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__EKF_MODULE_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp index 7c3c03c83b778..db1f59984adca 100644 --- a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp @@ -20,6 +20,9 @@ #include #include +namespace autoware::ekf_localizer +{ + class HyperParameters { public: @@ -102,4 +105,6 @@ class HyperParameters const double threshold_observable_velocity_mps; }; +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__HYPER_PARAMETERS_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/mahalanobis.hpp b/localization/ekf_localizer/include/ekf_localizer/mahalanobis.hpp index 1f0d75c5958d4..abb98b95d329e 100644 --- a/localization/ekf_localizer/include/ekf_localizer/mahalanobis.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/mahalanobis.hpp @@ -18,9 +18,14 @@ #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 // EKF_LOCALIZER__MAHALANOBIS_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/matrix_types.hpp b/localization/ekf_localizer/include/ekf_localizer/matrix_types.hpp index 732abd6c8e2e7..ccfa9f3679f94 100644 --- a/localization/ekf_localizer/include/ekf_localizer/matrix_types.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/matrix_types.hpp @@ -17,7 +17,12 @@ #include +namespace autoware::ekf_localizer +{ + using Vector6d = Eigen::Matrix; using Matrix6d = Eigen::Matrix; +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__MATRIX_TYPES_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/measurement.hpp b/localization/ekf_localizer/include/ekf_localizer/measurement.hpp index 396aaf7b9a1b4..f38d291d41c62 100644 --- a/localization/ekf_localizer/include/ekf_localizer/measurement.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/measurement.hpp @@ -17,6 +17,9 @@ #include +namespace autoware::ekf_localizer +{ + Eigen::Matrix pose_measurement_matrix(); Eigen::Matrix twist_measurement_matrix(); Eigen::Matrix3d pose_measurement_covariance( @@ -24,4 +27,6 @@ Eigen::Matrix3d pose_measurement_covariance( Eigen::Matrix2d twist_measurement_covariance( const std::array & covariance, const size_t smoothing_step); +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__MEASUREMENT_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/numeric.hpp b/localization/ekf_localizer/include/ekf_localizer/numeric.hpp index 358a2750bd3a8..d69c22263190f 100644 --- a/localization/ekf_localizer/include/ekf_localizer/numeric.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/numeric.hpp @@ -19,6 +19,9 @@ #include +namespace autoware::ekf_localizer +{ + inline bool has_inf(const Eigen::MatrixXd & v) { return v.array().isInf().any(); @@ -29,4 +32,6 @@ inline bool has_nan(const Eigen::MatrixXd & v) return v.array().isNaN().any(); } +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__NUMERIC_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/state_index.hpp b/localization/ekf_localizer/include/ekf_localizer/state_index.hpp index b2bfdb0bd9e2e..d09fa6e31a36c 100644 --- a/localization/ekf_localizer/include/ekf_localizer/state_index.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/state_index.hpp @@ -15,6 +15,9 @@ #ifndef EKF_LOCALIZER__STATE_INDEX_HPP_ #define EKF_LOCALIZER__STATE_INDEX_HPP_ +namespace autoware::ekf_localizer +{ + enum IDX { X = 0, Y = 1, @@ -24,4 +27,6 @@ enum IDX { WZ = 5, }; +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__STATE_INDEX_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/state_transition.hpp b/localization/ekf_localizer/include/ekf_localizer/state_transition.hpp index 09a87e5fe154b..22f38924ab31e 100644 --- a/localization/ekf_localizer/include/ekf_localizer/state_transition.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/state_transition.hpp @@ -17,10 +17,15 @@ #include "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 // EKF_LOCALIZER__STATE_TRANSITION_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/string.hpp b/localization/ekf_localizer/include/ekf_localizer/string.hpp index 0154e84b88004..e4ac56b55b791 100644 --- a/localization/ekf_localizer/include/ekf_localizer/string.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/string.hpp @@ -17,6 +17,9 @@ #include +namespace autoware::ekf_localizer +{ + inline std::string erase_leading_slash(const std::string & s) { std::string a = s; @@ -26,4 +29,6 @@ inline std::string erase_leading_slash(const std::string & s) return a; } +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__STRING_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/warning.hpp b/localization/ekf_localizer/include/ekf_localizer/warning.hpp index e7456d73ecfdd..4ec57d3541a42 100644 --- a/localization/ekf_localizer/include/ekf_localizer/warning.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/warning.hpp @@ -19,6 +19,9 @@ #include +namespace autoware::ekf_localizer +{ + class Warning { public: @@ -40,4 +43,6 @@ class Warning rclcpp::Node * node_; }; +} // namespace autoware::ekf_localizer + #endif // EKF_LOCALIZER__WARNING_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp b/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp index 36c0eabd588fa..579e845cc1c5e 100644 --- a/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp @@ -17,6 +17,9 @@ #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( @@ -25,4 +28,6 @@ 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 // EKF_LOCALIZER__WARNING_MESSAGE_HPP_ diff --git a/localization/ekf_localizer/src/covariance.cpp b/localization/ekf_localizer/src/covariance.cpp index 4655ea8a89855..14bc57b869be6 100644 --- a/localization/ekf_localizer/src/covariance.cpp +++ b/localization/ekf_localizer/src/covariance.cpp @@ -17,6 +17,9 @@ #include "autoware/universe_utils/ros/msg_covariance.hpp" #include "ekf_localizer/state_index.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) @@ -49,3 +52,5 @@ std::array ekf_covariance_to_twist_message_covariance(const Matrix6d return covariance; } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/src/diagnostics.cpp b/localization/ekf_localizer/src/diagnostics.cpp index 902efeafacdb3..7e6b2b83f3025 100644 --- a/localization/ekf_localizer/src/diagnostics.cpp +++ b/localization/ekf_localizer/src/diagnostics.cpp @@ -19,6 +19,9 @@ #include #include +namespace autoware::ekf_localizer +{ + diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_activated) { diagnostic_msgs::msg::DiagnosticStatus stat; @@ -200,3 +203,5 @@ diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( return merged_stat; } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index e77a1156bf049..3362ce3a0c01e 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -34,6 +34,9 @@ #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 @@ -495,5 +498,7 @@ void EKFLocalizer::service_trigger_node( res->success = true; } +} // namespace autoware::ekf_localizer + #include -RCLCPP_COMPONENTS_REGISTER_NODE(EKFLocalizer) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::ekf_localizer::EKFLocalizer) diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp index 5c804afdc8cda..d2c29c458572e 100644 --- a/localization/ekf_localizer/src/ekf_module.cpp +++ b/localization/ekf_localizer/src/ekf_module.cpp @@ -29,6 +29,9 @@ #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 @@ -392,3 +395,5 @@ bool EKFModule::measurement_update_twist( return true; } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/src/mahalanobis.cpp b/localization/ekf_localizer/src/mahalanobis.cpp index a71482ab696f6..be3bcb982f7b9 100644 --- a/localization/ekf_localizer/src/mahalanobis.cpp +++ b/localization/ekf_localizer/src/mahalanobis.cpp @@ -14,6 +14,9 @@ #include "ekf_localizer/mahalanobis.hpp" +namespace autoware::ekf_localizer +{ + double squared_mahalanobis( const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C) { @@ -25,3 +28,5 @@ double mahalanobis(const Eigen::VectorXd & x, const Eigen::VectorXd & y, const E { return std::sqrt(squared_mahalanobis(x, y, C)); } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/src/measurement.cpp b/localization/ekf_localizer/src/measurement.cpp index faf8768938b7d..9d6f4f7d5a4db 100644 --- a/localization/ekf_localizer/src/measurement.cpp +++ b/localization/ekf_localizer/src/measurement.cpp @@ -17,6 +17,9 @@ #include "autoware/universe_utils/ros/msg_covariance.hpp" #include "ekf_localizer/state_index.hpp" +namespace autoware::ekf_localizer +{ + Eigen::Matrix pose_measurement_matrix() { Eigen::Matrix c = Eigen::Matrix::Zero(); @@ -54,3 +57,5 @@ Eigen::Matrix2d twist_measurement_covariance( covariance.at(COV_IDX::YAW_YAW); return r * static_cast(smoothing_step); } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/src/state_transition.cpp b/localization/ekf_localizer/src/state_transition.cpp index 22b1f2f8a1c67..e46fbd11c6629 100644 --- a/localization/ekf_localizer/src/state_transition.cpp +++ b/localization/ekf_localizer/src/state_transition.cpp @@ -17,6 +17,9 @@ #include +namespace autoware::ekf_localizer +{ + double normalize_yaw(const double & yaw) { // FIXME(IshitaTakeshi) I think the computation here can be simplified @@ -93,3 +96,5 @@ Matrix6d process_noise_covariance( q(IDX::WZ, IDX::WZ) = proc_cov_wz_d; // for wz return q; } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/src/warning_message.cpp b/localization/ekf_localizer/src/warning_message.cpp index ae74c6bfb5fbc..0d92f1456ba54 100644 --- a/localization/ekf_localizer/src/warning_message.cpp +++ b/localization/ekf_localizer/src/warning_message.cpp @@ -18,6 +18,9 @@ #include +namespace autoware::ekf_localizer +{ + std::string pose_delay_step_warning_message( const double delay_time, const double delay_time_threshold) { @@ -53,3 +56,5 @@ std::string mahalanobis_warning_message(const double distance, const double max_ 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/ekf_localizer/test/test_aged_object_queue.cpp b/localization/ekf_localizer/test/test_aged_object_queue.cpp index 9be834bf0612e..f0035fb111e0f 100644 --- a/localization/ekf_localizer/test/test_aged_object_queue.cpp +++ b/localization/ekf_localizer/test/test_aged_object_queue.cpp @@ -16,6 +16,9 @@ #include +namespace autoware::ekf_localizer +{ + TEST(AgedObjectQueue, DiscardsObjectWhenAgeReachesMaximum) { AgedObjectQueue queue(3); @@ -99,3 +102,5 @@ TEST(AgedObjectQueue, Back) EXPECT_EQ(queue.back(), std::string{"b"}); } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/test/test_covariance.cpp b/localization/ekf_localizer/test/test_covariance.cpp index ed87ebdea029b..a382bcc82e851 100644 --- a/localization/ekf_localizer/test/test_covariance.cpp +++ b/localization/ekf_localizer/test/test_covariance.cpp @@ -16,6 +16,9 @@ #include +namespace autoware::ekf_localizer +{ + TEST(EKFCovarianceToPoseMessageCovariance, SmokeTest) { { @@ -77,3 +80,5 @@ TEST(EKFCovarianceToTwistMessageCovariance, SmokeTest) } } } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/test/test_diagnostics.cpp b/localization/ekf_localizer/test/test_diagnostics.cpp index ef0d7a6493756..bdde47b9c79f6 100644 --- a/localization/ekf_localizer/test/test_diagnostics.cpp +++ b/localization/ekf_localizer/test/test_diagnostics.cpp @@ -16,6 +16,9 @@ #include +namespace autoware::ekf_localizer +{ + TEST(TestEkfDiagnostics, check_process_activated) { diagnostic_msgs::msg::DiagnosticStatus stat; @@ -190,3 +193,5 @@ TEST(TestLocalizationErrorMonitorDiagnostics, merge_diagnostic_status) 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/ekf_localizer/test/test_mahalanobis.cpp b/localization/ekf_localizer/test/test_mahalanobis.cpp index db7d538b533c3..894af29f61e96 100644 --- a/localization/ekf_localizer/test/test_mahalanobis.cpp +++ b/localization/ekf_localizer/test/test_mahalanobis.cpp @@ -16,6 +16,9 @@ #include +namespace autoware::ekf_localizer +{ + constexpr double tolerance = 1e-8; TEST(squared_mahalanobis, SmokeTest) @@ -59,3 +62,5 @@ TEST(mahalanobis, SmokeTest) EXPECT_NEAR(mahalanobis(x, y, c), std::sqrt(5.0), tolerance); } } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/test/test_measurement.cpp b/localization/ekf_localizer/test/test_measurement.cpp index c77e39a67d15c..ec4be9f121450 100644 --- a/localization/ekf_localizer/test/test_measurement.cpp +++ b/localization/ekf_localizer/test/test_measurement.cpp @@ -16,6 +16,9 @@ #include +namespace autoware::ekf_localizer +{ + TEST(Measurement, pose_measurement_matrix) { const Eigen::Matrix m = pose_measurement_matrix(); @@ -79,3 +82,5 @@ TEST(Measurement, twist_measurement_covariance) EXPECT_EQ(m.norm(), 0); } } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/test/test_numeric.cpp b/localization/ekf_localizer/test/test_numeric.cpp index f84c9aa1d0bf2..c68aaffc4b6c7 100644 --- a/localization/ekf_localizer/test/test_numeric.cpp +++ b/localization/ekf_localizer/test/test_numeric.cpp @@ -18,6 +18,9 @@ #include +namespace autoware::ekf_localizer +{ + TEST(Numeric, has_nan) { const Eigen::VectorXd empty(0); @@ -45,3 +48,5 @@ TEST(Numeric, has_inf) EXPECT_TRUE(has_inf(Eigen::Vector3d(0., 1., inf))); } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/test/test_state_transition.cpp b/localization/ekf_localizer/test/test_state_transition.cpp index 3b6bd93fd3dd8..533075e4ac8f4 100644 --- a/localization/ekf_localizer/test/test_state_transition.cpp +++ b/localization/ekf_localizer/test/test_state_transition.cpp @@ -20,6 +20,9 @@ #include +namespace autoware::ekf_localizer +{ + TEST(StateTransition, normalize_yaw) { const double tolerance = 1e-6; @@ -94,3 +97,5 @@ TEST(process_noise_covariance, process_noise_covariance) // Make sure other elements are zero EXPECT_EQ(process_noise_covariance(0, 0, 0).norm(), 0.); } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/test/test_string.cpp b/localization/ekf_localizer/test/test_string.cpp index 013072e5145c7..6bd38db1f3c21 100644 --- a/localization/ekf_localizer/test/test_string.cpp +++ b/localization/ekf_localizer/test/test_string.cpp @@ -16,6 +16,9 @@ #include +namespace autoware::ekf_localizer +{ + TEST(erase_leading_slash, SmokeTest) { EXPECT_EQ(erase_leading_slash("/topic"), "topic"); @@ -24,3 +27,5 @@ TEST(erase_leading_slash, SmokeTest) EXPECT_EQ(erase_leading_slash(""), ""); EXPECT_EQ(erase_leading_slash("/"), ""); } + +} // namespace autoware::ekf_localizer diff --git a/localization/ekf_localizer/test/test_warning_message.cpp b/localization/ekf_localizer/test/test_warning_message.cpp index ec7d3420d7f79..2fffecf63fa1b 100644 --- a/localization/ekf_localizer/test/test_warning_message.cpp +++ b/localization/ekf_localizer/test/test_warning_message.cpp @@ -18,6 +18,9 @@ #include +namespace autoware::ekf_localizer +{ + TEST(pose_delay_step_warning_message, SmokeTest) { EXPECT_STREQ( @@ -60,3 +63,5 @@ TEST(mahalanobis_warning_message, SmokeTest) mahalanobis_warning_message(1.0, 0.5).c_str(), "The Mahalanobis distance 1.0000 is over the limit 0.5000."); } + +} // namespace autoware::ekf_localizer From 978ab43a74df660a6ad4022d997a27ae3878d7e3 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 2 Sep 2024 16:40:31 +0900 Subject: [PATCH 080/217] fix(time_utils): fix unusedFunction (#8606) fix:unusedFunction Signed-off-by: kobayu858 --- .../include/time_utils/time_utils.hpp | 16 ---- .../time_utils/src/time_utils/time_utils.cpp | 73 ------------------- 2 files changed, 89 deletions(-) diff --git a/common/time_utils/include/time_utils/time_utils.hpp b/common/time_utils/include/time_utils/time_utils.hpp index e69fcd1009db1..cb369b4874872 100644 --- a/common/time_utils/include/time_utils/time_utils.hpp +++ b/common/time_utils/include/time_utils/time_utils.hpp @@ -24,25 +24,9 @@ namespace time_utils { -/// Convert from std::chrono::time_point to time message -TIME_UTILS_PUBLIC builtin_interfaces::msg::Time to_message(std::chrono::system_clock::time_point t); -/// Convert from std::chrono::duration to duration message -TIME_UTILS_PUBLIC builtin_interfaces::msg::Duration to_message(std::chrono::nanoseconds dt); -/// Convert from std::chrono::time_point from time message -TIME_UTILS_PUBLIC -std::chrono::system_clock::time_point from_message(builtin_interfaces::msg::Time t) noexcept; -/// Convert from std::chrono::duration from duration message -TIME_UTILS_PUBLIC -std::chrono::nanoseconds from_message(builtin_interfaces::msg::Duration dt) noexcept; /// Standard interpolation TIME_UTILS_PUBLIC std::chrono::nanoseconds interpolate( std::chrono::nanoseconds a, std::chrono::nanoseconds b, float t) noexcept; - -namespace details -{ -template -TimeT duration_to_msg(std::chrono::nanoseconds dt); -} // namespace details } // namespace time_utils #endif // TIME_UTILS__TIME_UTILS_HPP_ diff --git a/common/time_utils/src/time_utils/time_utils.cpp b/common/time_utils/src/time_utils/time_utils.cpp index c8e394b98ece0..fa1516c4bfef0 100644 --- a/common/time_utils/src/time_utils/time_utils.cpp +++ b/common/time_utils/src/time_utils/time_utils.cpp @@ -19,79 +19,6 @@ namespace time_utils { -namespace details -{ -template -TimeT duration_to_msg(std::chrono::nanoseconds dt) -{ - // Round down seconds - const auto negative = decltype(dt)::zero() > dt; - if (negative) { - dt -= std::chrono::seconds(1); - } - // rounds towards zero - const auto dt_sec = std::chrono::duration_cast(dt); - TimeT ret{rosidl_runtime_cpp::MessageInitialization::ALL}; - // Clamp value to receptive field of retval seconds - { - using SecT = decltype(ret.sec); - using Rep = decltype(dt_sec)::rep; - const auto sec_max = static_cast(std::numeric_limits::max()); - const auto sec_min = static_cast(std::numeric_limits::min()); - const auto secs = std::min(std::max(sec_min, dt_sec.count()), sec_max); - ret.sec = static_cast(secs); - } - // Get raw nanoseconds - const auto dt_nsec = std::chrono::duration_cast(dt); - auto nanosec = dt_nsec - std::chrono::duration_cast(dt_sec); - if (negative) { - nanosec += std::chrono::seconds(1); - if (0 > nanosec.count()) { - throw std::logic_error{"Bug: Nanosec should never be negative"}; - } - } - // Clamp down to receptive field of retval nanoseconds - { - using NsecT = decltype(ret.nanosec); - using Rep = decltype(nanosec)::rep; - const auto nsec_max = static_cast(std::numeric_limits::max()); - const auto nsec_min = static_cast(std::numeric_limits::min()); - const auto nanosec_clamp = std::min(std::max(nsec_min, nanosec.count()), nsec_max); - ret.nanosec = static_cast(nanosec_clamp); - } - return ret; -} -} // namespace details - -//////////////////////////////////////////////////////////////////////////////// -builtin_interfaces::msg::Time to_message(const std::chrono::system_clock::time_point t) -{ - const auto dt = t.time_since_epoch(); - return details::duration_to_msg(dt); -} - -//////////////////////////////////////////////////////////////////////////////// -builtin_interfaces::msg::Duration to_message(std::chrono::nanoseconds dt) -{ - return details::duration_to_msg(dt); -} - -//////////////////////////////////////////////////////////////////////////////// -std::chrono::system_clock::time_point from_message(builtin_interfaces::msg::Time t) noexcept -{ - const auto dt_ns = std::chrono::seconds(t.sec) + std::chrono::nanoseconds(t.nanosec); - const auto dt = std::chrono::duration_cast(dt_ns); - return std::chrono::system_clock::time_point{} + dt; -} - -//////////////////////////////////////////////////////////////////////////////// -std::chrono::nanoseconds from_message(builtin_interfaces::msg::Duration dt) noexcept -{ - const auto ns = std::chrono::nanoseconds{dt.nanosec}; - const auto us = std::chrono::duration_cast(ns); - return std::chrono::seconds{dt.sec} + us; -} - //////////////////////////////////////////////////////////////////////////////// std::chrono::nanoseconds interpolate( std::chrono::nanoseconds a, std::chrono::nanoseconds b, float t) noexcept From 980890f531781c2c40c9f9a3bb1e7adb7b6339c7 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 2 Sep 2024 16:55:00 +0900 Subject: [PATCH 081/217] feat(autonomous_emergency_braking): add timekeeper to AEB (#8706) * add timekeeper to AEB Signed-off-by: Daniel Sanchez * add more info to output Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../autonomous_emergency_braking/node.hpp | 7 ++- .../src/node.cpp | 54 +++++++++++++------ 2 files changed, 45 insertions(+), 16 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp index c29247a978c73..3f9a793acb200 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp @@ -15,6 +15,8 @@ #ifndef AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ #define AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ +#include "autoware/universe_utils/system/time_keeper.hpp" + #include #include #include @@ -334,9 +336,11 @@ class AEB : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_obstacle_pointcloud_; rclcpp::Publisher::SharedPtr debug_marker_publisher_; rclcpp::Publisher::SharedPtr info_marker_publisher_; - + rclcpp::Publisher::SharedPtr + debug_processing_time_detail_pub_; // timer rclcpp::TimerBase::SharedPtr timer_; + mutable std::shared_ptr time_keeper_{nullptr}; // callback /** @@ -508,6 +512,7 @@ class AEB : public rclcpp::Node // Member variables bool publish_debug_pointcloud_; bool publish_debug_markers_; + bool publish_debug_time_; bool use_predicted_trajectory_; bool use_imu_path_; bool use_pointcloud_data_; diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index e8744d85dc11a..49bf307db0f23 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -181,6 +181,12 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) const double aeb_hz = declare_parameter("aeb_hz"); const auto period_ns = rclcpp::Rate(aeb_hz).period(); timer_ = rclcpp::create_timer(this, this->get_clock(), period_ns, std::bind(&AEB::onTimer, this)); + + debug_processing_time_detail_pub_ = + create_publisher( + "~/debug/processing_time_detail_ms", 1); + time_keeper_ = + std::make_shared(debug_processing_time_detail_pub_); } rcl_interfaces::msg::SetParametersResult AEB::onParameter( @@ -259,6 +265,7 @@ void AEB::onImu(const Imu::ConstSharedPtr input_msg) void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); PointCloud::Ptr pointcloud_ptr(new PointCloud); pcl::fromROSMsg(*input_msg, *pointcloud_ptr); @@ -401,7 +408,6 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) addCollisionMarker(data.value(), debug_markers); } } - addVirtualStopWallMarker(info_markers); } else { const std::string error_msg = "[AEB]: No Collision"; @@ -416,6 +422,7 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) bool AEB::checkCollision(MarkerArray & debug_markers) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); using colorTuple = std::tuple; // step1. check data @@ -495,6 +502,7 @@ bool AEB::checkCollision(MarkerArray & debug_markers) }; // step3. make function to check collision with ego path created with sensor data + time_keeper_->start_track("has_collision_imu_path"); const auto has_collision_ego = [&](pcl::PointCloud::Ptr filtered_objects) -> bool { if (!use_imu_path_ || !angular_velocity_ptr_) return false; const double current_w = angular_velocity_ptr_->z; @@ -504,8 +512,10 @@ bool AEB::checkCollision(MarkerArray & debug_markers) return check_collision(ego_path, debug_color, ns, filtered_objects); }; + time_keeper_->end_track("has_collision_imu_path"); // step4. make function to check collision with predicted trajectory from control module + time_keeper_->start_track("has_collision_mpc_path"); const auto has_collision_predicted = [&](pcl::PointCloud::Ptr filtered_objects) -> bool { if (!use_predicted_trajectory_ || !predicted_traj_ptr_) return false; @@ -519,6 +529,7 @@ bool AEB::checkCollision(MarkerArray & debug_markers) return check_collision(predicted_path, debug_color, ns, filtered_objects); }; + time_keeper_->end_track("has_collision_mpc_path"); // Data of filtered point cloud pcl::PointCloud::Ptr filtered_objects = @@ -538,10 +549,10 @@ bool AEB::checkCollision(MarkerArray & debug_markers) bool AEB::hasCollision(const double current_v, const ObjectData & closest_object) { - const double & obj_v = closest_object.velocity; - const double & t = t_response_; - + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const double rss_dist = std::invoke([&]() { + const double & obj_v = closest_object.velocity; + const double & t = t_response_; const double pre_braking_covered_distance = std::abs(current_v) * t; const double braking_distance = (current_v * current_v) / (2 * std::fabs(a_ego_min_)); const double ego_stopping_distance = pre_braking_covered_distance + braking_distance; @@ -551,19 +562,19 @@ bool AEB::hasCollision(const double current_v, const ObjectData & closest_object return ego_stopping_distance + obj_braking_distance + longitudinal_offset_; }); - if (closest_object.distance_to_object < rss_dist) { - // collision happens - ObjectData collision_data = closest_object; - collision_data.rss = rss_dist; - collision_data.distance_to_object = closest_object.distance_to_object; - collision_data_keeper_.setCollisionData(collision_data); - return true; - } - return false; + if (closest_object.distance_to_object > rss_dist) return false; + + // collision happens + ObjectData collision_data = closest_object; + collision_data.rss = rss_dist; + collision_data.distance_to_object = closest_object.distance_to_object; + collision_data_keeper_.setCollisionData(collision_data); + return true; } Path AEB::generateEgoPath(const double curr_v, const double curr_w) { + autoware::universe_utils::ScopedTimeTrack st(std::string(__func__) + "(IMU)", *time_keeper_); Path path; double curr_x = 0.0; double curr_y = 0.0; @@ -612,21 +623,26 @@ Path AEB::generateEgoPath(const double curr_v, const double curr_w) std::optional AEB::generateEgoPath(const Trajectory & predicted_traj) { + autoware::universe_utils::ScopedTimeTrack st(std::string(__func__) + "(MPC)", *time_keeper_); if (predicted_traj.points.empty()) { return std::nullopt; } - + time_keeper_->start_track("lookUpTransform"); geometry_msgs::msg::TransformStamped transform_stamped{}; try { transform_stamped = tf_buffer_.lookupTransform( "base_link", predicted_traj.header.frame_id, predicted_traj.header.stamp, rclcpp::Duration::from_seconds(0.5)); } catch (tf2::TransformException & ex) { - RCLCPP_ERROR_STREAM(get_logger(), "[AEB] Failed to look up transform from base_link to map"); + RCLCPP_ERROR_STREAM( + get_logger(), + "[AEB] Failed to look up transform from base_link to " + predicted_traj.header.frame_id); return std::nullopt; } + time_keeper_->end_track("lookUpTransform"); // create path + time_keeper_->start_track("createPath"); Path path; path.reserve(predicted_traj.points.size()); for (size_t i = 0; i < predicted_traj.points.size(); ++i) { @@ -638,12 +654,14 @@ std::optional AEB::generateEgoPath(const Trajectory & predicted_traj) break; } } + time_keeper_->end_track("createPath"); return path; } std::vector AEB::generatePathFootprint( const Path & path, const double extra_width_margin) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); std::vector polygons; for (size_t i = 0; i < path.size() - 1; ++i) { polygons.push_back( @@ -656,6 +674,7 @@ void AEB::createObjectDataUsingPredictedObjects( const Path & ego_path, const std::vector & ego_polys, std::vector & object_data_vector) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (predicted_objects_ptr_->objects.empty()) return; const double current_ego_speed = current_velocity_ptr_->longitudinal_velocity; @@ -743,6 +762,7 @@ void AEB::createObjectDataUsingPointCloudClusters( const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, std::vector & objects, const pcl::PointCloud::Ptr obstacle_points_ptr) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // check if the predicted path has valid number of points if (ego_path.size() < 2 || ego_polys.empty() || obstacle_points_ptr->empty()) { return; @@ -827,6 +847,7 @@ void AEB::createObjectDataUsingPointCloudClusters( void AEB::cropPointCloudWithEgoFootprintPath( const std::vector & ego_polys, pcl::PointCloud::Ptr filtered_objects) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); PointCloud::Ptr full_points_ptr(new PointCloud); pcl::fromROSMsg(*obstacle_ros_pointcloud_ptr_, *full_points_ptr); // Create a Point cloud with the points of the ego footprint @@ -860,6 +881,7 @@ void AEB::addMarker( const double color_r, const double color_g, const double color_b, const double color_a, const std::string & ns, MarkerArray & debug_markers) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); auto path_marker = autoware::universe_utils::createDefaultMarker( "base_link", current_time, ns + "_path", 0L, Marker::LINE_STRIP, autoware::universe_utils::createMarkerScale(0.2, 0.2, 0.2), @@ -922,6 +944,7 @@ void AEB::addMarker( void AEB::addVirtualStopWallMarker(MarkerArray & markers) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto ego_map_pose = std::invoke([this]() -> std::optional { geometry_msgs::msg::TransformStamped tf_current_pose; geometry_msgs::msg::Pose p; @@ -952,6 +975,7 @@ void AEB::addVirtualStopWallMarker(MarkerArray & markers) void AEB::addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); auto point_marker = autoware::universe_utils::createDefaultMarker( "base_link", data.stamp, "collision_point", 0, Marker::SPHERE, autoware::universe_utils::createMarkerScale(0.3, 0.3, 0.3), From c53ecc64414048cf9896207e1a89b1916f03bc64 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 2 Sep 2024 17:35:56 +0900 Subject: [PATCH 082/217] fix(tier4_planning_rviz_plugin): fix unusedFunction (#8616) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/tools/jsk_overlay_utils.cpp | 5 ----- .../src/tools/jsk_overlay_utils.hpp | 1 - 2 files changed, 6 deletions(-) diff --git a/common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.cpp b/common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.cpp index f6eaf3ad883f1..e74f43b1f3319 100644 --- a/common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.cpp +++ b/common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.cpp @@ -62,11 +62,6 @@ 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(); diff --git a/common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.hpp b/common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.hpp index f2b6fbdce0b14..dda1d05c2a0b5 100644 --- a/common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.hpp +++ b/common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.hpp @@ -89,7 +89,6 @@ 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); From a4ed8eb16d756d32b800b837dc58e0e4f75136ca Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 2 Sep 2024 17:43:20 +0900 Subject: [PATCH 083/217] refactor(goal_planner): remove unnecessary member from pull_over_planner (#8697) Signed-off-by: Mamoru Sobue --- .../pull_over_planner/freespace_pull_over.hpp | 10 +++-- .../pull_over_planner/geometric_pull_over.hpp | 12 +++--- .../pull_over_planner_base.hpp | 29 +++++--------- .../pull_over_planner/shift_pull_over.hpp | 15 ++++--- .../src/goal_planner_module.cpp | 10 ++--- .../pull_over_planner/freespace_pull_over.cpp | 21 ++++++---- .../pull_over_planner/geometric_pull_over.cpp | 12 +++--- .../src/pull_over_planner/shift_pull_over.cpp | 40 +++++++++++-------- 8 files changed, 80 insertions(+), 69 deletions(-) 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 0b27b4adb737b..e3dccb3fc57ec 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,13 +41,15 @@ class FreespacePullOver : public PullOverPlannerBase PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::FREESPACE; } - std::optional plan(const Pose & goal_pose) override; + std::optional plan( + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output, const Pose & goal_pose) override; protected: + const double velocity_; + const bool left_side_parking_; + const bool use_back_; std::unique_ptr planner_; - double velocity_; - bool use_back_; - bool left_side_parking_; }; } // 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/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 6a2f0a57d67cf..2d7872707dd28 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 @@ -42,7 +42,9 @@ class GeometricPullOver : public PullOverPlannerBase Pose getCr() const { return planner_.getCr(); } Pose getCl() const { return planner_.getCl(); } - std::optional plan(const Pose & goal_pose) override; + std::optional plan( + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output, const Pose & goal_pose) override; std::vector generatePullOverPaths( const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, @@ -56,10 +58,10 @@ class GeometricPullOver : public PullOverPlannerBase const bool is_in_goal_route_section, const Pose & goal_pose) const; protected: - ParallelParkingParameters parallel_parking_parameters_; - LaneDepartureChecker lane_departure_checker_{}; - bool is_forward_{true}; - bool left_side_parking_{true}; + const ParallelParkingParameters parallel_parking_parameters_; + const LaneDepartureChecker lane_departure_checker_; + const bool is_forward_; + const bool left_side_parking_; GeometricParallelParking planner_; }; 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 7cdb249463e08..e9332041a8321 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 @@ -177,32 +177,21 @@ class PullOverPlannerBase { public: PullOverPlannerBase(rclcpp::Node & node, const GoalPlannerParameters & 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(); - parameters_ = parameters; } virtual ~PullOverPlannerBase() = default; - void setPreviousModuleOutput(const BehaviorModuleOutput & previous_module_output) - { - previous_module_output_ = previous_module_output; - } - - void setPlannerData(const std::shared_ptr planner_data) - { - planner_data_ = planner_data; - } - virtual PullOverPlannerType getPlannerType() const = 0; - virtual std::optional plan(const Pose & goal_pose) = 0; + virtual std::optional plan( + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output, const Pose & goal_pose) = 0; protected: - std::shared_ptr planner_data_; - autoware::vehicle_info_utils::VehicleInfo vehicle_info_; - LinearRing2d vehicle_footprint_; - GoalPlannerParameters parameters_; - - BehaviorModuleOutput previous_module_output_; + const autoware::vehicle_info_utils::VehicleInfo vehicle_info_; + const LinearRing2d vehicle_footprint_; + const GoalPlannerParameters parameters_; }; } // 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/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 8ebc3579a9272..c5640d9b4949f 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 @@ -35,16 +35,21 @@ class ShiftPullOver : public PullOverPlannerBase rclcpp::Node & node, const GoalPlannerParameters & parameters, const LaneDepartureChecker & lane_departure_checker); PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::SHIFT; }; - std::optional plan(const Pose & goal_pose) override; + std::optional plan( + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output, const Pose & goal_pose) override; protected: PathWithLaneId generateReferencePath( + const std::shared_ptr planner_data, const lanelet::ConstLanelets & road_lanes, const Pose & end_pose) const; std::optional cropPrevModulePath( const PathWithLaneId & prev_module_path, const Pose & shift_end_pose) const; std::optional generatePullOverPath( - const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, - const Pose & goal_pose, const double lateral_jerk) const; + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes, + const lanelet::ConstLanelets & shoulder_lanes, const Pose & goal_pose, + const double lateral_jerk) const; static double calcBeforeShiftedArcLength( const PathWithLaneId & path, const double after_shifted_arc_length, const double dr); static std::vector splineTwoPoints( @@ -53,9 +58,9 @@ class ShiftPullOver : public PullOverPlannerBase static std::vector interpolatePose( const Pose & start_pose, const Pose & end_pose, const double resample_interval); - LaneDepartureChecker lane_departure_checker_{}; + const LaneDepartureChecker lane_departure_checker_; - bool left_side_parking_{true}; + const bool left_side_parking_; }; } // 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 4d4d31446aa3f..674cfbb6f152e 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 @@ -306,9 +306,8 @@ void GoalPlannerModule::onTimer() const auto planCandidatePaths = [&]( const std::shared_ptr & planner, const GoalCandidate & goal_candidate) { - planner->setPlannerData(local_planner_data); - planner->setPreviousModuleOutput(previous_module_output); - auto pull_over_path = planner->plan(goal_candidate.goal_pose); + auto pull_over_path = + planner->plan(local_planner_data, previous_module_output, goal_candidate.goal_pose); if (pull_over_path && pull_over_path->getParkingPath().points.size() >= 3) { pull_over_path->goal_id = goal_candidate.id; pull_over_path->id = path_candidates.size(); @@ -754,8 +753,9 @@ bool GoalPlannerModule::planFreespacePath( if (!goal_candidate.is_safe) { continue; } - freespace_planner_->setPlannerData(planner_data); - auto freespace_path = freespace_planner_->plan(goal_candidate.goal_pose); + auto freespace_path = freespace_planner_->plan( + planner_data, BehaviorModuleOutput{}, // NOTE: not used so passing {} is OK + goal_candidate.goal_pose); freespace_path->goal_id = goal_candidate.id; if (!freespace_path) { continue; 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 a49cd7a279e7e..4b377aed46f7c 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 @@ -30,27 +30,32 @@ FreespacePullOver::FreespacePullOver( const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) : PullOverPlannerBase{node, parameters}, velocity_{parameters.freespace_parking_velocity}, - left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} + left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE}, + use_back_{ + parameters.freespace_parking_algorithm == "astar" + ? parameters.astar_parameters.use_back + : true // no option for disabling back in rrtstar + } { autoware::freespace_planning_algorithms::VehicleShape vehicle_shape( vehicle_info, parameters.vehicle_shape_margin); if (parameters.freespace_parking_algorithm == "astar") { - use_back_ = parameters.astar_parameters.use_back; planner_ = std::make_unique( parameters.freespace_parking_common_parameters, vehicle_shape, parameters.astar_parameters); } else if (parameters.freespace_parking_algorithm == "rrtstar") { - use_back_ = true; // no option for disabling back in rrtstar planner_ = std::make_unique( parameters.freespace_parking_common_parameters, vehicle_shape, parameters.rrt_star_parameters); } } -std::optional FreespacePullOver::plan(const Pose & goal_pose) +std::optional FreespacePullOver::plan( + const std::shared_ptr planner_data, + [[maybe_unused]] const BehaviorModuleOutput & previous_module_output, const Pose & goal_pose) { - const Pose & current_pose = planner_data_->self_odometry->pose.pose; + const Pose & current_pose = planner_data->self_odometry->pose.pose; - planner_->setMap(*planner_data_->costmap); + 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 @@ -68,10 +73,10 @@ std::optional FreespacePullOver::plan(const Pose & goal_pose) } const auto road_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + planner_data, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, /*forward_only_in_route*/ false); const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( - *(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length, + *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length); if (road_lanes.empty() || pull_over_lanes.empty()) { return {}; 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 c5df07c0e9176..eecdc11937463 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 @@ -37,13 +37,15 @@ GeometricPullOver::GeometricPullOver( planner_.setParameters(parallel_parking_parameters_); } -std::optional GeometricPullOver::plan(const Pose & goal_pose) +std::optional GeometricPullOver::plan( + const std::shared_ptr planner_data, + [[maybe_unused]] const BehaviorModuleOutput & previous_module_output, const Pose & goal_pose) { - const auto & route_handler = planner_data_->route_handler; + const auto & route_handler = planner_data->route_handler; // prepare road nad shoulder lanes const auto road_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + planner_data, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, /*forward_only_in_route*/ false); const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( *route_handler, left_side_parking_, parameters_.backward_goal_search_length, @@ -56,8 +58,8 @@ std::optional GeometricPullOver::plan(const Pose & goal_pose) const auto & p = parallel_parking_parameters_; const double max_steer_angle = is_forward_ ? p.forward_parking_max_steer_angle : p.backward_parking_max_steer_angle; - planner_.setTurningRadius(planner_data_->parameters, max_steer_angle); - planner_.setPlannerData(planner_data_); + planner_.setTurningRadius(planner_data->parameters, max_steer_angle); + planner_.setPlannerData(planner_data); const bool found_valid_path = planner_.planPullOver(goal_pose, road_lanes, pull_over_lanes, is_forward_, left_side_parking_); 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 1e4cb0e8d84f9..4536fc8873b40 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 @@ -34,9 +34,11 @@ ShiftPullOver::ShiftPullOver( left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { } -std::optional ShiftPullOver::plan(const Pose & goal_pose) +std::optional ShiftPullOver::plan( + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output, const Pose & goal_pose) { - const auto & route_handler = planner_data_->route_handler; + 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; @@ -45,7 +47,7 @@ std::optional ShiftPullOver::plan(const Pose & goal_pose) 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, + 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( @@ -56,8 +58,8 @@ std::optional ShiftPullOver::plan(const Pose & goal_pose) // 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(road_lanes, pull_over_lanes, goal_pose, lateral_jerk); + const auto pull_over_path = generatePullOverPath( + planner_data, previous_module_output, road_lanes, pull_over_lanes, goal_pose, lateral_jerk); if (!pull_over_path) continue; return *pull_over_path; } @@ -66,11 +68,12 @@ std::optional ShiftPullOver::plan(const Pose & goal_pose) } PathWithLaneId ShiftPullOver::generateReferencePath( - const lanelet::ConstLanelets & road_lanes, const Pose & end_pose) const + 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 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; @@ -123,8 +126,10 @@ std::optional ShiftPullOver::cropPrevModulePath( } std::optional ShiftPullOver::generatePullOverPath( - const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, - const Pose & goal_pose, const double lateral_jerk) const + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes, + const lanelet::ConstLanelets & shoulder_lanes, const Pose & goal_pose, + const double lateral_jerk) const { const double pull_over_velocity = parameters_.pull_over_velocity; const double after_shift_straight_distance = parameters_.after_shift_straight_distance; @@ -135,9 +140,10 @@ std::optional ShiftPullOver::generatePullOverPath( // 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(road_lanes, shift_end_pose), parameters_.center_line_path_interval); + 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); + 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 @@ -265,9 +271,9 @@ std::optional ShiftPullOver::generatePullOverPath( // 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 & p = planner_data->parameters; const auto parking_lot_polygons = - lanelet::utils::query::getAllParkingLots(planner_data_->route_handler->getLaneletMapPtr()); + lanelet::utils::query::getAllParkingLots(planner_data->route_handler->getLaneletMapPtr()); const auto path_footprints = goal_planner_utils::createPathFootPrints( pull_over_path.getParkingPath(), p.base_link2front, p.base_link2rear, p.vehicle_width); const auto is_footprint_in_any_polygon = [&parking_lot_polygons](const auto & footprint) { @@ -286,12 +292,12 @@ std::optional ShiftPullOver::generatePullOverPath( const bool is_in_lanes = std::invoke([&]() -> bool { const auto drivable_lanes = utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes); - const auto & dp = planner_data_->drivable_area_expansion_parameters; + 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); + expanded_lanes, previous_module_output.drivable_area_info.drivable_lanes); return !lane_departure_checker_.checkPathWillLeaveLane( utils::transformToLanelets(combined_drivable), pull_over_path.getParkingPath()); }); From 01b3c3767cc7c4f9a5412564573239dc25bd5048 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 2 Sep 2024 17:54:41 +0900 Subject: [PATCH 084/217] fix(tier4_perception_launch): launch namespace of `detection_by_tracker` (#8702) fix: namespace of detection_by_tracker do not need to have the prefix `autoware_` Signed-off-by: Taekjin LEE --- .../detection/detector/tracker_based_detector.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 681febf1c5551..754542f65b0ba 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 @@ -3,7 +3,7 @@ - + From 1e1d2fcb84fd9db2eddd50deba94b0330690a194 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 2 Sep 2024 18:53:24 +0900 Subject: [PATCH 085/217] refactor(goal_planner): remove unnecessary member from PreviousPullOverData (#8698) Signed-off-by: Mamoru Sobue --- .../behavior_path_goal_planner_module/goal_planner_module.hpp | 2 -- .../src/goal_planner_module.cpp | 1 - 2 files changed, 3 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 2dc4788be9ce2..b4e4abbb9272c 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 @@ -108,12 +108,10 @@ struct PreviousPullOverData void reset() { - found_path = false; safety_status = SafetyStatus{}; deciding_path_status = DecidingPathStatusWithStamp{}; } - bool found_path{false}; SafetyStatus safety_status{}; DecidingPathStatusWithStamp deciding_path_status{}; }; 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 674cfbb6f152e..ae7e1a4fcb6e8 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 @@ -1529,7 +1529,6 @@ void GoalPlannerModule::updatePreviousData() // this is used to determine whether to generate a new stop path or keep the current stop path. // TODO(Mamoru Sobue): put prev_data_ out of ThreadSafeData auto prev_data = thread_safe_data_.get_prev_data(); - prev_data.found_path = thread_safe_data_.foundPullOverPath(); prev_data.deciding_path_status = checkDecidingPathStatus( planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, From 564de2937ce123a321d95fe86949824a20ab132e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 2 Sep 2024 19:08:20 +0900 Subject: [PATCH 086/217] fix(bpp): use common steering factor interface for same scene modules (#8675) Signed-off-by: satoshi-ota --- .../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 | 3 ++- .../behavior_path_goal_planner_module/manager.hpp | 2 +- .../src/goal_planner_module.cpp | 5 +++-- .../behavior_path_lane_change_module/interface.hpp | 1 + .../src/interface.cpp | 4 ++-- .../src/manager.cpp | 2 +- .../interface/scene_module_interface.hpp | 8 ++++---- .../interface/scene_module_manager_interface.hpp | 8 ++++++++ .../behavior_path_sampling_planner_module/manager.hpp | 2 +- .../sampling_planner_module.hpp | 3 ++- .../src/sampling_planner_module.cpp | 5 +++-- .../autoware/behavior_path_side_shift_module/manager.hpp | 2 +- .../autoware/behavior_path_side_shift_module/scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- .../behavior_path_start_planner_module/manager.hpp | 2 +- .../start_planner_module.hpp | 3 ++- .../src/start_planner_module.cpp | 5 +++-- .../manager.hpp | 2 +- .../scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- 27 files changed, 60 insertions(+), 36 deletions(-) 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 4c9f139365a06..fffb86767b0a8 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 @@ -31,13 +31,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, + std::shared_ptr & steering_factor_interface_ptr) : LaneChangeInterface{ name, node, parameters, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, + steering_factor_interface_ptr, 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..4d200411904b0 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, + std::shared_ptr & steering_factor_interface_ptr); 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 8096d2944ee2b..ddcfda50d18c4 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 @@ -192,7 +192,7 @@ 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_, steering_factor_interface_ptr_); } } // 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..c0d2cdbee5c04 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_, steering_factor_interface_ptr_); } 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 8f19613b50e6d..48c6084a4f424 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 @@ -343,7 +343,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, + std::shared_ptr & steering_factor_interface_ptr); 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 8f7deffebf5ac..8aba7d4f0ae93 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 @@ -312,8 +312,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, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // 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 c04914ed1c72b..3c730e6d36376 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 @@ -26,7 +26,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_, steering_factor_interface_ptr_, std::make_unique(parameters_, direction_)); } @@ -35,7 +35,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_, steering_factor_interface_ptr_, 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 b4e4abbb9272c..222bc4e49ca18 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 @@ -316,7 +316,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, + std::shared_ptr & steering_factor_interface_ptr); ~GoalPlannerModule() { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp index 5408dce9dcdfc..c4db636861c4f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp @@ -38,7 +38,7 @@ class GoalPlannerModuleManager : 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_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; 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 ae7e1a4fcb6e8..eb7e6e22370aa 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 @@ -58,8 +58,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, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, thread_safe_data_{mutex_, clock_}, 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 bd309dd35a260..fd9375c7e9f75 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 @@ -52,6 +52,7 @@ class LaneChangeInterface : public SceneModuleInterface const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr, 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 979004d439bdc..982cdcf3e78a0 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 @@ -38,14 +38,14 @@ LaneChangeInterface::LaneChangeInterface( const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr, 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, steering_factor_interface_ptr}, // NOLINT parameters_{std::move(parameters)}, module_type_{std::move(module_type)}, prev_approved_path_{std::make_unique()} { module_type_->setTimeKeeper(getTimeKeeper()); - steering_factor_interface_ptr_ = std::make_unique(&node, name); logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); } 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 8ae8441c95ad8..69df2fe14317a 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 @@ -301,7 +301,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_, steering_factor_interface_ptr_, std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); } 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 09e1382799f01..54254bf13e07f 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 @@ -90,15 +90,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, + std::shared_ptr & steering_factor_interface_ptr) : 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)), - steering_factor_interface_ptr_( - std::make_unique(&node, utils::convertToSnakeCase(name))), + steering_factor_interface_ptr_{steering_factor_interface_ptr}, time_keeper_(std::make_shared()) { for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { @@ -640,7 +640,7 @@ class SceneModuleInterface std::unordered_map> objects_of_interest_marker_interface_ptr_map_; - std::unique_ptr steering_factor_interface_ptr_; + std::shared_ptr steering_factor_interface_ptr_; mutable std::optional 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 9dfd30e15cfbd..adb0fc49c3bd1 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 @@ -298,6 +298,12 @@ class SceneModuleManagerInterface "~/processing_time/" + name_, 20); } + // init steering factor + { + steering_factor_interface_ptr_ = + std::make_shared(node, utils::convertToSnakeCase(name_)); + } + // misc { node_ = node; @@ -322,6 +328,8 @@ class SceneModuleManagerInterface std::shared_ptr planner_data_; + std::shared_ptr steering_factor_interface_ptr_; + std::vector observers_; std::unique_ptr idle_module_ptr_; 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..778afd1698ff2 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_, steering_factor_interface_ptr_); } 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 e82c4fd287432..d0d34b5d9a37f 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, + std::shared_ptr & steering_factor_interface_ptr); 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 3990a2fbf5475..8fdedf38ed756 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 @@ -33,8 +33,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, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // 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..d1c9c8e2535ec 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_, steering_factor_interface_ptr_); } 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 543b17aca9352..74953b7927b5d 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, + std::shared_ptr & steering_factor_interface_ptr); 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 929e890edc204..d831f65b23117 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 @@ -40,8 +40,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, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // 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..a26c48ad065c9 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_, steering_factor_interface_ptr_); } 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 bb70ae2638056..e0bb5d95f565a 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 @@ -88,7 +88,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, + std::shared_ptr & steering_factor_interface_ptr); ~StartPlannerModule() override { 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 6c88bf006b5d3..ec0db1e9c0f4b 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 @@ -58,8 +58,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, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_freespace_planner_cb_running_{false} 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..fa54ec52203f9 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_, steering_factor_interface_ptr_); } 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 ea12c66859a36..a2dbdcc1dadb9 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, + std::shared_ptr & steering_factor_interface_ptr); CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; 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 58db35f2fc12b..bc8e406a170c9 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 @@ -76,8 +76,9 @@ 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, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT helper_{std::make_shared(parameters)}, parameters_{parameters}, generator_{parameters} From abcf3eebca2a3d368059a7abab57c3fd1d465943 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 2 Sep 2024 19:40:41 +0900 Subject: [PATCH 087/217] docs(out_of_lane): update documentation for the new design (#8692) Signed-off-by: Maxime CLEMENT --- .../README.md | 182 ++++++++---------- .../config/out_of_lane.param.yaml | 1 - .../docs/ego_lane.png | Bin 0 -> 17530 bytes .../docs/footprints.png | Bin 0 -> 28711 bytes .../docs/object_paths.png | Bin 0 -> 26240 bytes ...footprints_other_lanes_overlaps_ranges.png | Bin 127593 -> 0 bytes .../docs/out_of_lane_areas.png | Bin 0 -> 19244 bytes .../docs/out_of_lane_slow.png | Bin 110077 -> 0 bytes .../docs/out_of_lane_stop.png | Bin 183400 -> 0 bytes .../docs/path_green_light.png | Bin 0 -> 23635 bytes .../docs/path_red_light.png | Bin 0 -> 22819 bytes .../docs/ttcs.png | Bin 0 -> 28315 bytes .../docs/ttcs_avoid.png | Bin 0 -> 31503 bytes .../src/debug.cpp | 41 +++- .../src/out_of_lane_module.cpp | 7 +- .../src/types.hpp | 1 - 16 files changed, 117 insertions(+), 115 deletions(-) create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/object_paths.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_areas.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_red_light.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs_avoid.png diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md index 54b7cebb7c8ff..0b6aa697fcbef 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md @@ -1,129 +1,113 @@ -## Out of Lane +# Out of Lane -### Role +## Role -`out_of_lane` is the module that decelerates and stops to prevent the ego vehicle from entering another lane with incoming dynamic objects. +There are cases where the ego vehicle footprint goes out of the driving lane, +for example when taking a narrow turn with a large vehicle. +The `out_of_lane` module adds deceleration and stop points to the ego trajectory in order to prevent collisions from occurring in these out of lane cases. -### Activation Timing +## Activation -This module is activated if `launch_out_of_lane` is set to true. +This module is activated if the launch parameter `launch_out_of_lane_module` is set to true. -### Inner-workings / Algorithms +## Inner-workings / Algorithms -The algorithm is made of the following steps. +This module calculates if out of lane collisions occur and insert stop point before the collisions if necessary. -1. Calculate the ego path footprints (red). -2. Calculate the other lanes (magenta). -3. Calculate the overlapping ranges between the ego path footprints and the other lanes (green). -4. For each overlapping range, decide if a stop or slow down action must be taken. -5. For each action, insert the corresponding stop or slow down point in the path. +The algorithm assumes the input ego trajectory contains accurate `time_from_start` +values in order to calculate accurate time to collisions with the predicted objects. -![overview](./docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png) +Next we explain the inner-workings of the module in more details. -#### 1. Ego Path Footprints +### 1. Ego trajectory footprints -In this first step, the ego footprint is projected at each path point and are eventually inflated based on the `extra_..._offset` parameters. +In this first step, the ego footprint is projected at each trajectory point and its size is modified based on the `ego.extra_..._offset` parameters. -#### 2. Other lanes +The length of the trajectory used for generating the footprints is limited by the `max_arc_length` parameter. -In the second step, the set of lanes to consider for overlaps is generated. -This set is built by selecting all lanelets within some distance from the ego vehicle, and then removing non-relevant lanelets. -The selection distance is chosen as the maximum between the `slowdown.distance_threshold` and the `stop.distance_threshold`. +![ego_footprints](./docs/footprints.png) -A lanelet is deemed non-relevant if it meets one of the following conditions. +### 2. Ego lanelets -- It is part of the lanelets followed by the ego path. -- It contains the rear point of the ego footprint. -- It follows one of the ego path lanelets. +In the second step, we calculate the lanelets followed by the ego trajectory. +We select all lanelets crossed by the trajectory linestring (sequence of trajectory points), as well as their preceding lanelets. -#### 3. Overlapping ranges +![ego_lane](./docs/ego_lane.png) -In the third step, overlaps between the ego path footprints and the other lanes are calculated. -For each pair of other lane $l$ and ego path footprint $f$, we calculate the overlapping polygons using `boost::geometry::intersection`. -For each overlapping polygon found, if the distance inside the other lane $l$ is above the `overlap.minimum_distance` threshold, then the overlap is ignored. -Otherwise, the arc length range (relative to the ego path) and corresponding points of the overlapping polygons are stored. -Ultimately, for each other lane $l$, overlapping ranges of successive overlaps are built with the following information: +In the debug visualization the combination of all ego lanelets is shown as a blue polygon. -- overlapped other lane $l$. -- start and end ego path indexes. -- start and end ego path arc lengths. -- start and end overlap points. +### 3. Out of lane areas -#### 4. Decisions +Next, for each trajectory point, we create the corresponding out of lane areas by subtracting the ego lanelets (from step 2) from the trajectory point footprint (from step 1). +Each area is associated with the lanelets overlapped by the area and with the corresponding ego trajectory point. -In the fourth step, a decision to either slow down or stop before each overlapping range is taken based on the dynamic objects. -The conditions for the decision depend on the value of the `mode` parameter. +![out_of_lane_areas](./docs/out_of_lane_areas.png) -Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the start of the overlapping range (in arc length along the ego path). -If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used. -If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used. +In the debug visualization, the out of lane area polygon is connected to the corresponding trajectory point by a line. + +### 4. Predicted objects filtering - - - - - -
- - - -
+We filter objects and their predicted paths with the following conditions: -##### Threshold +- ignore objects with a speed bellow the `minimum_velocity` parameter; +- ignore objects coming from behind the ego vehicle if parameter `ignore_behind_ego` is set to true; +- ignore predicted paths whose confidence value is bellow the `predicted_path_min_confidence` parameter; +- cut the points of predicted paths going beyond the stop line of a red traffic light if parameter `cut_predicted_paths_beyond_red_lights` is set to `true`. -With the `mode` set to `"threshold"`, -a decision to stop or slow down before a range is made if -an incoming dynamic object is estimated to reach the overlap within `threshold.time_threshold`. +| `cut_predicted_paths_beyond_red_lights = false` | `cut_predicted_paths_beyond_red_lights = true` | +| :---------------------------------------------: | :--------------------------------------------: | +| ![](./docs/path_green_light.png) | ![](./docs/path_red_light.png) | -##### TTC (time to collision) +In the debug visualization, the filtered predicted paths are shown in green and the stop lines of red traffic lights are shown in red. -With the `mode` set to `"ttc"`, -estimates for the times when ego and the dynamic objects reach the start and end of the overlapping range are calculated. -This is then used to calculate the time to collision over the period where ego crosses the overlap. -If the time to collision is predicted to go bellow the `ttc.threshold`, the decision to stop or slow down is made. +### 5. Time to collisions -##### Intervals +For each out of lane area, we calculate the times when a dynamic object will overlap the area based on its filtered predicted paths. -With the `mode` set to `"intervals"`, -the estimated times when ego and the dynamic objects reach the start and end points of -the overlapping range are used to create time intervals. -These intervals can be made shorter or longer using the -`intervals.ego_time_buffer` and `intervals.objects_time_buffer` parameters. -If the time interval of ego overlaps with the time interval of an object, the decision to stop or slow down is made. +In the case where parameter `mode` is set to `threshold` and the calculated time is less than `threshold.time_threshold` parameter, then we decide to avoid the out of lane area. -##### Time estimates +In the case where parameter `mode` is set to `ttc`, +we calculate the time to collision by comparing the predicted time of the object with the `time_from_start` field contained in the trajectory point. +If the time to collision is bellow the `ttc.threshold` parameter value, we decide to avoid the out of lane area. -###### Ego +![ttcs](./docs/ttcs.png) -To estimate the times when ego will reach an overlap, it is assumed that ego travels along its path -at its current velocity or at half the velocity of the path points, whichever is higher. +In the debug visualization, the ttc (in seconds) is displayed on top of its corresponding trajectory point. +The color of the text is red if the collision should be avoided and green otherwise. -###### Dynamic objects +### 6. Calculate the stop or slowdown point -Two methods are used to estimate the time when a dynamic objects with reach some point. -If `objects.use_predicted_paths` is set to `true`, the predicted paths of the dynamic object are used if their confidence value is higher than the value set by the `objects.predicted_path_min_confidence` parameter. -Otherwise, the lanelet map is used to estimate the distance between the object and the point and the time is calculated assuming the object keeps its current velocity. +First, the minimum stopping distance of the ego vehicle is calculated based on the jerk and deceleration constraints set by the velocity smoother parameters. -#### 5. Path update +We then search for the furthest pose along the trajectory where the ego footprint stays inside of the ego lane (calculate in step 2) and constraint the search to be between the minimum stopping distance and the 1st trajectory point with a collision to avoid (as determined in the previous step). +The search is done by moving backward along the trajectory with a distance step set by the `action.precision` parameter. -Finally, for each decision to stop or slow down before an overlapping range, -a point is inserted in the path. -For a decision taken for an overlapping range with a lane $l$ starting at ego path point index $i$, -a point is inserted in the path between index $i$ and $i-1$ such that the ego footprint projected at the inserted point does not overlap $l$. -Such point with no overlap must exist since, by definition of the overlapping range, -we know that there is no overlap at $i-1$. +We first do this search for a footprint expanded with the `ego.extra_..._offset`, `action.longitudinal_distance_buffer` and `action.lateral_distance_buffer` parameters. +If no valid pose is found, we search again while only considering the extra offsets but without considering the distance buffers. +If still no valid pose is found, we use the base ego footprint without any offset. +In case no pose is found, we fallback to using the pose before the detected collision without caring if it is out of lane or not. -If the point would cause a higher deceleration than allowed by the `max_accel` parameter (node parameter), -it is skipped. +Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the trajectory point to avoid. +If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used. +If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used. -Moreover, parameter `action.distance_buffer` adds an extra distance between the ego footprint and the overlap when possible. +![avoid_collision](./docs/ttcs_avoid.png) -### Module Parameters +### About stability of the stop/slowdown pose + +As the input trajectory can change significantly between iterations, +it is expected that the decisions of this module will also change. +To make the decision more stable, a stop or slowdown pose is used for a minimum duration set by the `action.min_duration` parameter. +If during that time a new pose closer to the ego vehicle is generated, then it replaces the previous one. +Otherwise, the stop or slowdown pose will only be discarded after no out of lane collision is detection for the set duration. + +## Module Parameters | Parameter | Type | Description | | ----------------------------- | ------ | --------------------------------------------------------------------------------- | | `mode` | string | [-] mode used to consider a dynamic object. Candidates: threshold, intervals, ttc | | `skip_if_already_overlapping` | bool | [-] if true, do not run this module when ego already overlaps another lane | +| `max_arc_length` | double | [m] maximum trajectory arc length that is checked for out_of_lane collisions | | Parameter /threshold | Type | Description | | -------------------- | ------ | ---------------------------------------------------------------- | @@ -133,20 +117,22 @@ Moreover, parameter `action.distance_buffer` adds an extra distance between the | -------------- | ------ | ------------------------------------------------------------------------------------------------------ | | `threshold` | double | [s] consider objects with an estimated time to collision bellow this value while ego is on the overlap | -| Parameter /objects | Type | Description | -| ------------------------------- | ------ | --------------------------------------------------------------------- | -| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | -| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | - -| Parameter /overlap | Type | Description | -| ------------------ | ------ | --------------------------------------------------------------------- | -| `minimum_distance` | double | [m] minimum distance inside a lanelet for an overlap to be considered | - -| Parameter /action | Type | Description | -| ----------------------------- | ------ | --------------------------------------------------------------------- | -| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | -| `slowdown.velocity` | double | [m] slow down velocity | -| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | +| Parameter /objects | Type | Description | +| --------------------------------------- | ------ | ------------------------------------------------------------------------------- | +| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | +| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | +| `cut_predicted_paths_beyond_red_lights` | bool | [-] if true, predicted paths are cut beyond the stop line of red traffic lights | +| `ignore_behind_ego` | bool | [-] if true, objects behind the ego vehicle are ignored | + +| Parameter /action | Type | Description | +| ------------------------------ | ------ | --------------------------------------------------------------------- | +| `precision` | double | [m] precision when inserting a stop pose in the trajectory | +| `longitudinal_distance_buffer` | double | [m] safety distance buffer to keep in front of the ego vehicle | +| `lateral_distance_buffer` | double | [m] safety distance buffer to keep on the side of the ego vehicle | +| `min_duration` | double | [s] minimum duration needed before a decision can be canceled | +| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | +| `slowdown.velocity` | double | [m] slow down velocity | +| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | | Parameter /ego | Type | Description | | -------------------- | ------ | ---------------------------------------------------- | diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml index 67db597d80752..5d36aa8d3f018 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -3,7 +3,6 @@ out_of_lane: # module to stop or slowdown before overlapping another lane with other objects mode: ttc # mode used to consider a conflict with an object. "threshold", or "ttc" skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane - ignore_overlaps_over_lane_changeable_lanelets: true # if true, overlaps on lane changeable lanelets are ignored max_arc_length: 100.0 # [m] maximum trajectory arc length that is checked for out_of_lane collisions threshold: diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png new file mode 100644 index 0000000000000000000000000000000000000000..65cb73226465ae3de6c27b35562d35c57c5906b5 GIT binary patch literal 17530 zcmbt+cRZEh|MyWTp^y_2*($>jiv)`ZhCH&b_`CIsu_%ImkmZE};1`KvZ4+g`T z#Jd9ilKS1n1pK)9Nzk3I#)}d(@2BU>3%1CK>7_U#O+ELl0v+OTNZ=T{? z@hU3ivlg=zml|mQ&9?ol)S@{e_>6CC^fS-PuLN*16d~EGZ#OngtKQ=Hj0MF;hWrj8 z@|}`Jic3-~1--eKS8uei;pR9?!%YX z$G9VQ-WEiBBxj+aa`R|#`3!&m*K6-N_!0!p!J0K3hZ$S-T&?DstxX&*<*qh-rnA3BZ+!QBzXo5 zX41=ssYH@bhT82SoStpWw6F`R-b7b-7P6_A>vR>eVbJ7KK1)|9m}Kn&^exg0$M~5F z4;=l{ja%{dx0BZTxP&D9-U>fTB_}8EVh+HLj~`Y1*v^=3ru#hAu%q{4m1OPg_TI~v zFU>R~3Kq?CwH}76j+pGvlbSG(+PWV~6>L95*461O)F94Q3l2R#9)p)$K_9h>WiN>R z5^1fRYiiFIsp-tIH9dTQ_^9>E<7YI-qSqVRYXLYb@yC&okv+G^zQqKf5JKlyNcru>rIr`-=c$$^MVTDmKVX4}Jqgzx ze}1OP{<3n|?Y1a9D;R|gFV6zIZjxMHUXG38NK!J&C28=G%04hH*v28zF2!`Z+!Wt( zZeVeeskNS50Xt4B>($p49Ua}$((;Y0vgWO>c~b8U>JCRyYhp1~` zCZ9hk9PHuJHp2J(l%`hABW-y8a_q17Hl~{}Rhx+^;e2Uf%@>*-i@mCRCsdD8F~umi~FXrH`VYp^03KCge}b#6~&vZkAd0|_AQc!t(U?y zGyHkL`+l8s;~?(7|5lpo1%A_GwIHCL6v_KnoH(4uoM^e1v`y{+v*92cJV`pbS^6`85Qu#~Y zj^xzz8K$XebL(wsDMDZG&|Lp~w5RmFE;QUtjndJ&y1MNnpDI1ZT(c^Vy}zT}gfD9; z+va+c{13K%Biu4Y=pQC!Pk+H?S6r|j;s4-rjlKd?`DmfGibA0V{r#5zjv{{7_sJqx zU~G`-t6Y~vhFbqdq1rsR7l#vAWK!XLFTh;HX@w2VKI@TOehk?#`Vs!{@6{aG&R60d zTPD`aO&7lrr$nc}Pd3|{z4k6V54UDBoAEiXnFqsY8=aSWlh`qB`?VRN?}qprj4LB` z^T$q4PYaY&$jHg>%D!XlaWle3ys0juIbFUu#X+1WAdZ&m+s@ijl(bEMzH&}2^xXNQ zDyxnk(hfhXmm>(ly-6KP;zz)RTA9mRJ1;(oUDhqxY#FxG^g)WRN8 zCyJbtp5hM$!!@I${%uVs2&^K%5p!ZpO2t~CjTLX23Nv4`yVV@zaU&^FGLx=bBl>t zw>L+SOD^@<1X_@v!6g09-@heeUc=YU>%UptgRQ6uKL2h-(Eo?TU+-ZO^H!dHGhqie zVbHQ=o8!R#e(e0C5r^sH`l3g13Qt*={GUpb{c#qlD!%3aocV9tEufSGPr{x6u`7|6 z1zTxsf=y_tQ7*7Xqh}GG#{6meV@-!y_fGupN0ET7{5vY3I@0;;sg|~`wnPfwJ@eMh zhY|6a(!5pX(&R&ua$^jpUsWiSK9|w>?2XdwER2rkaB!R|ZvV46Otu4x>MCw=xVx%} z%_R|?&0sjKzxPx4<>uv<>NiZ76QkmtR)hxz24Xf(7LEfETFWP8YPPioZ{NP{sl)^J z93gbO#cgfYs^&se(yh>-e1Byq&qHu^(y`5ca{o)=py6qMj|Fd36)m3J(OrC_JQ(fp z=N+HqBfq(mJL=!+)(tC~TYUf8lWKf-qN1Oeoh5IjV%*GgeP=WhKb`NsIb&pKNTn*Y z`rOeMrZMatgadN`P3oJzV8^4;7 zFv-r@`*GJW)&WGf&7F7l7*G9xQ?Z&atCrC+ZNVJCts~B{v0ahZd!5q7am`Cgic92V z#_isO9lAc8b(a_nuUuU^yT=6F*{%%hxyM@yGp=8{%f`I8O=a(d--7V+Z+*Q5i@INE zlU{iA?FNmw&*3NZwC~&KZaVdE2Ulm^*^{nL*4@8Vn&NI_0i^Is+F9+Mm%uir1oH@E zzrNW<+c~4SyfSs)7~gsA^1?=(sNcRVVP$t9!HeC!z(_}LA{ezfsoRr<*STXav(o4SbvR6kVwPJtg(#PVDbDPy<>6K=aN z)T+-44+qxUP_fWh=h0O)R76W+Z*PCIl<w0NY;VlJ6~1_n?A z1G;-&`{elcQbLI4( z@F=DxMO_`8fs~MnH5H?qtZ|*!VXzko=roDKxq$)yi=CV{dD5J~sh}G~f`WpF*!zyn zPTLl0s8*`;`DY|oV43B{mFw&FY!S(Zh#AhO-zMvk6exf8>}&-mqmOIHvM7Qga_C)k zrx!jA9nPrvZ6isCPBu4<+s-RRE7&qsoKIF-f*1<@6?7Gq6#zY}GTupNKv zK^~3o_gKf-a|Hjo{z-bf;{NXH$WJRe6bP8dbuBHeEiKu7BHc#}ep_do7u+c)A|&_Z z>Qb7h)M7l8H`XwfmF4AG;v(qFm1<6D9xtU_tj(UUThbrT9GrXkonJ(7rB>v|h0WWK zZ6BRJ-Z#m>{|LtBl!-qdwazIg9y(|}z@%_poGca>v*Tkhm?K7w5&q5DHm>Y!b?BP| zgVlapJuH>UgrUC?jydvtZnCEMEbr){TWqZj8qF4QgL#TpzisOCQ!Sjx3N7Xd!FJ4v z$JbM+%;@C$hIjqE8{+CL)phhbGmZXI!#s|6{eRyOa%gtnCLHP!&P3(L-6425&~h^I z`77}F0j>JKhz`H~{j2sgTg24c`)nu=2^5%sfPKEfX6q1Z?#DgJMEVfu#`$NWTd#F1 zF@y}dm1;;??b6Z1TN#{2jr<)!A<){7=R9dpPl8(VY3o~BI0aS1_x5!CckUTm#zKPV zNMP~rB}z_d^WX04ix5*7boY+vc?;dqj(rlu$K23+KGWhozq;D3qkDm@vM(cC&@~%* zVKYJ0#SG?td)>P4?BqaogfTZ(@>oG!Xo*6dvF@85NG>}I$K%lwBpD`kQDOFtnk)Wt+t>YI(=VI$(a z&R=SkYFF9NSJlsWDcjv=9rSh!s_0o3o+Zm*exB!~Y?p2~`d6UprioYc#W|W?SI}|h z)CGG@rQyR3y02PmXBkr}F`PTA+d&5Q&Gq#xg0)BUkq3^`UM=d&!^5Qu8f>IO*~JF6 z;V<0lv5SgN#4&9LGtcJ{XIonr8%w$?L+@usO<9wa%rvFj+=o zWT64$RUk+E^2Nh|fBTuw*4!J9dDjDwKKq@ClGxkX?e2Bn6a1>r2l8wQlrfdF_{_Y? zeT6#=pcD|q-gTsYQgtA+xJ0Y*jMyI`EU!+H;=6vq$@9Q_)OL@)zz2%7+$SEa+k+eV z8{riGQ+b-7joQ%oO>louko4u@XnUMV6JL28;i@8YF2&JFCo0>t))JH`Z_<70eR_!1 zi&qN(OXUBX8rIX-L6yemwn@95>hFZb_?=NeHOA&y?7gl%A7Py`7R-B*h0S@g3P&o*E% zIkpB1Gq6D~U#<=1$shT&>T%pruhQ#V-T|Iweq?wVD6M15UUJ3S=?6>w#)`E@$%0KN zWuHqrnDLIK@j1nIJ1zYBr6ZY>!l;PZGpjn>pLA4P?LK>4R$lIV&@|iPx_ZYS)GSzR zHx0t~c=zvU>FJs0?#fV)wF(XhgfNn!7ViU(rEc`M#bQvQ6{+PgD|eLYR)(7Dm5#=z z^f#XzYy!uGmHts(hP*h&lIaE)dCVT?)i*ua8b%o4 zqYJT5E_{G8fMsqnF#t7s+p~#NYw(B@-+nT?q7n}{4_Kr7=7Y@*<<}9fJH3@g_-w~! z$d7As&dSUOm?GQ3LL!P-pwKfnx?j2qZkW|g z)jQanjcs~DBk40%Kn(9R|EQ@22d)rkhVvGxA$O-dcxsvgtVd^z!+}% zjogG1XO_X;^>0BpPR~^fZTz;r-B{0fwU6dU7wVHef6L}6U&4u27=R<*&Bps}f1tk> zunUzKB85Gf%pw*Z@3cb;^;?~n$jr+$Jn6FUrwii_W>QZ?u0F)CS`~!lYdKr1W2Zc^ zW~?(MVh*eCY?8^zbO;%gWsrVHFR{BnI_otW73flT=e}J%Uuy%ImhUZ|7+m0a6^g$l z2UV4qKbovN8s45M8r*vL%I`cr_oIwf`Npp`hKKprvjeB#cS9%`t_37gdWcXwMK~q2@EP@y|yy6qNa&pH}L`U56 zMD+uHRCE~?70A*?G~i}Y;P%H#=eVM-_Vz0zzDG+b^Q)R$RaH&yn<#%&o@GzfW2xFk zv2^FHAR@`R8&?&-9o}wfzWt}rGM^Y^xy7Uh+OLUVBmAC+_d>rtr|K4Q>e8R6`Qh|Y z%is>DvMs;yjh?NkHvb$NLvGxV`WG%PnqN%J%@>aMK%G=kUao3K1_|7)F(v46*>$;ld{ghQ)E7K55V>p8DdnFh#Rr&D+2I_iwp{GA{ua zvbB!}MO7s7&zZZyy)TVz%zN3Ii@BLq26#e))WV~3M_+b7;g4!ZF&w2D<>~FssaaWB zc7ho_7QIW(c|*dYq7iE2uO*y*&oOCkbtBHJJkrBBe;j!h-n^Wc`$T1=Z^^kpLve(E zh8}Lw@s(Yij-c&yTiGuq_a&yH>%=q0r03co9laNDu|0e;GC~eh??3qSeNq`&)EBe) z^!@?NDrc>6&&$`*F}BilY-Xm;{(1Aq8|6Bsl_y$1*92sTc+(84hnzAS8bJLH$3GqY zh4D{lHksR)Z5!My+Xapy23Nn<06Y+p%Z-9Bo#Mt@>Q}5ql*=TJ8Jk=o$3RKALZnA4 zYg-2A#V*3LXU^WSlAy*UCMM=#5#2cN>+9=WZKuu(n|;T}qR5ws zH)0i#>v!{bVCM*3M5`_c8*lGvr}UoWtSoBd_+<2w>Arlnbvo;<^{n45)jqvZ9u8$c z1n^-t-yG%Is;cOwZs!_T?!;(f+=6IVh9$-vF)zvtrXRuoBzQ;E8I(h>TT;J|l6KB2N9|bGnt%cB%$a*HJfLiUVt5WYG&Q z(N;dggNV30npVsuteq4g6gxt$YeDKt`uFc~Rz$W#;YCGcq?B?PIt32KiQ>DnC6 zU`=jl?mnS1B-inm3D@SZDSH?z`joQ$`^phOFKHh!e>fEGe{a?A%5eigL=PEQ_q>GY zrhig_Kww2hLo43xGeqKjxJ74F#wuP;wYYzP3{%Y_^geNP$bFp#u$`|_86VS*jSPK+ z1~v$8u#~fAQh}h9YMFp|oa*{clFjvVFNJJZ22NVPo$$S8rKZOzxvkcY{LAv zm^id``kF$IDb^$y2i%(qK9KoSW3lZ$AbkrM=P$S#Y#1B4w&46}_S5E=nAf*7-s##w zhG;S8?$*F7AaK;!DBZv__kC2cSxS|!S=g8P%hJnf8vU)R@;%6BzS^Y^)dl&Ylfgq9qgT^jSVM`&c z=$;w!JCQY~mdC$Q+Suf6AfiB8lL!SZ?p0B;5b{;>rT8F#HL#5cx4f-U#vktNGY1Ld zSHkqaY#3n|fSH4q|Sb7piP#6%t&=}B7EceBvx!@NXk!Fy2|ZyqU~P#*ssEr zmxbRpBX4Q`QR@n2(|RaDno-z`*9zZ1jJ}18YP^49y#|x;J3R#1U(fTs+s!l7c4V)S zyh9EFZQqYRX{@@D@04A80BioWkP^Fb&;O*Zs`*sQPL(yqyLZ#iNPG}=PA5iu>Ki71 z4J6IyAR%<2KVBpi@*Hn)yTELAVI1ybvFhd8;|@$uU%Q;tIjzP&mASwo9z-n1>>aLe zO^rQwY+<;G}Gs0Fn523(c|JQ#Y{7&!f>21H$&*cQ2ZTl z?L?N6<@(_HKe73n!j<8-r33g^ums3WWQo`52Cva9(TxAalA6C4o8RH!`S=C1B0@0} z@j>h1O(rcalo&Fv$-?q}1FZ z-jBUq#}#)0D!vf1jbG(c8IGL9L*&SR2+v_+wR+FZmI4hnhPv!rgW3clcXwo)jx0r@4fB&pzJ<4AdlCV^3hUFyb+3pyr2=78VtsKs#s1ZKpWU#pyqQ+i)9n2^kDb1kuqlru;dL&O;ilQcReno-tX_t9{_3cOtm)&R1y8JKD|<7Y;V2Jo^xxEWt*V zIi7rlG4sfEl^(dy;g)Ia8w>%*#~T5wc{T`+6a;;)?cRjVSv_Av*ee^h18nyu$xw|o zf_O0cIZ~NN zjrG7!v9bQ*V{k?w6_rZ9$aekFg^3@l&J$%ubhuq3K~SA&b5|{)SWA-Dj74pru)JKG zzR}xVQ=BJn9zHcTMxlWZwO9%#0F1Gst$sKgzHCK6v%MIJi#X{cQ5(#)z?bycdMqv> z47nvU?4RfB3?Y10v_k2rD%3>+Ox`kY(=S(AOs1BWRuSzyVC{RxjG)+`$w;6zX8Y!- zDy{`R>EP2#Si2s?=gp+moY$M-c)q)srth*jBjNW6l$2W{x$BVgnQko0OXW%GE%imq z#oaRJum122s*rPw(Bg2hkJ19?p0f;o<-h0K#tP{X>a#)R>%!1tzGOdj$QSmd{>FXH zeYrJkK6wJEaty}uG>{XF3ft_~DxDVbyk6Mxh4~o5uL>0*5G643GSY^z#9Z0Mg?w?) zV9L=++XYuADfc%e(5v7#faVs^t+0zwg%v?#{hMp5I33UNl^4f(B?_%MM$G*|q$jwVtzVtY0h&<%`FaOG8c6CYG+W}qtUsGzbm#W=M0*h#=a3B~z_jgg>zFZql^#F!R1Ih+q(GaPsmew;*oHS%STq`XcKK%&Ri{r{ zF@*4>IWG^GSJ}MyWNRh}^>7Qtfyc=R%`+EKkZH(d6Z~cYy_?-J@JwBW@4j1XgVz!S zueDMzobW%n0FP&rQ!qccMERh>gZP`n^YW1NX?LK#YIWnf!QfxL1nu zPp3M?buj(cxm)J*FD?~A>KTL)3wQ1Bd*zvSxtJd6(f)0-xkLtoEVVgG>FXY(1USk4 zaklD4n_Ph;dp)50LAxWRDX2{WBj7F_?D52&K&|zDi7^-%_T#UunkMK@8bKfW(x)F*Q*;hGDK+g|X41KO<(o7P-%G^gIh%*Xln9+cFpmzGTX3ee2?fCLL10`A| zH@Lcf3HqU@jgjQfi)er#Vc+e?%``I_wMjFqu0Wq(Tyzm2wmN?$*w#u^*)T)86Hum9 zu&QVFQhG$fR&Sa!)fns}jF!H-jL$0AAW8qZ)OTq7fR(bDp?>SOyBSuv&_Ko_!n>{l_ zw+Zp-(i_xYdDncDDQ&Nzq)?ZsSH=;z68epe@H3+&v*I{ z<)!carQ^ZLgnY~^ze0V%{^~J&O~`5Ttt6-!0-xY4;$mtlYZp=saR-FkG;9>@0&O7n zfiTMqn=OU@Zp>4NJo8m#$+-|XD=4tMdYYz^O=FV!>XJA!(8FEbj-vu`Hokgta8)wV zn5Dk*f^^_ItR-)R0D9m-d;3i=5EuB)IVGwKk0FWgyqi2b=lK?*HXT3QMSLJ$b7tE-!moa{3TE?u~#w|555pT>%1 zPk`HKJru}L)lVh}30(G6hx4GekD3>R(+j6teNUdx9_!SMbHMQ@Cnvd#n_mcK%&P_7 z1lbqNLsdP|eb!fqu%n@&p{uJ4fHoQ!w+C*`bKo8088L3;WMtxlBW~0D{T{caC_+n0 z2KxI2D5F^;9w7Y6Se2^u7ArrswOyPZ?Ia+GQA9xATM-p&{#!Tv=NdPrrly96HCl`> zCNQmqYsXVlhQ!xE4PHHi`-f z9c0X&GW&6=T!FNheY5qXqNJqDj7Q_=nU`;|9wYti!NLB%-6S(TilVK0)V8Zzrt`+_ z=jCMnV|Iet+Izk^VZ8TR{)nE`wRo(j`@Y%&fV5c5&SFo(VFUMT$OqEr0!#F_w3O{x zq-=GhroLBQ#)fa+=R_rHiKER+kU(KBMXV4Hmwi`JVq3E+Ht=DsA^!7gn(3_xg1lGDpUAv65Qi2!3*)$>nO;IZ4T7Vd;DD%%IgtFr%vUs71S;MZ0l
Md2#QV12}HbF|XtybrFNP3dYU(K$k3~uJp#q$w@>Bf8f?Hp&73eG#BD*R}dL= zJ;}Sx6I1q28LEoOQ8FKxWemLAvzTu;C>6B3FZu2N8(%`Fgn$3O^ta+=i(Pu5ezDe5 z@mq3`S7l>DJ4@!wPEKZUEtVujFe)Zn_Eh&hj4vqx4rD`O>nUklU@mL+G7pNd;|G6q zSgy|6u=IEd+miD=DPbseQ78@x!5#e$k1X`n<0A|Tv(V=pObKtH>?6&2g(F40MWg;O z$)G%$1Fa4pEv+rIKWGvsxqe$}tTaaK)|Icj&Q!~vyyE&T44V|y69<=Xb$nlPk%3=( z$aM2~LH%G`uKPgE@Y(`Y=q2`A@V2gnKAJrcr^gQrnDvUIiPS}^2xcr* zmaTb}>!2-ou_fWeHFDihAZ5E7YRa5oBS@JRB_$KZqdjtH7HZnJxG1FnxGlfj{;`_< z`u$<~q+IGP=PtptFDy<2=<-G{D?JJ{&v;d97OLOAc||23&!`yhs;UW>)lQoCDdtBS z=;;x2g$zjp-C;}Wu>k8Vv5_ieQgnvP`bZLxjMrriE+>%Za8V~DS&HLy^Y?djq?g!+ zR;;BDa9@~Afe03-QD{RM`oXqjnKzd;qVuD9w~)!532$l0)>^ly$)A_BWzSKe+bvOwReR7Xg7rV)42oeXvuVz%Nrk7WTU&EQ*Dllqh z6GX&W>Z`-)osEPVdg<{3r9TiOK>Gp9ua0rc=(qBT2s?b_A5JeP^Ca~HzAvb-9+$|P z%D`)VkZkak!@BK~60*oHVam0=#zGrx^lPWPEd!3 zKmn(74ES=25V$%;D8M1Q38lu^|8ZR9HgD&)t2HpCkTZn`n|^rq#d%4|M`?tAaEAk( zJCabz;Kx&W^mk8GO$Xx!!W2X}3Xw9QK$)&T8+l&Mh$|I`UZRW+J(T8tc)1fZZuevX zz}n8;_n7gRwYA5{~t&HlSwi6jjat$#d!MM_oKG5Bnf&So;@ax zAp!Y{#zVX-lXaH*uc=uGpHz<0=Yn{OuFho@eS~X2`BZY(7eV+$62mNV!I#j(SV4~( zYi|#<)R&i+cPT6`u_gX|nmiarO-+3lKLj*#7WcTJtXY9=aHpO28C*7=i7heky`}!I z-@oZd8Y*5+*11H5-6kSB`g_P4F>krubJer~7tuw5wyJ5YP>%m;C%C-4?9z}~Xw$kp z8MAOwPK%enAR@rcd1;7VEi>D`+S-8qx9l0SaK4?=Mi@AEc?HZ$3dJ6O}~Q_6NSq8Ql-ub4XFMnQmq z#zVjk#G^2e;5aEyw$yLktT!lUjX2B^AC6B;A#AYFsC$b%8E1{~nDfjQLULl(+_bd= zbs~BGe4wX-GWNdrh8y8yKMRd3Q_z;$+BFTCv$jd(WOeSZJ&=|Zq3h$QAa4EJsP&$p zeU>}#7!}1WR}c5q(hHZIJqLG0us6A-FLxXCMZKi7wFOj5F>6sgvg*048rs^d*AlR( zg=cup!ng_RfIVb0(c6pP_ITv8kEA~!tA>Px7;?J5diANLg&Kh?2W2E|UG9DjK1bVt zA-b`#0Z5`A99X&*;jwu{@!Hfq93u20PFpvrxt*V1tJcF1(~oOj%n84RDr37zOm~Tc zed8E!Ug+akU7r=;$Gg&M`66#$U!6XM{R+dW+0V) z_i6XR<%)~Rte;oQCq^c4v_3K2w%Zo=OO1N+I{?X`sKI;0uc|pZ;NBAO4zgmet^@UW z#-5$##jI2hQ*tJq-knd2(Wilj^NSsexLB#?<7^(XP`WnKkX_qh)on`?Ldb_1%Q2HW z68Ex$&d{pxsD}gAJlg_G8UnW?M}9>zI`F8Da7THyJjh96Wb;Hmp^yL~&DVmx~*pO4c`@?i=! z1CVtEWZzMD|EXd`I}=|cARy?W&6jEJdgSzue8F1G7tv1c9?FoOt)gr(6&em11=($Rasd%W}y=&xjEZfkKBoD`z@Az3$Z}k zXI0a0wX-vbh|Oiq8AMl?y#(5!#GJqe#|PBJ@RVQ@Dd75xcL29m42?z$InI;`*_&xl zgw`6^`$N|(H{pyXCFvb?57w|9UU4}Ybu*=sinVf`NG@YnBi-bsygV;k# zvd!GdSt7F3cM#0TUdELoZZqkxJ|7vpNSFQQ-nx^uSng|T0Tl1+056Qs#KB<$B%5C6 zry?Z2XXWl5v{>4ynVEBxQ0s3`;{uKFT-E^*$nWkF_W`H)X>y-OL zMGbhXQZEwt6qbrmbx2_v|7~obx}_+vNpD;;je)-#w-Y@7HOX@-`iDxb_OSX;U}1rq z@F;O;Q8fiF`x~QKe_NM=6YzQ;d+|hQ?YT*q=<5LUSYw@+YF(kAj@@^vL@rSv?jvas zOsxStWY=)~&kot5!kq{hE>ooVyJ=OVG(lh@(A-Y8MCoO!Me(fWA6{AYIH+CJpSgp` z>dt0V9Jfopz?&KHHe^Dvk|c9`tx)0yxSA*aOV)yS)!C2m9~>OyE$sP=??-gelR(9d zI3n!M^aoQ4rFgjRn|>=kyg;v(jT1kLP;oZCG?nHeLK3W7a0LBZ)8P15QI|R|#UA!_ zCd$v<{h(iH_NSY#jSX80df8c@etyzIEQXZk2lfnC%$dsC$?09pOQ~+BT-N!J_nRk9 zZLBmLKlzPx7C()yalQ=2vRB>Yybj#T>Zt9JOn!-NW{CL5!|6pMjB25g4p#Y!)YS@{A%TUJW7UaEGY)NL0}s+l5kY4PB)`i6$$d|O^c zYoa-{z1V=C{L!pt>N2Sud^(UDtW=S+j{j+UlwOGCK}fD^swY~kCU>65dc%=@6bn)- zjT>tt-A6^=4_P0uG@pR(O&8#KeXItC_NqBQD=fXA8ElxVQSAMM-x%FA3S?hBcfo=| z+>T*N7$fsN(T#qwr-v3d0(N_ss@wmDutoq1Ky|!%lqK&yzgG@Ubg71_gDfMgC5^7D z8o4BLP;$1Kgr?lJE!(KoDeWQ}n+x3_>>$3*5FW-g{o|Ie3F7(y1ZJ#ut;k%*mTAD5 z2HJ5%^$G4!SIW3jJ%90*1i%H4y|BeRiLB>`1|G8N!MxbO!!U+C-2|23(wsv-4Nr_i>cWihV&###T z5#sd1p6bkgE0+c;8evzX6h~3~1qim>^}^1}0`HRh(U6migM&Y#pPR5|+%A`X(QWc8 ze&^AVr+)I$l$NZz$8mO@70D%)d-d)$oXXR7?!}OFMn#|QTGPH1y8XY`gUfZ4lP&3o z`5#5(E~d-=$2;l*n@BM8AV#gL!>KpJ$f(Iff=Fc5L9B3RGSt(Xi&mjrj12%sI8Fkx zEMZoJTsQJqx5XVn0Ut|Zn=XhzsL9ls^O=P@?A{4kCp8w`klNW^LW8nJ@{UdVpHdPf z*}IiNBmkIr>;<@79o%-44*Zm-8v#)~=;}Yq%R#gzouZ-o@)E}PWJzcOqTbSJYj;un z_J9(Cb)d+kdh=nuW3TH*|ME-@&^?u+pGSx~-I2TH3o>V8Q;G;x85xT)!O0o2=VCn* zEgJ+iho=pulUO|EYEJR>N}N21Y%r{xO4<8%qn+C@C4UdB_11$+S&vm(!|%+wcoEbw!jm) z#Q~j_wgm{ZzV9w`n6clvcp_sLcjM+2FIU%mYAP+S$)wMVC#Ia3>?R5ZDlx6#vv28M z0s41B>1Jo5QbL<~B68P9wf!A7Itz+E_665h!Wf%hZAbkU%C0^|1QcRW9MvVh7PG*O@*rkzVr_Dd$i5oevhYYH{LVpH zw?!KEQo>yfuY1&EStD{;<1IZuJ)t|Dc`J_eoZnv1DGiYv#!@aK_yBAfuKZOv!UKPM z!NPwPceQcAdWkinokDpaTCsv7xC(&yk4uhP2Pqb^K-R7ppNL*+oDIV$f~|~EQ;E*~ z_>4O*Vfqs|L04HB^sZz3CNQ?ygB*mvBm#j1?C@Fx;%hrQJ55bZ_ZSlTEfd^XRYbe3 zrm~kCDozfu3qU@uuAi}|B9Qi$RDOKH!`_JGrq{_x($;KQ@joSdAD3_jHn{(dN$PSUi0c@LuL?l6D39tSTfkd`$C z9aRNvbM~Mnt?x3Ua7+wc zjU10!-|=Xvf}k+2!c5qqQQWy!x0v2WFyB&EQu1fVQ+0$woik%ZAUX_G#&2k;O5dFE zU4^MotBwS|UuwuMVTH?vn!aefjf^udZ(9*hQyUqLd_z03Vx zP5=DYJJBzadcrp#x< zoGAyrr}wNq4xo>;Ev`n^QL7Vcy_MYxk;Nsw2T#{X{LkzJ(G&@(`NiqEtkuJwOOjF7 zFGUc~D60+XBL3)Z5SycT!mDQf^v10@;q!T<^F{5Vpm2 z&H4^}^^=VTBV#th7LS06wM?b{I5=aCFg%FL__@>4yx=^tCvJqf$CDdIbU*tGGRoH)3eW3uj%qQ*#_wyf{bwk2oEg6?%GS~PELkA*!;m~|X; z3f;D9BXxIp4nQDFN~DPS*9$j~t{OHFEeE*MK!RwNmK>zuDf}352TO_l!U?j__Go60 zYuU+xiC=hRyY~*&;g&VywzYq~ANUt@;{|eqK-dhIgCM_EU>k7R?B$fhUz6oz2}?eb zvpgtazY=A#VK%n!4Hcy}6IfjJk-84r-4=(+Yc^O#I)qT?6s_b<* z>H=va=*>6?JEo_nb?ZxLh%s)yv+h*#+M`w@w*$W(_$VfaDVPz8p`*xWe1U_8(yZ3? zMsSjeM6o)t{|_*QLK}cUN)ZEWOmze99|RRCK=BUFRG2%iRzG7Uu1enY&PG{ zt_t5)6EL;1F%*D2wF76$OTi2&;K_B2#fooc$;NwdvttsEQV(boN)x+Nt_ zGNu$(HTv`qt!nO1P7dZEVv)B{(v4nwf1&eDbz<*=eR7d7ttBxF^w-Z5Z0g&NK+?_777UOQwcC1F&3Me?i zH4o0dzyVgQ^-xjWg7RML`I`gJZ5Tion+FnN91GApQFjDr%%j3Q=)Q|Z$74GAq>l_U z0Jve>u2ZUAd;3i1rGo>fzFGT_`AToMNLrEjpo@)H(> z0l8TCBX!^4-TTSfl^E3#Lj!}}e5rz4s3Q@=%rJ7RA z9-@Q}ojbnP>FOlcL#K$vAGTL%hJm)GWEvFccfcVC;3`suufl9xTwQ;@;3wGfH-Yccckbv%moQT zZEY=U1UNx^KNI&23;*KB-DLS>_qj}@uQqfwA_;seo3m2 z@)knrpszAwRntRp0vu6io6>P=A>fbvDqZ@$Lc2~)!vY$P8kLw1?q=VU{fh&P|DMHW z!LnzC+vnyli^8`ncfgUVpSHEY3Xw0qeERfNOdJS}jGX)kwB9Zm*}%*Jx-vb%n-*14 z67`}=YdB26;Jnq16}=7IIzSh@+HOR3td&qv=fmQx0Gt8jaXvkJHmwF0w))FTGDnED z_k}?NcfI52p?Hd&;PXn%kXOlZ0JOKA&ENZ7)(zuxz8sB{)lb2Ew8JuCl3WD z06}LE94=wY`AlT)p6g9{IlljnkpB+oYeL<@h+NPe1e9)#Vl4@A5Zo%(T0OARBcG)| z%z4gCO=WVRduV_11IPjUATKEBs-%;gwl@8QPs0;{)$gOC?}H>W$9I3c#(Hp`rF|?5 zuN^d908R(ax@_Op_$LK8-Yy;0`Lk9fCj2`$p`TN^4rqS3N8C{_&`^gn;RSNF9tO7IsqpgP zu?xR;Os5zk zZYkivOzPZjOVhVsAqOqyAkCmSM^EnkEJtSI*U31rRHh=o!tRdXR4#Bbp6}mJ+NifT zfgU^sJ|@-m5?h#q7hR{LCL-Oox4?nHtTgIr7r9mNz?aLO6N6(liJ-|(4F0ZN4^{?C z^_&iT1x%NS)J$Ijrh*GGFRutI|JOb1YjiZsfKkK<7=B>p7QaICRzg6Y$-kgcjS-E> T)*PUKflE>LsZ52mN#OqghXEdX literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png new file mode 100644 index 0000000000000000000000000000000000000000..a04727eb5b718ffb3e7f6c0ae3807a0726a26596 GIT binary patch literal 28711 zcmb?@WkXbL7cK^hAYIZ(H%NDflytW=NOvpUT|;+@G)N0bch>+S4BbfAxq04m{=wNF zbY|GI?^=1SYfYHqCn;n^d_*`nIArOM;>vJv&o$xTo-H9f2cM+&I~jui-q?TCa)N`y z2CuO(p4Hp7tir*O!byvZsJiR#FWY?4S@2-K2}u-Jj+cNWn_eeH^M|t;^Kj)y@6kdB zM#5ORqNhHfp!{&bH$=-Z`e2!mh?jGN@vmDN5liC5?*R6fX>S~VVafY@!673;J<&`Z zF&p{|RDM^-q(uu@=#5zXo;MzJvoKj}-jugSsxpZ=Zoz4>S9qZKqVHntam|9f~ivK;{q z4qx|nB46s<6kGk?oFPS}_|r}VzBpadBrZp2PmhF;Qh?K$7@ANMTv@4}0o(}9ySKaG z@9T$6L|j5Im+v;{uGV{Db_gwohetljOdlN`X%H9=dA(B2((o1T zAA7zPU`LnqcXoX!g?Vq!(EQcw*SEK~*8%nqSb@t&a1W6ix5mC6P`?vGQiNwYkP{I| zC>XI@1h46*7*lu53p)pgiT6uos3Hh(jK58pM!_{UHrM^3Im>~=_3p}H$gM_@Z4AR7 z4NhC5Q#T_slQJ=E2^j^2SjacyJ6(q=oy&SJa@qQDZ6G)UcX7uFLRgngF{2I@FP5L~ z_3}@Le1}!Mm+#@e!lOvAp_e8NiZeY7ALj=%J}|sTcm{{a?Q>ISxXFYqY^7IfH^OVpi zj1aRo^Zv{JPq&%cgL7mG5H;#s~=&=6ZTJqX^?>C$Gv= zm>d7^tx8a@vbbUOf3MYZf3S!Cngm-7XO-XTP!fd%9T2O>e;S(6(m_+yJh`*86G+fN zcIdCqPgA#2h!9ILDyk1^ZpF2Ddc?VCRJVVjkrF{b0B1WP8yws;v_hwGc6OE(GJLq) za_{@t8SvWeV9{l7meHmbJgqp}*VEAO>mxXt`|B~k_PV+{A9{NvY%t`qL&?STrw^s7 zyY+MW>r0BPPxHuBUblC3b@lbt=k3X1tc(0_&>_OlBHLIhw%k$(aLtA+SKm;*?Tyxc zv_B8^@61^}GB7Zh(@^aN6LCFQgq?fd`wB5j7b*)qUXL}}!Sg*S;c~862nrGJ%{Nqj z90cbZZyS1g`Wqa^FJoB(FJ8R3zrQ~?IMA5MhllAy!5Df$MkY$0v)Q{>~(2Nw%F$7)|M1Z7$CY)p2!MV-w0z`lW6ln^W zmzgp@RaR68cwez3$?WXuj`K!nUqm?6%AdmrbascJ?#VWmcUQ`{w8O#uQqs^+(9js$ z-DQ2mLk!wI9#_}-CQOQkV6TsJyV=hovh@rj!#gAB?$NWq>+sOlC+^#7a`S(?m4l^C zh@nJ-wP-{+od_kloN20Ej!di^V{lejfu#A_*hizmIZH*qz3~?GDNTw-@skSaXyMyF zac6~`UtGA>BS|l3VJ^NoBg~aue8YC2`gdol7$%OLjioxbxJJ8xLd^eBr}*uv@2!nb zJ{{e`$V59QjCX9880e4lYgA$fyg(qd&b&TbqnUD4D&-_s*lLT_`t?ms*MB-+oKtr# z)S8?A9jDj$q1)lBr;ZII^xv$GowVKL+S*!ueZ96z_QG}g)WX8fiF?h$7Y;wsTuUrC zXF&tnz8X2I^a1xUPayxzEw{F-4T4QGX_Gtb=*ul`3bzh9`cebe1vzZ>kbl#qDnQ6) zEU5$>{_Z$?y4ctRg%S%g+`Gjr->MKj8BaZ`1j@XbnSZ^#MGS9)F3^?Cw|;nCuE-YR zn0O$`6i;0qE|ZfDt+%B4^BrAlm8%4Q6V@Odmk`e#Z$CT~mI|Rx(4rr;2jwc37{;U%$rNkwz)MJl zROWX}iRzjo%V#vbH$*I25$BfhWUP*x}VZ>w>7w7Ol(MokZV^Tu~XVIXvm6$7K{=liBuDrLG zetFm?720+nV*xGKMXZ55U3ebJR#~jPB^51Aowa)62c))@21EOp_GwAp zw&vE>pH=p^qnU1d@Be4@v9u8}l)St`OqFOb`=%-2wSuUO&u&|wFOAxgzW(>%iD4`g zGbI|01bd+Xi=fnm>VsBxXB5%Vj&!a^Cx;VTqRnh!wC8YGeN6BJG>9`;-_45UU&Cyu z>XAfgpY8GdZx{p=+WrEX@7-7?P`PI7Ii`-)j&25B1B1OIzekzYDCOr?PuABKTTWz= z4pHbd4)x5V(^FQY0Vv4DlAV*~Pp`|vOx;@lfU0U4;in_csWPlO8qdx3r|pj>5%T>b zEHq<{hzP|0PiH`(>DrBF^O}rsl!gI_=z9e#cWt8hv>nZ=|n-q)x5`wXjs zzIRs_Nk68&x$j1E$zH<-*4kl1CvQ7rprA@uSP5 z4R51$QLyBnFv1XE3SXlT{#oL(mD7o){jShxyUgpj(LZ`S%1-m-WE|AhlNXnKcK(TR zpm=$DcCE3jexgbsARyRG?ee?;Yis<1Lk8SmctcIiZwDH!t4>tkSUZY@0T|4bwHIr) zqjA;O%iTRS)b(gZPrDEDDrl4yPVq(DM{$GcuePgM9(xrAOiU{RuKVwpwKO&VV3~Mb z5+^PpuMH;Ad*|0hvmqk_2dFx;v9WP>V4JnZ>o{{G zqn*)AzTL85dc>6EIJzZjX;KUb%=chwIJ4A^t?^YY4w=jZ41d6e)v z-2B_A*fF-Hz<8|mP_9}F7sXRVfBQ-yTd<(i)BKjYuxO@AU(et{EI@V3MvE}9J(D|=H%$M~s; zP){$fu?(KG-k zJ5{U@BAR>tbh(_@U~HmA^zI4{PCvtzUv+o|;=G`q&(+k~-tnOrVIagE{_}?v9RzfO z4_E8(V`ma%aZl4H%nK7I!;iw4n4VUx)_NBv{&33tcsf9x&F{4Nw$Hw^_(usC{_5Vh zWAzdB@fh`{`M_a5RN_7D3p$xBp9-a?VDqacL$CQccP|w+_2Z`9!)6$D);q$d>uxfo zeIr&n?xTsfcZQuTVohl&tuLBmTu`;<{`FRNN_?W#@^?=V!e!+-xw_8g!W92jH8xg) zttK0UIeIg$%2BN!vl0*ig+RROfyZm1$1Q^gn1KxK!qSp8-Y;wp zZf^I#zu%C_6e=H9a<7Kc_9rJN2L}hI-I~1jN6Vr7{kdAf?`CQh%sI>bZ`jjorfxB7 ztQieVd3pK!;}D@l&3F|zCY4w%vs^6%K_Ip9aR~_tTVvT9=-@voCJ%#Z5e{ zs%WKO?EKJcNpm#G4e?uq6LxCxy>GrTXN6>BWx0-0D50U#MC--~(#72i68{EwAc9_x7AR2CiWrII*-zDI8{Ms*v*~timhX$(VW@cvp zB;YD!M&6OdH{}j|DA~}*W!7hR>W{|{Q5`0NxVkw)1s3(Ie6NQLMz_v@4JV81pP!%q z{re?4cD-!bCQ5++XqLc`%Io8$dAY@FCq{M4%d(>XQm9?E|5B*>rxXeu>j>M10uhxc`JMMPND|z|5WSQI8+1Y=q%-juR-wl*kwwKw7{5y&9^ZxQB zvNoH(9|Tb=HS^g+j!^4PEQ&k=F56>=^ZkX|%C?KN_U1T`E0R}m?6GHCV<5V72O)Oo z5B)Y?Ha4e&MGl{Q#-~FWZt*U+SjLzXcOuDWnHn1)Ac`Sy1Q5~zi4CSt5&q}6peV;3K6H^XCfk0kT& zb}LqRL_@M&Dsl#RDT74c`zS3Z_;n*QCdouaMtWb=X3uDR=}G0u_yhE1%ll?Z=w8JJ zyTyL(Ij*1FNL8iJfprZOlIEY`y^FyXpl0=XWMri6;bt!&Ai&#zE7z2&4ewj4OoKCI zWSp!F7bKlHyI~)c(*)p|w^Xd*TYSQS>W)O#P(b8-Pa+H`aD~}9}eXmU|tM2#B zh3H$jxVSDu{H{X0bwVe1sga5K1p3u+c-}3&0DmoX@6TFFo`3|pfJb2IAtw>1f4QRNSrDFp{ zb3yttQ|UXie$vlbrv`r-gtfV~bscH=M&N62Z|{}lnF|JO)W5VQN0?0YmR9Bo^-zi^ z!~5s;hUx@nnSPzXa9NG*GY+_ue!~fmPf5Nu!Eqh7^@@s2`A8#1dZn;f#;Ue@GutS5 z5~dJ)Px{)-EVuc$(Op1#xH^(5ndf>Gm+xspHcdKzSMF8YkxvX^w(87Z0SQK6VI3JkkCSA=jpk~+G|0NwXETe5@yjzZMJLi zrXotPu6%x9bJM4DP%d1R4XGYMjw)d{89J4;CvmRtSXA{#WlEhV6l=QwC;%f|l=hae zE5;aP_DV9>;lO39hU;NDWE|U!Qq=aZ&wi@mh3{vGkU$n_z>Y5(=*}a(alels=3Zi($AcD(h%Kdz*TJ0AHNGCVp4maYKKo z*u5-uE&RRbJ-$R{lN~7xp>DVXXzVn_H9JCA@~_u!39fK|$%$+fs78P}7$1+lqfLq$ zJar%OAZ4(|N^qT~ha^kZuvwY*a@Ez!w-z=*2yI5{Pk&gsWTnj}+r`P$L?v>n)zeO{ zA*%*NeaBZi;GK*0@hz$2ujTV8iTBQ{*j9G?^<9L~a?BbxZ<84=VLyhG-`LglVq+lT zj_A)f!a5G5XQ>$k9~sXS!iAh}@kPlEaDmj(1;N)S!gxlgb4;S@`@oM_Cu%s+5v2U$R z>Co1UAVF2#N!33p($D$sDw&eDFW?_Owp9TnCH_z||t<7q1B(5MA zmy|e2+ficR>e^^1%9&VPh`$Z5v&b{TsgjVS)NjsCB1%PnXyH56u7#gD)g?uzY`h#$ z)quE7q?wPjlngUOz9T1_CgivsecF+xYbjA}5Zsa6Z%eryLf@O7Hl!H%YK`K5mG&Gd z!6$nZ?|%9I@yu*9M*UpD>|w}lUhW~N1=`F1p@_&jqfrT!W|6btpO$?`6l@A2bT$&= zSSwp2|Jm9Q(mh3)hz{KpD|ORwQ=qiV-^W<>^+UR~nU2W`8%W!7cnxFEx(ucy;C-bSlkAny^bjxnTY{K*UmLd z@p79}1GcEBsAtA$3dQXSr$HaGKe<|3S;;ia5zDylK%1O4bDkF+#(U~4OS*=ol%w`Y ziBTPGOiw3zM_mguPiG?)+_A(jjf8Yy)Frtt*1ruhB}>!lk1>0Q7%w^LjhB3h$fZ@n z=?i>+>UFVi=;^&uh}?0b67O`*ZOLHdFaKq!J#{{Gc{#b`xt`OZ!7Wj>%}YlUlfVwS zsi`UNZfH?fQlXvfl*(Ctb$?d6fcl0ZeoWuBb%q>Oy&pUXQN({QF!ZS(z*TI15X!`_ zK807Y{>(J7%O=yk#&VR3|BaB^Y74);Q^SFb?7Z(KtZ=MwtmyndrYe&U=d?084yX=3s4GIazb8vwD-< z-90%=K6NqnsVn|cvE{EJKk-)I&sTg7b&$=X8u?n=rM*lIar+4V9 z5LcgP!aP4C6EfHT{pDoh8x=b5cYqcY{So^xw7Z~d!L+u{if$QH3Q6()y6J>gS8u#2 zy;`&WJi^Y2Cha{DN(ePIbuqY#iZ;|fPB5I9Woc>nk(DetHBspx)-p{KCnPqK5u)fk zc*jvyANgLk@Qcx=1VkPQvalR4T31TrIse<9P^6g_&J-DxIKa(!35grJ;QXwlnMInh z=&NU0BBmx=;*$d2`~L>`H5u32T<+ zmaM6PBxrqoeYaGcW5vXn@j0H|nE4K&Ot(8fQ$_uv@ud0*V+R2UnMYLSl(DjSoHnV2 zuEW$1q~#>Z;@tUtuTM>*yA4^~cc)7q9v*`Ewo@c+km~o*K~&Y9^cR5a1V3scH4GH3 zM}-b@U%G~rNj9EUhU2j?HF;a5q+1S;4ZUYpgCa<)3wi!MapxzFk<6d4P$hl@`q2%} zXw>86Z;v=x+(!zTC7ah^su?D_)jQ>3U29b^R9rG%5bN&0pYyJv1BuV)>VX020}TLy zwYs1DZE^zG6<^=llTb?pbsL?dzvO~oOkAIB)f*&iAWh!dAB^bY}lvBe7qg1}9oPqN9Yj+=K=@1W&SKCKJ#oZ1?GB0shf zF~5NfB*hTBpM$U+NkRYet>=s<`AyJB!ZYR1!o>26$s+}F6c}J7R+>}^(w}5{k(LRF zh>~8<5sSy4-d8k==POx0BPJrs%*cooCj(jsj$-k}De_Q25|%$$?j~xEJO3#8_H`K+ zzOTu-5wk%%bZW}!;qIE*dkqN)DG>pI^(^t&qUv>+k}t$(kso zV}e3kav>BdDyqB*8eAP+#j+1tiN`oDxxaIhLr>hj-Q6{xTY7uzj&wxeGNYiPme;Re zUH!a1rIa7ZIxbeo-n5jEzOEoG(BF9O?C5xUbG`>wr66!V4Rjs1{Wu83-(04a?jRc! zJdlbG%8?0HU{_ZPC4Jerk6%gm`;c9;kVh!fiHgU(LK5ZYC`ZYcO*B0^CpO=^j}&C` zp_`m!7-7fO&X2~F_)%rd8G9csEntYs3$0ZX6G}hsuIioc-R^H(4n_c|mf?3ACy}od z!VuZF-pcufJr?Nkzr}iMU97%o zQ3T~Q3<~CWUvIW_dy_tF!mjo*?7Mh8i3YV?auYp|Dpx*5ZzeDGr(>?}dSRf16k1Dn zl2A_Oi>K;HhC_@p8e}97kI3T({~+p@tN#$kijpimhUqC^Qs76)9HsZqnl@3iJq4Ff z;Xh?ws@joCoa&|lh_1kf0cTxXTMG>c#`nv~{088(F-iM$zWPv`4;&^9?(@2{4>XkTVy+|Hw{;ecah z%_vl*HkHi(?h}irEg@Z#^X+Bm2 zA!?NWYBnqnWsvS{`{-EF`)$1(chu0P%8;YtsXIv9xIW@1Y|hiZM>0k2UaRu({bXUM z%8n0nih?HY9v4+lJY7nMRQXIB#OyV{jUMY?O#%StDILOP(&cvAjJ&A_k@JAb>EE6R z$LH}W)&q17+^no*ZPEdqe?a0o%0~KbAL$i9^^*#sI- zDB296y$048HWdxJR zM9KZY<-uYku*(eUUOPE)IIm!-ja9gk|MY3lyh6>F(D#(}dOyGQY*Vm&==#G<9Cq=i zOuFktBbIr${rQlVmVnY}|MnlBDd3SVP+an>!$m9Ga|D0#&^<#4$*^C@8W{dZ_buIX z&ekHwHMXANoV_N>sebE@G@5Ws(hBLT=oHvE;|cYq`QXdlv_JOBAwHdd4!g zC^J9Rym^|_>IALf4>uUq5!hrTXSLjRoP75Pj z83Chqh@*FkUd=F%5=$~+KY5Ecn&nrbdi>_mpF@RCKUg?uXT+U-_v$zm;-L5r=uyCn zl)TMrWO&#Y)z-1~|nmJA;Y!~8*)31dNzA33roVe%Cqlm$UgolicahH%enbJC&d@@U$7`pS?DuU)i zR=Ya8P)H)7adPEi^mOT@n$gDBPVMIF#&B1EsbtecX18YCrw z9&XGsSfj`nt=VgOZbwE(gAisF24ikL_J3J0`)6QC=nOJO$mhC$3~Vhb3Chdot?Emf zzT^E}{Wxq$sD$tM9sXJlA()_&6#bLHCJi8ROZD$GJf5#MKE>H7Cn$KDV^qIs7mrD6 zdN-PCbocGiX*X;nV~K8=J-b<&d7(EqGXL}dLnwOLNKcK0wx{W!)&b`&8`bMe07!DI z)U~8DLkXL09hne=n$!iOcXlj^w}f@%i(Fr@Ok;+ak7n@rJ@Av{!wQNbZ~g@E&4q$; zqUT}L7O}v~2>>?@at-VK4PwRIxw^WVpMPh*rY@xXczk>mD0*AxRSKk9-KhWfsE+tG zBd^2Xmyd$6*$73!G>8P;2)QCnZ+SK|c+Y!z9s?nGUEd)YTEr(1*zI?YglM|%NxjLM z@%58!oiAZa!w04J&#UNfr%^blTBclv-=p-X0Pop_#C)7EC_OUfy~*Zi|G1;zH;A08 zjW);xtd7k7Nj!+I+Yi?4Q#I~4xz3P~2*le#t=+gUdf-(N9ea3|pigrh)<&`d$KyZ7 zFVlWXn&N2M4=tZjKv)L9K-9XMab`Poxw^J=SYu^k+fe=eV%SymwHY++{n}lZyj91z zozI@ml7=njGX6j@XRK9Sp5oFl6ID?6Qh%kYK^ZW_!(dO&_vT>uNKboq(t~UI;>RPX zAO9P%^F2#nz1#f#`!_(-uF`)&%!#pq#U_jU6XxhXkkY|VjCjxj!nLlh=jc2pM%Xv~ z{Usikv?UzA&0|7Jj}k`cA_&6juho-0bXl5s_L~=aDOU8NW~D6&BR+Is{#l9LaOc^k~HN6L*1)*VEGj6?7jTA5;=S zU48vzHEV17!C+W%QI0N$Vz+z|C_611?L(O6E-7gh(M4_cDcAIiHzHez}C ze#0_BWsRRWrFopEu;APDw+wl9FAQn<(%H;YDsG|rtGg|s#~xruD%Zga%2?aIfSO24~xlD>6^p;tPVf0E9MS~r@u1Syx$Cisq8ySb(XD!XFeK;(5K zxyoGUuXciUTlEc;UWX%e`5Tzh{VQ}nL#XH;$*rR0@sp-2(1omRsyNlki=aGeLiyXp zbPB_TkZhsrl=;0$gsHHH5-l3pX`!IS#-7vK*lDf~;^d0_U9-&jm|6!y}ds395$Jy218b1lblqlqC#@qFy?kIr|icJCG|g`d)V zTw%60qo6s@(X)-yl9D%9fz1+hmxl=U%dPT$eI7V00NHYE2*gUu>5gRqgcO zrBSKxa}7(G!Ste&mf2yjTJV{MQqp1yT{evkh>`($%$Y?p^YG9T(9+xyWVPZ_8p6VA zv|IJv%5+=t+^gt$x+HwgM?ulYUP&`V&kQY4T>P{aeXwgp1d2RFSMbm@Ol%IH5P#Ct zrpchrg1$WdO5>-u9LI(UO_uaZa+UllVMxmN`e-YKTuF{%fchjzUq67T7}W8>^@I?v zK3p_1>osFV^!z>fdE+T>g{n-8D0E&bb&!#a+;^fdGbUx;5}0hePs@H-zl0HyD?|jXA>1)Z9;W=G%DGgRc~!n2+nXsQpwc6F_#3`< zeCQGvZ5r=Sf0Bd<;>+w5F`RIv^a(82qsUn-TFRWnDjkCM4%qMCf%~=M-^HIl4wN(L zw_02V3!M$KF}Gj+jbLu4kyry6o=4IGFMeY-At^=}ILLHu96*4=M4t%eyw&y?C=~&w zC0@MM<7{)3;8P)SMPnYC$aeC=@FW_(bK`O?UtrQN)?W-Ub4e=GTa>wlRAhZdN&>PY z&TdRea@uF5rZ~;uSSgYhh^;v#;%l}5&SQam9Sk@~4H(-XCAMupaI7@X@&JYH7qtc>6(Bx0!oMowB8cMZbp^nGBurIYVu% zv~Oyq#$nzjvPwD`<=Vy!C@NU^a9Hjsl0R~a<)W>Qk0uP*mSpSAzf+~!LZR#$nN{ME z@ApHzE?RE6%xb>F?YPo{`RCS2Dsj0^+SBQo(Iws&(h>%uJjTM&mFWsGLjx1iZJ_qG zW3G=y(_h)ey7013Shuj326mpXg7uBAC9iP{3dd>XNmitU!Fj&gZ>sl}c}bC0Dg|lw zcbyRI0*K_Kk+=@i#^;c`;u{2Q$y3|(ihR*>{A+V@3XCTEwGP3v;r`k&K{1`P{{GnZ zn%4oh)n}Ab_@B;a)C-2>^rG@<2m{qNH@PRbhyC*Slzx!A2b68%nuXYL_#L94l2Jnd zEWqx#Xd1J;ZcjL<{R2f-(5D1`rX+%x-3q7dO|DszGdl;lc&bEhE6=WI5z}-#1{6vc z6=+6hf6j3GWr2YZC1fTtaXDGd>h{FqZs>~C75W#u=S~yT)uL1J(WVXYcR+j??@ABCTL4V`=h6T_g!4Wij@{k z01kuDb6Z>v)G4zO8P2D2XsN3=EF+;l-YMQ&j#JTR-}rIswb0eG>$6kXkRzj))=x~U z{1TXZm|<1SBcHwD@vm>4fS57-n8|&@Za^l}A*S`e8TLc(UcBI9c%)T_==F^IhYu3J zwk7UkQYDKE?GD0!Ny3X67Px>EjQKJAEm!o;V??bO=P$_jun$EeW&j5#xWx6+&#cxQ>{QWG*@qJ01InoTXj zB?(KK_0)%&!7JSHkM#73AE4tXS{RUy_dK2?Yah+Zlr%bEE%~EqXPkW~yxCp53?$fe zfKt4M=H}+6t~1O4$Lz>goMz&AM7_wQtQlJ(^SdL*h*J$uZLijQjBM*^b)MMSj}KFK_)dIlPbIqBg)zs`u!#zN3Ei<1RFt7WOzr7`Y)}d% zBqmPA<@oRc%@T9^zFC_fn#$p zCKPz2<;cD$?oQbNw2ivjyzw7|CX0WN`I54(5@*!*EEfD@g}z*WR!d07A+}IYmXeh3 zgriRZ8U84n8F7l`?X}SPDpCm9YI0w-_e()EP(hP*^W#yLB^%`2B~nu|7Gw+IuDf#^ z`F2yAeJ_`+xsuXgo~tD&6FGp#{m@Eb$l!PEfUqNL1HiAQCZ0vlDT*z38)dv03+c(l zf_B1%LJfV7pvOcts-b$mBZ06Gq z$Xj^p$_ixy^|fzFLU{&$-j6WwZJ<-=&LF=ON=yzN=26sQg|I7-3{GL+C0)aq{j@|s zPxt%@ubPl&{~@PV78jY=Qo<}QKwC0n;s^%_7%0XVh!47Gu1oe;mKFK_m&r%;EgRlf zi_)1JEaKu=42b2)iOI`a)`gz}&<2MNFTWu35T*qU*`&6Mu2KCO^k0GwyXll)On-?G zCxbrp8ucy#xVu(!gHM08`KBCC$%<@HltYmbGY)lXkqEYv;TO-!K|vvvbk57hoWCT? zblpm^wy{j_UKB;x!MU4Gb&JLkZYJ)#c#kxrI^kBP$00E=}%)XHf=QqpI#WMl%0R zQ+m@V#k4MRI=-81n6OQiqDMj1w{2n*cLvCuQvgWD&ik!x^Y5FpQ&SbixPZY}4hasf z6MqxZ-5RJ89tunj|NcMqMrn_i($CRRLOlE^229idE|fCdNp%TxCmQ71lWtF zj#-2V`K(~J<4R@Xv7Dl(6UfQQS**UcX}bQZ8+Af3ntphb|Ch4o_u2kf-ZnH8ZC}69X7B^<6+L);8Ymlk0P9VL{W@+}uzj zD&DBK??IOY2y?9GddTk)%FRJRN8smME%_CThd(Y44)Wq_2R>6U!!qK{s~lRt#cF;G z%PXT1;}RL2z1C`)pIV*Bsmo^Ymr&@hw=Zl6YyzsQKe*`P(_UjKF`=>x2pphA)v0Mn z_XG0Cf7njj?;}7$jN1I74j8EZFIIKJfDL^6+@rT61!E zB!e6ZB!j_GPiUvHj#F`|TO#bPYH=kxDvBrN79chJ{>K2A0m$Mmov&~Ui6q@h{Ho45 zhgCKyAadQVT()xw2r!b!gM=hT|0a(2Q4A2wSm#{(Vo2Ob0&NFH0C&p^MQoEq5UON8 zDy*TAQyvj2dV7IB@prjJ{2w61GGdj8TMu;$_yD!2`?5dlo1|k)Zt&S`VY`xugQ4*Q zDq6D80@SWsXyhumJ?MlRE{QY=4IR*OcHW9ctK~~qG*6oi+Yr#Ydoi{Rvs1!oDwzr@ zywxB&GOvb2>%aVk5&G63KWZK8d+Yd$QDD6BIJk4AOoGVz{mUl-IHl@CTP-MT+xgut ziT@i=@I4)du+_Bj&-Fy$X6CClBnDf%rEJQt}t680nY1}6JzdOa}60cAs>Xj3h8-^3D7I6T>!ZagJH{~Oa z5gj*4w~Xc$8CH$e(8v{Qta@z8`;;Qt`U8~bXhj080cYqr7Q1T*1}PT?duBj| z+T2{V=VqWrpJ5BVqqc#MS>97q7+_{%8k~7qzrudnYO#zRVW049MRit4MEo97eM~S$&BzqYCgP1FgBFxV4KiysIyRc^&si}4loX$=_XTw3EPoXZSy+dThj&eGCOSMV z^fefYN|lAVzJNhiZm?62PRJ!U)Rx4J89qC9Lxteu404wa=Fi_rvlB-?M_x70I(}SV zU&kAuA7!QeMPVrJ!6P70*=m`XWvy6`95CIps6NQ+^04>OvJj(U2TcQ=hEj0k__8jYU0-k3wDe!`}Z8Yyk(!FesgOSD8CKqjt|oI%Gcf+I6GYd^W{IERxz25 zfS1;o^oNnMsl-NJhNs)q2i+CxJ(?t$D*a4wRZ5m&L=*75$Q-6UV@dj3Y9fb1`%z|V zei5*OzK-&6PN%YaCG)Q1C@t=04PGWmeWW2`xPF`zrduj8P1fe{J#@-mM-HVSL`m1M z8y_X*r70s!oMs6)xnEUe8is6LtyM(JY3e>fHCnOjd{qT8iwaZWUJVv2y6@NnfV zjy%Ui34u-QXEl;m^e%g}(5#oAtLGI*raLMsw>ID!gG~~auxEE#(7#}k&ibxkU9km(FIpRJBx_z;*_-I>hJtL&Xrk+xf zq6jr=p`mxLU-4&PW>Qk+(Ok+6JTM>2nn}UK!Non7KrUfeO~qd{dVwH}Y&nB16}rG~ zC1rC#NJIp?P(GK-eQWsV+p+j>T)n^L%uROLiN5sEO!M18sk(%GLQ6A0lBm|eD#v?K zt-NRsXR+Pl8bTZ^FV`yKV2p;Ag%?~)(;c4M>2;X=d^Y*(s|``*kwST>z>w5RG zE2-$FiOT=VSw{;& zB#_Q!cdB(NA#$jImO`&2wjx(j|!->`)LA zF6aOP%+4fGK0o8YfzC9~&PdqUh>H^t)cI()+=Ms;{$SVbR_#8pkD$LuQGX-k9Deg& zdCA~S3X@*5^Ufqdpu+m)kfwh9`l_k{f~^>Vi_~FeUOv8b_TbA>u*UY&q)N1jC(bMC z>3OA}-s;CE{`Z-g9dNk7>*iIioB|rkNBuO=r$b}YKo>&R-jMy#0iO~6jR=AwYWV${ z^8N)3hPFgW!OrG%0~pZn(c8{vb-+OLfIVJUPsI~(RUPBA|Ku4+0Oud|?b{4~59L+c z7C<1+%8oR*kfp#tnd2wROVRfXvui!>LRy;J-cbHk1j;gxLmhV!?TP(sr7-*kOiWB$ zrZH6?Z%Qg2zU^bmiGP=uLyBm%YttrN-CrpW8iPC$zh*~tR6q6OM2o%U`%V`{xM#ZE z{DStOxuwN4mp3<3&t=;Yt&K;&>)T>VeI%gJ^SnaLnyq-VL#{H-^)0~O*SGyo+oxpQ%OlW4T{KjRxy) ze8~p=C)H0%VpMXY2fOk9pbHN?v=Bav=;y2B2v&Yn6qYYSz=0@P!K1A{uzLJ{O~kO ze1X=(=QF!Oo|03JLIb`{1n>#@=n$f!)MWpgUB@T8D8^cOk)xb0NyLfi3Nw6D{Ho); z!cH1dztw%BCY1g4RRE=Q=fc7QVj*en91R@%50D(3%pjg)BT9>ej1Ufr)UQp;dlm5- z>#{0DNXRfEP%y-Ce1afbOA$pcSv=)CiA)B4XM%iu zIv0X@PrX#^4WQR)y)UK%FrHn{beH65$bnreW&}B1^A0)rvJCkCwW1soiW-hue=vU8 zVyVctA|*JBS93q~YSZEQ2vM9yQsk%@BZQ)O^}FN|2Q|G~uqe{e{~1c-OOz-0gI3qC zRQBt=QK0)3kilEb#WiP(n>jiv0~)vgaIQAIGPv*Z)sxd=(*!n8d1tav zmPrbytU#&G5V844Cg0(Qx(=a%ji!M%Hc&u|S7&Euora2%i%-n(r8(T3=#=?(v-HdY zLkbL9ZvQSLnFcysX%3}wdO0IPFiGt8@5}Ypa~Jyyr4A)I%L%C@(GWK$i*ot zf=d0~RY_C=0Zv|WlQQ=+6=!XPT)jW2X2XZP56{hg-&E-;<$_&eHOVCNG-do!Rhjf; zUgDS*ejalkMA3tlzo)IF3DS%GyV16uBf|e1LTi8=M@F_2@PG2(hHV3?$0pGbM@{>+ zss~})lQJY!wc6|P6E|94I4f!+0)8PNW&D5#<>=$%D!t95D%px(r{Z?lPdzLH*g9Cr zvHoW7Ef!|!!j~z5W>4aFjz0ZKdVU5|0z1eGQJeEiTAk=I7{@h;bej62Ctx<;;9N&PLZC3yMSrV0lHrkm#DzZ)mZ`#b^=tHaodQlImgcRkUv?TdYjSDzn zP|ez#t1LHvDf>}`EG;c<5?3TDhwSCoWW_3%#Hg59**q1x;$>bcEVc37B0&r~i)& zFi-$PyZT7M%E?LPhr=IWL5&kpdhhTvg%*9`096$e^yX-XI;|>2rRlp$YsH$rbWCfw z!cN(JJ&OKZ7^%7?IzBl%nH)BQ3=Qr147xis@)L{o6Vhtx{$dQGfZnaTSOELf3#tH! z!g0|u$gr9mMji(!N1=MyCA4Lt9F=VFrvGiw2hfoLSPMR-U2E({|Al6|YEBVEv}4p* z^;sOQ=m_U8fK*oWci)@!dffB77h*a>`M*y%WY4{YV^CkosRO^(GlR7HL@wnKS?K@ zZL@k>@f(1;fJU?C-$2rLoyL52L1i;(#I_9SK+;-R4~zqcw(vV$*7dSp=a2y->?gB= z(bm%rJ2Frc$uG*0Sp`G16qDz`Qv22iKvPXP70e!cU>D38jz3SHBwwCghLcDJ&>uh( z>&ZbnSFuWI(7~P!WD7r+>VMB^DFI=cWdb|-AnS7oXtq9B_Np>OOG8De4+0`pRFmM! z`Qs5PMT$&S-Aya6GD6(Ap<6cqTxNmT%5jQFy7T1eW` zKrQ=IFr(wMaMJIL;ND;48PSKu!PN|}13KGPtvcl&N{2>Nga6x0dRA)f^@u|p4rdYi z*J0bBfGS-q^|0i3TdDnk9yeqkv?~U7Tm_PyE#&#Hq26i~VY&Hy zrM&XtXCR(bZo|`Vipt}*2!TAI?IyZJR=7V&^GsN;K`V)Z z4nk4@XwxMn`yVI-Do)AQeE@zm;aD$G>_(N(ae1=8#~*=Zi}>~VBr@Myr)!Mq`scG* z+X{pr(HkNMJo@q4H49{M^%s0DE?v>tsn*#H=GTm{P!E0X`EXOBRxit?nt ziJVQ5%Q^7!boGWFJIkQ+lr0<2Yqzxc)oUR`uA=e7T}(wCAop-&xQq$Opz{le?Cs!K zG)xnv1m!>RV5;mi;Tc!#4@IKG@>QgMI*;bM9Z4xkNzhzb<4a)6SN~Qh`6ETB1wclV zOS-rAc(4LG1%2WKhLYEUpMKTD{WqbyCRTgPa)5={=HAF!_m59;pz#wpLpb5uokQfC z=g&Y(`)HP)vyQ?1HW&cz)3ny?z8Rv6CBQ%o3aaQS%m1udmCxCn=W6_a+WPKzs{8QoQ+KzJlqeJuLS>V^Z<3J6 zxXIpIvUk~Anc0z@5e_=Wk*p9ZapHusj(tM*dakeg_dKuH^LieCoL+Rk>-v1I>v~`7 z{dKfdG#=gl?{4MJKm)wh_K-p{$Jl*tF0Sz$JT6edxXRGV^}u7wc%}#8yp1rUMtE)BlDq zy)VCD217>a9EP`q&Fnu^xVyRg>luGjKtvb+*t~G;!)&yanw_bszk6)M#!T6b)A#v~ z*Afu*G`*Y{J2dp?EF^ZlnEf2~7AA>=GTAd@$obdBm?xF*1TT0>|tL;%^VvI>yJW{kbFQJ^g(CZuP;mPmY>oZVV#a_rfLL>Y^!yk@FD{It_<# z+#a`tdsNyilV~gQOv%^9x)>i6oGvlM(KXHtwfieQ$~8^|EdE29SZj!l8kCy4Bqk}laUJU+uczTg;h>O3sIZ0KEkx&JN(=`w%| ziz+I4hSEVrOa;p|4vG8@R8yq(f5XDOeaOR`ncw#S0+MesE^%*ljs-UJLv^9)k{#vo z$|b3?7o2@a^Qhq3`eiCOcly1+z!vPstoiwQ7}ww}mz>WQ6c!F+C_g4%;Z{yfgQU?Z zQ#BLh{#jnDaG((zfkF%YpHEqTeu+wX#oQVS6dDbudE&0|rO=vsRMh8YfEI}s4P4}D zgbk>5#zN>4^&5i`y`baa(ItxG|0&j4_v`uNaGL^mDI9c?lf!*nW5dC?^%p%WD{C$J z)c^do_U%Jw*6D>y$T1%`F0!4{7sw#_@6?b#ZggzqyzS=MA;J|3GXdurghW>;Srx>hz^64mEQ&{Bak64-cAlAqMSh;|NlHX^ z3JP!&Q25%_yh5k&UG?}+FLw$;k>&O1nJE(z*eIT9dQJDh_!g|s)2t^Wnm049{azr4 zlrQRAYDr0npL8W}Xp|g4HP9MK$ui#RNh~X;Ag{W!wT(@LN+(D+zAKok?3lfPiu^vk zel-kn%0)!I?fEPO+)vzRVcGt_pMXVC5fMMsh4fFRvaTG12$aId(o2Z_&iXyViW)iw?=oo`Oq1AhBU|G?=?h4x)k1 zqd$sqUOz)he=?I>JB9r#dmTAGB7)B?*AfXpUSZ!cbdb&j0SGoJavJlAcebd>z~dai zs+RL=Qk*>t5Ir4P)TM8^|5W(&FcTIKFq?i4LH?NMs_Y!>>|VQ{gGNV3m&NOBE?!Hh zymowrC^12#Uwiq^=c2(k&=XdOMW4@}@^x^aXw{=e7IpG_0kc@ellSzJ!or1>PfKMh zA?CF0xMVsSBEYW7Klm8g6*D0>tS%$o_Z4aGXK8;bAyLqer;nhiI+FAJocyAVxg2aV z6iWu?4h#l;lfmQtpUKuYv}=k>Rbw!@yrDjT@ldZGi#m+hlTbgeJ1K;0pcfVbCI18T z9|WwdtFkk97`(1UczZZywqDEzs1!d3`ki~0raY;GwA!-n*?*(bAA#*^6bczb=UtxG zn<_OqFPvz=Q(yH=+61L$@8ctWId(ziR>$Tn_Yd-ciBaOfiw3mbMx{}Kr@(b%WiVl)Cf>z@T4v-EUfML zjX2bmm-kJrQczOPuJ5>s_XS?iP*PIjNnPJNaCCH>cT0D!tgPHSI1E00PG9=Wx4#gl zx)=JYYs%Ky+1LPK)`F&?F5-Bz@6z|Gii!$Y54iK*88|n4;_A4p68^2#HF0;C|Ud6<%z>($dv;>4*@T+ zQeL)%Z_bDS?yCL${n63OR4&wnZtk7WMycfpGN0p5rG=oErx9~gSC6)V0t+wEc-2avWM)S8QHJvyPtK7~ zO_f%;JyWX|HF}k}i~+&{BO~LRH)(FWt-GBKI0@0mzaQo-1j6NvA^CjZ^nevHO5)yY z7L77*(b|HVU0|~($1qRZdgjP)_ z^8?R-E&BK_S4aepkk}!iL%EZc6+12I4Zua?4(kg zTlQgtsu?*eJ=%MA*zB1g_zmC2u>%qd&&eRw+CeBdV2yCY!{QPLi@hqRH#d39xSSmv zK5_prRxbcPf=Fhhf>qDgaar~u@El$7UO2lVE$#MWaYNdmDUdKWzp}EDjQm`5SE=~@ z<0n>dad9yr>zS;HlarHrVBjO?$G=+FmK>^kabM8W-P|jS~4T!&6_t;jX?_DYoA}R zD*ch5sSZ2}@c)wHC*6WZx2HACuNDrAF!2MS{@cKvk&b*pZ zEk6eBGwVCCs&&0N69$HcdV1X!0+_y~(S_3bzAJBA(i8SlG;L`N|NR$+jy@9Bp}piy zr>y5z&#sT1(``Bm9xg72#w%L1h>*2F6P=x%ANfA=^xa!nSb$dJo5^XqIt*a{e;U#PqGQ$N8Gmp@>8a|y0kLYz%Hk+58p}Jx$7Drqi4uMS4x81 z?akEQ<%RKD%!~Vk>a462@m+(z)?u@2ier+fPG6&PcXux@!mW9$FSG{7s#?|j$UV~` z?|K!5E(UTKM|)NlY}x+otQ8;KAFq2k4?6YW&V8DVDsja1+WLA=H#Bh^*ssWz#~O9V z93c2S01$(O^~K;#jFpt6bGE!bE;>$81vJ@#^@hAKUL-KT_@&k@mHDR#U!CN?3v<8! z-VbOQAj%yD>m#`gYJCHPZ?yD4n1@?*bhh8}X>Qr_Z2{7{`v;rO>!m=nX4`F%G8iuY z&Xo|iOMuKpPtQGd^>b8G272=g3rhX*Kw zzxi11=psTQDJD>l2yJ13C2vN{4zzS2`vH4R+Sre!@mhN~H!VC}Db#*Y+&zmMJ`t6i z>O}0Gldo@v>XSMQhMx2k13RUAcg#O5Yd+1=#!AxaOxfLM?GSj#U3%=p9IR>_mzR$= zosWh`MlgSvJKg|=#`U&$S4)1_*xTDXJ9FegWyn2AQ8;5JMZK<};b!a`Fd09zdM}zb z;`UmK4!2gu$Fjx@9mngyw#YDEjX!Q=f8zOHiV5w8F7KX;g#A6RCox_{jM{@GnX_a$+hke48;1WGNJs0CoY9q=1OB*&9(hT|=F>oIZ zb)EMu1k#{b0-pR*a-he%I8g9|fusEaWVms?1h?2nZ3*-!>)!FW*L5ZGpnoS`DO%Qy z0NB36|C(v8Io6&mzM-u2_Uz93{|{@H9+zu4vI|i)}XZD z2fV#8B6Lf0b04il1T*N*d8eeNQiU9+^Dfm^Rec#6O763g@MAQB8y{0G&^*T^$qZ|> z0qlBzF0uIh{&^xkZh){Zpla0I`VX%KillPQOA@9)z;`TefbU-!sVRbuMp(BL7OsH~8tdM8%)266jHljh!1$xhMV*QjQmh+$jL9h%tAe-V`j)V48OJu);j zpR{)p;^j|uMaO9d_l2#O!nVw{|oo2tjBYAop zbT1o=g~y7E+gzG01SALZSRgyIu$VRG~ESP9U(rIa9PcX>qxB?ZODj+c|Gq7zS#Q>@Vmj{!uTIdcXUGEH^%@L;dWU`_o{T>%Dr;#VBh zg=cC0cuCq-U!d}2fQ>$2RkPz4;O?${#r}kL7&BK8ZZSDf4E1>qA{ieapZ$O%5DOHP ztD*Ixpx`>0{OI_{8>{SSuf&hvZhkoDKle}5Gs%9e|K7W@CYX+aqd)=S$ZU1bikB1Pt2XQBbC$l;XC;Xj67hljy< zEUfQnmV6sOJp2}X8oFUxfI2A0Z%z4>X}QUvD$2$%(wg`c(Yt=- zqkLl@+XL8d#x9Znh~x}_yM>=FCSTPtrcw&T+AhqUmi~Eed;f$?4jSxguT>4~3GLwL zNnVN9HK)mp>@oDb(|AALoB`a}*z&5E*Wu-y2_pRaRihY*$I*Gv^-a*`2-_L_ducO^R#KY8Q&z@~=)~WkVQt$X3 zetf~&+}sT5a|pOJyT9nXwB7MspH&-?eR6-eXR}F7I;X{DisT&2w7pC>iAu@0#TKur zt)sm_u+?&Z*{U&?^t#Jg@>RjAhm$K<$3~v5DCep{O0my5#re4 z!qN8CzxH-_zP#E+OoIN(c=N6L8jNJow+|oWc~bF!eE4FpgZS^$;2%lluzuIgAKC~=*G?7 z4t~z6c1RO1bNKG^lj^kJUXnnpN)amGvO81>nij_(_H}4zX4Pxu(^&J-QN1T`i=&|@ z)B8XIcITa6VuIz1NHdA581Z-#J-6F~d2?*hdhXh8IR9rS4;}_N9h`F$`$)t2HJ?$H zLoJxa!>%iZd!&j@B}E~Mrn`3!YkjG!0h`CB0^Cer4gxN94E@3+eLi`(*%VMT=)r4b zQ>zbFx?9&o03`9;$b3qWAId-3@5c9~B`IEoEKIR46L`Le;nOAe& ziu&qQpPHKbnzI3#3BXq@ZtM;ZZ{{4W$s8Sg3G8U0WJi?Xh6nSh$Osz6D#ykLoM^lw zl?h85oq2&~WCWf0j-Qd_r0CHdb@lZVUQ=fcaaUsRfIFS3R$#mTLn4k^=KKp&x^CJ;hA!~X=oZ;I zQA&crx7!y5EAlc3-U|7)4P_tIjin>M+x*3gvAcTRKvUd!Y;KJ4e7f>tGt*WjH=Iy=E2As;w@>B4dsch3d<4qm0j zhVoJ1C6)un_pMtdI9NKrL+=x;62wxg@kh-=cCjs}M94`!{nKM1;MWqD{+;U|1sKiO zFK4RPo9&4BkiT)K`HM|)X%C%wOfn$CW}}?+mn>b_VOE%@Gyy8;3^x59C zhF(SxdEYHT_y<>qFKTN`4Ls7tNO+6r-IxoZ|6(mUd3V*a|~Y5g?{y&45y!%C?Ul%)YJy=QLaNBt7`U= zHjCxdFIQPh`lo`nj*flnO?`c8Rl!<==z9h73U%g!W?@d5?BwTCjU=i``XF3~-kA>R zA^BY9fY+tPQwJspsrqxHRV(`5>h|TQF;xLA#w9_)-LFunbG67j0<=ExS+vJd)Uak% za{!^4Y-jKD(o(b7#|>~CicR=!J5_SkvcvgI0lblHW)S-54fWLz`KA@;V97FFWj?)i ztiyKZoY}PG}xBMildMjx-UH*-!sWW(sx! ziKG6Tq06yhHlR7+e>7;CcV;upbX6Rdy2``P>9webe#i)w#~9oXKsPsM?ej+=%#cFs zJ0r`>d=!f2H6s*3vN(6Ow%e+M$F;wE-!8+7NfWjlC^f9C!dwHqoN6FG4n%X^${C=I z?wG!<3eky&hfb!k>Yq^MV})1LXs2t0nNn!49>(DmUze7G8>_HQN2a2IJ~82->rO~U zM#kR*4|`{@gjhpueqlVl;tMwAWe+@GOxtO06GXJnJpeTTAORRoD+BZUl+rsE#AMyD zuqrg#?Je=$!irOo=C!;^?5^E@%_&2iV6dDL1P-ZFjqLq7GBQxs=IlXO<>IAx=YC${ z6Z?L9*Y9y5)6XT-n2|ch_)Sql#`=0dmDgL`7X|X{h~*^<5s^sFibCN{iiaVA!zY-B z6x1}d{q^xPzk?>~2{hzwZ*&v6&2sKn|6Pb+fEyby9DV-9lxPe;RY-SevzIfWm&MGv zCFF)iUd36Rv;VW_%XJi`uj@*Q5;9%&QjAwLBT7p%U0+nPxOCKr%JC1=v(H-|4p5+e zAF%Y-JT$}H&wu50zdtoVrJRB#w(rR4fE^NiHVu6$_Y;} zKWca<-7j>?NMsiq^oWV{os4(ycBKs3aVk< z`2|J{Hs1+u@IHvauS??GAq>MWdqAT@TkY*mj3Yj{l{sf1kRuhai$lZE&m0&1Vj+K2Ig4nsmzQ*TfG$9bTAa;LGrl|I1ysXsWk`VfSsAv zRFezGI+p2*a}NXpgnv^2PZciiLOMb^$GKl5y1=YNOMHz}aqas*e&W&|KZ0_Idth3u zt*wPF*Ww*}tKAHFX~@%5Now!>C)S~Pw>v2XoKcGn7z1I7*WiQc!@j(<1=4^)A@vwA zs&^vA3%XnkbrbTP>KkGH4SFZD;^=~{1nF_^kIIL)&+y5SejuRujtYg1H^4O? z{X85W&t7c65_NA4HQ6pStn6W@MEk4+DcT?&Ud3hGmi?%ERcc2UmR=ZnQLc?oe7UZ$ zlqFa&?bGq;z+6=VpHtxa&(;a-;iL1Xutc0)Z3H|s*hYe%t82{!F}}t1d7*7-sea1s z!&W&K1BtA-DbZ#lb!{4)JC}XZ0O7WpFHFyN8b2lbuu2B@&&6U~NX^V5-Fv`YY9P^4 zFJ=1Su#6xDYerx8T6?Z&9Vd2VE0{A1nC00s=(F5Pc>RiwMIDxVTJC*h9^VrNk(fM= znxq&y^P(HuliuU=o+(kJehDE8Q7pYtKZxhzB#KTXBE3d`64>-oEEQjz{U_B@ImNQe z1^kdQ$NebsOxM+(?bAx$;w(vQtFJikNvEn@Vh-&_RK1j+#n4xLO~Nw2LreQ&?cjZ7 zzd+#(%NS+VuUcvvH2>T1chDuW!70@S6&NmuwbCWh`Oex#6dB->Eq8?GZ}jU%F#CPY zqN2j=c|LfLhV&wHv*dtz!t@@NtG9x%dT`~1fVOx%V&gOUYe$gnJ_l7B+lNH?}Zqv_P^f;wrs)rt8F( z7!{$NZGI$t^;cuq#Zkig6C%f7Pj57Mt+G(@cjoa;XNH@y^;SFL6WC%M9%+ArNZx>l zLpW!kphL2%FzGex{mZZVMKSH26lLVbNGkaL#j>IzKfV3|}YirfSJq;Qt#o*ix2V8Hf zO=X75{ad2bHSvrL$!+-Xcaj8Smm2~a;VlDPmNgh=QXw__db}xJN-t~}8b#BX$PXg` zVADP4eosJ4w$uQ%guHE_QjDb@mKYrc1s{BvsaLkh z2?tYC(R+zpTf>j(6kinDVhs9S81zzFc4n`%@wI1dG*rAPy&3d?;k~Ef zRySt5J*k9Lk_Avr6id}Mp@D~BfOhTQJHQgW6WD-s#DJ%Zt`?u=C#_qeHA#H-pDMuP z--=4>yO*HFlL{52h`Sm|Ff6EhGa0N;RY7Qk1KuholHZu&SxgllMPi4%7-5nP>-96! zH(P{((ziLAxCfb`Q}Cb)T)+JX)`6aS5@))GD6?Jc9dkaqq}~~*l9$>EXIz~6U{?zj zN^q_h6>rdx$5h$X_Rvw+yk6yR9UB{CCcRgXP_dY&L2=a)?_pR!L5#L$`RWe&Vf%EQ za-Cr2j}`)Tjw069l@kr2`mYC(wmGebG}oi@)@y36Y4D_)$CQ+cGf>`Ei?$X81I4D? z*w`3T1uwrS*SV-jwQ7~lPNkP}QSk+W%*5kZSLS2e1P&D^TipRUx?+CV2$8ozBfC+^ zE!F5XV8b_V3Gi>Ck9*c5fU<_{-4`K8cmIPST_Y$Oj5+Ckvc3Q(%F~Q_Np+n?Il%!x zJ~kF>tgEeUFiztcO;DUN6m(H{33NsWK7O0jC;j7x!J|jf9Qvj=^Q~&cWMpKSY6}^=%C$U5_CV$}KJX;!`N^0nK(Q`Hd;*jE!7tZoPNZ~Ow2P{b zw%pU5roZ0lXC}!(5@hz3bA+RU_2%a2<9^024ei^cK~8}K=YqDsORGl9D}>6Qpw34< zzn{5|aDP`U_9tXE{mm;(u_FV{Nh zqVw+hDNE<1vXx8_TgH86rdkepJ$h8Lz7n_2gv!^9IMn0mXiv(HqV>xWCKtd;wW@J5 z0;#mLS7JN+GDJE$@9U*h8eru2+OS>*oa1UFrVL&Re~@u;w8EZ3NJ^sy#daCs@Ev{r1&iN@!{xnL%EyDH11-u2D@`YSZ<*(-gx7*}%`4}kwnh1Q?oIF6#aPeJ8f|RX( z`LKg9zZ^NLFMdoYt+PfNcWOFG@`<| z#faaRJ;8Hy6Ro!lF7&Vl8eJ!@-g;a3A9m^1S@PD|?Q=!|<47(Y;I zqV5)eofQ;ZC-6!i4Q$Eqg{8=Sx^7pG2kV--4){bbMVsqV<5kmrLbqpCUCGB%NDi5aqk zn%niGFi7D{$Mf;4tCX1r(V)IAL2(+^AE9-38f&OsvysXfxY90|u5&wjIY2!jALfi4 zgki+M5O-08zoX{00uAlAVWHRvXitC=5nWi@uLtC;IZ9(j&eql(QF)pr7U{Flx3GI~ zIB0xs(Dl_YC;QzK%ze^(OEr}+;LyA^K9vbk1`xah)E&b^60u^@$-%)U-73A1;0=*) z%8bQ%yL8A|w#R%~S*hUa&7(L=Rqiasp64LE2NN#KOG`hn{=N>sJ%K$Hp2YNY(0K{C z1Wb2q!b>5{S)i^3KYl>kxWC`D*Z|lXE&@pgd*2R6wQ!eyNBpq66h)g;{iB=7ANb02 z-aw%R3J`M}KHcI4zj-HR&tHIBh8CQ;&1Hn*hdpmV=4cPTw{NOY+$pZbrFd~^a4Sx*6nA%Tkz&P)dx7Ha4lV9d+zS+U3lij>^t*T7 zn|W{EUoVphOmedKI%_Zet+f*NK}i}Ng%||{0-?*wfK@@Dr`jOUlSSmGz&pwP&L4q4 zuN-6`&L9vz@IOAzlRCSWRS<|0BnuW-_b@nE_H`iL_NBjuj_G2)6~iQc_KDO1*@8Bd zSA3p;73J)=6V7i(h9jN2I`1um!(dp`hqUH*jJ;YtWs6HQ8k^--%niB?3lUxV^esv2 z8uMoq5P_DuDqlRBkU@d!Hlywj^|CTQ#3Vj}KGTAD$30RquizU`$VGOJEH7HGhJ8dg zzafoX41WYUwBLKL=nzv-(1Spqls38e0J>dpo>Kv@-2b0mYkzik2Q`(ACMG5hE3z7y zne{F`2Z31G-U^u|GUC z-#rh=B6#P2z1KYI6vjVsXXDxLO|))yoBg&&$<7@9T>-M$XtL1X?7USHtXFVh zc+lQ--yY4FxgVfJegd+o{7_3r?W&s6A1-QrtujR5Uyl_80(mDVCs!T{nwlEv(&gAb zuNOZxmzTRU4G8Vz>)i4V4P|iQFtK|I+EKT0HnUE7Cn&f`?x@Z5xR8Hc^G0Q2Nu9{m z?)Xhx>~3gN(Y##76OSjO5bq$suj#QyX;A%(bvdxGM;aWTDvMm zW<^C{8kS<3bc4+F9u{7^D%G_!>&_5XZ{F>Nl`L+fyK?$FWv-UH514utp!@NIK+z7a zM08bGG~lgFtl;=z6Dh%tedEyuLnB|x+!#-4&Ghwrf(5eP$?bxh!+sYqzq#K_#CoP) zmpwxf>-3F7v&8@z@98Q0cOS|$cFxKj!u7);{?H3X2e4(T z(w5U%!Q;3ywyQ>EVKbo&jyx*o0%FACV%#@xdgoT#WXRi`#u&z}f;2nAf%=|i+OKP?O z;5i%MOepctWj@s0ehV>ey3FIvng5$NPWAVLo);5)SrL~2;<4~&AP?QIi6DUTc_D|g z@AKI}xZP`5?jOUV7;4zB@F%itarV9SH!%se2E1As>kcfOyo%BEs#w$x?8p+I zX3R3u#&IMF-y4bHr~rq*Mj`T8NPI_ha9)j4x>9z~YVPKi$Sz!JNLnrVIrwv@^#!rL z5B>dUpfzSt?$6T8fbr(H&p^aQ)zJ^(r?MS9jMUb_WAw_TWhP2zb=I@x`YpU194cM! zgk1OV(lBb|O19uXRrX&1w}`AZI!_R*ekns+!(T5;xHQ^_t)(%Nm9E9E)kxaUi=m;x z>dq<8nSxi)Wl>bU>K9U?h}8^jc?PQ6bb24AW9g%Okh$TRCq?b~VwaA%fqo15+);tc z@tQcHukO$Eb8KL#St;&jy_;}kHBzQ;@sY%Wg zC;Ba$kgTH3#C()A5zWfFPT+0je1s+^Z1`6 zE^IZ2g9HvY8l14gVmWYXzO9|zUb9k*pt^A!$Em7g{iH*EmYX?Nta4SARPH;Tcon?O zsUo$^Lqgx??Og?-_uz<#h%I<43g9`+s+W4~E|8GiRwt3`2PQo7@oJ^2i;IP@Wv`bo z_0b|HUXMxeqW8I&s>SuG*|tevc-r|V`wF7LbhzKwBP?Tq}6xz|?L;JG&uDtRd$ zx<>H{!_i~yNWQ#!6uMuuv?qY$<)z3fpnCuySmS&bjtJKwg1XIf6a z<6wkv+a+y`Vf$JN68p=D-X-i*bekFZ^1(}S<=VbHnxJ*bSr@++tBdQ*q?xA+KH#o811zsQ zceHUT1xFdzohR0V@hTiIm>Wxjrehy(WDfSL_@F+MJ|V%4?z~V&iqxtKVn~E-2-D;5 zjn+xW1ut>r59RqjnKLBt))KXC!?z4+X`!JqZN^7ohet=IkIM@>t4n%Zm!Eh}bIUj* zk{U|lbn+-`9!cPs^q3K@hC<|g8WQUVAGS>c@-e121~!bLWV*8Dm5CH+58s2UV=TS; zEYSmEveG+6D%6IZSGm)pi5nVMz&vhA0aQOH0!=Z;n!7utobM zo*Pp$GqbI$dhmYU&aE2}Wo>D?rXs1MWR3m)gh!jR=b<=^h{1!*Y(vYz zlC@Ev>WEqlVc*qx%hswD4Y7XyMu%&9!FOl(LJ}haUe$^Y``IL_I_BS!U>mEd8XZ@1 z^&*(Kc7Zr5u1nX9USLZ$G02}bK_x!9X@ELy#NL(&+SBmPBL_9CV5CaT%6!(FAHVvD8^+?}sxTC=OLbz17d zCz>Ty?29#{OC!2)ZScfZzvjg_6X(s+!U7$tXxE(8?i^Q<$cv%9C3vTD`^oL;Y}gJ7 z^tM-ih~!UOrbo(Y!B3;#k#}XvnWV z!LY*OhXcKD;h()f^M(o+FH4jT3S31!_MG~jwQFU0CxjZnM`n9@hqUXV<>s5_()3c+ zs*ajJr#!JRuD*1&6$^m5dq?v^3kTQ!?oA_1^@s^@5BZg?t(+O&$~Mpu*5C^-UxS7j zv&j6>HV+|)CKk@bANQBg+q9&)i_zWl$*|n%#2*-QKMiSW#uq&8@G;y&x|Y>@9GuE1 zk+W@istMaNSlC9n@6p;;E>OLC{K)~!m9JrU>hWy^)9Jb?#lX(H?GB%KacLzp%~n=t zmPK8oZY!zA{7r@hO&n)pc)pZwt9x4*cK`J-I_Qt#Tu6o2y6KzZtG{ts9~lda-`i~w zaR|i#p7`#m@;UwXyeo?Je#V7hO-&8>2g6_rmpKqB3` z~oMJ^+k|;l4-^+!qp+mga`4kM^eA4q7ZrGEs{i zX%Ew62K>1<{IFsEaAIOYtw8Cpy`#NV^J(f7B{E4^mNu39lkY6~Lvjc0H8wMNCNE!p zQDiMp%3%6Rs1QjvBcMSt!E{8&I_)pQ#pS&FJ5S0juKF%5)oXvH4eIgsv5^2(qOeKl zk`?5U!uXnA|o{5m`<>O7#Xnq|p3jCP;SbYHl5Si*Xgl?Zi({fVL# zQ4qee^h;17#ePqMoGbZ}Y)$^!aSB^)#i8!V?|G$5$Zr zQgYnJ;>T`4CQ?$p`kE0Pb}Lyzr|xi1w(M7}Fs?*#L*Ly{q)pt$s zc7czpt-Lvw+e1Eto9PP4!&&JCx?8=sDa|~lc1&f1qa~{5^3%rKy7{8K8-<2?g}!wv z;dPJ2w|-5k*A%ZFBSX#8?_90VcA@t8{sDq&qm0IJizLaX5kl&ZjwT}#94}^PXD!Wd zckWcuG8)Og4JX1`O1H}N0nr#v;R16D2sGE$a&sAIGlMpnG@r9scp5FeF$F`|%-prSk$+xl$ zuy*s2?!S)@+WRth@rS(1P(s-YMvHiMt>b(9`bKOC@*l+1wEV86w1rk{-N+O7ZW}T| z3lAt|r1jF(A_c5T?A`BL_0Ug`m+p_JH`6XttNpG)pvx^LxS-tsc$2&viz{^g-TCCS_ULpZi%nVJ# z37_W>0B*C8*$?9vSDHKT)ZdL{q@RzsBEDYq$XV@5VD7WA9V==_C6(*u=2IHiM{w~p zjyH8Gkdm{dZ#&EJ`MchqJznU~Xy03hbt^Xan42B$8I*7?Rr*>VB7(y5yEQGsEH*!pN1a~j4ApIX*^fMq{SAAW5xxbZz{kb2m+ z@96C)-3qpuH=`Q5)@dVHWxhOYShYJ2;{s@&TYRA}$}g%6*1~;7ZPYNIv>oJ|XB#oJ z`sOgpR=KeBvp6uTJ*R*39jq!@1A}Rz0$BFIHQ)Gb)6jlo-E4}NzC=CKR%epzpVb4 zQWAi0WHA`~>B=g{s}sMBGWM^ZyWBbMY1fQX84+d1`pYl6nn0c~!ZObA9OHt8@D<(% z&fxuxw9BlQTQ8Zt+a#^-5Jvd!AF3HSLfals=;`Luiv^x1ABNH-_IDyloJC|Pk{2U499T)(dXgK9?3-K{HPC;T?2MrQLnu*R;l`O zPTj-Pvgi(nC-LpddkdZSYR+nqwlIZcL_KCbW*3^|5>J~J%FP|jmf0HX1B3JA)_5uJ zSB~#9o6w2nXGgrb8~ALu6)0K{_y`E1IvxbDM~e1by3H0lszwwE%+{Z@#x|vTv@*oB zU}I45pb>m5UBErwypeNbA2E(*eM3vV;(Oc2-ge>J0ToK-cZAo^^~iz!FGkq!ww1B5 z+pJr49j7fK622K>L(VVJFy^dJJ&P64YbqlJWw3)lA2&8z+_StdHJnRA^hLd4-pazJ zc5iMMqWx-*Bl)@s_G3%NO3P^*Dw1krv^|Vh%Qs5gVYl-I?dIog8sDcp&j%+G?0s)^ z!50bk{+nG;_y-?U=nYKEh|evWGLNoY8CV z=Ma*C@6oC3&oCtV;;>#IUQKx5G9X?hFPB?Uq`40|Eltk+JcQavYf7Fjj^1u{tHPBh_L?v27EiP~{*Lgx;(iPE(voFBGYgVIoar^| zk))^4Wq2P~T5zHE*!!@V?q9sAa~&Bx8{Ofz{wr)^mCTg&ar5z-eVxw}U}A80=dX@; zGT`LC2L+gMm|i|CyoQ} zPvN51PYyGU_7wDp$Estlvclvs=kHXvE&hh2u<2;Mudi|H_WY5w9EX-9xY~ASM1_0b+(IP&y-Q(&ge(Z{U)o;;7 zi_wU{Z;c+ReI5B?AtNCF4ayOr{ge=~{K#O{h{V3TK_c;Jsw`a`n{jjqX#^j+4Ueo5 zK>n1JDMZ@}lKm`co}Yt5T%wKPu$It$5X`r~Hk!_Vo?CGr8rkrsoX*1hvW>^dhKGf? zOguSdxHKKYcp0ui5bOgnd?8824kzu5?#axzEcIXXaW6w4!)Dh{#jlE_@{;fqjr2!5 z3c|u(g@yXM5eB<$ga1-o`M1x{PX>d5Y)glUZ~FDjVv~7nUlR+8qMf25paE`!+bu2LID&9W-kxkr_JrHRMO9z! zvz3J^tzHG}*DZL)6Bf-Zcp8M;>PkqA5n_vXEza9YYTw4518#^%Q=A}iQCvq{MW$sV z&NaQdaHIRat2BwEbl)#C$0>IL_F8Sbz?NX9E^vzX(c{!yxIGLot{;roU)mf67B5|w zerNd0PGyJMCpyAE1GQ?YGwZ4z@AlTf$+4FWBl zz#}a#u5+cq@eBkVlZ)0Oolz`9rousF6g*$;n;)G&XqY&>f=BMSiQ&Ww6wp1;PTa$nJKs~BubxOp?&NMnd&pnfXBQL{R8%M@ZmKio z74M<4x5g;YnL@UZcA6g|pm*zlb2ZS{$0y%rMZ^TcnZYVu9{fqpxHf!u4_(#iQdtQ5S?1!`lMjBA?+N}rREyMk(@Ys@p3i<>gfanU{-G@+QJcLdMu+hZec6feidjUz*7YSrYQRp?|sCu5Bk&%&^ z3G;Ym0f4ZdyqbU$!uM1+Lt;E8bB#+y8yc-EFIQC_4LtdsCttc69eR6v8%4@b-J8vb zy4h9j<9Y0^C43+7@TtJ>C#xo1SibN7uR=~n<}Rdt=7Ov0;gtV>2dPsmqd1Db2E@lmpZ+3P|mBaoN9RoK*`6brjv$t z%gsGUOn4|=U0vX*a7iizAoqFJ)2=$EFD*?qnlRWqF&fR=tYg(4Wz;;=Q!3GPvQs>E zPK{~k?BwJvd_0ML$Oj@(R$aM*-9K-ZeW|aYpg=0>2e4z(C3$*U!vHT|wP=QzZfT=f z9R#X#5+Kh~)1VgM7ZptzNIqVPWRDZAsjh~TbG6_4jcwyqC0s6bcR$yCX2A5K2>?E- z@UIZ*z@S^{jk8nSa`wa=7RH!1it6 zZ;@KTb>=gGcUt9oRrqJG**@Fr#%ORws46u4;6+XCu{uR zLO_VJJ&N4@ycU|iw7f=XDy5u%aU{(>a#N|Qts%`eC_VusS_*lFJ4T_<-`PveZ@E$+ zt*s14tGuwmWZN=L%t3z13~wKe+kTfIUw(h5hod3)fhsJ#)5sZ}5(cm&GAOc_@8e<( z+u!Ll=Q^#Kc%uDZrU`-6yxH+1-%oFRY%o)u_B+3zBMHQrrX08D(_fA)-!55LTm)uf z`ib0~e_*&+q3CFUpM2|9oYl!=00ZG=?y^H0QBh;*cvE1!a*Csp=GH;4l#4k;IE$sZ zzFyM~>)YEvv(ct^=kc)(D-2vNtj|u&|_>(KbeJv zg_PeZDAdc#>u9CTx_vPYu-W6!g-~<7ZGX}!@wp=NTW4&GDU6hl`9}4d`5#uF{EjIr zz5dfeagY+sGf$IW-<=Z^iXe8Wj&yNWH$|n?K07{<8HGa%88qU^f!CZWgEbMFuWz8o zy~_IW{ioVlG*uB*i}u{w>RoB|u+75govW29T4ex4ehJD8-achp**!S_`lzjDTPB#YW z>o{6V(@mO5{mZWUqzK}PhTc_bY6H}2Z(OaR#i9JVa0zvQGYZ>y!PCL?+uQ6rTh(EL z1q?PX89V+~u)2M9Uh5w&+PkbV?|7V2t95>}lKQrc)8}+6qLpn*sPDQ-DE;}r>< zGE|tjk53uHi&&%2EHvcr2OPr>RmS>NZ739aalcbtJ-jFCH$o@EC8@j@xJvpXgQ>E^ zA4-WuORebLST*roVh^Z2*l<0mFNyMj7~I-wYKvm*s?ua&=oJ2wuJfh=2@$ehs_iA^ zlrZ_QrX`>F!KTEv+8>t160~ZWg`U!@NT5!^}Oiw*00f=d9aZNAl0Z!^4Vx zE#(S~{lpL~9F=t|qa9In{;^xeyx{z3ASe8ZyJRDEo3UcB&Ak6@Kj-bW`vV5au=mZ_ z!!WF_xbG_aXn&vi4nkEY+T(8T>2jy?s0_z6%knzumX@0Gu)25HS=l(wHr)Jfi*j}< zPkjcz_kFCjA0w*FtCdp;rF;&m_(M|3Um8E>yvma#xdzzkH#zJpZQds{tRY>mB~?ry zA`X8(6&D|ECzY3%pNaflTQjsK@Vgy6-8EJN<9!YJVz9X4AU#RWYvytS;26~`ac^GC z?@%t9j)W4c&=5Dj#;F;H2`C;&(+)WaWNby2sp27S>pg7gYy5Wld+oEF%Bf3+Icl%4 z9SUgUABW@|29~>9I2>Q{)$^xKdZWHr-}DLGD0aM0x?y_bz@{ODnfjVX?95lvbsU;_ z<)tk7lZ>abduzZ6jWWI#B{R=W?g7W5Tb;4^(CXEUU(oz^)kl-Cip{|ST+~V@eNX(L zgr8VZs{NQNo{e%{fti`eWldJ>=3Cerd2}D-`o+^Hep*f9GT@Su5(!%!|4F-dm zL5CtB{gpWm5A3UiB>RQ{u&57R;eR1J=Mt%CtAUs2T?`M47UkgMlm^$}*5oc&?5vbW zyoUtF=wu_r@zeGR%h$xYPqt&evmVEVmn+YZFe)kUFh%dylDgIwDIPuip{w3qT^Kig z3HU)al3=0CgS~JY8=LFF{>?lA2@ki2V-aIXMl~GYJ)svpks3Y!fQPXF!~3o<_$vZ$ z%uJ7;Tw_$Iwt+E1(0}~QO-DF}z$qO(rtq`7^RX)!3`d12ffLQRP@8nvr1|`&BMhv7 z*{~^sJh`h*iM6-4a9K-2LekdO_UmJ1OUvThujA33`7A8Jo?b>MXC*IFRUQ7cJezq~ z%WUw}A&t11$({J0to^8xt3fENU07X%9 zWm=rBAbD}>X6J2;me`cx6Fi~&V`cxl3Xx11TAVQOoGNL@^;QJ<0;s_OC|4Zc(POXQ zir+q_-6>4fMW3FUSGLa@aOs~4`0WL{1ZBvYfzFUqf9Ap7-rnE8e^(jzg<3c|awN!M zPlS*0Rn9wLtAj&m##kEnx-4mi7 z#-8Yb!09!%xZ+ZF&lg+j>B{N8J}!@Qvtl93d@~_qIP@$jxSn6Hu4W)u$g?}AxZ z*iA%qEPTiVY^Yo*U*Bn8uZ3LgL_4obIu0%W>`8g2crjC^Ya%P|_o6T|5?yf;Q6X2( zFDbF!=4bd8p+J#lpqZ#xW2^vq{SdvTD&E-KJP1oa|9H#*#Bw^Hx?b9h!pp}AbXL+SHr`_7xZ;+#of&*avaiXbX z6eFV7(wLee4Nh>1Ri*o7JZx6xp`pREiz-W4M^kJQ@LV^Kfcv%DcU1Y?nT+0e0~yxk zRy+|L$_x60lo8d(jvHyQ0KkpJBrT0x=bJ_hE>arO+=qYf?tYB3tz0r^-3(uahFVx! z!hfS^Hka4%lY#M~`@&>2ruC)O*MQoK(9K`^&b7m##qx>@cDB*pjeD@m&NvmX3!x}k z!B96FiZXa1R4OT~!hwAjh;LhdvBx%gc*Y7h2^4&>58{d=aue?!sXBzby~|VNuC^3y zb+}%BcHHj$XPJH{?0$9bk-7~~1bZtQoxc)4)VueZ%NfFR7zRwfwVASu0pUwokb6)n z??-2C&Hkg?fiPUmF2jXg!cDodceQSqs`&U+abw%~d0GCR_qWg*L$0cZaUH_yA>M?R ze51ch{h!S-U%&5N6@fR*M(KH92uAac+MT3x<@5si6FHgx4|-SOA`+W;jYbev?r4#| zwLb8CHj5NbB$=Wzm%p}`e*5>7o<=`5TI3uXTiEx0cf1WNOKszA??Az@NAbTfmUSzk zio-3#tBS4lH42#`t5n5OKAa2Z5Bk{ZGx}z>5^~%vVEavD4G^tKMV8uF~h8u)-|ZmF{sFe`4^Rjyx(V z>YWZuO--#d*8FRzxuF^7`Nb#|#77+hVVc0<>I9E4>--RId%+-Mzh=e7q{~!L92; z9rN33F!-a=_b@w+zq=Ry{HZuh6o&Jq%5)h^x*K)I2&no=P3`FHbB^G-j!ION<^CkF z28|bAzqFxA1@b7|EB&-#6ASY*lURnT%C|X|r4vEIKOjI`!!?EppiDeW+jzWQ=0Lxn zLB~f78KrbaCIdaj+dKmi!)XXpouOTIsD3zhEN@Ois;M0KbkY%auiIfLLhJ>odQ}?) zaX_6md^7;WUPWTAsd*g>j`!Opv!>x93&Wa_!RL}F>E`PssQJ7ZiN8t{uN<>>otYzg zcZPXm2&|E$plK?99LHSlIo$?cV9?xzx2*sLMnkO5)Rs zkbc+$!Kw`|0xaBw)SS5Zcw^rJW=}*7+DhI7qj5jsxt2yRfF!y02+CwcNVqDoCPbBz zw!+Vr5&Z*oU)#<+CM5MEB-#_Zx~Wjxo&m>wC`L+b0=XWXdyNeMgqqYj8R(`SD%aPs zf^%JcydxQrktStv-L0~EisMS6wANEn+~lmKqJ9PK!l17K{M1pm-9T8S)#LMMg!Hi`3jkvik;7 zSnA_d>~E>gb&n_zVZ;4G3)%nHf~Z_Lx}$)sebRk1H~|%a(kv*1P{)*&mCZPljH*(A zYVJ(%9J9vFDI>2UDcz3@UvWiAD*0Hz46KnDW(qIe4ct6?9DAaMqT}vrI9PlG>xP=1 zcgRO}oOH%zU4w;EzUqFtzrLH+k8D=rSstk~LTte-G&aX;1K6_A9e-^d&Jo7C49<-g zcSf>CD*fkXo5SHwO4v0qm$B`BcdmSlGTxU_c6JMdgWg{5*BK*(vt7%}d*d+z+}sbH zs2l99KP6Q3de*A>>V6>vOOx%3gpEr~=qS06HZ65dcjr^6rnc1}+A&X^Ql918{Zt7Y z0ZG7-sQrVaDRXc!l`6YPRbybOoHgdFMfen*cYpE@BkrB{#y{L2ta$guVaz3o@;2G9sAsp74Ek zN!W7=N^V;*wPFUF+iEXB@xDakg&+Ee5>D#85K){G5bV_~s;*c{;nYl`?-;UQy(Q#R zU~Fvk&S&U&YciRHgCJ5kLk&+v>|K46<%0W&8(A=6;xt!1)vqMg%A5~+y;pnA6%Qvv zqJN=BMT6_g-Q}y@%a8QuV3&R9l85^>8II})@10tIOJ{@<2m`>Nh#135@{*^vvnn2j z5Mkq%#>}9c70;Kw2)wYtJM6l%lywO zXU_Fm$L`F)kK;bvoo0(Ky5iMGDjMqRDNCsIYtgh;9Y+?lU#S-zmdRITaHZ^06;)!M~tWGi7 z+cPVQvNAGU8>ikg=I4y3MoeR=#T*QZ_tNOv(*R%2sN%of#@kHK86R!82D^AVPPh$z zl}?;i+g(vPqQJ_#X!dcZHpl(4?7Ht9UZzS_Ze-Utjs3=YjQwNe_C59!`(dl zedLXZGNMhM9!F57t;VGDbCDS_8QEdWe4m{z`vIlFQ-|BT+V=$2j9mD`@e}Mj`FJKJ zbgwn>aAKWh_hR#c{z!;ohbRkp-CD5 zO0122%1Xqhp5%hi@r@i2&1dH$|?D1cEh_ie3hjQrxzj1OU3JC{4{m z$!Ktf+iG~U)Z`3&vpzK7{>|J>OTDMsIZJK+pCfo!&>P&ak}$xIE`$=KeVr#C;J!De z8vk_sa}!GI5}^5LT)1`xok@YbC=fTjpIqVklQ!+Fv5D#9;xct32&KFY%vfAy#S68F z-vP>OzB$stPq8!3JT2}l92{b%1Md2qY#!$JX)008c46({F9g6Wh<(Sf+LXXzz@;vKq1eiO}DeY$8gamApr_A&E5 zdZMd?wd3QA9gZv*+)eHf5gM8Umh=PHq$p+LNzT(B$fjOred4kxNwu@cn)1o7>q5zV?eRyg8DO2DQg# zSzR~K7v|n|IB)qrWhCw=TQ%7?b|rY{Yy1jRg3wbRb>%`_^xX@MG&D@@KkHAAz0uH! zCPX=aDf@_=!Zrd^e@xla^5W)hhgt}3ugqQb(r4Y!W+^gx?RhI_*%Ljs|O}O?4-W%Il@Ei7JmSag0DdN@nU;@xj^pLr7 z%4{M&e%3Ef(hNBS1-%a!c-CTUadB}=&l+8JzukyPClM0Pcc)CAzH3ng`;;8f$t*Q>U*_62f4*4Gli;Vjr^++ z;JgsVJvxT_G?+8RBunogS4~4h#2;)TnA9C9U-dc*NE~n{Oz64@)w%V7D>yzfg+}H| z9jGb@R#+l3t?pVP#)5P;9Kw3~%5hVtxL~##wG6eJ>9_qCNe-WCDngnbH1}3My zsxf8ACM5GVQMSjTlv_|nmLFj<9pBR=QakE|PbIQKSN!0I#1AWJt5@it59KK-DXLm# ze@I_qlW8}QUv^e|MPd4<-UdNfPBW%U_xB|S`Gd>c0FRCsP0>#oK!a!biElIZN2NFO z@c8<9-QHc?4R|Kz9{8_!$p=$+xWsqedTsjwj4C^}{-A>>E%?^W)r(PTbY}^^gKQlj|wX#hmdU z9E>suUt#GpY6!T-D0JK?Tf1)?l$y_2SXudPh9o3p`zkMk^AhjFu7y2FQJK)?{KcPUgs-#Spoj;sC%byad0eRCPH@R|5`t$r{`EB0;aPQ|>btybRjd7PHav4b zT3XvM&*M$C^qvus&E#7MH5*AwjZly-?Eb64yz<1FxCc*AvIq8$;GwjX6vNGr!m2U$ z&0E2S61qN-K^jG^rvX5lL8uJL1PXmag@>fz=Ep7pNg@OlfulrpE_0f_nqA=%BL35x zsHZB!nEr?FXF7*|r7E~MVFCj2C+L{bd1{V_q{mwBQnoq|`|m(bOr#OQ^iP{>$}%9? znm?Py1mc>7&-s>{iE>B!inInqB!XHY1Mhf#z1$`}$-`r_uKThkxi%(xlccB`}5L?f512T>*pQs`Zp&tUA-S$4cd)*9=EprdhP?D8lcozgYWpFdzckk$2FX>^L49U*Dpe zl6nGm_I6lWMb+Y&f1>;9JSBnz+>uo09Wrl>(P?i$1JAW2Z(sQC&EUz80EvUoeG7E; zamMdl9Q`v;7qRd>LfR%)!xI=%Fawr4TmCs_APPr#4Pd5&xHT#hL2sJH&*1$9G5y)u z+giXF^tQp*O{DdJ2{ju$>YxiF+QELW@5Dc8wZnLq2kNQuGqB34CYnhSM7+n>uCb+vZAzl!o1f z)1dxbV5%_^LFmrAO9N;Jf4yZYc3fj>rPOz6L`3bYUcWDAUOaj0l~}P5N(T#$q9D5J zclgc6&^vOMRai1yjjvS1Gi8J5zUIkvIa?j5 zmIez*lp)s0U~^;4&zKDb?7U!w^EmrXE6o)DQ@~Y)9vq($yF@+()xO;Jbsk*Sllp7s z>ubhIGaAZRC$_S%?u&4OzCdN|-!v==+ewbY=CIt|dU=9>e*1X$bdWYrBFgAUm11yu zxco7IG=OT;RM)_4noHKe3`Kn{@|N=GBx_anCLmNGtM@8K%?1P1L8-|4XcL~))Ky+3 z3JI9zfa7k-i=>$MhAB?|yN;4v+0FHmn*+Hiwfl8nFNP#Wl8@0w{4~8|;J?qsG(ymf zhn5z!_tKf7{>Huy>@A)uO$0npZCrl-nphIGG_zj+1j|27X)b4$o6lO-2=9wSG}fmb zTj01Vl~MkDT`%osQ~kF&6c)IN3j$56PE$FnscArCG~xmA8`RBTCIHwgZ4@?kpf#PX9{ahW<9Aj&0X*sZ@PEo%} zi7iQuUv5(ID*8gUentWVAyKTZu9wMaso71FJi?s*({B*(&99%*-byaMMC_E9D(F~S zcS|dbK+!(%ZaYr^LA_C`hwo|N&t+r~zaaP}@K zaOxl|HxuwdmUd_4h^2{^;sXtm-!0(yek1>PTi+Cp$keCjYDjI^Y}nME0M~rdwHp+- zf_1C(()fOxhEg{^K}cJjR&-cy@m`p|@q+TtB@hVo2AJ8fvD@=uLnA@GkhtF#-%B4H z`~{5fZjjX@cIVu=4KJ@q)^(Q?%Z!Z;HS*T(vY^pPU*FQK3`8*O34!+rx@aLOLGm z5bJ*W-GtZC_OQg%k}ceJ=J1!s4Q{{g--9`aOHp7V)ZTx>aTfTNj;m!P5g!KRP0!01h?c=>^P&p4KtpghSKo+{d z9JW*W*XIlF7oQHP!^nc(|g#VQG@R6?R~p8g(GhDr*ZzuMA=32;ZH-sf45$Pa!ae& zmU}CQ&L%s?%X3MG5NF*Yzr^r4L7kFd+|5y_EiLdKD7k87LTQKapC);id{hsgC*%r#%zF6%d!N zsp+J4$;bCZN2hsvLrr&*YX9Jv5%p6l3^2E-eqh9HIFok&#Or^u)qP9LOrE|UWXXw; z1CRjmKWRAq#SbXFW@St+2SRekkrRMjK?qW(lKTGPJD>&JRhOxn|L7#h!kK(GuGHhf zstqA=3vrH9Co)+-`evs9FbDL#-GjbNdaEK8paZm!ZVvyCWf-q-9jD)o#g;=t5K^yk zKfPxiVE^-QHZ1i_J@g5;Jx&{U=Dd^1bg6IfT}H!7nUU3P9^ZX(cmvgP7^{X=6EI`NB9dELWBVPMw{)B;)3*u_PcqeOhWB6VDR^LxiX#$WW-thKYyh{Z1L>+f0mL)D7D!C{_0C4 zjqV(m^l!m`Ugkf(=Kp+MNbD=H_Im!mWXCBSM-3Q0#MeOq-dl(%-`~o=4F$)4{%q*X zd{F<-tRsFxLu^yswSVb(8N%IspqgPM#&FMdugyb<4-;M(!xo)|_!H-6AW-Av^mLaU zFvqrkJ9s3h8+e}JEnn8|Kz8!ZpT}?h;PDt9^SbxkbIyI9bDrl6g@#;_ z{n3Mu>)DV&p0P%7GG*DFGri}cuN#*ALuo!dHFtQ|PWON?2a?$2ITcD%pL2tnA{*@m zUd%0ug-8yGz6rupZf-Z1o&dvU4_^zW|1b70HFScEtP`D*m;;XKht|t4i4IL&+hR`&EKck)K3YTQACzOyS?PR z2?XNg{~A6M-4nsb1}S@e)jFxNd~%!je;(rh{KWr$rXucx&NVyAo+$b;*8J5F*mI~l zklv$~nN7e{fkm^>h8+b2igN*i$N^S~i=HE8oerfW66yJ!2Tz_D;@-K- zr+3%`cEJ7nVqg860Sl>SATip5b<<8ZFcr?lt6K!qn5601v zP=xK>`KPx6(jr0Yt7x(v>JbKWE~Lp-MqACwYU|;MnO-i{T@52pOTYE>tN4q>Md!a} zPVy92!~7kzb%aMmoUw}Uay3Dr82=n+-MNE<62;$tJ$+4rP8|oG+xE%qF@MI`aY>kZM z*}UrE+@YQhIkQi8fQ^u-4hX|=I%QdA7!I7woNdW#t=yWL*`33O*avQCJH>i7}-mGM#(*#F?&=YO*e?%zbBh|dtV(i z^}10auV;z}vk9||^K@Ybu(ujXpVdesIcr6a_^z{ro}C@utLixCiOn*21r_080M>}Y z&#gJ3)EF>qTTfA$YV#@5(o%pXT>atsi=0;ArJofD1O0ycOg+c&N&>#7_Rpbj?Yn7w z1D-VZqah$$5HTvz8uD?v%61txbOC`gIvnYpG{}10!*veihLPRCJ+=K%U9fHc^+Pj3 zO}Gm)9$I7wS+E3-Wh7rq%}U8x8+9eSu<*tfVm84^c<-9F3ZU{mG-eY@*VD$8RqPln zuIXK*Iyi=3$%>*7smbP6R$cRSV*)$6!`WVc?QNw5WHc=vSOBGCl!TDIvm1Kwc4AfT}^Ki|>W`9q^@HsA(hm8=Gj z0~*Vw>8L{BMepAXl}^9BaQ1YHjt1@>7~()17Ww`)Y4uX%V!?AWcsReSC`G5aYtO-)T}YifSm{|FZ6I)#~0c zY6$POv@XJ0r)@kG(K+`tI(tae@BMkAI94gMhn(?Ut>#;D6=hJhYtV}1ReHDYBFdx9;xLwFJvO{l2grVno>z$5I> zZ!@M|0G5x@?B8oR9iI&YGT@?h=wlhZ)9M~n_UzQvd$oQ?CDZqS6tPNTB&7~=@_R0N zh4DeQ)YFcFklrl8cujsLn!__nnJ+bM+0&qk4Jzn?!0w@ES~xb`oV)xD=5ryZka*-i zT#6Z7s`6}?N)oV22pqVXCf3OZrltW1+A!4?+jvbuTun`F*WEjISs?!@pE$9;e}MfP z)My5u-}b4PieXQ?+xZx9g^6BFvBhy~Y%(b&( zhK7RK^4|=?2oyk{!%nB3Z7Z5~VP~(e8$B1&^Z2%MC-_}gW0z4{s(1~)xW$|TJbSP-Bk z3f%Jh>l2(WBQz*U<%mvu$uO)E6V2}K^_YHKa<=**tV@^XMsz+Qm}WD;~QY5;gb-fl?0CEZI&`Yad#nkuj; zE_xtF2g!>>O;lrmVrGxB@6N*aoVzQ&p$bc%%mmtT`t+*(r|D%now!=JfXhSyYXIwv zarb(R!Gr}1;0cR58dw@Bu78TQ%y|Qs*kLa#BeOoysNDGZ6=^OKmev)`+)lc^hq7kd z8e-k)?0OuZtwZ^>*n#k;$bGPbo zD6O_EGJ_LN2%4-n_33X(h!jpa)>ndezL4xCk4uJHTQ$VF+R0CGP_zNF3_E2pKfrr% z4&dF!;x%QGV=mCc#~XVNuhE4COOKi{MbGg+=6r0%r>O?4C>OqJ`Bwz!nxJBe4qieT z!cF1G@Lo&OD%l0cBhE&Padp+ivC*83Zm|{Tl41|Gtt*j}I(J!Lr6heYEX%;j+xs;y z6Kxo1&|tW%ASW))6s2}q(YLIss-5q2ETxl(p~W*`xDi0ez!PEwNVM{r!TE<}fyU!Xs>Wfv-3oRl&h zEy5o?dIZW$ZI^4C4pm#^UyjZ3L?2n-;{hHZ3KZgWt|mzIg+mc}VNt!_Lo)ObdD9ZJ zodYaT$$v1<4DO($3ZwSXAUOT<=v|w&tJH1#+(r=Ym;(|FBU-iCelOd(%uPw@^Ts-+ z4PEKnfXd0}GNk0Jgd6y_9i4Cq_`m&`oRG9`MTln3gNLx{WH20_ukFEwlsYyln@POJdGfv z@fIsG+LB;Y0Im7vnW2OY4t2xksg2fFs>VU`cGRG>t8!M1wU`g!fA?mA(|C8gufLxt zO2BL7Mz;tqpJRV%b29ha>IgD!wj_S}eT%IGOH{Ak0>JbJFt(VM4BsV@O>ZahZ`|jC z7^DxsvOW)*5I1s7>|Wm|Zy!8=eoD9hE79yDdstMCt&!x4wdcD<@$q&hLl|4Mnjp}7 zknGpQ3n93H(mf}_X*6VFchWh(w_W#UL6sQU`0900bIXGx|YdJAdBzF_3RrU&CI|kDCs(Jo9TzmzkZm3R9Tm92FN1>bqkUJuN=6X^}21ns{G>0+8E4= z5uD@9^DhGfCQ{s1NMzO+=x{&L$!b3#J&l`aG5=k^qTM*rSYDpgVQk=4%KfH$;U7)nSq?}LlY-LGkdZr5+{cq4j7mov{|Wl~9w9k2;WV6_ zoXUSUUxGgWq$GBeR%S!6>~qz~ztYNOQ%71`i>~SH+LwSx@U9v#_??~4m(;Uv zml?o-Nm-vGe8>WxdDyiA7|OeqrKM@VP9{Te>2bt74{9`kWkX#lLAiSoRuuKiU*a%= zkuPAyjxPc2>gDM{u|eTa3C1jYBDNT&$Cd z?mvNHz75W&kGzl;=H`;JDjp!+&|Ceq8V;a?N=6v`{m{?Z{>8G_o<|><8JOEQ&J6Vv zsMkg-fz!W{*0n{1BCc^n^-7Ppa$N!WgJ#bz&nT-C6;~0C7=Uz{Xy_Rj)-HOlbr8N? zjg*A*|ChyNXn2j|d;&U^GAkp!pgo5rnlEkdBF)*aeY#%{)vczfwQ*mA z#nbha8~lV%P6uGwWLX0a(UUpTklxF|0htr)J?n61VG4p4#6b~w^f)XWg+vP~zsA^T z-7e=(K;%cY3m-HS2E~kjjBj)>K+><#hbN=8$@4J64*i#j zj)cn2&TmFmXHU~f2cM^YVJEntF6Mjty5Cgp$(NO5m%4RS-xR5NZDFI?^+)g6f5bA{ z^I1msKRohLZi`_Q%2iE19eTENAIbC~0V#4$ZDH>AAU6v8nZWc0rQ4I>tV61KvORBk z#Zm?wnz8BFv&Am6F$=6b3vcnb5^lMME+k&cD-!#*>wN3G&qN?_-!ji&F<()E5{q%bO)QNJ4?9u zzgn&UGs!Fp@rgKcUTR*)qTfiWdKJ&V=V!yJw(e;?$#USLTCds@nJ2ySeg?70ARB23 z5-=7nij5A;qI{I?6qpojzT;wOCRn-nmt9F!x<)G&KHw{#zV#tAT`%HN*pv8))8m}M z8;TDcF9x}UlT->lQuBZVRnTx6^(^=)m<@|Ndw%dqa#XXIaNV0K>MoE8DKIVehDy>C zWv?XWmH+0kq}YqGX$HAyS;J5&UGKpCj=)zZsfXp}>V`Bd!r{YFc&w32*O^yy;_uK% zt}Auslr6{?O6xxmx$==i-8w@o1;h7NM@4Y@v7#5N=%vF$$lIDkqZnN^wONh$p)o60 z#VF1jwPN3v_9`x^&(V;uR^B5oPbE{TFUEt-KMXF{+|yE&eX;kwNoSi8UbXngD+(um zbc^JT`FrsyQX}uyiRzQtmG#q^++aM`d(m9B2$avE0`n#|<(GK(7`pJgt42XVsYcGQ ztLV62Ta52O}zL7)IeTAT6JbgXKF6_rUguZ#TlMBmPA4z2Ao;zyIpQqUi*17*D=G`!~w zm>c*$eW0$=OEjvhznC2U>wWpS6{?3j*6wA-^xL22uJTbs6Z@WCiwg=@!_$8%vHmV+ z016*E*|LJ)^?aPHU-DXjf!LAxS85{rrCv?YbqaD?x)v=MXD4u$dI}6m8cxsV3$j~x zqPv$}eREj?IscFnt=Dui*B%%$7M2f~Yx$J?CxG1(AYT_2MUj2tl==$7IwXP4qtBaZ zFz555Ebty{k_SS!;)tbBb^6&jjX7z zAA49HP6UA+JUaX5!}@^Zn)!jc8reYAsk%90ablh`4%&FMMS394^|CE+bezNduA$WB zm;MvVUQL2nBg&&i+n(^WMP)n5r0HHwQ0UR^FT?mrrmw87j)64Z>HHEWaDcD%@>Q71 z%x@%-ZMed1su~*pjy`S#fz*wF$(-X&zQ0vN?kataZyMdVCQ%Gjm&hwOH&Q4?3yw|r`>_7UQ0k`c zJrNH%9$%C>ll4u`6I90X>b)ajW=K)=jGPa?T6&OxX|&#dD4lCuIy_s03Fw-*I~@Xt zleYXPDljU>`%7^cR>KUkXz+%X)sXT{$QRDGiq-7)erUN)LYb%4pywMX0t{7riU`4s z;?cT2xBY{2ojcXD(5dDHi|+F^MQCL67mk~z=XWnajFXpZ;%3gO+zAf;qMrZ-E6bId z#r?^wE?V{(KVrZ*PVW9Wnun8;j55eS>r!Xx_N9!g?)>v+Qo0w2y=or~p1fhxs!ypD z)TAl-7B1$TDym$Xcx6MEg(W2~F^?yCLUUE1_;Hl}Qu0coPCVW?#>OrEy|g zK_FCsew3iwpE%!feShjHCA_YoCyL+D)^Z+|Y0Fx!QKk7Wa&ErU00%YdME4~)PPj2O z_*gPA3pxAl#XZ{i@XtW{q$EPy2|8LS?>;DvfZq8&DP8=n*Wx6}LJ!=V(tg_YIV*e` zB2_-_iYAluWf_G%DN9Pi$2d9Bh!yQ48ft^Q>fDupmP-a&z1gPxYCs-=+w}g1q7^6` zK;oSR3lUu517u-Qto-YbI{}~HUY?YX?}JCHGC3EYyd9eyI(A0Zp2I zN!>2#X+x_8pYdiDR-Whix%^$cI!~s3v4!PipO7Yg?Rx=9*P>NF$Thsa$2dg@yIoaY=o}IUt-$apzI8NwN1K%ESYIee6>@zv z>k{Q6W^XI$GZ&Fg>!Q66D-1KLw|;DAH?yM7?5H;8OizSG2Q&ICZOjNEK*E)$4Ug_}Ff?RCre5sh z7yOTA1^%pjqmmKwQ#wTl96b)Yyc^m6DxCatTcHwDJGjiQ{@qmuGb*Edk7i0v506%} zAN5QXElQr$$Y9pGd($?r-x-hg$#6stEbm$l>h`(%%Czzf@{eKtwbrJ!Jc;`%& z;mD;?I{a&RSU|8}3RUm>^I`d;iH7t%5n&{ox&k^;7`t^Tlu6z2TXA5o`L-6eq1Qa$ zSw2MvWEJt~a`V_Tk~F6U;~kNy4hbFB2T!W76ickx^#0{4<3CXeCv7Vf(T%R|xyk@k zlII+51EcsMRhl*48^R<|$WiDqH8J67o6->F%YkX(?4`IjrI~NVfdu=*Q2=AQx9dy_ z)D7JoF{_&c`1L>98BR2rrvV_jb|YFa_s2wGA-meHuN93Aa=>1)1XH^*r64CKPML+zN1ZoIyf?ArLAC%6A0J$juvDyhfUv#3BGfH7Xu-ECmG? z5IcgT*|vVO&`mx?-<{u^Gc68s=REPJsvH0&XFA*HRqNGw_|c@`0@azd9;jdj8F9Bw zm^t2t%aCpN&+*m_9=$oGJ7e&laocO{ z6X=eVIRi2NFM~X@DMwEvZptB8l=!3U;3UbJ$V6cIB0^+jRAhAaq)We)Za@4n(1VK6 zimu|h#9alko^2^H^Xu0WI?gWB6yp(UARV>tSsUX8fn57S_~cOP?8I9mZGG~^KZEB1 zIHzTWnFW|t_s!ITgHR^5uVMUN++E7|x@qRBWz1cybzhSY9=N}r^U3-CT1;YU>!KQ4 z_*Bl_mmKS$mU#z{E*)NRliv*kF7h`Y^<~~%-Wl6C*0?TIDZwIXUWpV7WDED7kfpZ+ z@#Ar;DFA*j>f$#N+_8}~yzd|e$cA<0z`u2TEg=DbPY%|G#4}~T8E=*_xyJhFuMp3h zPj#fgt-J3MjkJj3^67C**>gV`_x5MxL>WH?71%2H?Y$^o1JU&n2jq^>Ms zePNfZ858Y6s#1$UjPLQZ?XQh3GyW-T?R1w))wycJHD2|ExPM$;UM>!tH{g;hE&UEA ze@`4lcL|5O@qo)7G!ERg9Q5CqJS8Rz&tBMDwGcx!?D+GsPbJ-qS^$F*Vl}SN6T$iJ z_$unWITiHr;>$J=p|KWK8C~`1R!jjFenjr>jx*AtX-a>C#3w~*-jx<4^X=#1@7rYn zgaE3Mj8q}Rt{m#|1M(RQ$law(Q- z{T^$Z#N+oGYW<5pDlnHB+@;j}hXY+PT@E(|zQ%BhaReqVohQ1LEIzGAUXEkvo7|KZrSLkWkuIsRG&i}TZP28H93m>V#u*R?dDMmHU zCwRxIqRlUa6OWJmbANPpYB8M!)~w*nSM;l7&Ds6c={rfs8$?Fssn6*}h%p zx4*W!zOL-EHM>6%D5gwfx@N`%+?8JbGjccY8h^`Wp!CvUQ=qwBky#Pcf2W8MKus)B zD1F>4n0W;3H_lF}B3a+XH+eulTCnX&bT$_~)%EMw)eXx=SHTD1d;ShZ9cy+ z^LO@v-}Y}_Ifp0BEI>Yx$c2ssVf_pRfo#6Oqs^ueY9K=J9U599gC386RY|1iM7Dca z1$fKx)D)4@v(?<)+#aMl7_up!9Nlc3m8?D?7xnw@_dE{tW0awKwlDVcurctIMLC>G zpv&Wxr#z)9`K3Q!KU2xSX6Ue*&{(=C_Tz~7)Aadn;{Y+Re)?h-Ne*O;7>wA$AP|(` zpWA;1yec^?rr3mw&o1ox#^^#IkiqXADrP3nhl1DueV{TSj+oBtc`PUwHLstfP^S8Lr8ZI-Q6*W5aNybW8Z4KY?B6WJ>&QSBKRRA;QQwdqorB>&SSAW%d2x!ce8qrdh_N~ zhq_Ed;=vvZgL>4#OGN@_XJ?c5lhrw=5S*EpF~7WpFU6WKynARFkWTJapDrDE-DFY2 z@3G=P&&YG5U{I*>;28Lc@ z?gvY4bycz@$|Ey#K0(`=_>`0-K~C~;#-pJ1Gj)QYAyq@Y28V-@XI@xp$Zjg`1G(zH zzND>A=h715Hln%S96#5 zIQNqz-0X51BMk{7P?z)EA&5c56PC)7p*4OmMHIx66ag(4K1*G^F-fRBGIRIfYtnbn zY}sMJO&cG-2Nps{;J21DF-Rt1|DBHn+a-OlJ%m_5ux7VFN|~F3F%{Kc;@*=jj%eM* zb8&P$_+~6z+eW6VaQSwe7>15G^bZJd?GnDY{#kC4CphGxA#{;QgL3;bO?7Gwg7WcM z7O9{cI1zBA1Z<*YvVP0QOioMnGJ3Vtf2W%=red#)W{vi1#`5K34zUijnb-VczJuCc ziiKY&ruMT_OZLG4*#WkZ}EQzK?5aaCy6IXM_gy8$SO6 z#rr!YU1<+Tbm03>9Ni=~-`;fVj+;AB{p45Puh-~oHbKDM`I@l!=Z=Pb=oXg03kpzP zN*dj9mi@QbKksPSDH2%k&@13y$lJVmk$k;T;N4q7dggKkh_m7GmS`^RrqIj}TVse^ zd_(b6YHx4vB`J2Cw7SFQ@T+1(?)*Iz;lH6UdzjSNbN8O$+LMk`vVsQ+LQxNPg@(?* zPXfB$!5eB%bw3KHjzW=;m{?3!5ovJJZgID_lv#UgIHNh;3q1%S;KKMf+V}PV z7|}yOhe^RKcR5h`g!xEyIq)+Q#RhTXc%p&>K! zI}bw}2e=Q3iHQ#;K~9)Qga54~OP7RwT(J4hR@|?AUw=3=ZQ@7k)2h;*#gWF#-R`E2 zGhKdG;+QM{#@%fK?q38N({>^q9^VGal%OByP-#sz|90b}yX^-P2(gtA=B(sadJx$z z&{TtfdWoE#{}#0|m485>pb}YQvetS`fJYDB-BX_nO>46F@6!$7({?CZT!0^-OP|-U zF4r4(N4oEs+zmGB7211LqhfFjk$YlWwVBoQaFLMyicEZMtg=eCMg_eHu_606h+15o z65{*Qlp{|Rtc<}0N@ zbDguvbLNnEW+JHyTQ>rauX`(+H%W%?SPTjBzs!ICGVn!!`Y|$#JzU;k@S2ze8$ctC z61l(A&K2W=p9$8KW=DsIpPX%RAw(Z!ot#Rod}t+LctI{qK8Oi1qvQMK*chPu2vCh^ z&;;8K)A)AD7mK_HOaQo0`1oj*6t2Yn9jrwpyt;ariu>E`{}5sr8K&|7XQ@Bh<2t`` z_>HseJfiE?LpTi#%DzC`V*MvRJJLwB9C|U!FG%9MnS(9__GSO=9VQr7JcbwBScq*l zV1FAM>sti{fSGtZ@0O&{dM3>N`xXSEciP#sO|fz-@LNBX@(_5Vo}Pj(GIxKtl@U+Z zJxM4H)h}^%RvyhWSG;ncE;+OQ?>iD&Q9qd93t`8RY;iUxzn2=pf8_2=y;vC-{I&2Z zV2$U0CIe~}U!=lpVOGAC#&M67Ds_mhMiT$eqenY+!p@_IUjL2f<3pgAYZA>GB5Q0U z)}5GQNgwKoP4-#=nFaU|B;>!H{=(C^eW@&diXxI#*-xNZTcYwGoPw0xFv;1qA+YG* z`|WYBS#Hh-ZhE-YW0Lp#Q0q4Zs{JYRf~#~oxBeD*aD&pm!UPa15DM0C=Y`4LU7i{( zHBrZ$D(fKUOfJ+ELkgETpp2a_^SWfl4 z7`HVZAqCauw$42N`?+snPrAwx6AW4@T#;yas|!E5)gz${WvVj>i+`8~qI2q^WIy7# za?RP+P(<>FQS;1uzBJqT z5E9Y@Y)SKe#;3oN+9^{@LV!5|wV_w$jh11eee*K#|7M$O#EoEmr`;OsAyc?Fv3mDwNs-|30(ajWqH$dJ#j+-kQy`2Qz_ zm;1p0j*z{Y9Vj2w`R@4%_zV|?Eyc#Kv%ayhQ1c&7iCY3`OS%eb(6&b-caRKH zpc?{33+hzzAD)t+dc|icJO0lYKTQ!wpGRL~4dI*)!xW?7orfBa18L@CTZ|FVd9-V) z$-v-GW3tO-KP}xy9D0(vkHnYOG|$ieX}BGtJAF{xtc71U9VT`XZ&^j)?-&aXin*4* ztk8Vy{mfSJ5g4ErC$zI3e`fV~u2lciXAny(cT|fLQt25_)1UiU{>A1*G-L<%^Z z37(xsYx|~ngQ6$J4GoF2_x`=EbTow*E&nCj>g}_nhVmR~zXuPOuOu%B`X=YU5z-0^ zJ5pNP|9cbU&Q*z0w?;xKf7EHOsL23?Z8?^cU!eUA0&qyeO#*Ejra;nO&MAYt2q=RD z9>cmvH9-7Q;G2{4FC1uS>WC`a{yTgN7-4iFY1UKALdMbWB^s1NgA}RKY`}mv*7|KF z4}On~?8z;K6G|d8I|j3wn?>DYQgT+dG9V1^LS16G&dvhpq#Cl~DU(OW*@63yKFj6q!76K0m*5LPa{^ z`TeKuO1*)pc_s<@Bm;5$W-pX;jVASo)$WwmZ<*pzwRZqK6N67k$o~8gZL&YOxX6Th z@|G0wbLQvF4l}BI*=>cUJ~MTt_kVhmYayke`qZ9i3c1 z3a+a|MX#<1w%eokLG~skqn#I<6`XYqB2cGGn?2{_tJ$pH^dQhI1tmL0GOPOCp+qs} zkZ3_=`~-YfrE-T7ySx%x{hRt6>C|dO4E&9rd(+98d8*=-K0fhZNM`jNERla4XJ%N? zz-Q=`S8|j+{(?gf6U3Tp@yi!hWx$Xq ztK+2rL!u)>9Nh5YBz+-Z)8b+FhzMn~78?$b5Ah@QTSsM@3Rz67;4?qVvZ_CGQ#Cclw5Y)x2m=9pvAuaB*oz0E#95V|`7%R1RX4 zM;pA3&-<^lw`^xVo`wL1=EVmLs}`Uj>weJkJF#Zx!^6(4z{Q&>Dt2`hVtQ>+@~lFp=&=4!}|r z+*UFW(zk&_GE@#=oMS(4?OGlYvE*+Yf52#TRzmnRSO3+N7H@64tPkXx91=f6yUYAqF0nQ`clv8fN zqe$=#)QVyMUidE-MxA`M>{n5X650g{^Y>^ncYYyLX=^iz8b=bnBy8Lv#wT`|pj}^C zK%o$v+h6Bqu@)9$M+?V0OX{)jz>3G%b~3TcS|JO@J$E_mt2Ph@+hdH?XLF{a29 z9UY0v0!3zqpEwjga#8XZ(}j9h{)bZ~+eGSGygza+5yYi)> zUyJ}MjV-?6LnYTWF65G9JtYtrtIjz55ox z-5x)fMnL&+46AyJ-FBuNjUB5Jdrn>sNcLPE}KgAw{kg~ zH}zsm^~y4QZ$fmcOAJ!0$ZJsD4D!`Ub&+C7j&Rzh8p`a|)PYOMLBFQdrmd~9IJ^2E z<%tMtc^o~A2&(HB)gFnhxO$6z7gdDeBgT*|3tK~|)M^o~&_>~$K|+Dd)Psi$y}eH+ zt3{p(2}wYupfAzL7jsH!YScu5IBzx*SwRp5fI$^CBPfZO#q9b_V#dcJo_ZlxKV7*2 z{2Z>(p>QAv4R}vf(hmEx@a{lhKP8bLVv?`6a8!EYxYi0{;J70862BM&w`Owy z#CQc&3`TQ=LPKfQ;CgaV@Kt%PnuYi=0EInxk}lc~&&}Ui_+o(`i_+-PG&x>6>$)*NZYD*Swot-Kmx%FT@6#n}uJTsJMOlVQ(D{f6X1Tjw;f@jRvJL{3A8^PgKjx zIY_nHaqX3v7@ny9S_NpP-r*W?9^4OeqG|97WbrO6T5A;3h3auoLq zQY3QK-175(=IH^cnK_NujLU9AIDhQCO~T|0Xlu z@4~Ut?{Rg9mg$pg|4~`@?zd-b0zWzXpvhEz=y7FY0dWq+15d0beUxF2C ztwEU=EFeA24FollgH#JnA&_Tq$!9>Isz>> zh0KXSGf}ZijNLiobf)-{Y-9T!e~+U_V4|HHd?j=xgn~lP3$4zY+WIHN8cqlYdVcC{ z4O>k5&aG{)xKF>mO|O+)Squ#5jj0%-<|G(`)bmP)kuI;nrLu&^W~_7c;Kp92Zm2cBg%a5$HMArta2YSR~ zdG=uS9vjSqYxIn9?T*!_vzDS`L-`VK=4vU219`{q0Z_&g7>qw{b9rKR%KDSB@6@$f zBx{|QSX8Sl!9(qnpYhj@Hw01q0DqmVu^lZ*yCRGmIo7Dl&P*rW(BNkE^|*}eK;(Mq zH+hAR?{Yu15G|XB>LNKxI6F%Zk-*!=@!Q|clD3uD-5x$YzHXP z)(O5Vw3_x>5kM_Q2)fVA#bOr1T<`$I6KitYz>%Z85RlM*xZG>;Dpsqqa`Si7$t+(K z1Q}VJ5?vVVpfBWwHWrroz_QnM{^6ny7pzae^flHsyL@IpKVEI{HC*wJdC5m7DvFeBNh+%UIE6Ury{=_=y{Q6%gb(ie|p^|*mz# z%RyEfCuIq`Gvq0#TmVXbhn2rh^!h6GX3hBKAqsykOOe=fVo!hZIcN@nt3J+}MFN3A zqvQ>&J_PGN`)(h+5OYXl*WQVz_s89>sG+U0*n4Dgm_^R`QnIwMjT^vF9zU<*(n}BB zzx?4>VB`5|!66q)C$BY{^(iCcPNGYh_Mi4ARn^4|NFa~`a+gXAo_G^Dbd)I|@- zWo&57a!|Pavykbg`iPRnW~ApED2HOvV&8>7xokf_Z9;q;J#wI0x%%VDK?C&AV8df` zvLAK&X?qX~<#)H-ekZ_X$nO@10s7ikER(4k0bl*ZB%?Tl0DOBK;PH7f^)2zUfK^FWcUQVhwQ#cJ+QM=v$NefL+8 za3>MlKqH>_&$rKiMu%6WeRuzEP_aaNttE{9?-A>EKKJycSomSxmp(O`scLZHi+ zez|GnBoNmh_E`xJ#Qw!a?PgHksDZ=Oq(`YRsecLHnNeEU(9lp+6ar63OkCJ|jv6O) z;{*0L#UN{MZ_~*}cKJzZh%r#u#7ml>4oI6~rbl@11FO_HgA0@;!bLCko2tPc6`H)4 z5eml(+Fh{-3w(U(TCL2YBJ1h;JB(7VrKQObU%l?+!vOtwe?<}-M4U%#xlzX5Rw)BV z*dQ24yX0;d_#Dmr;i4M}9?_@bIz0NTqk|-19D)X&b1xNVDzBak1PD?OkfnUF``WPH3(#f^ij%7lmFTih*=AM@3sMz*QN-) z&lld*apJ&nn{d4{>#!Xgbvpnjs(=}XLZ9i?*e`qmDoHfD^=LHWzgoq#{{LW?PA&hg zj>GThjX)7nV@L0dPzI**9|pGCJka_N7UzaJVs+lzRo|)rFYYBl^q-)8G_uL-nI!w; zU|K?{-TKPpvo?9IPgM_o|6VsKr;n~rR+w$}h=tqCG`js+9}Y8ndSN2e*rov@(P}lk zY%`2&K8^9J^mbY1bVb&jzvyF|Et{jz`TAUOzp!yY z1|;k2>&Khp#^=7e^BAb7BYRKOc(1M6YdGfefV#-v#FIY2b^l0JepO=oeTW{=T;+gP zuK#3r8QEo*{Z{+&mfCJ@43!PlKXIyEF1^-ey(0+$;Wj9pG;6at#ksoKeoTKFsgagx z*hmvsxIQ`_#Vs9(`$oerA?)_q^-dW z=I7rw21q5de1`fwuHGCaLe=un;PP}k34nDOQMH4o`>0>xbEFU*aKSy>O?1+nglWa9 z?09mU=*;DBIk9W6A8b*g*yNt;C*0^@R8(Fj6tP!~_iX{7QeR=82TKlXyb7GBhn=Cn z^IXc?>>$$cfP9SG^;hVyr~R)Npem44l@}k#%u1HUSyC&H_Q-p@=(Qf!nSp_m;_%+s zf#!-m(n-NbM@RN7EAIk@_XU@Q4FZ5#(BE3T4gx`XHi(_G(seth>F<(5vVrX$8~nvw z#-Fd=-T|!QtBz^#s!MTND?}{7Z6yn}ET^NJn2-RM$uGEQEa=W(Dk5L%jSKc>=Kqc% zJ^%#Ti&n*pj=5^;2+{@JvWS_sAjaFG+yMPo*!9~pmrqeaF^odag0_OXe*iqhV7fZb_2%b0605cVdZ8NcGG=->%{KSH)v3CImNIo9egG%wDZmwD~u!sJiHq6N>FFeng zP&&9@VObn{zNy1V!)E413D}}xf8B+;jgNI+JscFX(Qa0wOT$BC) zT*Q(zAW}}DeLjKm042Oax?52WJ}$_}f*arCEv%*3vn#}p>RWW6y~_I383(s;a*Fa) z{xwszH?zBHgX04;rD9jMtcw^;Cnbf1jJ~mhd{Y^uQyUyg{ni_F3CDayPyIhh2Isp# zYaC6fm#x*)7H?9~0dZ&}w#YS4UnX);Qa2g9G9IwvL;I(I&Dv$-lR?@Wn4i~>Lh|R8 z&;g`O{#i28i;U!(xMqqf9YpM2mLS5w9mz_!;>k8GrlEOY6(i6R8Ga(L%L z+m>PNQ!9uWmJjb7R)WRi^CqB(m+yTYpDMpQ-kB}A8M&q>R}qz#NoR$25&So3`WNuD z6wmSljX+jC-Y4z!p}I4$MaQ1XqtqK}z&MnWa8YlW!)4-@VL(W~v9WO=M82wd9?nV) z#M3&unsvH`i|$CZaiD-R9X|~Z3;f%E!0u1^t@IQt>3Kr0iok|RoZ#d+l1WHj#8)rP zy6b+Q|%RVYZ*qD{f7jB9?E zx}EP7uDj~)Y(oH0C)&)~$YfPUA3L4rWy$q(8#V*G-I}bKlsConvC7=lDSGL0}A?~ zE1|V7+NBOizYwoVLKt-1&h|s3f|xhfEsPo-37-(XV+N&3zJjm|X|gK-;n-&hCfK*& zP(v>JcPERB(A)eGcJ``*;9<#sM=&d`(KNpzH5(*10?1r*&`cj6uMeU9^#hjhjH2L*k41Y7aY5|* z-_uFYQaGGlU2pWxgiwJ{v?Q-vUfELvC$gmeA9aa|iDy}9?5qls^rYll7*h1e5)%h# znf-g=j-}W>MZwPQRyLNrG?-=VvcJ zIAn=<9M`I!e{@+cv_w|2)dNCrVn~<+>I3u&n65&>VStkg=0Q%H1Lc-fPBC)CeV{y5 zpOK%+-sP-b^?|kse&|X#t57&+DIQmH3Q*(=c#fxMG|{c`l_Kyw9X-QKp4YKC z_DYzp4#_&q=Y++s63S}x)akBeaUMG=^9S=lT+CeKPIDdj`H zXp28QwotiafAXxWuIRo!`>S`0muCYdUeWhx95qIYbORzFK2}O9xzOr5l}p9>!xuH1 zYN)}RqXpY1^hmv9>0Q#Cu9l6^Krnzs=mH#I8Css#$0 z3Ed%6M!?@?jub$lMj}jX{z3ugq->ex=^`gHK46jT~n*4vz2ii@Zcp(I!5d zjStFSSK%%(kYIq4hG*tOO=p!Kr?Ur z$c};np){)tlKs{~ChAbm_wu%uXmW;wm%~)c{VzJq)SY1`habqX!(~wKq9B8_HQ)-5 z=!Rf$!-U{H)ao~*HfL(}riNXONj?MgeCg?acD}+3IgtdZvLEwBnYAA1p&G>eSfi#p z*m$Y8v{LasT!wk#8EQD=UO|HW9oVCyl3u5{n!H-p_5m_;BN^ohN1<&ZAWF*)HK4pd zE-lBZjhQR6{S{~_d3pOZn)lNtu6H!v*8Wl!L@ur901MAAC@8q?=)`LG`ad)-q`iW9 zYZiAKB>^=y|EsTGvRPi&DUz2g@Tv1{ww1M4;3Ae)Gqok?CVyNc(aGdL(Edn0G-~4_ za)h(4U`&?_%MN8&VenPTDPS|MON`M@?0P`k-oDYI-wxwIDK(WtU8(#F=%?y zrBtB6`$Vnj^67OyONLv-vAim&egmN-kc`~ka<=5E89v_c@$&kU!iH=hAf8aI=Wv`n z7A-@g_Wi$59q5Z2C$OEiFw?`>y5jZvKDLeV?C6Jg4*DhQy}rL}-8F_yMJ1I8#y@_- z`Bxn6({&M#L_du!JO7*+kFTKV5I!9SJ?;q&4J`rMQ4O7kZ;SnEX_-eqx2;5{6Au&w z@pl=22^EXW+J@5=4!@}_)Y;5Z+Ak+TputPnpFJfu1^c|emvW@BkVvVMc9wpZgi3u_ zjM}s3CPkQS%-wmZBtlvik{>j7z%iftyrZ~?!qaYz#aPXpkr`JfVDsL<-JstYJjItJ z9cG2Lh3bNbH0n*6tmlQ{2w*ClQ zj8|+$23fI>7)`dxEaJuzi?%tj{ozxg4}4EU`u6! z+xeS*BpgOPv|;kLF@oZU)6Q_Mg&uv7)HfNmA0?kvDK1+G@~G9H%=?U)p?-;8(FcvH zv@dsPfUbI~)-VnKU@=%-bv#REm4+%KgITK&y4@O|-}t?eineDTQIYs)(QG(#-&ntM z3E;XSNQ-EDi=>mEV1Kubdu;foyu!;XZ+V4H+&TpqplDL@quoXQlqUEGo0*;>ZjZO) zDLBW#foh>Fp2Z~kCbK?WbD9_;stpeZd*!j}k?Fk65iY3E)eDMUCz_Ki-N$#{-KsLFLDL^*QiL_J?Sdu( zaJtt3b@jTic4-C`lubdMSY238rH@ivTB2tzvSrs3=Kk|=vAGuML6Lew_C1eZGuTVi z=H(0a5@Ct>bkWOKMkwde(i&Xn>!GqQk zwGfguuPR$D@(6*;^@si*(QuP!8@$7t;VBMPlvNCdr^T@?)~Z8uPn(oTz7BWb3dK_H zpICuF2I>@H$OKC_baA_%GlMEad7(RKCTM_FFvH}w45pk|)@sn8V8VOM4V5rEXRx$= zV_CwY%K&D05!oBT#itLE?L~fMi>(kU9KLUubTIGRSFTlQr_e|i@{PNnx3~Y%l!u&@ zvY7JZbwzwuwQCh+>$+uCyM`t2xJ$8mL{UU$bdl7ZKQOM9m&#omzDPZ#s4CI_M>BUd6{2D z`MMzmInXBMRaL_oM9*v7XZbl5V9eZ4^or$;f+Jz0#`lf$O1f){^FQ!|9;)SaJXjhD zoTr@LOXN@sd7D`* z4P8m2w8raKK;!xYsc^V~VVvnE!#dN8@Lo!LPak}|Pe*cAai;kMmAp>3Xh4` z|4_jM98)h`o&8v>q$r|NhGa0`J%|u3^5g4`8XQZoL4}_2EKzD*= z|5EMP`yeKvPkHt#<(X9#AaVF^M~vuL(!^yaPUu$~&Ke3u;kl`3d4qWkcAyjSZBw~u zru`tPM3~e-EkWnjR9p4HMpJ?#l^uKru~o%d#YIQGWc&0ku+%x~m?-9vCSx%}G0d zUw4H|8p`nEF@j{kygr1hL!4GCK^6B%8Wa|~CQS6POOzu|AX|2XQVI=6{#gASi!Qa% zw$Uyi;+v)(x_{DjSeU|%(u^WNu9n*6d3sT*JR|2yMlX$-IEDORe*R`A;x@kebT}Xl zKr=3Z;j1j5*{VJ_$Pj`I3tkdfvc!4x{7>Uh2>kBScc3|Dg}53>lOZ{_o^Jn&O1@&T z>?5csDOjhFvZQJ&iZD_CwOu@UAT&xUVWFvptfND;iErL0E7SS4GwnJ45KaA2%&%eX z^oCShM0q!oQT1^k!$f%(mye=1h?Q}u%WxNN5941e4}NLyf2Cm#6!4}Drz*Q`5p;T; zOPkX6k9Px5;1o@CkeDC8ffdcJl5VeJ zpJn&i)73RgTz1D7SqhGp!~TBwIHCIH{z=kUfb*m3f&rkz0NHt*HJ0}Yv09(My!@i` zUX2u((Uw#}(6;Zw0fzX&fLGSo& zHn6fD`NBcl`(iPk;Ah%XJa4?C#;|k#8aAtAF8|)x&w|iq7}P#6z*Qh|!#H|yjUT1P zrjn=j(#Cs)Ksu>ImdmC7PGBS^WQdXQ;vP_&ISB~wv{oPP>rlh5-uMA)3KsU2kF2Qd z>>^Yy?8HTPVFjuX3Xe)l#gOG`>0{I9kCh=bm9*scl72DtZO=<7!Dhy`d8_?BPJT`6UJ z7Ya>|h*BAjvfzVk;Jnke_m;Rc0@|klh zj_tS~xN^2F5wB8rpTHz{j5CAW(R=U1$QYUVZ#LOtX}Q;4GoRY|7dYzeIBn4?hK7c# z-$*d>rNqjuh)L}7mqiVV!f8q{i9D8FJV7|J6F7swr~Ts?;} z8y`g`8ygesZzIph=-Y-LA?BChA0@x3=?0px@8HeRmR?7GCS#M@oByu27feH~^!npH z4?J6f`fYT|FLJWn@@h38a~>E>1$febYFT zU=ZhVyU*^t)MM^ImS}UZt>7MeTQB(Fk8fPOXoI828^0KvuS>mZ$Fo%I5-&V_X2W^F;L3<)2*5_mdsFDD{L2w4NU&|5%9+Fx#USixIFVT zel(C|JIh*kaasPLJ)b$Z3YJP_3(h)jh!;xeJ(e5Pkv-RyeSlsn^m0bn6s!X*k~LO1 z934EopW}q#^J{Ol3X@K$_P|B`H9rYgJ0>-|G+9!(Mr|hHLA8pkpIke}y0A$+EH_yi za8j#dO*0g|?8-nh{UL%BxU~h;!;U!abw>k{NWt9N#1c?Vm`$!v6jXi}TJUDzjgcbI zEhi0_vGB6)OmN?dLrK(bbb7tP$I@5l+I2!#tb0gnfN_j$RPgJ?lW=yj)h%l)> z8=zW#h2}C6U^~p`K(ipOM~LjlcmW`VHh|@+x6;VM#TB?0cJh<@eTSZ<%q{oVs&z8~ zq$7-nDX*P1u=nxP&Gi+KWV-a9vo|GCsfre+X0ZYfbQ7bJYQ)hu>r6wu3_G>DX+QD9 zE7>z?${SzB2t(Mo0yR*+aDemCsOvM~zAxhbQOcfqP?w|uKZG$Kz?dER6KN#rBRs|| zcUrtf#jXknw+(Q?!K*~yGR6z{qS!dQ=P0{3ECenFdxC$oW>IAf0Qn*b!Ot5VoK(hJ zS~*O0`};P|VV$=g4Hy4oZ~17+;o~^bmJ%*<52n{U`#}j%hJoqnCeI5OFRX#%t;xxW z3E$LLIYVm`6FOd1B&w>amnzTVA9i|9aVb2A!T~P2oekrcLrE%C8>xlZlm@97w67io zh^j|jK=Sm-f#^VN_R(aBu`tQ8W;RsLk@k8wtjh!QIjg=R-mBLbUER?c&w12;rHh`n zJclIsKGj2ay8Tg+32;js`BvwwAsWSrft@70^G)Mb6#lc9FXf@xbt2O!M2KgkwaSrjmEq~Q^j)*j&M8ZXZT&j01Wr?_ zBVpGz#V{U>^TdhF`}6k!TNfN+C=sj@dQbo<-bk}HTd;H_e zX3vXb(vk|-2($^?tMI>g!Ojy#{hY@WxFH3c(^XQk8s&wFTL7n^mQ!1W$f$2Sz0iuu zBhvSdd|srurhj&^?TDW@+!wD)lOt%oV+#9h`a%y~^jS0o=*YApi#@d_XagvA?N8f- zZ0y44uV#|)zI|bn14%GaUj3|~?(S6qc~yxElu$_-nm-N>4Ly*1YvgEkFf+UTj1WRC z5F$)R7FB2khy7*@viYi5 z&1RG-oaBDA;x4grS6harjE|3ayh;mo4m1)++uya3c6p1%xE)BKjJnd1A%2E>Um7RA zY6B1*=hyl22A}3en}%gk`B*`r~_+-KVDh6U#n2l%eRo zVT&5x*C0R{8MINc9>L#v^PhJ-d-i^XF|*_~L-!q{I=Vs6Jp=J!_hfySga6_QWm+wXveu`nL1(GOu#k6?E^xf_4b z3K=0YSFcrb`H-XBA4DTl{zM|}ttLGPxL>G=1WwTV=DKFqYZ6_{P(TkeNo1u62r=R7 z(|m{dJmN{be06m-r9Dxt%K37uDIi$J$1mTJv8eB2LyrCHr6L4igLgNGe-*QLNuM3F z$lEW3;RlB7zpLQ+^769W{Szeef@l4@54f-!C%L1$dn?09EYDAlm0?CRx{$SeAHcK=b(r(k!6E*#H~EP5Mf+{ct-kkIgHO zROH|fAJ9U7s!lWNh#t%$Z@Z?M4y2?Hw?Q70O4KTnQ)ve)CMXXlLN#xh?*n>jLbfhS zDZK05?yhzK>t}$pdUC{XuE51TGJH@gW|OUvQ4;B!6jN$ZJJB8wKi2KAC2_(7THc3g z&5AK0Qu4)}9+mei*|B}_e~ijch;0;-LQ3T1HeXo?Gzr^2T29>C+k5tYWVhgKs@^%s zFrU*g=cBOAATRpk6)QVfcrt;IWyMsNBTyg&&yW>1aa>bMjvyr3eId!)<}xaIUT4@= zOCLyN?hI5`)@regk0pq(!z{xj49uuS;|LJt{0u-;oPsvK z?d;~?#39=U+Lyt$=_ZI6#Jf;dho%oi<5a9ya$K(Z>Z*a|U!h}_|LX;iCof@z!PLED zdt+Q#TKuaUG|sQJXXd#XBxS!1Jd@QcWF=X;fkbfrtr1~Id8Irbc?^VU>{%#&l5MR!k#9|6wC+Vqn` z6n_BmV}YhVc@kJm;D%4ZOWT*1{=L{)hz@22ucbxDfYb#+Y@cS5wWr!(z`0%U25g&)!jo`&U{BTX(MqT|z;w0JZZw)b0S>BaK^Umzfe zJkj>=uWZdKGP{U(*ZHHO%|07aWnBD;C!Pu@1YDBSPnu639DW*gqPqR71SO)^>jXQ^ zEhXoWa2Y38SKHak)k)-BO5RuJ2Q0(G492IAMe-C#;&CE371|*}k!^&x@bk z6qi7d#_1%evPPJT0i{sbcZk#d0UAmmR=75y78OqDb%905JI&a62m!XnCcCw?ia0>w zeFFk@C%}JrVS&hPw#n`f>8-5|(NAhvu6) z@COxu_4kI%x(6AWYkeM+-U~e?^kU?Yx!Lesm*D(B@NV-8e7m zpw(^*xjY`e6gir79Uz+?;;Bz147;-=Vbe2aBIVvIS_IsulU#G6Mb* zUMB8;*~NS58ndN!w~D2Yf8n6WuIG?07SXX_S|}-Q#H|+LVcMj()era?Yq#!29%uOn z7sT`4_bI;&`db~qBuuvwoo6rvpFL~i_R|0^Sq^ieqq4*iSu$-QuN)-Bls&i#NZU5d zQq5m*Dp^qx2qz11Tku)rOlJ67G)MM7zngH~Mo zE!1@thTAu4DJ~~sWHR(CMR|w6&kx5o9X#j z$=rs93znNhvWw4CKqXc)v7{ZncxPIwjek+B(4MzCrWBicd#vSuwCyC-S zhc{dE$-udQET!jZQJ}$ zoaYz0^e?KFJ#d2H+?E9*at?{MIUJH>j;ovNBk%qvythiaTrYT`K~A#tP1aa|?MuUc z3}+p!iU=}^-0Q`lHMMJu=l6Elsrm#PLDeWzft!;RsfN_*4Tk6 zh5bL8zB($(?hAK7noqjB28IUdmWH9bySt@RrMo2s8M;FnR2l@NLAtxU@9Xd0d)E6G zYi126-W|_=_H&w&dz-5L0|(z4a}W$BcI(OfBNZsT^@f*aHoUlUb0+)RC7J$QISU+W z?(+&0J7!*K8D-miNnGqh>)P=<(62+|Qp?~2?<$9~R8RT`+tig!LZj5%w8F1gZJx@4 z|Ju>+VX9yJ=gIhj=l=wRPKr-7p&AC=)MHO179OQo-NaPhh#iTc)JGKxZ`d?)9S66pjur!vCuilq==m{5qQd^*+UN^? zS4lS+!gCATrinW3ygm0nb$aRNqp-K7DlA@XZc=(%Ha!=)=U~$Acl=j+U{}=~8KX$( z167PGeOt)#)##+oxxfr_P{CcSe9@a}-0$IIkn>c|^%u#H`Ac^@@!X zj7n~iWWNFr7F(qkc=7D9Q*y;%_@JV+?0-4yiTX=A=kM<#`-Qq$ZZ{%g2CeVJP&R+;WYGDW^&iS;#D2Y5BFH;XR*BAr72i)H?L z|A^zq`1Pjm#Z1!i>*L&uWWjAMW~U>gv>OriHcX3y_|}l`RYdQCyHsVs z7=-!*uhoDg(f(V_Dnh=zCf z;Gf8ZG~a~TCGq^W2)c#w%~X5TVE+E{4Y}*SXO;=t#|}j3|1SM$VD`~m>ETtarYR)t*mtE z^D&_^c9rF>L>F`Ke|(eBjV%$l96Jv~D+hzl2Ziht7vqkW@6}zr+SwzP?0Ju=-HC4) zrR)3zenmus@Ds=#56z^!5jm8j=vR>+5TFI06&?}Rv&!4*gB|pR`m=C|*f?k~PZHtcs&KVZ(eM(uHGTFdN&Rpo34=&s&d}(DUTM+Q#)bAE3K>i zXdiN{7C`*EVsFo6d1-Y)0C_7SI?aA%fd4O0_Gg;m5rj&;Eo+TVGx&aLiO5)*QN{23 zxE!YX)l$=ZNS#GnQc6iF#@>F5y{pCScUrguA|M~RwqWV!$sw#b+o183KZK4YLtijy7&%ljZLHE zl9g80qCbw~P_tagI;(!7=-L0mQP^(&FVz$J!_WaeikdR^%^@U)X{H(JPW>x#ZjZI? zN$pR?5B}WGBcnKm*DOJNT)JU6Fjx8hKY{_g>P1S15=7>uOTE{;PM3usPR7CB9?-Rk zDy^yll7x#4bQ}gm=xfHG{D4!D8vli-*u<-JlwW~`J{ovRViKs1p~+<(Z#wkSx9H?1 zJth$%LZQ_a0^?H^WknG(kgo1$F3F5kvejjtfu# ze8?}HVD3vN1fY55=wBk6Ee&k$hNuaS^Z6%3X~|&cqHw|p1(1~+yQaH)A={1RVuMWr zXRj4lOjNO(O@9TU?Meqt!?9AGg#h@^X$rHlT4~}J+dOoUzW9bFUkP9*rFJw~Z|Po4 zE=-C2ec$*~Rr9Dfd3N@2bMvWOVKdS2JOr}BE-&Rdb<~rxMhGGPlFovk0p8zs3R3{u zTA5WFnFQbrH8$17qn!5~D=K1W6v{bDU)|B^Us?uzsL0!zeQIrh3`5F*uB@XyOWZ=E z1&g%>eaAq^AuOhB6w+(4y)D13(g-^U&-Sc-x4uBIys>){6TRBpDO+7 z0v|$54pi!ydarFBye5utZ7;rBmI3lpfOHfLCOwiYVJRMpqX5`nTAE~0GeROg-~CgD zAmt|vUCyUdD~~WGReP=@^LN#R5W5K77cvLHb$7dM?!XibGT2SDq3K07QwV$l0tK%G zQ16~v14H60k_?=Qdf2hl^!z+g%nXaYp{61G;%`NWN;sCxT?;-_h?^9j-zw8MR@NFB z7poz(%)b3aLW1fS^PiG& z1LHHe5ci9s&*~f9S$Qd7!O8`BxICJR`?sbtX$%t`x(qeieR!Rw5RlpG#o!EExOv!S z!sux19m{JRN;7EG*(yr6A-z9>@?QV=B5Yd)Ovw(bCNVXkjtNz|?r-ZJiK-dWM~@(e zMmm=r#C<*;i$O3;qN@D`X4QXpQ|adIuEI9(Ruywl@4ga)XkmC~G&@FA6QNW%i3SJU zfAB?ydMIu1gP%7xScg|{ax|MSgVmtepOC21V zC$j+l12<_)#=t}=RxGp;cWLkq1So|kFR1CM*iypQfi72D{V$XHYKAN*-kSJUQ2a{s zthJ|rVH2I1!`3BztvGr0Z&a?QHQt(Ok9Y0uS`{h|^iqUz|*=}s1>M_zhZ7rNxfW%YI~Eod7XXQq0|;IJVf z>CRdnD8_`wZaN&(879%&VSgB-v+1HP$T215z910;)z%F4)RvP}o`rj=p@RUYqZ6x==!R|` zAX^K4FwiCEa9-`|{G$pm7Cx{T);-W6Q5izf(jcpQCwt%2{9+6+2(l5f980`~gjMH$ zkBuD+FcDkOpF*C|u$@lT^*(tzntk$&Wf6;fbRKwJyspsdT+JLwTQL-PYLD7PXP3a6 zc9W9^@cHT&?bGPOC(-P;BUKG$*$wO3L&>uUw=OQqFOnKuW?z#tx{`+iiFgvkKlTvO zVPlUZN6N)ZCxNxNf{O>?=KaAb3;0ous1lC>L+asseYUAWUV@tcStN?vhIxbo9hL5@ zo|$|l8p*nio_!BpJhSnL2QFq>a@c1L`ETxu0X|+G@iIA@HY)cwc0DF;g-KU(*A+ks z%b53jkmJc~I(BjygCFLU6N%tech3F3{D=7O(Eu7z`LLXsT3+lfP%&->4+E@OU0q#u zb#-J!DScWSuSjlupS?m*%?J3FACo&y4OCG(F~Ahk!SeBUiD0F1 zMWDe9L;zIK{)s|F|N6T+UwCPcj*_eM?hE0!fDF&~NDl~DbEIP*vXua+_aL=MS^jS! zWKMJDPV-$AIl89g29R>{78+L2 zR`%X$Y)_*I;4>V4Pc4_l+kb?v0Kl&ZC(-jM`*W@xyMa}0Frg)-+FwH|l$tB`tU+CrQqTpIBZ#-NdM1yw0gCOPwokRqxs?w~QlP=~HI0dd{VL5}A zv04Xk#Cy1Gj+xER$~@S8(wxpolOzrU@G}UqQc+UB=5s$rErYhqOQqJw({!2hN0m$m zj-_{@hR8Vv-{mGpkasXv&{(D1HxL+4HTQ%Z^5DVJX1mAg{Vn^q$Z872l#_q)NatoInfWr%+f)@izBq#7mGZ}%&5NS@0{j;UzOtYafT zeF@%SSHm!rPF9~Po2@L3+JdOJLwH#g^a_2Xu7+jYZV8&8 zh_Q==5FQTp2}VL1T6B!3r86FF*E2uXi``!9q*ZO1lS{pMFqCiqz0@4zzb$Rlzcz%- zWg=Q(q%wIjqtac_E~mQGKBY}=%3L=R5k}0xIP$t2p{+feL;UWKBow_4uAt ztWk{aLxpS9W2Z8O7qG+(gdf9zPz!-|WN;)OGq47N<}G_oq?}SNt&n<(t2dR(yQTyL zpcAr`Zc47_K1)Mb#>`f$KS8davkP!W6CjfkOF&z(LjmIB^XGJw2NxfomaeY6ZCM%M zy?FcfE#Ri}a&oqsx4!`bDe8FO*;2 z>OrG~VpbTPb=4WsNY<*r(BCEGO^{HSQMhPA@t>nm3HPsS%d4~)ZdCNMcFG^2@-^!N` zICM5>GW`!@{Kar_a&_|7`BD=`wPxJGYy+IeKPc^;yg&3Q?96SQ-0trrv|L}j>z+zK zjz>Ce$xWNy*Kx1IfZaG=Z7MxTqscIQULXfVvi=BcrX23Zv~9%*y}GDb+SJw;kmC^6 zHJd(l)&;aqE{RQu{0C1O^6p`pWpFO#H<~5HM^B~&ZyHy&Ep?WA6FmqQfMO4GDAzas zYfw!R7Qg^%akW|k<3Mfc@!?=VeElJ zCfY^S=G z=AWoM4>O93wMKC~R6A?E_jkrP zNpQ`6zOF@(mRFiX=r0PSsR|6+SH!cLaWhE@{&_FPU&_QBj*k8>qpV_|-bMZDn%x)15Or88$mR8&=Gsq@prD zHa6BG_~i2NKizy)0r!#W+tUEFNVjHG7tGbRaMp%aI^WqfMnwp7L{Ujf!EEg5>=&6%c|gEl338- zXs67{*0yc$er50ODZLn2#aeY<+~=rPUKTZ7A!T{~pGSf%ITNt4)kUq<8}By#EMwhc z+EV{sKa~RuUE}!IGNO6=VFl*5#D$?{2!i(k)<+_w-s893VJH)sM>8tM_LC}{ z@Dfac4rfYdblk1q9UL^n?&Rb|%J=em)al?#rjx$vdtnVmbHSrPIH!VyA>x>$<1p6A zQt%F%c{j*9x#(VzY_8i{`1J@Gdsu|8N8L{*_C)7?#U`KPRQKTrO%aQyu4YvAxWmN6vV`?!(PeqipR7L^(Pex~Wsx^ptJ?mdR~>U0;j2o<<+s+bi8;GL?5V#1e-h1d|R| zIi$lwg(<{>UxX>IannV58;kn;Wp>|OM@69)GizySoiBnwUtzGm*6OW-QUoDmI`RvF zD2k|LIP-EEVzmg(YsK^;f%}IOVsc~E)TwB5LC(CdSLNm5X7uHSZEdYhO%|^&{oi?a z=WNbmy&5zth2XMM2JKvpeZ&+daUvr6A0c7vAgme2Pe zrwqz8y(A?o>*UKI3JzsWamUB0jk)#8SW{swBXpx{NU)tM!_sgwlrV&ZICYCY6xdiq zuTgz~xSApi?7~Q2R$cxP6CaPQj@zi~Rpy!)2zwH}jLQI_Xn4@|3jWGPLR}px zI(otpJ{UCr_b)=ogvqlOiiUPaT4Ar;+$T9r_fl68$|Iho>!*o$S`((48WW9~*0k+7 zOLy8Ysf|^~c#b8eP71??Y}*m3#_N)7)CtJ-58m#F%*dF&!lq)v^x65B)WNk(Qd+T= z*TJ6&Dk6+PNAy+N>Xet%Zd~D~7i4qp}oISbk8~)zxi$Hfyv{p& z`KRwWrs+UMPkErAQBya3y5MkA+&jY`RiFyuBK2(?wXiF=Hh_=0-O=YiD2PKyNQjsB zJFjS0{rB(n1o7%@%B3N_4;_JUr&U#6pwiOHCp!mbyr>jI4H9ywfZ3YHewikDW+Qjd z;m+0FZj6Tq@PKO5m-H2!N5K@%&SNzt!*K64Gw4Qz&Q&6M1h$ZLgJ4n%FM)gZgPXn)> zC&ACNvr0kPJbmDhzwPufpT)|8v>MB!j4~!IjYswzb-fxqerUq1zS zz=Je3wd0$b-@K1aJR850A4<4WU8iFHSlpIe#3n_s+9{1v+q8lfp=O%ZdcCXQp^!jP z4J<26$;sJh#V~(mUeVEop}9Hb@Q}GYOA);xNr0*>q38 z8ZyvmQ^e)XtnU4g{Jc3$!<)y4A-Z4_M%jPb`Pkgc>3V-kEh+^(odxGG;+465268ggqYp3UEVKGzVr}`l6G)#0Ad0w zE2|d)H{i4b2Q^?_~jf8*k8UD7QSgsHZoJz2AOZR*K}VT6Ydw$jBuWcGE?z`4$S zBqs-*%^c31dV8L+x&=kTrzceucrsY^B~DKZK9iv3KA;wa)In&=1_3u#rWbhs} z0DHLe8n;esX69=ayL8~uos}@02>d;X^3PMPIJ%k#2;URn! zei{CO4mLK--&JMJs6tSFo++Z|ohD2XnH4AZk>MeRmc=F_4J&=FI%VJumMG&FVT#fK zVbi6VO5|46e?~}I#9ABui(?SQSf|!WF5+ORHZJeFq-?8qy7togZyuE!-mGuIH$$mu z$CLXPe;LXiY6kdLW8QRpB{PmZdL37-5e{0^RD&;Of+tdda#c!|!vA8^ocjIF$}Us* zw{r?6st(V5hO&oEqEZyT1>dBkHDntjMrB|N%G7s43$jft+I{zGD@2W|WH8Nbx(}=W zEmfMc8+&Qy>DgFPGBESwgYi^s{>`7W&s3jjY}KONfHzG|=U{)ouI*OX^25K8-U&1j zB8Bw#_s6QVd_tAcZo|1_XH9~G4^Zj(6hp}VvdQ(d`E*EY(v39N@^zON%;w(x&7!0A zOXmuo$TKq+S8oimIy<$j)k3+EvZ`O%SEg_VpP=iV_amWi@SBElmljJ= zw-&sUMg>vLTy<;ye%)^he9W@8HvgnM(^g*?XW#sL+=)$YD1q*JB+ESLijK#yivvlI zn2w;KL*WxbHz)@;op2|Ea0hPfXD2E>2i$u}4=#|V?8uC#ev%ak!W_c{jhE!7%c-qn zTj!GdC0BQ3&+kR7k?L=g<{!Y3lZpP-*pv*%9@E*kgvYV z$o%NObA9*|FY^ha`MJdN6G@4+D;^tS?SM%VLj z^Ng3VeNs*Kc-3~uzG7}QB#w_SfsfC{#W^qNs#K)gCS;$|oDS0YMR}K2KTg#zD*-<* zY(B$WNohOlyHz{CQTh5zpHqlaspdP;Vn%=4;|f-CQofR6W!yf{FVF%9dx{_QO~qs`sW!ZZS7QL}m&#ZfD*>7jca#~}nT-R1kah}Oq`{f~ zD4dCwH0fq?qW~J{Vkf0pZ<#>4i0Of0#y9ff?zqwP#e8q2EqnjUZauHs>qeapUMLNsi?d`@u={NlT6~)nT$}Wj6DOvx@;5Y;xC@Jp1C5?3E(uCH^mm&rZsjSQdAxe=^QqIq~`dd&?KK3F;E-qVFo6!*&MbgCM^ z_C29jY&N@elSS<{DEdF+B{(MPh(UP*xM=HxA}SF|9Q^y<(2#Ff6v*IZGF4On7II`O z5+^D(L%LHvqi}mWV34!a^A2s8Qck{rG@~~tDd|@mt8lMoc?>oVg-V>3dI6__$EV2; z4RkFYNpfoWxdB+adW)!`@0AZnJ+nkIPSyPq6F*4A%Da;3Y3Yv>lab*yxGLuf+c7aw z51xE8EyU4X3fdjd=VL9RBx-}BYd*j4?UkZQitIDjo=jd{a3xbz+ki553S3){o=yj3 z2P_g@k#U|o3Fqb^4W5<2y|=bG%*md84ZD7Dz9&tM#(q6g0KV}JUjK?%l~i{)x)dn?R(WFZ-#fXSA#d=4T_} zVfL|~K2hm#yieSaK0OXusLaL=loOV;E4#LY?~zwu#|LK2rgzeJSubhYP(_;>R$d>q z)t>s!E=nP66Gaz>-{4Ax@WucE6)9+*l4Il8W)uIv%$$MU2Yn;JD*3PiR*9zjhVISS zptPTwW-4gSXYRaVSPyj8B-K1`)|L#-U6Vk%8k;4Zu$`S<4QgXQOgQ!HXksVEhh5aa zd%WWFFWM>r{RuqM-Pje2$W@QoVNOI=P#ckNMiF@XC$$(ea$89aZx4RzF8)Vjvt0sx zQutpYkkq$$eNz=VReP{5ElSu{Ps&Ra*QR;~OEdD`cL+}o9ex)5Px7?w#7OAR$8NN{ z0J4Is()F4Ky&)v|heJ)K!z#QGw;^uy0Z&td_dq;(CuK&0m^(2sAw^?B><-%7-(RQs zYy}u%N5`WS6;ZdQmdD=S-oe4ao(RnQw@CW>`tjsKA2vS4O>V^3SmpiMd@~>|y+7K# z5>N}PYw*qfU}>S z{yc0piT2ESg{K=4(tfNczu0~xAoDN7kl zHxfe^sw`t;Y7O?o3h%s6kdTr4LaS^|Bodb+O!)9O+X9|r{lXKh&F!_(TFje0mgolr z7#r~t1}XnzySMNF`99!c?Pr->k$!TU;^aE^+_VOosjoL4PeV!y z@Emy^hQ2u;8++*A34hQ{Tmd7Xie*OV#?}TYu)~f&&0o1vL7EY1+`$O)u9Y{f%0Bk_ z$fx=^ofakdi1V@aAFn2fs5!+vHhM!@L6L7n#?J6{38=&FK6Mu+<0^KBo%zx#;)P4mOqD zZ=Xz!rwqN{idgklhO`B-yTS^wu*aaoe|mO~-JV1t zj2V%qS0}no%KIhYX)gHr1oL(E^~vV-MCJ81nDb@Cgl%lRWX3RygxU4;I|Om~elumV zT58UnUc^DIf(l|qoSae!T!?;f_$3=+f9%(9h_96$$xt_W*NxUcE?^7QPusn|{>=E- zfNOW}X?SE%k*YDxOj)ZOJa`!dk`oXMDF$dM==SyeIQp>$9Gu_PL*r2>-wOvG zuezPi(NL8vDwHrE$)C#vktjOgtaWdkoU+2+`2(L$GLZI*k1=x}4ZJx{&VH*au;bwd zb~1NhfkZFU5#p{t$Z>c=X4q+!9bx^=(x0l?;NAn0bQxqBTKeWDOHIW$vRj>VGsR*# zqCq>}aqG9?tB*(R`EL`c>T43vj=g3X;YrybXwAKnLe$5feycvXF?n(2j&)C9V*VVz z)SU=C%GB0Q*ELY6tV+vB10HE$c82zfZ9r=k!@sQ@ud0>-gF+gos`RCpV>4~Z@ErTZ2L9vfln$>k*N#j#V-?~)ZsXerEL z5YB0lnxDgzmlKmeL{Z~=(x8jr5n0CExyArza78F9{ZHz4{E=OavrIGy;81rZ`@*%{ zmwJ0YHUE3>x&*HI@_nBZVt?|LtbFQ5TzxrP?Ek9L>at6NeIlOiv0MBn5UUp7H|Zcb-z?rr{ch^?NUk;f$h zwd46a#jueGu!OyW+xN+2lb4GRW6{ZO8-y{Gv?%JjK#*BU@_sf-P$X%f$B?3TP^m$~ z_2+hPwoal_SAabza`{w31e{Cv(~Vz|Jq|lLSUD#U$B?KV1-n-=tSbQ1MCfBsmX?-&ep#=jaJ!R}-ODdE17fEfGAlWLm;an9R0b^e z>b@#waGE?6+|r5)^8J1-4ZTqC<~7#0c}+HH`}P6jJb&7BGu?VpH#?W0o78V zHP7U3QS6A{BM2aKu$}>&I98D-%A`|hWF!)?Yq3=eOcmDB@GI~cet3a4H5zfcPoGSi zKO^0}Jq_q!>pLg^=M+)Yk9?M%wq+a+LkUfUXXabH&DPb*?ArXUVL(ct?ZD{qr~!x- z45ctAVfG~oddi5r0X@F%um1UX+IgK9Rk)R)G{h~vptV8D1&QkZ^fTROGpOK&ZZFxY zxvImUcSZ8d(W}E*Gu2agA`K0&Veh>>Jd7-++OfZYe?IdbKn2vY(0@>y_1J5J#IamZ ze>+icwEC%g{+q!!EB;Ty6sqar_obmV)h4@=umKd9bIKY&S$Siv2XkxNi&91V)zwwx z<%#W@bad7)ldk3E0YRa5W+o;$Q^zA2Mu)bKA3rMUZ}1UeHLQC|N1g9XuOfu7uRLrV zfodS3F1%p1|Azmvk=F4+jI^|tzta6;QBX=w?Lm;hHe)BLC)LhB@fe+STh=jtH6Y+_%Lc$-m;7l7C(c)#` zV{6Ey1g{XLagv+XT-;&`fIq_`DMOp4YrWzXdh1l!fCm|FuSLu?FkJY!A z0CkeO^0YU{pF*<9(YX*cQ%O>Wwr+Sql`O2%->jN52=$)Cq|<^Mzf_i7Wi!qtI9Y0? z>rWfGyAh-lL;KR-ieu4j3GYAg8wiqv*yPmn6iPDQ@lEYdh2@zyl?RGS1q1xBqLPY) z5r;XCJm^wYtm@x9WskWhL}_d#MU1+(H1~ErHj}QU)zxuCAyN|hR;(~Q)&LD6P=5d) z`EqeD$Bd`ImomKC@$g6g;EUTktRDjxHo@{irddtvvM1U6quWxyT$bkfMLFxn%@^9; zB*mSZYaLs{NIPP}*6?AYadE)oZ((uU-+!{&Apmgl`FNU|+On4BIf9PtHQ@k9gXW;z z4%2?~Lw^}X{he!GB*z_MV&d0!Rw=$XY?hr|%wny=XE{Ld^1>(N8Q4bFmO?r|WszH( z?T|h4%PqrNgQ#a~1`9IgUb>dQwv7$#2Ej3J`PHWp0`FzIG>doJi8=qK5&?z#9U71; zfU=1;F4hf)KX$&}_!}aC!iTE5>BK+{9fo4=tBSin>!Ei84D@;39wjnZZ+{k2H5**T z;O_pxJ^3{UP6QQWZ6#vYb0(j{J}~dx|)(lyltj#b(x)m{W}?~BA@dk z-Vx-n;v!o6wtw}3boiXctApMO|JP_8gzDhKhbF#iVjdUTp!rlO>7lMUz%jT8`ND>*RZ&sd*VNu1A|n%a+vpA9 zb$uEbXjMw+y4lOU69TDD&CH;>x;XxBnPJGrAtY|DwwzWNRMY$Z?!%6%_z)^>Dm-j= z{wbSf@yJ;1>yi*UN71Z}=0tLHabY*Vd8}ohhqRrC#TyWXvdWtfgY&^?gHMf&Nf{dZ z1W+Bi1f< zsEUouFAbNg|A9=gv>53K8RJ+XN>@AGAJ+Hw0D1zm4lD4(g#|FH^L0tk9vH!euSjm) zD|Agy*N1MWYd=%_=md}x^{P}z48B->k+1nXA`AC&UGwbl>}8;#VW2T}`sR19`O$k{ zXASqXJL{*jjh=|ag-p>u+$NN5euRLS_PE}u<-dtC*BB}4h$Z29luqwO74~Wt#m&s5 zN&RBRm)}~Bd|FjdPb+THV5R;h74`}7=#m;meOh=Q1rPK&2OjD49sG9m+s_^SKMagKvEV!|MY5;?Sqf2Z;H>SPscG6fiJW~K!!!v_ zNNE41ITbgs32ws48A}xGWxoaVB7@J7gA2NitIN#pt&U~mQ+2d&Zf{KK>l$TB%QR z_8tln$rLz~5_agYsdWg5Fi0C*2Awj`3K#fzPv!TB?SeXkf*=n4Lgv0P|16{d&4n-k zZhug6#5Jtveh^1$`p#WB?D7v_W_c8A>G(6ha3WzBMV@tW9-N5IE-W~eL!xxk_IB3L zvc=`KkAjo}<1pd=WA3R5xEt>6MQHvSl5|S>DoQxSb*psb;YuE3EWrkezT@nFj*rhL z6QigtECROU!TB93s03e{1-;3@tq>B0_&v9BdWTO#NQ20&DphnM%)n3}n~D{hUb9*6R-!CW`~X+p#2Eq90#Sd?Ud%fWGxC{==Szq}iN@h3Z86A4|dO&DMV zT6$aE$|TcQsSsj(NwMF)OY|1ccQrpEib$_0_tPKBlohLj&<+)GszZ9qfAZktN8|j#V8NOqcm!f|H}G#+<|Ynx@H=)LJn% z{uxN|1c8ti^PQ6hPn493N&;sXRbSY*?BQ@Ac;9APRT@ZBic$;1Z&w21R(>3jUlIRt zC>#JDnJ?HYYO&W5N^|Zb3{2wciiL$mmpG%BKJ!b0;<19Da`Fh;2ny_dS%qVZx!F;; z&@!)_;Zw9JcXdiKt!@y z`AK|o5$62X-aD~q^YCaX4=x`ZXoDaW$bLT}S2!bfe~D!$k8M>MEE^g1%drpuiogvd zG1PLl>sIi)z@F?K9qoLJcXQA%k3=nPzgub0KRK?tXueaW=SuxBbg?Tozp+uM6h%uA z(`U{(mD6I(^?LaqjF4qXzE(q=(II7dets|lEfko6u|$0kI~`@$7wGHocl+|#Mz!Pg zd;ADtaT8GdY6x)dsah|J98#grp@qT>SEzBd6q{_>r5=5NYxf_dp#M3ltUOC0H0!!G zm?u@}v6{k?IOZH=*dI-?=U7=yvI_qLx+5qyW>uE7p+`Hzjmmb|dbU{H+YHw?;Ko5OFx>7rpGqVqg9sHN59QrRbM`lp4Msh)8!OYcYT}{+ln(Vo`2vIT9rKt|PkyfN-#=Wb4Z~Ez=ahiq5=cr1 zeeLeH`bstCg@+rhlkl5Zo? z;y51__?KbHP5eAIO_qU4~u5D{Ng| z&-_;(R{#h`_r-8a2hPvmU#PtucrbCyw|%VxCfqY*OLZ+f=2vQ_Eq~iyj zG#`(P>|qcQI!iPKMgbWUcFduCS8WPuECf_k+V~jXX52|}IeC0Qd|WdM$sjw}Id-|F z?hG=3mly!36whURbC(a{*gwvvs-N0mLV5g=Bh;X)B-JGFYo-zv1I1E!5MW7w zaoYXb71ub;!#7~udw38(auM|gS^fC9P{|H}Bs6mvU3h_59l#{m^n#?-FgE5V`SRqa zOcu0TQ=9eQf=rE)MN@|G#M64o50fqRlhB6X9=9;)_|8gc2H7Mt(t8VpWaq{N-C$qY zmbryU2!$upJar!D<4A#==N(@-3R_&YY9vYi4Ad1ab#LeHYBS*;3sj8|frq`|?`2G! z>Ujb97O4gt(AD+zd4YM4rdn2ViShjzKAY`F!CwE*{Mk4I04c!PaD&%tbo4ko4=Lo~ z`nvP-a-xbAMD=*H-w&SWgdi?lAfX=8DQWywj;v<>qMa$>{#88LIMwRAebk`MyZctf zKi(gyP?FOo6|-c1^`~hL7r2!vq_u zf!>OIzBAAu=3wu)(=Dz(1(^^boEf9ONjPam0eMgE=a)=*C3`aAh>s-ebU;SN zhuoVM-rGhcu9t?ntB+MeaX?3sH8>k$nbeU~k&%*ij53kH$~7Mo01+f`!$BUFEfZPU zTww(DTNIZ?`*XLO)rOe#h?s}B%5jwuIO4Xf6TFnus7 zB2>bMH4m@4U&k%|O_jQ;cYS^O{bd#g-cdGZnVV(P(yE)QsGGNRIFzum0!s7-Ox2|Y z{%p=(!baXIRbp?*YkHoW2{K-NICDki)<)-5Vg1^=FadR5VC zKZ>Tfm-{Wqp5u0uueOLgj4D#{s!s*<1|C@NYb<)0t&MsF?b#Y$O=o`c*y%xX|e+UOEfP`wG@#u}5R84tQ!|28ga zpl4vPz(~^EbXnT6I^iZlVZtF?z46cE0-VQyB#L0963G72>LrQ4TgIeA*)%uIsQ&1< zQa{R)?Fz?TT&=QPGpJhX1()r7CwZ4KFmG~Ixx719(?l7DS+c**ZH1WD_Q9xISZ+rx zQxXf|96lX)piSlJyP~f0(g_z^oGKHE<&#{P#cyThAot^}V0(i7gwUihQ7nbO2%G%=scS}Hz^haZ8WTjcHZsLpca8WuCY5c_YA?pV(Ot(OS{kHC0% zh(2Kfg_IQ{fb3d@$sd)Tk1e2jaHq?2r{`%NNrQIMoUDJ^SyC$0wwL8XGuBbW6eS+4 znMO5>03=5^S5t*y#t+&G-38n<3J%jr(UfzH?_(0JHkJ(Jnif_0DOXSw_RDU9a8ir? zObrD3V{csC)G?1&zQjjf7a}M`_<1;Rs+EuTdyLLEi4UAAr0>Sj-I03$T+QbcU#BTx zN*yY|1eG{hT&1jbwF))sdC35-yCS&WBQy!PWe{tH=cwx(b;1E^VgRv@g>4guIo}eo zO1M%>IBn?49Io=WWnN&I5vB%{KttUa3$>UUjjbw9U2-Bu86yLex{=@ra$;p9D|Of> zT#Zf&aS0SIHUL{>n4GkeUf}8LU@t2#g}ZMne+Eoop3doP;dm|K=Jxd$gRfQ|)JE4~ z1c6KfzKq2Xizql0S^P|BSa*{>Ov)at-Zso0ctqFe(PW z#en}2h0CCCU;x}0bjukJ>|RWtZXfI{!vLy7xhuKwCk8P`JN3r1Erg5IY{!t!9L!K< z_m?o0-e@qdJ!hBE>6^Yr7W{kd(a4Wl8XG=&>Y9gG2;zygoDz&c^s1(viy#x5NCc{A z(L5q&t!u$i=(xD{k6Ug5iY!3=feOhFLy1ntL> zN-*@ZxHfj2Q_>{etGpsfRcV1A7UiduWvIA!SNYoqOQk zE`qP;QDark-;3=|D-QB4i^C2FzSq>SR{(d)voI+C)>@3^Iy5tR=WI zm10TjPFblUcZp(r7b_I}WYN*GzNY?zcAEgKo@%*09{#AdRY+bvdF8TCO_TXNayO06s4gXC=w>BYHog6!4-Eu}|a!A@Jw zwe?6l{VF67R^Ig*#TMP{(G&=j1&LEb%iAdi)1iXWt?HGVwB+@Z@({!lj&_P9nBU5A z>t_{%V)Plpj^Ih?%Jh@V!FEbhmHMU?{F~gAgYOkrChBUOT)tW22Rwy;3S}T?K<)>B zZ}KTQ2V4gTI4Rh-NMDGkd7J450A-z{Ez6g5uzo+ginX+@$Es&63FRTc=$|gpy00WE zNOka9M1_O))v+4HF>L`R)^Y)mKmu_9-q6~jE_%6O##4j^hG5MLbNNs9dalypz5IddlNxrbktd4`xTq`$yEcTrG|@hE@j`kWZ4EI4ntX6j#Z zh5y=xh?<^8_Fd>SwbLJq#Qg2@Au_KFD8f5wYH)l$RJH_(Zt`PinkUaWcqtvu^r9?E zWu`UK25%A}%nuoa18Tt5EhxMlJ(6|xUG+1-`T&X%TnNgPOU)Ukmj2>gri5n3b)a>00qOBor=!*MhjaACfj7M{j^K zS}>e@=&S{vYH2`%1|&h#CkyKYn^H;C%3g|r;cqQo>*K!Jyu^qIp0|M2|w;&KY zm+6ug4iy?u6-8Yp&};1*b~26tQWl=Eqy?^dPC@f-_=`6>MAWh?zH!_Nx73-@ zIJv}Ydyrxc*oL!bCHzp%^iHiDKK(Y%n9G%X&>98nc?dV$n)aU0NnQpj2U7+-*|dxJ z9xy`D?B9JHfZjk4`;(rbC;nf9svsSSw%SCCIMj_(<}=f6o&;A##^)#Y2Vw{fLGUK6 zkFP1_;ub=GW8X9OphVt{nVP=x1E~Q{jSL9DV!lIoK>DaV30iG*6d+Geqj_j1ndN9R z7+U|fkn;*uQ)&4-3!}$C9cM!3hf`oi>?TA35o9ARmIyK!^a?H8ICUxevHhaLA`Q2A z%0S~pe832+23Zz-s~D@$@2{806exbI@a510$q&E@!8WgQ2g5jtOq`7Zk>cI^R3;4G zx|HN{BvTM-d!T@Ts_=OtbN@x-O;9#4w5k)s<0yR;qJH0)>LjWEKub*|``&W?C*IO5 zKD{X=fYbMCF* zn7NHb*dQGl(k-K=Cf*<=l$rMs<-#@np@+DJhzcWheJ$ZyL1xtSOdG&i63T#a6K84k zON>QyX=Fjz?8F09Jk+KhR)sE6AhpCR1m_7Ioo*8a5M6wJURs0gZ&|%5OHu@1CQBQbqM^d#DCQ-7pgZ zQBcqjwgh51BmK>EU}amJWouhnZwbZ4CUid5kSWl%(XG z3p0Vt%fjW*mi#Q66idwUneIZkc3*o zIRXSy73jTzD(*S8it&<#G3TL9X8l(h2e=l$eR~!tYwS3bs8*6Z;VP!c2yI>O5c@OG zos)ogj^DZRM%9!hZEl+hQK69>;hl-J7?_)U`+aSuY2zm%YF9q4+Oa18Vtox6{xBM! zJTmo3@Ac^PQ_dSV?t9UEnej3BQbFWK;2%HPxds9cqdb94Dzh(#c2eQ5OXn1Vy^nwL zofu4UrSmgqs>VHai)0r}8sjhNd?tM1#R4-;L)tFMQJT4T6BAB?sD{&BN6oFw7D-=3 zKaY>)69>Fjhv|AYG)y!RC9*kVV_u-B>+I@E+^{t?tA)T&2jE<>il#6Y2Fooy^5(gb*3U6>k= ztvZuLbbi%1!#ocTsJdD<`u@zZAHPSd9h9ZIENXHlyUP(^=F~V{sf$<5tX<6IRg@Pt zAhysOedF#bxdXj}yvwYb#vMixur0!NEt7(2K@P}^W2xgQp{ZrWgBH?|FcZrrn%9J2 z&*5wn(0e}i7iW{TvvyZ5+c-*1a=ZFaEbueI{cc?ctt6}=j`)zKT^3+Ft!obz&%e9` z#N}cTJx{xWRh@_D`bpaTr2X>0a8sal2?G(hs}3&pSGIP53(uGYULv6~dp;E)FH`r; z**ZejUZ&`WJKfl*;xj+Z78Oxz=u73F&;9&gwD?eW%*_IsfT5bZjK12RDd7-d*7A#J zkPJ2WN*M0{NuDZU-i?$b_x1Cg8kSZ46KPEiPqe?mxl^e6t~}(~@C!u&4A_)ywKFCv zZlbyc5j(MVgpg;RwP7!fg9zLL^uAPR99HsDh`-%hHH!_;B3R~Qd&qM`*`2~?U0!hT zgGPZcDmZUUayby5{VLYZylb&TWrrr?K+FN@U762}(H2oSdAs zl^}%yfAL}UsfokVVj$dM>C#n9fQjSf+ui6i4ncl?LH^W2(_;42#kz+zionFepMo2? zZcI`?nq_+HzQ3Ucs@3=}+E$_VGVZJ9o@VB>=H|2?yiV05C0T~#iReQW!f?Kom;v2R zV|Wl^Pc(jpA3sM8M{oxPq2KTmyUP{7NUhQ z(R7rIi?JiA-7x58jF+IsnaUxP5>dxw2o z?dg0I(ylY8j?Of2tN=mD<^RogSjzVHxSB1F?yCj6 zY|RRLLt?Sq^W>x>6&+gHjFW4i0U?NQm&xO>PqmPN!O4N(mGTiWutG#Kd4KU(61LZg zU5yhg6f4}h$Kh6h<>yCzRt2h* zam}7}SUaI{=bn{d-*_oxSB?5CJoiKt>{}iEuX@~6ReXM-6T&laulKaM~WtVCe%}&|dH77fa^%$&q4_-i->7OSh14j87uY%WkWpmv(C?|)dFRfz6CmWj}>`(G7y4&OwxzyVk0W(Aj zvsLseT@{RvFQITSOc`zBL#5dp`7MSuHf}=pknzIsmvnd(Kte?3N7ZDlHP3Dl!@-4n zrt?BduRSEO2B)?wHLEYgwTi<$hygA7H#MFu1<~fjO89eCpyC2i_oi~nT0W-cqm4|% za}Nu$NOa0K`EB|cQE%e=)rGfHBAxK3T{))@LD!pniF!H~fB3Kk#ZI z(E_Z;23&6TzT%?ZCwqGZN&04{YLtTB;-h(h50q95wai_H|>-lM!kNgfsiJwrVMailZgBWucc|&+0 z!NqP&FSm2a0THXeWfmdLLEShqqsK@^EU5b1)SMCrGMUTY~ZYZ z82_hwY0K^Es1GJlJYHGi@$s<|H5gP?RdoVz-C0kbopFGeguMuY1MF5jT1rZ&60X2t zc^2X%aj~a8%lF&qhomp#{7aI=rkGjAqKShuFwM1%n(g|YCCkR*v7?PHII&YEFgm~_ z395hx)%piuG+yY_*8!Vq(PumMTp!3Ns-CF{hr>?0ul`~+aPazbWSA2Ar)F~LYf!d` z!klX(E1j77LY0lrES34MYCkM514S7loGYWtKMve)j!}N9)80#)nVXBUse42#bP%`7 zfS>v#Y;%WkwJ?f36pXPh!#E`A&mStEv=wOE@hg3*`wK&hxBJ>816~GFokBx)q1a)s z{*dhExio+Uct>Zvqw6-?A-Q|-i0~6pC9RabP z|1x?@E|7V*W3)S`Fc0l{5W%&E4r)v1IZT4bmxb?K2{rms9Dk;?Y;6J6C8zGqG@>j2 zd!F@U6BgQgir*o7CTa}CDUUL+y{9DL4A734QfLB%q>lNN08u}?aIBpQyY z*$=^r@BoT#W;agmxLKubT_co|MCrjBz z5ul)fIFOKgmFHqX-_rL%B+|sgBe%s< zRoRjwkyT1Tvd@yKK~J?-O&VrNe1c z@ULYk*cgPHa4y9?ke*OJfM+kba3hwAI)1mV>EfUq!mmN$GLWV8W_MGT1WSR}N1tDoIeH^cQ$Jt^to5NRbh}$kMR>dIgyO!W2S)7cWuD&oAAWgc4QGsa#E%ShW z(z#VM30BFj@x{Tcw)<@o-23MV&+py{5?V58yJCW<4mcTlFuue~z-lA``auvU-*O?q~k{*nj4^SJQc2 zB|hiDeuv*-wZDm4BMf;3{pLXU?Ev5~Tt?&ZP$-kk5^Wda^x8o+)rkJ9^bEh^r|u35 z2ZKn$-uxCfo84|@4*-8wD>DBhHTV^X<;pB{9;`lZ4t)FOzhgM(9g0F$BQ%^6IHefs z?PdZXQ}2CMiF9tw}1Lx|1y~?$Dtp#r+jtILneyO z!A<`v|KD}3_P@L!+3Niww+DBT|u+kJOb0?;e#k|Mkv)LaxNqAG_*Dm9d?+ zOTNm_hj;ID4ir=}$e*Xwhdil;3=IIq>iVcRSRxHTV_L-C|D@e;w^E$|@cU={um76k z7->WD{r<2p1QAY#FI8&|f7P~-A)U`&9($gdpfYIr{;c=y0Ke%BmyPzMvkUzgm;MK! zIKNjpu#V7^l>1emuNe($PG<`LbfPH60n53_Vfs$J`vQ82YqMBFypo}}Oj$M?kGWm4 zxg`$WmJQba{O@H;$=&V+vYW8@48C!4#1tg+2(l;NrGNW(^N*F2O?#OL^1rGe<>D%?Xd^*%?s(~z~5g; z@181m=BNmMma;8L(6FKIEpdMpP|B~m)XYgwwWQY=EnjhHCqHNpc&g5Re3joza-5J< zZI{bct6R-0yGbR3V0QQ~q~f!;)icsPjFQV0g;#}Xg4il8`oAWSsTT70Je>IaRxqyHWDS211|ZI=aS>qt2`a;g`&(v`hE zuoso^x|Wv7((5<>Yeg?GD&@C=LOujZ$T>CNZTOP-9yZxC0w7!nHLXY*Iq&hA%}xg{ zPh{aFX9AJc?dEaO1-`0e*w>ltxL+*63|OOZk_k~UK1uq3#DB)Hva){GkONyzOiC3Kwsb$e9u3d z;5h=7_#j)5f|+YvFB0UhL9!-}+#q03$y8L-8@;Tojl3Z47K?qlTW_5d)8D;W!|#Qu z|Nd2JX0;}R9FpRweSz)l3l%AD^kIqAB?V!c|G(Ia8@*q&+3m*3n=i*2DiwJDWm%MnM(_F%NovhO6zbrUk`*m6)~4hIaJt-TkN!r5`i&#pHp| zco7)R%;6X+e2E>V;1gX=TNC$LdoKpY!7CtyN~WvWf?;t6VomfoR98^Q8d4<^eVw$! z2D!|k&7!V`Mn9#szF0qCwjR>h1qH3V_N7_TpWKx;NnRFiv@I%37Fw3KKzk=$k4W!E zFwm_ak4tpNIL>@FklcB<&&gRIY!Z}=@JV+e@;9f(4yByXyX`+s4wJ{c+#|D43T?@x ztf$`_VRR5(4SALdNO||9zUL!92@654F*c|vgAc@)B|It#`j^R_3%=J>=eCN-4p7+D zqoxFc{YushK8H10LWth8KAPkaJd_ciSb8X?(_F?!J1?hPHGK4R{wNcHfsk)s=+HJ} z#?z^8oS}M-gW>JP=~mV444M{dHP6HohW)?bZuui@iU9BJjQ%kse~D?kE0mp9k?GLu z$@_VJq`_TR_jY9_$;o_bbO8LS{+Up5IZA-~ReQ}uY#+@=PBqg_`np`$Qb+rHD`BmBzi;Z0zaFL0{{(K*csV(|Ihx$#A zEmUb4^sfA;-Frp}Y|?ZOZcKDG3^ok=S20(#yNURp(EZ7bu| zb^>`ypS_IMTCTq%h>A()SF%=Cd(O<1n0|fUk&P2}uW{g&Cq6LyT92EhTC1$HGrL`w zvx^b>)SWV4slOjWO9t|*Xy&ir9@mcQqtVr!9vm#pZZKVadA#xVGEep6()AJ0#+6LZ zwRpT!WMMnwyC#Q=%N=Z6Co|5TbrGhOv9KR7!6SX zjza}mAI(l4xj9Gj^0qcjSpz6qJ~lz!+GaF=U>apZIOK4Z|p8w7B)A>4< zqp`!U4I#K4kRz_a)U`%^c<@I0$<2!bvcac%AtkB5wEXw4xrs+jlIZkIQQQ}8OTBH@0 z?Xgna$}V)Pb41uysIqj`B3oS*aJnKm~x*qTCG>eU--YV>ql)c{ZpO+*W{uGQ615`03C0?HeTk4;KTo@VUbv$>M+sTBkNgl^@s`grM z1}0CRIk|gG6T1Zg2`&K6_}rX<&HPV^u6~fw{$AdcN?K0Q2C8a0ST*5};A;CL&~IN_ zof6-<&{S;*NqB{M9~aC1yX({9Eb2S4wMdyOz{`7^Mo_&c@U8+1@qfko_d+?xUgO!n zFbiE@=b51tr?P&#o0XjJP<}yYYnA=}oVn0$f*C~ZFLqE3J$wHMY&Gp@g^c%=PQ4K% zHE?94(2kJ-92Tfs98}8=%;*MqafqoD-xWW1cpeU&^Ke;H2ZZ~>b1=37@6F&QSsM)$ zRMq5U4cQ>&myscfA|_tz{zWV0_y+kGVw>|V59q`y00Gn$5F9KR6;;)av9JJe*V*5e z4Pt2g0DZsuYHI8qfTc~&qC;ELcHk`f{d-I~;{_t9Ywd3BW>0{O8C;`*e43FV7quZP zoCtM9Ucd#~WUwbQ_=M0#{|vMwCW^ZqAEjq?tc?G5L&i_WLKuZt=({FDLNE60@RPI) z&PY{6LZ)IstIZN?-FJ6ts*}A)BC=zsUDHM_sDD^V%I?eQ!X3&BkqVNRDvzCkw!igr zcKitbMH{4nRDDW@W@{LU;fn6P;kxhJiwKnZhzNKdW2s?h{P=Ca%BH6M?ahy071`$LBxI(dJ%xgMR!M> z=i`O2B7q)ppxO6b196FjJ>4RovQ1aDeY|?T=pACKLo0X+-TOHiKI)pi-np{&ob>6R zI20^Uj*WvuV(fhllj#)(HIz&u&%~z#$M0aS7CXYb;?x5a`{6NLXx9@>dmur%;$ed} z%T0TFw6lCB`*$8_aH7ib_bpio^wiPiHG6Iw;Whf>9eHC-gw9(oX z&`DvBu?t}7s>J>OKsWBMSGJ8)H$2b`@?SU0tc~HWsCImRE{>||0g$1PX+Dz0J)V%! zG}D3H*$*@yX$@jK8e9|zH>Pd-0eCv|(BecI&&a12g}y7zoI3`OqwxTrtQM0QQ;6E> zxb&E?XRo()+~?yrG!!FN^DhhjX5cUa_){a@?3i3<7Vs|2RJcX_!BIVyjhX&W^%wDJ z**!X zwGXv)8yj!9Za7`1hxUlz$xN$!@!BW1R`m4b}``p5lH?5 zY{V>x6@`Vgs{j)#H)Tad)yxbcko48FZ*;u9I*g}PItz!ry>_@Hdw~2Em9h^h#k7vn zRvtTHh;f|JQ+@_g4ydw|5*qJx%1g!u@i7dA2tVH0Z>@J~z}gaHyQrvOLbg~P80~>T znzeK?u2Y5ZWtntVdQx3=hl6kbRKgXKn$4378sHPKw~t+U z4~=|}o&Yr0cc^MyZORA8|6?ZOB1mX4`HP`#)~->>75%U2aUKm}p<};UCVwDS(L8vh3g{uV8=4cNRwmSR5Vzx%S`(vuC}CMwVSO z>Gq|O<;niVjvkbkm$xPs^{uFn^X_&;ATWjOOF1*y7{?mA^sXIHr_j*>@ZVYaeWRm_ zL_B7OelOcFE6>M`J~}%)zaw_PF~|z2$@agS6Wf1wQb7ce<_x?TiV^621e?yPC<`Rd zDSin^4IzZ`)8{8+i%g-@P}Jj2P|NBKSq*m%rLID#F;7=%>FP!PXv`8Pyj5oKhHNA8 z^3=Nn$8n2wxIz77FGZmkG+>}(bQCihx$Ng@{6H+gjq%ApkYDjUKFq3x0;xZ;XIH9m}Lz@z@i{n#Nv2!olC-!UT$*zHO=)6$dm4?I@thF`?NKMFL5Poj&!b4HOOyq>TwAVFTi3 zsZO`(?akP;?u*r0ZzoBO02nQ_fNaAUI`R7J&%z)YjR6Y__Z_l>6hg z=!2fz20yz$VO{qUhfAc%jg+2B_ zmx>zD=%}Hsy!)RAa$gC(l05&qLL^Y}?MkzN1C)X!fL5nU#SNQ6+sI0d?dGGF#6+kQ zM+ZHSjns}u(Lcr}AaqfX+rVCeuDM%KUC-jhQ(TSDNzZ%Lkkek9@F^nRpmh<_ts`4x zThW&WEM^zK>y8fJ2%nonLBTRxq$w}A;k6||L|ucl6(vlksp%3A<$cm0XUoUTR36(w zhV)-JDa}w>Sy`qjQU@QeT)WO555lRT{BH(zNj&+fXB{XKE6We(T3>^%re`Y3%0OLb zi+cTIO@@+_;Dlfeu{CVmm9EY1MqWCPQZ-MpQT4`4B;G05KM!VrtkJ^Z)cx+M3sb{+ z*PO^EWQt-}Hu>_+`=2=o`H&xMxM5XfyUCP1CDK49QDRnj3RKMA=8=24O9G?pTpNBpLml^+-ToOPdcEZg$@feH&w$$RnP@oDI~DRjvGmFE zbJngeo42RPRclsg}li9E{OCUiS`-L*bMj_7Q;+;T00NvZSS%jD;c2!%joPOx;Wa|Ig#| zZ&I1hWZ6!!&sTj%ne%@0ynQ?S>pG!XB@yHPWL2v}h-FUEGspT@n!)WweUF`Y$KSC& zglh>2%^Bv+L|dErgyojY17bS@CG}BNd0B;~rZ9Rm!cFRDlkpNqW^;SQ#8JO=b#!_k zTaH;qsN*G^+w%fKY0}b`)6qV#aZl5Y;61~R())|yMQ{2jgivV*&)Rt-w0>>Dn=0B!;KoO9L9Ahe{~nM3fOTL zSZB0qVlLKwk=aF3usF34x{?#xKWoQ`pIXOtwK%2l9@oQx@;vClW*B5A?LiOWZqCk) zb<|5rE!^DPLj`!WpE+*r9|1X29){_{Qzqm&JlgY&bBpO^rxq4;6F-}A)2qrhm`1_F zR(^gB+EA%Jf_WqzGHth)Y8*0O#uxkmmUGSCFy{FtB=vTM_Pr%5ef&VeU1M4fi`+9{ zO{md@)lDWGsq#Etw+kyBo|ghRnF5!_f0;Fs&OH^;f7Ic8R*cC0>6E{nHMyo1N`r^{ z$$ppU)IvX-`kvH#T*2)794Aq$n8(VBY-f>B$7YPAmd3IUBsBU@5_8OtdOsV1+OWM% zBZ-qdujAi$yCaUDb~LM%q%=RIF4wJ}iDMD=0TgOC?&k-NS0k=CF@BF} z1y0HE`E@5wBu!UK3zH2hi)WbRe2|WSx9_vwriv_e+Uv03;@s!2Z;O1bXop9`PRi}P z_c26*R~N@RiWM-FYBeRe2AlsVaI`E-N=RUF^6Z}SvdeSxfX5}g@7?uDarDb;y(;rV z-dNIlp6!3gCLp8D)j4KKbUU@tRSqseNeI7$WqeIW0+yh>Zp6eQRd*NDn3Z(|d>tLM z6$b4clmT*xR=>fS`deE3R{6L=myh&SC{?le9Y67%l#10XrfU1_oblZj*s zpq&CztYRp)mQ{f}UTDC47ru`Gj^y`X_0F{NHq%3+#Kn}8AlW1%|ACU zn~NKylChnVkRLdq`QR1Cox(WrT`ZIG0%wLn^c~czwrYBOJX7&Qa(I0aFimJ<^Rr`O zXlRGq`sa`p0r`k@6fok}4bXuNloLi0O*lMGR=c6m^Z;)v#}yeNOLDpsf0q6YZUNAe zRUi9|!c)b?rLIZqxcWPeaCP6}Fa?zcM~;c!VUpbPZ8l#LAy zFBRbZ)KNj?FyVDK-QsR?mN4Ff=G7COTUe+lbH7sMXv<@T&arRDNX}Jhpoy(t2pK(J zm-e`_Z_s+TJNe7U!Q%R0OOq$Y*X6E@6)Pp1h=fGVZWNeKs&j>%F_Z$cIVjLl?P+gq zQOw95+a54}QCvLNDGu7-O9P17+uU~FzpZc$4cGTth)KYHXiMLLC>NV9fG=Rco_>_P zx$P7ojMTM0>Z%mpGt+zOk)3KKN zRrx$yvBbjCwJd5DN8_5N@tCn0&8zufrM#*hicPAxLaI@6Fi=K>34YpR*6X|TFOO$& z?tEv+yvy$E1<3}m@I9rRK_16o$>P?Hvo%4K1QM8nC>>Q= zptmd_<%u6QX|8$pJu;r7EGDq0z-Q^rq=@n36|sN(%U!R~rlHg(#V8kWYq=9;8pAYt zv7XIH2jSF#7BPFZpll{(9k*oLMz?)WPk;=AC?C}8L)G*IOulf_NC6w6!0Xg+VoTFA z?33@KkNzZ}3n<{E6xi>x`9o zWknlA@*aGc56l%vCWZXl($#L0I)J?3iumx*3V3<|cx+G4_C{kU8#lSQ#Mmbn@td~h zwXS=4y~6&`qWHZdOTE26P1b2m$`Q48$Sz-QICV(Ja{<$qDptcSlo{vhVq6YJ>fT-G zMnB&exZCx)t^Y}xBk?yRbf;eFgP@RoT4=aSLeY=@BfutmwllkN-kJ$27VvOuq=fb+ zShIGd;B#HDH?UIpPQ9dPe2k=0gt{hhq`t&49L4~)_6^D3xAY<`)HSZjP~_y$qQb&f z;Hx|io7ZW{M>YxlVR$l_)WdO1sBhPBM8Tcp5z`VX;h~<#4(V?APMgHoEKAWG2pl?Q zt6gaU7x&*rCE8bablJWh4|RGpl=Hq+r^~w4$satl-;(eNoeXYiUWB+ zZe|(*UBD>b=~9rFwXvKXHJGjg`Zj^a=hKtA=+*aVpieM`J7^bmQpfBI*@P zgPS$80u>Pby?$2zS`l*cKQ$dnv?lB>s1K5w=Gx6X)5XED`L(tX=4x?Q!Ge-Js4>Y7 z5j{K&iwW9QxN9_;VJL4RUYo~1FfX^Kay54Hsnx>>I&WKe_;T}sB=lZnE`IHI*Y215 z`&+sGgg}6>I66AoNZh`EIH8B#lEoOR5~SfNZ(-#1*89FiuN-+h!j9O8Bar01W34FK zej@@P+v14;zNWZbvNa+HOETk}z}Ib=50-M<#OWI<)ci~v(MzF_W$4`+fnci8T=rq1m~>d^&GmJ1 zBt2S#xV@2awvTo*fW*|btz66eU;E)y&ue4GKKnqb6v+tK`QI=V8 zR5^;o?J3J7I&Tu2n=W1%uSK})GP&-CoI%^}5ig01x6A_5643Y`!5yK_386)DyM$p8 z$0Y9s;zxq#6e+()Pb4yG0*?yWfI6_B0B#_%x`~ceAF!gPSly`@yLW_9A143e8%azR zSI?~7$9?0l!>6K*@wL@_{yVd%`tVfNki~&5W7h+VhK43z3he3+HHWY8bomK2b!W0=w5oki2{ZJ-59 z!7WIQ(+Q|@BP*2lL1Hqgr5H(7JxoU{BS0KFCA1M zr%W7Ci}6E^1Bn&~BhE@7`BBJbJ3{9GGP7!t>ZVY+qtQO_`hyY17PPP*?$WL$G8*rE zAZ%wa{mPM&=F>Q# z7gcL<4|kfzL1^R2_R^;sVQA0ekV*$qRxsp@@MCiU|KBpg-n_x3R8 zayMZmPsWqE2U0ia&eG<-CN(LJ4=; zv5>yCi6Ao?#^ur^HQ7NB(XLBPrIGkWA|x98?B5oDr8j1ZrmS_A#rW}u1F4W>G>ocM za>{INF1hYWc@LJf3;{cpL5hn|U^dZ_-zPkEE-@u(T~xNI`Yl|q^i`BlPgU=3X^RHm zaBH0YyRgvcv%LE`A7g%AJR|5#qoW)Kqs_qq7jGi<-e)TxtXl#(4%g}VH-L)5EXK!l z6gW8)`rU%&54o6^TWOO^df)zOkeYmBChvSvW+$mu;0Kmke$s?ocw2Q7;25gyjRWs0 z19I||Uu2B9J*neG%-rQI6!N_y8QgIc40d>L2Xqt}~N28NQ8snh2G;R)j<3kHD) zA|N&${f=|Muj;0mnIzz2i0+$X(e#umC7#&i4AN^UJ?ByFks+$Yt%x&CZM>@sOJALU z8Zo`krf5&)qMR@88{KQJCo0Xa&96}3+u4a6PCzX~GUZ83OH12S*%?HoL!+&wZG0SC zAUpb?Gpdl-mk=mVW4s}q#!1K#lo+WIozpS4b$t%_E*1W+J0CJO-%@76Iha`{zWM8w zf!Y6<`vQN2b3G(#LN^32px8-g^Az`M=lQYBxMvez~VpaCPN+F7Ah(IHy)p0YfOb$-H!&&KFsDoc~?0xhR)afEb3D z6fV7ol)+zSLPw~oqABs=>VYcJD3gYRROEG{qN)ing1L?vpYs{ipX-lC`Tw7}Wi)@2 z#B!_L*ZQPLzsRo#o6x-8MqS3wTr?PysmUHnFyT$pRNnHRbG!jNr#Q?jV4nB}{ar%Y zuqv3w##1N;{?LN6Q5BmWN@QSFmFdQrF`UK4x=oWiiCFl!hxHiF(8|s`t#Q4gNXDRV* zZr}8>UJ&4>dTm_b?dMdF7naKy0CD2OX6|`A1Q9By80V1)#u=}@$dfQ-hEOsDCeF(X z7N!#u52U#|qPG((N?lNpj88cOGKyxgMO82YKCIxduEZ$Io)Tg8!O z=B6|WM8e|aaBP3ihmitH&PS(-$-HLnCo)Z|z9yP4n3la8rB z94H#8KXWj;Bq(BKRM?-4kbi@!IE(~in2X%2wH>{^g}WvU5_p|QI2BspZJ+k{H#9dl zH1kt}A6uh}VnP!XadGCj($D?^kJt^t0$xNhX@T-6t;^E){1gBdYzK^)fAgQQ;vO8) zTD-W}9us*S0q)c8?wI%|hBzg0dvO6@Gk!zyC(9JNu@DXeR8_~SbZAmgwH5iIkJXaB zx>R=-%3ewK!n}COxISG?oWl z3&w?}Y>4A!sXieg;oovn!QsTH%uExmL=t1@j5%G8hx$ArxZ~)P&!z3@P3!e&wcz*A zow$*7R{Vz6OD2{IR{83BR;D6A&AHPh3N0E63cM|$Z3g;)v6k)kOc>dbxG2@DV0h7t zMr8+_1qcf{&^J(eeW>53MoHk!UDAAz*jCAH11@Lr_$UzXQ7SjPja; za-V5iU*gt|TG7tHa-<214o&27bgW?TwD$XbI6WG`7UMfHZb zbiE#Pj7d?sF@&ArfyIkcK24zRs%t#ldw5!t=J_0$0^(+wlrHgfDq5vTKEQ@|!{xead-xxe*$x!eaW&(fmoQ<2iAOk<>_cL$~8_{21rE3@zzRyF%IF z)-XI}iHoYsY`kmd`*!Oq*3xn1Z$F;G`mTWCP%3XAFVr9`UObgY!Ic=gqtNjOY{jNI zNZ@}iv1iCn$C|Gi(fjH*^=_lfaxpulCBz1H0Tspv7Se5qi@WYPl9_~m+q&Y{J3649 zbzq3)_5e(q<4iXjPCUl&8e2($+3#Q36vO0cvj040#fD4C7wg2vX?rG*TW*L}m(6ZKLYG93< zO_piX`S9ppb6)f|WbM>DED(5`42QiI7wERhHqNK_=nj`!e>LPK44C``iZ~#UyM2bx zZHF3;xV;KH`7xb#%AwAks2rMPFZUW}K5m=?K}HN&gxVf^Gtzr}*V8roId4d^?NKXz za+~q@6c2;Q(6jXOJ$Y^RmA`-84Cd~_o6jnDKcti0Ap3vSEm5K3}$ZSy!&iZ)?%q5Uum-n`|UzF3gNnqcE?O* zeW^O_X`wz?cC)YVR)^l@Sjm>Uqpb4Es;iAxrf0&}Oo`0L6$4;3tKFvoWOp`rA*)lHP@CT9 zsutd65+nbdFbY1ZV(Po-q?C(}5=&13s>8jC@p@>6ZVW-7rLLtVFqfef7%S$oud1Bj z&KT!A2ZIb`4JTP+T>?+Ei%Tlw_pvv=aRywPUR?YPi=_=f%GCY+m}pHa^jn)uhp6C%xuK-SVM}P|6Z_V_Jg!_@ZPmAeB9EBf z-&N2|Bpbu{%hZ_Qbu;sJG`U0S0zJ#6a5&-FAJy>c^fyxE)9bT?`}K1Thk-2p!lT=? z3J66foJM^DP`=H>?%y@3n`a|l+wkp8yPk-j=fDL38i<9Hp+fWX^F}PeuHePk(N?;~ zC4tMUNDbcnAx=8%z^7dHp&~4J6)w9{+y{4A`oWm^t68q#O=({~SYqU?G0geKQ%=x?7H>XCiJL&{{7LXRrO=i6krnT$7l-Yob(c#ZOufSs4pZ5*YJ$7F|a z3*$Pf_K2>{BP_d9tW;_H_=koXalYPw<%OM|UR>@wPQR#ZZxHV9b#Ux!E7jYJWfc~H zVtd=BY1=LXyr!T*PL4Ax`Z5W1Qh%ykn7IAg1_z2tE7D>LwRd>aMfGe^wd_()e&5Ln zISh)8G_-AsD%a{A=PtKAI}#(nO?u-qPpckXZLHGwdP{hGcyZC$$*DR8mX?F&do`%N zHmd6w78(jxMYP^((qpcGsY5qCDB|d5ln3p7`j6}z|49Q#0eV02e@tCvR8?)T21O|; zK@boSq!EyoMw&x6lG4%*(uk5$0*CHCq;wxd0SN)=IFxiF-Ed#f@7~M${(Q@|&fa_W zyfe={^UUl&f9i`g%VgU@PPXTE#UF4tHLiU*qR+^;@vYQ$M-nR96470>Uq;Uhj+HN8jOTP0|U(QqM2zZ@q*Sv47dtrir6XSUt-g$1u!~G z5Vb$BdxXVa7(rA7FD8nj$5V|%7&cs@ClQEVoZQy0VH*j90Gf=P zd2rpK)$Ln}G_PE@)(hN!abvxk`yEknV)9W;Ju3$vGb1s;2;P#h*H^4I*jNg0eV>H4 zF+5JP_lH4{jg3;B+_y=y5b2%i{-di_)SZSMCg_Tlc?)g40OW~uo9*);ZxH?_VkFKX zW}s;I-5aKJ9Kjj%SOcLiq$w9)PF#^oz_f9d?q^=0XNVOli7lK~AJ`L%$6$X_Iq5Mg z-HApq(;^^)i5{XKe#4;3IB;b#_uTCddaNoc1(ak+NCE(ORO?cCT%Fo==e|i%y2CDB z)x%bt0~b_NK!MK;EWrmQSp^%N&uY}xR##&gk@P2gF(Sgx ztgq|0dO|Wmna&EQ=&ZN1L|LBoRo~VZJdDX7&Xeq{)J*%r|D#P7xT5P1#Lo~W1r>Y&ex+uFfL{7<99q&G; zmlhi7)Q)T>2BB2EgqbmucYt25Pp+7m_iWJ1 zyk|9MxeJ-k4G$+|VL6@33!!mcZel@>hhu?$qwgw>;s#8bO;T@scuX zwmdY&)%vw>nRcT29SwR0CdKM^W*=QHf_szlwEz-<9Lkpr#Z?Q_WIS-U@4D!{2FLv} z(AlegGE%#lsc{RL$8ll5hYP@>0!^0s?E7%ZPt+k(sIkGFu78-T!XE$iFC}zfazM2P z>S6?vL}kv4*}Hwpu?}^ZNZG@*^K>vAqF5p2h8$WWhMJh8LgMyb%HioN3lSO&Z1yv# zfF8j~-xcY5``!6J&msk8X5jihSs6FUDWKHH{BrYh2}^0>`^1@XkFmq$#MS%ho`D?j zT8ol2h;c4W^;vC5RV^FcB7>7iNyn_mUw~-yd8&Ww)1C&yqwI+ML$(?wLZ(p#aD;Vv z=jFAp#L<32cWPW}YCNs+>E&v#lvWb|ls2UB?AiN;b!XxkqL z=N{9*r?n@t*<8}Buq;Y)@CF{VH*%g%%q@=jK$nH$ioQ*jRh+)Exr%peCaF=8)1@$E z{>9fJ!B z>cfAuzhCso%0DSD=XZGe%IIh-zsHX7U=wUk%It`RU$yYqHPu(aERD_c-!cXa4WlI* z6vc+RXTIYL3GPc6lnE5utvi$bR)4Zee^a0Nu_~mV?e6#cR#sQH>&oSlW97rd#a9le zIJ8siEA&3?P?mCsO}(WlQ8gCllrLYNzsq?wNb1AnJ8O~UKjKyq@bI|vHwdX_Jzch& zw!gU?=5+*>o7b>H4^OB8Demp9n8;LJr-4qDd!T8D7SyUPP2$hN?Yi^M4Ha)|XO?yS z^87r!7Cjbxig1-)nX;H*a#OvNag$!=b5Mp7*CV1Do?qH@(WC)4oI9tll= zL9ZM~0?0@k>p@0!gwpe&=YgsmlZbFHIsS@?GH_1CQ}v)Sm*?dT^^Hx9P2dyIpE4%9 z({PPGAhz6nFj`{gdj_koVApNb@@Q$~K%^;mx!3Nu<2V$J`q=*Um#+qRH?)?;A4}<# zek~qFXFO7N8?=Y7k|pJ>zEC@8kRWoU*T2D(8+k|vPszgt#o_{|-394H4Sh4((|^tH z=lCiN8#My9=Y`oo_9P;PaKmisRlcIT%T>d+6y+JG`Npm zsm5|?DPnt^`(>GA#bq^RTkOAR@l@O%t#4@#`sMw&0<)xeNfIpy6=|^i`upqisayuV zu~?SKVRXjP`_Zzk$)krJz5BRRot;vHD7rT2S7z8v4kKz*S+}`gMQ?KYUvDhhsod#u z;;U5uI9uF!YUdHF&D*Op9=NSfjj!*uh>_nEOFL^i-}zDheGW^c@2$&aK*o-7YHBMPAfc6huU{7=Aa=UtbWhmz4CG9y|V6PZc-^ ze7d~;aTH~$o3d@=;VO?s{UCvZQ<6nVN5LP~GxWv?xquuwr7R~^4>fX(*Xt;~m;OAy z@^;r{61&!3C8svQ1-nNr@r-!R(+9_wa$`Ie+Mn`>HS5A8G(nvV8a)$J+|bT;Lwoi3 zmr-*>b&vf$P4}4^6?cScFQ42KJ~zwjh^@JPbr)~C!Q0b3bHM&IGborI3Mt9SQ&}RT zskjgKc)Ve>xj+^EmZv$h@ButC`=;HC^geVMH)X7~=w2!zXKL{FhOTqKR9ImB8nk$5 zf4F|PZ`I`#-SEQq=ZK3rA}y}F{8Yy!eG?k0uI3o}%UW_0KH5zb0ThG^ z8`MLs5JgI`S^t5)j07t1=e&*dwX@(fUobk|MWndOyJjlAGWhADkznAmlW5e%rDw$d zq*pk!ca~iw96W_`shGT3H)~=z`@5k{M?*P)opZ9>e z4xLB+4jIjj!O`Sh6ah$di+vvEaF!6u8_h2N3ZIx}1+Fqp=SeEONyvK0b1lZn4;j>& zo&45iYw5HVniexNeo9>jIG@FbBK4s@X^&zQ3|d@mPCu6AM_N~N6=(3sl-Zmjaw6adLJH15vvw+u8>*J|TGzGCd`>OSujmcyLCHoQn^9bGS`jfUwrs;Ifv@Y6fa8Q zA9DsV`U9B`Sd2*CI7xjjnys-Yi*(te@Tm( zxmg=ixV*gj4%60vmOHCM>S&ai4_lh$)830gITE~7rNFr-aZK`xIzB&VCzFapsv-K@ zn3U8<>4vtt|E~td!vZO)<#_G*Ed3MSfYx*u{K@`s!k@y$O@y8vT^8u!sWC#U0=>a5 z<-1ra_j2~sAzPJ|(`(L7w9nv6W#v~Zi)p34u|4iK_b0I7_iED{Yio)Ax?e%u@83>< zNhv8|UN%agYsFe?`s9cxNyS{tEV)0Z%}JG2LLmHYQGMu<;*Ep0EHiOrW3#HR&iI}9*1rNB^lDfkZd z^d9yH#O^kB{bKr+b<4Y@r8Hj_{rU{7Z50x%E5`_iL{0G`!(0-*F+D>m3xs*PpzCkZ zN(*cji?hC$-KVIh7s4KP_hG`TXtu(~tshX2x2KCD_Wn6*ChQD1g(QkHi`63ToE5RD zB4}}#!}YKlZ~r(~eJI+=siWsi_v*I`>7uaEULMqVdNj(b@>w~Vzf=7x28dJw+y;m= zX#fwVyEeO)P)~#2I$W0-rQ<3`vms#g22*DP{%W6%Aj^4yB#^>(mudWkB^==+wi>YL zI$R=-ZF=Z1a{sg_1^@Gy{Y2(FU9xPZQJao*Sjt?4eg!Ra5h^raXBw za4t!va?4Lwb5ik@R$VRUmDyWcTZ`A`yqvK0yx=0%_=A+)Jy=@H8}HNHG;b+`3!(UY zlb^%n2FcU7PevKv8!YxSmkq9MsL*H=x+za<246-6*R&gXr+99u);Tm7*fPqn(F}2j zizmuSu8ZfWFjP+vyoNr2hwN6xb;(#(9ZY{z?vvn$2^eC-$pqdhojrZ{4<}>gD_owO zuCy>8?9Zp=HtRY`S7aCI&%1H&8JWOM(t*g`0 zG$%%}vbCkm>fiA)WAVtkUlF`o%KkcUn}LqX1*s%Qki@DcPegL-{)8G!&|F?VM@dPK z8|U&E@>Ee3jDV|SGx@jTTDx~FZrM&~yO$lKsbY72bfPh&rc(3SvuB>i+gzIBS}@u( zNV+-u67$Nov9;#&Jlc?t4_0_We#Wye>^?J17FT738w{&M{^f=0u&|4UvK@5T$;JL` z64Qnmst@1k4*5JI@SynweC`Y-XK|M-@P75ReLQSsCS8W>ysXW;WN4fMZJ0zmzQ_L z8M}$9?dXfIt5=20QFdGPAgOmL8)M&#Fh%59x^_a zahH-Zug7Pg{H=SHEILwBkf&09Is2pXb++N}b6njT0|my*zD!BHJ?FQU1%@gSSbAVvay*t-7sD-2m@%10YbvfD+nfH6wJ~g|$OZ^i3AM1S$MM5fW zZ26l`cXf=4(?&xo$a11o%Ej57F>*dtPAm1IZh2+?*EK-`CwXSwFHUZ_8YJZxfUKz( zKLG9#EBl^!upW&#QIQ2vFmbIaEEQX6`xQ<8_?dy$*a)+xRZ!2f@sWG$gEIC*Lvfxe zfFWZa_jMo3%DyO2BbI*fxU40$hnU~PO8{LVoZ)g*SdV1F1teeaNl+CUC`1N2=|WFF z8!t_O$T+ZYI|k;XOG;|{4zNyc(^5er=W7b%8X$U`kN<#*Q^-d1*Abp#07p>2q^{#R z&EjmL4V*iA8wR$gz_NAV^u*$Y?eJ(k{v>sl>=MdUgNh^QWH6aw&$G~V!8L$h3Nr3~ z6oJQ-={4@tz?IW@xJW>NfQlQVAQA=zy)FKfn5al@i3ht(tCTMX`$bQ#;<2ZscbT!4 z=`#yw+Vf@=xMol3UR1!yXdb|CYBdq(6u!d+(B8>4VmvHRLyskiS{v4KTRl#5s-(Fi zIIzP6!)$K`ijW*~1D(uPDe<)fn|)RB;ei1Lb)=Ml-2m?}vKU!p=`EfT+Onw54B^3F*{^s&e&xR>)TDCVeyxN1l zs6Jm9(=lYUwJ2Dt#iCL-lslVZF>P{zBXDlGat8Ebn)WV;*FFX2TWf|u%W7-gF8iNb zjoY@_CQx7qVYg0n#I`YQo0mySO6G(*Q|n?m;43+qW&%-E#v&t4)n~S)yMY6M}za|AGCTG>-daDqsS5eI7&jLc5m)m@+h*BCbVD-CtCpC-CymF4 zhxglAdq$+!_ugUpejEWpBsDa8*r!1$Nug*)q_lVEVPVC+?mhIyTbs$PPc#_q&`QTQ z5e4xH(HVhI%eQ*Rm?0mO-b+DN$iO zOi)9%e>00+zzpDCE~I>d=hfu69w5WY69(0Zun3?Y5yl5&F2`&~mfqgwt}221pvO^X zL5FU0ye;!+#S~HF{dJBHvOY&@D10Lr5wV#U$cd07034P=imq$XFG35JgJ>hlBPfI% z$(*nk9&J*xkdyqImzhP>u>B6iY*3p9Nm18Zax?`LosM1IP36e~*sZ*6vAU)4aRpl; z^g+nTl1Rihb&DnKvr(TxH8&NJ6ihH2J1!rqfiJ#eFBh#RklyuRTsrwhe`iTDIaR6D>y|c+S6O#BZpibs0Cg{UWad4cV zUNb_o#R8%gX+FG>pobccPDm-#{@ygl;vzC(P2TDKK*aa}kQvY~JJ`b@65Bjwd#Y|N zL)xf^-TLSg1C-~)Oli!8E@ptQo9$P?RLSVhA@=(+`pp%MACGR15)#!0s_=W_hb7@)vAi<&rT?tg2n*-ws7V_$MEsCU{x$)QQS=vB%J|Km{w(?XafJV~7xON{` z*QfSL&H1PIBg@VzG!|rsUT1}68`yl{z%=rI&WvQMu6;E1pLZe^KLsiFJUlICRN)8a zr#SzGo9l_6LE76wG(Kx6#xl9l)xOdz`lvTO7wz3L_ugn`Ts}g~-ck;>fV1HZW)Up= zv$QuFzCWO^o^GU5x6Vf!iImOwU{_Na^f&GeH$3&FCwBRb(<;N9Q%%BO#wnB}jlc)V zn0h+W>lKT{2Q>Qj5W?W?m~B~+uICk2(5IGJ=OY_|eCMuD9YhLao#UK%#O!OB8hXiS zf({2+a)&HnD$p;3{~HS2MY`O_s?U-sLVt`L|EM`$#6(<9S@wX9Ux57#ywSljz9$(x z4RiTmnX*b;(x)4eG>osQweo zD}0yg%~40}Um4DjNWoVe@7m?6=ayiYE4F)bL+hPOcG_P}2i&V(z`w)A;li7avn{CH z=sDhhqrpI8`r6r9w)AiSaFePm_beh}s~!&E5vmzjTr6YNFDe_Ws=9y)sQ)r+;n&KD*l}n4c-;N#^=R8mOgoTdn}3?v!)j|BKBMyH+tie z-Feo&2((o7{Y;=Je9wxQ(*mXkI2RiF*QLH@u|pK=j|E z(H)X3-m8(eFGOgv=b-_;B_EfhxLe4qW~pJoutju1iMq-*0p&x{vj(#3^*Y_c1lCHs zz{-?l1Tk=a@c6#jPh9I2>z(0p#uI_i?qol3PknYC?m&T1X;3eG4m}55d-~Bg80M62 zY`vo`WdtXD1d&B0ESoF0u!+7OrYfuvGys8X8r&5L>RAI-r6u<03TA9+^UQfJU5H_2I&#A_wBfD@a?-G zz_Sr}o9Mm&nM8xp_>O{e>`y4@z@N&q%6ilAAm`4pzp^dZAw6=s(Q_fGQB_gaDQ{%i zQcY%;yHint8@kS$&FvEIiHtou+$b8Uy)yq|O7* zBR}~c;=Q?K=D$JaO#p~5r3vTVj=9`M{r7%pCOI{&{h?lj50ZzI8M^egnMt=~tdudx z^Z9~qLToEM6W1GY>Izfo+DryHD%E7uD&!-HD&)x*3&vAv8$-9LVo;_vA0p=hKHwIa@SkN}5Qf?c+isO>pm)!GH`hPW_nmivIfm#( zGnxWY{`kdc`*_QGd^RUl9yOOKXcj%H&>PzlDsCfPdK~{}WXfDB|0>JoD1HxLoWNED zmh

>GnC3_8UZ@GL}>^C;JKLVg)_fub)v5#as+fj@wMk_fG8X$iVA8sEPzB1^ZOP=P= zeOj>55F=ANOTUK|_m~LJo9lQYed_!?-~39WkhIUFQXRaYzMsLGpe-hn_ch)|is4tF zrj%5W+AF!+j-f^kF6dRqa*3>WnZ_?pLxgZzPhF5wasZKbG6Rf6L**f5;1xrJMPH5L z`ix=;$Oll_4^SUrtUIwObqU7`S4M)4aIWYv8G=bR|65`L5Ax|Z?&3wqJ1lIbyl6Y8 zr~8Wi7dGtYA@2%IcM{TjZvtDuAB2o(<>3zf9Rqb@FR{OOLN20C>>oqDc?N;wwBBp| zapRuNZ6x9%Yv*1wPn3X+HQ>G#^lReO6Z9Wv=_T>9`kPnpX`i+<^oxQ^l7%K6^&dMS~>u z%A4iBl>Ej?ostZ$VD_rOXBbN=^ZPj;u4<>xsQDZwNl?%^A zZK*74&-++xMDpiQXFFMLy#owdpgE&$mwt*3PY~lR`v|=t^T+HvlixeTJI+a+qKp0X zv_SPEvho-sm{A!dt!*@bR&&9exTMRlwm?3Qu z{IiCY>0c%kt2PM|`5*(YJEvV0vHeR%I1jb>W~DG`KtcEOws!jZ;kzqZU;LNBfN$#>IZiHU3X5)xJUZh`Bp*BS@@|rvI#F2a6jg@WG#k%{Dh>3niI-zevG6RX2>4xnc2s^B33Q7LF}QK8G+XDR}FOi>za zRZ=1Y+OVj5f?fw)0wYh=y`~0jii0(bA&BdY_rcL&pb4Ej6QspThJtXJZvO_M%E)1% zewc-?#F!_wMz8$mynZA>g*N8z0eEu{^F%7HdVLs1kxWrjQ*&@A_*+)13*RL>s-*|& z|AL3#^K#y<)aT;;g*cuk=Q39Y=qY?Dk-jRrL7HhNM~Os9@bsfZinF?0ph99IRDB3) zS*zG);a24vthx8wP5eNV$`B=1Z2(}IB=&-2t`hb7!dE*hw2cXaVD3Wg7J9zJEg)@V z%6FA}+;zPf-;~|so!cGHG)>&h5`Xb@Qs&vt_0;7KC~ZO#;p_m+8`exvRcJ7rG>Xwn zNf;#lR;6nJX3%@S@a%QA1&)p<&wG~3axA9AGBFC{ve7XjD>@0@jA83D&yq%8-${}a z3`5~s5>+ayf6=nA)3tuEH1s>E~eCK&&a!Q#CvBOm(Nu%G#N1l4hnEl6y@$vBm7etopm1~u|KEz86 z(dX;ZKwO^h$#}Nnz(4EB$xMfVeT3i-nm{$P%+_lUMnne^PBlX)>mXTzK8eYxWG(LB zy;)`6DSWaUn-_PM>6iFz_gluQsJHlm-`ti}cwY;22jtVfzoxt+h>hWTN;tUR8E=q+khk~=ksNt>E- zQ)PkDWH3)l%7tudIMZQM2d_2_E=L8<-7!t`vr12$_Fn3?b8|^dGoW3bjxb*u)f%n> zfL7l^OP3_EkDz0gJ>}WIK=5?m8#EY^?N7O87mLW3ipYCwy#;5F4yVq1WtM7Uf>(K& zw_WIJOQKtTSrPs$3I;R}8paVv|BLI=rZes7h($?UordtsDU;ePezqvwvXmv=kI*ph zK_GF1ytvnsB2nj>^-#RA{v}WC`d;&OW*B&-r{qfPQ&cQlclAxZwK9Jjx@+9e zNQeS-g3`GX+b0l}mX5e|>;yD=o2L5M)5-A(3m@)o%zB%U>{(Fa z7w*-H{7nKGj89a!0SN-##8^UrKIqN$)_a45>l)UME}qrP`x^Tc0=m{Sgi8%vJ?6~n zRg9~PlwnCUJ3q>2r9MsLYLxO^guux%t}1(qa!0qvR4TD%ro5OK69d3S;CY+ioR~!2 zKHE1`R^>maf`sx)u>Pm_Xs0XMHgSnUVcnuVQi{8G^ne1%d6TkQg^l8V4N*9cJ+0(S zaObg~O2W-}3kIONOSCN+PvN)Mn-R3q<*?e4J1vbY*WB2sZ8zd@iX%{WGG0i+BDG}6 zpw1au>&?zyP8bX;Ri!_#x1qc>_n)~rfv;FUl znER_?m3H59N+XlbUK%wYu6UEk)JCMYNISDWPT)iy@;2jSPN7~g8VkZ>JpdZ4cEI82Elu7e|y z!cVh6?=?D|JEV6uTK1lbh|E^T2n$F%JcXlbd)>3l(<*m6dqZto6B6*n?3YKQS;g%C zDrk8#Ot>egcJxR2=Cp*fdbQ`H%Ait-*Ah!Wra6qHHxB)UZ(I_c z@F6*^Pt8Hojoz492^+^|dfoC};d>uTSS)}5mQ!_+3^GDX0v0wA!IX9EHS$H?EF8uk zxG0Dx8prm?O0u)RU%WUQZdrDg?Flbsf#l~l?1;-*fY=O}o{vpnGScYpOE65L>A_hR zBp!4pTB^|*lDQRoIKUnwT%##{_9MreiB8v9LxMJEf@;p|(}(8gz28aUWT&cyd6_?Y zTrQ8!5B*BW-yPXqEj^iM$07XOQ?_<%6Dm9CjL0dyhOAKlQ#;`+u{WrF_)y*aezxwU zNWLAWUIZlK@&R9ojX$hMy|{Th#qUm=bl+#l(8bHtnxw_aX$qmNgvmFPx137NOKj06 zx;gr$_XkZWvtPF_kt+K!?*19kkpOD#4d0p>T?RW@Hwt5wbK3oU_v1=CJxJ}Umr%O0 z@zbBEk_EMYS9uV{ZwNNZm)z}ATua~&gA~E zO~$_OCvxt3L=&-@49|4{sa)CJj|_0$me-{ck*qomHphhZK+o%R(>;>i$^?OiVnwA> zdiAE+rBR$Jo`(ggk&LZ|aQ#*iu)TnWOQ`L;xXeRgBSjzdu}wX{2?xuluhlb1rPst@iEC_A>8ie!UXRTKI9b1$K}i{pu!MM{5nDCP1ToHT z@=`dxzo@1AH6t|CXI}DBN3pi*FqkLpnVsaWcuRaDUBk6I*tgVH)3%fmXb8)ggMn}QJ9gG(z zZl$X1u5~Wje@oog+!34eZa~lbv~eV{SU{2vtCg2^kv5BCqPXFe%%jVz&ya?bk|arS z(B}L+ElQJee#>7dF*|76KI^KrEY{qDxNMw#T|K3eq^v=9@0A|d<$v>MwsxSUs939e*hS#*Y&qs> zC_ZyEt?k!tTSob4ADxvB@q|A#%tx7n)_af#Nx&+t68tiJ;R;dMP59PCagDRTz$k04 z;gTqlZYaL8`Y0op@Pyn>kAzN{@NNU=`7)HVMp8U}|MYrjfildyn=nV&st_EJ7De~u z%aD(g*6gu7I~qDxP*5LKm6|(y=kI>0pSZBb{i1YRux30UBO?tAS~6N{`=!zJ;-#@~ zlP{FAQF`-&fAiX8kMl%nK7rk4Nt`FXOS?Zel6G`(J*rb zWH)KRzA;ZPKN<+Ey|QLQum*idF`pfdS)exO-RWNG6^teCXn0JzbWx~>=ya#7rTeT` zl%qiQP`QJX`(_XtsF=fSaHKJidsizO zV`udfl+z(CyRK^8v!p}8-cI>m>%TZPEk7aLff?>5B^!(5-DjKoraN| zuufF>aE5v}_@CK=qLkU8L(hgQFs-_M6Qrh}FS^Ecnf%1bu74rjd}15) zdN*##tv_$rw*y|{(RFJIXt;{@%OvIjeyLta**3C6-w4a5jb*Jq*ey1!W!V}guZZ+p z%aT#uv?N+~FmAhN(sW-8wT3AR40Ke`K_j9+B}7*xFsSA*0akVamTp=}k-!Hb?&~+H zgoicB%gISYXJ+(aDta|U*A>%>0bm+rF}mzOk68c7U$`Qj->ty_>)Y7#9(84g|7iG* z7V%4KU(+Xx|!i%$kS5IZo0V%8TqNl zeJlG}zRm*4T$A*0l-LJr&f0}wX_qu~y`uTVZpCqZ(D~K{{4j1cJr5_B9&3Q4`K;Ks zk&p;E7h_0;5`V{PEo}l~7_aCjt#w5$kRoVZh^nC1Vq*mcN7YUjVTw7S%!rAi3S&rG z%F@&-MRRHoF!?10J@Ih$)cRxwBctms;CSW!e6Y}|wS_Wj{XLwxWIoJ^N1P~hcOc?w zI>4wU%XZ%yB4+ zgw0CT;*(O6eBII@F7JmUqS-vv_2s&lDBR3ytEv(x^qbxdTqs3Da)#B;~r$ zyyPRo2S!W8IjcRYcjI1t6}_b*{DO=28(VHx77b`6Gl&jIg2{0a@%RH>=KHZvzI+?B z^(*{hpiPK(q|-1PZ%Mcw`qucUF#6H-ptNSkSvFV}6Tz%glfd*UO2O&LlP7YyD$D8+ zb%UZDeJ{p}bi|8+Ve0r>|CxJb=kYm&wKrA zMOpq>UAWJCUaD}8F(&fbt<{iuahR1chA_xH)9ct_$QiQO|L*5?b-DtEgW9VhHADv5 z5v8R%7zF>llOSiu*BM1@Ih1utGhJKHhjpH3MMNmnqu|ttv_vs2xyaVqsAlgaM3Xu> zfySVnNsiNNUU9Q_^!(U9&&>q6VW< z)M@BRXm%X^F%AYPlmxCssmdjXMiW%Hv%Ae&%FEec^Q;y}B?)TXgMpagTkV=<(IyS` zuUSqpFrl}gl#F7w!eL=VJY;sr0L=Z}v@MD< zH<)zkD|=3xoJI6UB7J&H*d1@P36f}Sw5I?PPQpp}I2P{?#mtBEH=U4oZEJsdU6DiQ+draFC zXNJz((ad=8+7Zhk`f8IYG(H{JhWWar_*k$!ce1rqgJ(64OzL&pD~QWh>Mf&}!C-W5 z+nnTwCY9n{7Wq$Ecpm?!g9mc7<)Gh6+aD-J=hthp{YDwxX_`sf zf%QMwElSCS$Vov?l1M$Bi`Z-8y) zGx5^6146sbndK7VZb5-HTjQ?+h7~hxNYuMN+0oLphz17ytv1woB$}9$oY<<($QSHz zu^gxhN405CS!$h$bntAN^xfsUV#>?Q!BOrUp$hXEa$M+|bjcE3u-KjC%BIrhko?Xh zGkn%X*X!m|G4h`lAUvEjy!NTKra{Y;3uD#Sw%68{qcH1j)LE1TZ$h(TRnIH#rt-f) z=4r*Sx5#u`;EQid5o{7~aTn|ql^%@Yej}pGlHH6RR=Y)Y@FaPfc%25f2`;Ws8q@B| zyr{A+twxUDbxG24a&o%QuXsEvR&r`=tU1mDlr2(E1>ip3j$XO~oP0c4$ke8(&r!$S zH~D~y;lau_>y@)prS5If?T3oaE(EeL&y zCt+U_-SAvjPpE{}G-smd!q%OjD0-r{OY}z@Zx07Q|Aw9F+I;(`n-Q}L9R)MQrq268 z`ovxZ2c|=6e&fzkt+6%OyNjEhT+Y8MrWUEdZ6H zJ#EO|j6mR|_mtv4B2nZwW*bmuXB2maIw5T4so+%{gow6r^&tvM?oX(h+1X-+FLfnv z51?O?8UCgA>z7hd%nflumotzi(~_azn})E5Bli~Gm9BDo(3Fhs@)#q# zvaLCL*xD+T25xsrT~28MRJ2Pq>H0bgXU~0i&z9vF{O9}pc}kZVKuGcX?h65c_qO@e z4yfm3AfPY)K@f;>n!$H_b+O$cQzXl;dd+P%u*kf8wj*SP#U@39*r}Vs2}p?shoJ^+ zxg($wk$myP&_)S2v=_eX5(h^Fjir0=Ri~(7#BQ}4^aZ~b#wZ(Q-Rh0@aC-mkU!r`= z=;}zUMql+s#j0qDz|JqXzZnE-5K8y)LBcaJn;9$t)s2fVkNOkU!e8U#3Az~5#{5E` zWqs_Oc5OmtQXKsCyS{2p{6lh2=Lr|@yyJjeIMHlJRU!PaaXIr9`CT3`Kj{PYCqOp2 zjz+47Nuux$Eh%ON5vMqX{3VswPq>l6C_NaI>-e4?UdAIx94pizpyw5YKkJX_W%xG$ ziNwm|rROgp-v6N`L3)bRQ+pXdPNUkKWL@J-R3Jm#v-t=QZ#R3YY@*hrUQCCwSRJCv z54x$Q+uj2Q)HE?AmS*{)jj<6A>pw9NH}fu_G`~0;S5y2% z{N{!D6I}(z^!w|LlzBVI1rOq`I^Gc3uSC<_3J!)buOwBc+Q%a>$rb%}G zIX4Glg2~qyVrFWc5FyGhMuy7tVG@j>mg;*!ca>v2oT&ahYI{TSHzN3v>idXd7`~0h zoC{agMtLetBXm4mJwe%6zmvBW`j$sN9D~?Aj=0J84x{HC1)KYgZ0zh*>cb8%$^dCC zKvVNzD8N8{hLshNgZBn%ZzC(x?8v>Cir1~|<0DuDZ!AW2!7K(&kA5_g&d&_ADf7TL#yh ziSg~PmaT>}U&J%c_A@_z&+6b$?w(HN3?B2p<3uxw80(}Fo~q>*7bUUz^VZ>qr;|Yg zi$0-SQ#|5;XHQ2&t7$e+^c{o~T3EbYr3S{-5FG&*dIQYda-`;QA*Lcm%~hI|ieF(? z&~7t?vLl5myTUKk2_F=uoTI*f;oxfwXeu}^y|1oYX!iOpxnKx4G_KiNlRkv{6!g@Z z^|n4Im&v#5p+Um$NxcRhd+|bPaGSbykfeaW<-+4td7dOL8_n9!id&l`do$5OAzd^? zUQfI@{$B{wW@94Cl31rF{!8;OS(+4MGwp%pg$(g?$h1FXZgrWqH$sF5iklpWglILq zi*N>I!|zqBK%K&r%zD=V4#exGD<nS+K6hbnJNlZmGrCG_# z{&o*t_M(z#&x-R}Ya2SWyqmUFsNjq&I40;E28o{;Q-wFI^*6F|)pCfA9;wpyDf z?@+6ytDinPa+*EiQBA%E-tKaGP=vW{`BZC-q%ANV(?N+(PDpQFB9Ex*1lX=#*)J;r1H$=aFg zkEI)FRh$~k79N~X%AbDswM@f*b&+LfluQ1@fI5=~YHqg?!+ez-X`;_~TLTFmHdcB_ zIsweKYu|vPiGZ)=R#x=wIz$iaRqXAEc(78rXm__*{YB(a*IE zrc^&;_}zA_C+lQN@0%T6Sq~M`?w(zIYa$$)a&CjC_1GzP+AT-nfk92z!D0)_#?bxy zrDF~X;-A8*OD)0Ahab+1hRu?tCsul$aNCsYW^HCQ`8FqL32;00@9F3@U0heXt*|*R zucVHr9~WeAly38#(I455f8QPm3*=yzk>%if?r1WkZ^|8k$J(@8x{3CgvXfmyi zOcWOGUACvx3e+W7R^_jmj*Re3?jbJ}bJPS@nb??EnQ=Z*ar#q0DWTz3*-+THeJ;57 z1EF_0y5qg!GrL~6y@Se}F_T}I+-p=RdAPJM(4w25dTm<$v!i4+Q`up-LJS}ntW}*0%^jlKAk(V<&*R3B6sI!<+ zd46-}no7`6*_ju_KI*`LVzhr_Sf^mLv8ikUUFB>rIrd$HKh>t3!n}xzqKD^5N_Ez}R!&uV7q;t8$`h&v%W2ikjAbw4bo4`)pG7?yj|Y-AR5G+UfDR9StT zT81x%M-F{o9V2iOqoOif%sx@@Xs`1l*T!!MklH;+lr!`8)-%{W_u#S@%%<<)&gI8; zSmdV3rjjy|fS8(Glsv+?m-jbUz90}fRu}p~n2*sh`-bGf0qynPR*!X;rFQ;LQPFwy% zm{c-F7rS&{d}=wb+<~9*9@%n)bW$O)0mwhjq)R)p(E zF0FnTGIvVaC51m$6xc;kmC5H1}~7dR3-smTKuVE##WPBE6O9y5V781E|_h1mC3GeXLS=dYgUV8NS@d%Jm9%;D$jE94i)mn#}u`UAZw zugyk0*3cEdvOQ!%uNgKKK28Wx!HMJaTKf;5`OylDlX@XxCSLsX9-5f3G-*5vUA5Eg z!yQ-`cB+hgVQi2bE$M6a`g5gYvvV!_%O3ODFwcOn#-L47ub~$cDP&LdRjTtgl6;Q^_SaSkSapG&z`_&rfdn#wt0w z#&A+dkaq6*kIi-3@7lS+)_cj-U*ut_z3ML`imgs8zyB*Sh}GFHFb^Q{Jo&%mzdu*~ zMnEZ-aEhb5P!hp4zH8-hnXB%zuqA6KF>rr2c(tqFJ!G}-RO=jBu7->FXQHWlM5R|V z=l8t;NYacIv{bsn!82AJd|bc*8i4h;|Aj=S8=@9-tcMiCwR(Qh&xOhtYeVm|WOoez zHTWH;K)ajv+ALGF{Flug+dBtVP&w4u=hmu&=1w%8 zHO{0&jML5hYacLgoZ*dR7j2J(Vb;NW>EIJIZR-w>Ac<*vf}htjGl!Gc%TuR>c+E#e z=T^{aZW_(Auq#SQ;CO5?bX~S1#6i2`>=ho(RStLhZtkBP5wJPaPo_a&%x&)eJ>KDO zVT1IO3RTB1(_%+Ea+ZK{Zh5vgxqRNd-ab3D{N*gwiks@SX!#BIS>*jLFs4COsP#0mY+gBUB3Zjc@Q{mhcoj2|XWasPY; z$q${AX={6%9lDa{nFjkBVwy%vy+fB6y78Jwl{j_3vCL;h;~WA$ojC1H?{f9$qN1yc zK|au-Bw8LALiVsD@gM>&s zP5B?P-ZCu8E@}hCRzd|SX@~BV4yB|7ff;J(6c`!?BvqtKVhAaT85mN!K|s25=nhGx z8_pxV-}jw!ow@kKkD2G$d#}Cjd);fTz3u8wlcA@;ZE?fLo$Hzt6^wQ%TaBgOb$s|l z!Do2VwmWXQ2nnBvZZ>_rmIJBb5yka8f7UW4iUDWvv3&Awa{rOTjZf{1U{|M-!t`6y!*;dPYPM150~m$ zo{UTAe8H#xxklXR|SFM zCiAC%SOOK4xBZnmCj1Kxxkw}07I&H-4pxd`U%Ld9Ml9iC!)l?kj}Nx&+vcROmH4;# zojlM_=)r@mt+z*sN-Z@jW-L;Vn0;~$ko(h`5=RE!YteW7$)0Hqh#C1A8{ICkvsv9e zIkbth_PK5QlhH?ssJBy4-ehX92NrP+AHVVbfQ?2iLzF|uDSpzq;2}bLJ66XAe-_B? zCi?7NaoZ?F{0gr$+S;G+mH4f-l$kIVylp|~CseYTVra6dh6ayC;qfGNM?aw|pNt8V zgXWqJ&5`5Fm`2CFOeCwn9)=;D`ws=EEw^Q5Y^>a;>AtxprlC|5Q^sA`U)}+U=M7hJ9*D_Z18T2aK=~cHtibyQ@JFYqE(iu2$^lKzm}-?xwpvc z(+8NKJSLu6=x&CH>zUxX*th$681d{g_ngp|4)WjA-jfq+FUyBj)~xBx|Jv9us~{4_ zEBbxEdX?DiwH4gi3#NOfS~to~38y6-G|=I2-b}d>!+!WWIOE9Lho;I#^WHY<+{Z?! ztsbdl*wuKR@u;tD1=EoWfLu(@7uEyD+?t{{wNNJcALk#yQ5Z#o$R&89TE_UWE%2&= z?TZJbXI^YOq3L&pulj>2v?u=(;ocv=mYcCCa7ebOr-cszM-x4~k+tP-?~8WB)G8qb zP7GY8WxQ6;lMgB|2Ske`S9M(tZQxC7b)I6A=6$-g2eV{h4ERKz`Zbd=;nHdS2W`0j z#{ZqXxq%tD#LM2@PXR&av2r1FLZQCaD0qDM;EA`Y&-i4P{yCv~k)2G1zhx2gBVGy? zOJ6&iF!$s@+rGXE)*!?{-|j|Z<)&z#1Ml?Tn{)s_cdNT#70mvF%hid=tZ&*p4nsC3 zVq)YVSBZY7^}GBp_0)Xw2eaN=vpy)VGr-yY-d=;iN^0IR&piJ{Xu*&DK~^>XV(LKW zz?-dj3%(Y@zcX2@-tou82bU)SKMsCFM!JOoyvX0c__Tw8i)iApleFp_qn9q|pk(oX z3zH3?A{UdIBE(1MX9gbG4HUuCHVU#HydszIf|1B@%gf&RVFUMCxJ}kB++U$8p=agV z7=AJwJ&AhC@HFUq%Y8%C{t5XtL#9==1UFrT0uT$=cP_XaLTuX6Ykk$SE0$ z^Jn^GFyQmU^%?#Ek^EzFZ%$VVkopTyBHU#IBFMq2bRM3@v(6+#mGu z#-Ds!A1dKD{n|fKwXPlMH)t(v!6+B5vDRJ8`tbcCzXaB?2C1C(;6;taY)bSv4Z};b zFa@=xz2c)gr%#4-gMb5<(?uTd5UI-96kD8(JA_VD!v^VYRsd_%-T8-7kQb{*C{t%l z9s2`c@iet{(L`z8daneu^U(R`CHLXt9^KZrk@fl4OvJd-DS~^O&n!~#?t?a`pJi5a z$VK+$K8C|a;#s-Rs$Lcb-iCreCCk!_I4-^Q2tnJBie1RhF+B)NT>On+3`MkBN`?KKc zVQ*Dk7J-EdeQ)(NRmIsu5WCp8Ph&ij<$l#5kvzYR`k<{T&vSFN?(i}N@9`P->Fa64 zdR1KqcFs#g70rfsFuwuDd!dVS?@r`0 z@@1c7)5fDpJ*tYX<~>RNZul=H_Lk>EwxrMK*Jn_f-29hX+bCo%dXsegnqz;=Fjo4< zQ12VU<2UU_YpT5ux?Jn?3X`Jy);J$5T~S`$xA9!`Ico*B3ApCiBhJU}#JX#XBeTML zIsZ`4J+^|`vII8Jj*VYd^L3?!vTacFOSlEp+K#MrPj4d+_Rrs9JmexaI+`0~eV9 zfS*O4!9U)$Kk$7~j@>T+R+v$_cH}z7R=(~#>YO>51OvIVUJ%8&at@n|!z(JH`lp+t z?@Sj%xt z(ty3#)JHC!TdU00yh)eJ<+FY%Jk~eu9gqH{0E%9d8)^j{mz#(bGQb#vDV9uo8qqe+ za=l?7 zegJDfxA1|~?BaxM`nH-(gb(*vl`MW00lEJ!s}!^Hv^_G?&uHj*nJiJWh|Nw>K+yNc zJhAK>w`!*;58Rc7dpEYXK62dA0Y{4a`VHc_OzZ}+cM20?j08!9E?+u(f4VpgPzb9K zz8!a5CMcHA8M-}wwKE=;A2x_l@NuvVnW;Ie8oufjrP-(98{V9J_c}^HPt`*4kZIFA zql;C^SIxk4i_&bHx!iqjL4RGT+~i$>b}l#IAV(A+4XKlh2htg;xsC~|riU-B14?#( z|LboBK3r;nV=13aUh|Ld-X3ZZb?;Y9R>{9S$f+-eyY~nZ3-H)XtF2ih?ewdgr9`O|B#fl{0*8DoqTs`i3j8PtVVr(y%Z2Ew z;N(T@ocOd|{cic=c{I|;EpuTeu*j&e=Rfwo&CHu{`j`ir2(!fU+~dGZ4Qc{eCyckJ zL)_aVmXj&GfDh@?=GOVoSReft1!M8rn0*vD!&=<9a?+63h!1w{=>q4ac`vo7Tm-FG z7sx1HP0xy2x~C@$Ods_`gpq4+87>}x=M!E1c8?~hJ-6COcJG=0%^!iyI0OpR*zpuw z4ca^<3g6gC4y7Rr<3XrZ{Q_T4sNw0zK&UD6K3k*e^JTFs0K=eU@(Xw+R0%63ocbrJ zV9Y_E=gw+hc_!y5nXj~>M^#a50AnXGIvHnCdn%6J!qLuZkv7O!&uA{pWcdAx^(MxW zKXLm0>_mJdH%`_(fq(Liw4si(p%dQkqKDh`OL0DO26-F*!0gD(`X<)N1qB9XEGtG|{gy~yrslJGY1If%MtRo_tW&bv*f2(T?hSm=YbTNP50k{O zW;kz?ihPt^+`vVYOS2lZ1TvB07Smr3E#BccYb_Gu5;XNCwe=tUXKxG|zOwPz_2%(n z&M&M?5!+lSQbBl}Z#Z#m5tjT&PqLA(b3!V?WAtRCODAA%^zsJiz>A}}2$Rw>1zdB0 z+|Cqeo|QA>t6K54fb+1eYm-B&Lx8Q4z*7)-lSI{a9T?zhfbFAndJJ z`t|4RVN-d(n6NL-yjrs)_JU)X$cO)@% z1PxZ2_#FO~TNRYvU;H$>!au+^!eNGF{eo?{m@#C4(GpHfN8KFnCj;8;rZ)r z{o04#M2tIzTODS!(aK)A@a_7;0o|)l&g;-kT2v6v91X!oq#Gz$#spTSPOojmvbyA? z)Z$o?THg~J82Fn=^*E&~Qbg;vO=#?)qsZ2z@52${;-KK){RYa25!vQ3)V?>}t~-<9 z@n$0WS7#;TY4Wyin#O!(;vwhyHG+IJF~lZelh67m6sCJI*F4Mr%ZL)yEbcozB!=Fm z0kMOz1Dat~LjYTYt;tOTb&?x!jZ(4rNqb-tkHw z=C`R*dt3447issnuuNrXX?N_L^g>YfA06bO`q4Q&CiAn3QIR$-gh4VFLYvE)eRGzF*XE(!9FT9xNXA#qS zvwzE*Qr|T-bZKM_#wg*3Z!$e54M^L%`g)+3JM5NA>**k7{rXJy52tZb6|b4@+(nDd zBCW^Ttwe+|Ui3_A2Pr&13cwW)vBH4Q(tJ&uiDfq8eWaJwad$(ckVXO=H2PCctT z`2Zq=AHG#*`e9(7RHo1sy#7b@g5Az1D{80W+P1MuB(L~GF9fWTbj?>lZPwHc-9fWdP#%Hg)TTf+oy$fyQhEImq4GPy;!YS3A@hBB52lZ(l(0|7lD^>YjEti73oOnl{?I>+Y>~bC_)MxAAD^-9h4SY|lTQ$*+w1(cg1fDo zcnDdPop#P}=Zw&7f-byXf7;0-bU-b8bRZCnPkB;RRE$V7E$3GebBN7{^H6$P15dU& z%ujsJC#-X(BE9XloHNFC#&5oIGb`#{q+jx$UVW4QKyW;zNm=iN%4)!m+?dCVM|~0( zBID-=ff$6=)0zqdE4uzu#CtVv?I$Z(XJOoxe(LEpoGyzPjB1XS=TD(c^P6Llj=gL4 z!qOJm8Y8>3CIx)Up*9MC-hj6Fk@ym_=T18E12jfHXBWvJHF|`ag_A zaf3V7J8=3P+0U`g5%J=Mflb7HdU*(yv(>WB1YHdYyow3f(@0ILG6^K8c<%(h;A4kT6XIc;N)Arj z)E;^kyfz!P+U>Z3k1zA>$w_|UQ`LCak|$!{TV#h5D8|Xi5#fhIxBCMW=IymK|MVT? zg|w2_1sjA64Z(`?-!#3fOceEr&NOhX;wKA(7g4gWQMtYEn|`^F@B?rUlNGtk4tF>e zM_I&7d=l08$N+@?_puLE^0sunI*?6lDDyF)me@_2Fm*$fAK-)+Horpy4yY9xP=$-% z0>otE)7HkeOdEF4As&-;PMxv}jXr%QqTZ#)yx(}M@)n%esAQzU#AC|zH3wR`rb;n# z7?kv4PrVColMawr!E;_&lnJ-hIpq{@oD0QczlOh`?=}O027OuceY`hA#N-DnrOVoP zetS+b#0wS7RH;lJ7vaA(XdY-sZQHOXVM(12 z1AMRc73c38$57+{Zc)xaAwme+)@~{Q1Y-5uPk=ujc10@ma-9M7mt9 zNT8NWFSm5!J?Ui3{#jK=@VJ2b|Ls2tN_HVK7XEaT3Q}@IVV5ro0Cf-({-5w{%bK%T zBQ5@5<@4S=DJ2D#D??oJQ2y^jIre~|;BJBk zk-quk$p7LZM*TP0!yfsA0I(U<@0ocmCwVIS2rZYFN2ds-PHw#b<(sX!ZV$)h23&|Y znoGqjmyC4YX)d6La$6%fmT=OrMJ7zeOuQ$ziu7muMek`KmQ<7BVW0n2q z>GhPOh~NBr<{<6etnmGC&0NPDELaJ9BPZ)65+DAoZy;Ge5YTcrkD(D|3a#!7VRzYq zUJevqqh*C=VpwSx`%Y7|U!Ig|V0O!nbm_b9iwxuK3wvqn_uoVp=b$qiMiVh?|HuSt z5bM7RQ!G+w4v!qnIh5N*!Zi6*I+RO<00G&Ay%~`hKj@vEsT5)C_4?S+=s?8PfKi7GQ9;|iE|)QW$Q%p-ZDw= z_B~!0aFsLHQ3r|IyNC)A{|n=EkZEkJn<3r<{vRfD$9Gac$cy0~pwJnEk zyZGSI!GDt-nuk1AHu_+ zU^>=k^T0ems%_&rKn(POGRy0=Z)NaPX`cjh|Goe_DoH+ z-3|8r3$qxLef<^Gn@Y9O48nm-%Q)u{=QT;RJp(54j}nazu(wSPovZ;ZoE4!+3q)~2 z?F#KbkRBlw0-7ucMc7S+uepMUb1vn{dELaI+KXSWXhq(hTbp-~eSE6~pUne85XA>K zs>p%RvI90z@Oa&na<&FN=uaaHGWa)5dYx~{{LGU#f!XvgpGbuLhACEq#*10=ek6*O zwUnC!a}R8AAR{zHhz(0YXsx}cAlGg2=SRNh>x{h~>|Eu$C*u6_AKpT~GU3^Fab4c$ zGCBtisE-GL#DvA>pO{Q!2RoFc2Te>U^L)Zzbn*FnrK49P(kD&?%qEF7URMVF5a)ZP z7#PoPCON(z5xt=sWz7fERh=6rnRnX0Bi0TxmV`C()YQ}{Emy6kSg?#Xt=aK5F7@~b zQkW}F=i9j2SbsC`V^Tn>(WO^4E7QXh3GnMyQfd~t&`@%Ay~w2!cC;GHdI-wb&a`s1=)9SvXhu>3Yo3)XyXd39p< zi!Bcs!unOmC0upA#R|4Ei3;u9vTtWEG%NU#3IhdP^koUgEWY~>*jYE1ppmqTCD;3a zE1ApS4sZU)3w8TpH&ExYBdn@s_#}M)g*UscJRRY`ux-ZswES|=5nuZSNF^hO$@kJ? ziJ|YRs%s$M%(C>oJh`VyFbdH6{HDWs*I*+yq&@A0A{Xout;dsdt=hN$6Be;z=Yrld zHa~{gU9|PBAF`Kv`^9oxBe7fq4NW)Q z*n~1fKL-wC*}IrD{p)rUQ(<8-_%nhQb&ymnB1EX&sB;4K1aBjm7wI1rirLC^dOBZc z^L^KpPJ~+hug0s7v|+9GAT`Y=!2j?B02qol(%QHF+lKvZR7G8U zhTm-L?270=9mXmz^xI@_na!J_7Q#Lxbiypl*B#@4hJ574mNxWrW{Gx+WrA?P#CMHM9c+?@O|Sy%?+$ebL^U&9Z(p~Ua)9mkK?{cSn# zI&m4P@7y5?X^rpvr^UBC-ZJUhrO-qZ9!JLkY3gpSU7~H>&Y;~l2T*(359R4y z8=xU}2gB7I&YSz6+J9_EpCs~p3=--Vx1Fwc*=drQ)*}pQ4W(3)29Fz&P}R{j><8=z zC=IlazLobCp=S;OKoB274~mma=kG}zcdynz>OCn9SY8$FTfhB1uRjvOmFOE!Cxa6d zYGQi}K}=+(nl^cRc6-B!0NFjdf@bV3=Vasu3O}wZOOo>+ql~2zZ_+$T6tBN1n3!l* zceBYfK52$=*<}xWX*MdCmX_wk;q*xnFD!I3(Ra`0#O?EY)~=%QdAb|;HC03MKxw^Z5yqT za|(2|L}T`w{H6B&Th4V*pBrh^xy#jWEC>r<2!^v#U~o16M&i`L%go5=HBbsMWRx9K zn`$bIaL3sWQtD6VpNC{iBrC_^LJ^$2p*Yn2@Cl-g;!1aT5y|~4>J*}<6 z3~t-}QB?ExquXt)7SJ=BGQ991@96{I@gmW-3tg$T_Dr?JC1;T*_kRz%ZsU&7nN_{# zn^-igJS=u%7v$B0+-R8nnuW+>rA{Qm_pq=`Eu zWx?DRmP3OHlHBBgY=+0!$Q{qLisDurcv4oi21K59%B~c~N)T#mdFg%i05`q41UqIB z>lvl-g5%58heAxi-0LpJYEWg$=Y&1V%r;;EE~DdqX5VPoPs+lbFhTdc;rWf}V#U|$ zFWUJ!iEX5F^Irk$bYXU?=AKkI8aJvtL?vZS8hgvEI8mo0%5MT1dnmvp^y_e#oLnwQ z@`tv;hlM!s>aPA*l`09iTi*=ps+EM50offM^AB(>)ley`I$rdtEk}9Tbba@Sm2Y7y z6OBPGTd&rIv>&0ZQWk3;BrC{-x3e{qMbEBU+(bHn+I&w~k{;NjVF!3asI<)Z&>^EN z0+%&QvVOX()#_wzRMtyYh_%^a_)aYd`!snZ-N=HvR62=~ju|7OCz+xd$^ zYnj3{U0f7rKh9PcAhUbvxE^i3C&;3Nwkm}I6QR#p19Im9WBkO{*5rU&3dV_9Mv7=; z#5v8c;?Ym!s7($YW{MLAah;XeMHj~_S8&D=y=0RQxfl}KfUrW!Z_w|)OxpI<1P;Ff z{@I@?EH0<9xIW{e?1s(q+#28zUKT+9FlQMGdj7!rM^#U~BsUaI(Zg(#V-2ZMEr|DY z$}xHEqGy;Jt6+l~BN%v_V&?7}bB``GA-4Rl$-8kWH<9B#?%+}x8&)SXt|E90# zeK#q~{|W=OMXHiWAUoJmOVUX^p_X=NYYDQVm=V&erdN3OwZk<2&RlgFPFY;?YM$-8 zbrhJR2vCwq5lmD8Rd*sUu6VGxTyPoNlt{YkDG`|Awabo=-VDTCjeHwd*kq6YP}>*A z)ut*L2G9`XhLGB5nu^mwAkY>T%G^)>#&ByG1qT!-LDKS2o) zow{{wWu-OFa}@l|R;zZZ1Huv$|9Qt7*Z8r#+SZKg=TZV&#ZyYx<3$%75o05li;FE z@!0+V(2&p%0O8t4mR>sAB;uuzwo)-2McbkzrT^t|JFr`MyCzz7?>n=(Y&_yIce>f- zv_GLZAGIy0P*c@jA!r!D3yDl5OBsNytkQFj?=T_&+VNnw*U>uYbqwzlA_dA20i|RMrrfaU$)m7L0KE=0J}x$esSm{xjTXd+ z1}wtR-aFOcicigg-}PB88ZdF}@}*l?KL>KC^M>Pf6pmf3SGTRHdk(1Ovg%vJ7qZKQ zIc@M($}1|yqQw6CsG7@R2!8@{7;zXkqEp!qT}#*S3vB**y6dBPj03>wBZvp<_GuGu z4BkXu_#nR(%~{TA=9*4)DeZLepgI66$yrZ|KEqzH8>~;PZ_Y9kABR?Yw3uKvn&&IL z9X~y$c;N5RYucwe<1aYn?DOn;Rg?w?2SL!{x9{VRvf%#`4MdlBq4ZJHL1>_yYilZJ zsqq_0d|rW%WmrH>0>C&86gD_9<>UBO^`Ut0TJx+tClbu0moSu2S!p8j!LN&%ZDh0; z#ZI73%As+Atf7t@0{HX(ZK$9EDkus?boqtgQmU)mTF|xf{(gBRx=Y~pLV^kBYp@s4T**w8`s~!=SSMK&78E;Fnv*IDw}uGg#TM4^YH>z zj^B|je9+Z9@3uj7cheLe5A4eO>hi&`lBk`pl{4b!znftl-lx1>-vusokoILOj>5F& z);CSNhNCui62^+phBv0yV&=O9#s;0^(^h{xkZB}8Oc>aB(mwxA z^dO|VE@#xh$qnP6ci)uAOG5R>l*3GFY|mR5CnTbr`DT~o{{5$qV{r{Jsu%$?;_9La z7goCua+miGLMxRFX5Nk*H=8nD+Ho&6TRnx{V9nf^z1X=hRCuo4>&g_Rj48bO3S|E< zj9?yP)MO}Q*#{GS6c6Ewppc@dQ$H%x0ZqAqe4};WIlc7EH+H?Q+|h1FF8=!Qh7apz z3@Kg$RmpF*&tQmlpho)mFE8vMQ%6h7P|?0=ze61$y)9rM=3x_PADey`OO(e!9^wsz zS3$L0pUhVOSK|B0J@_5%oy8!29!h)Um6l@VQ%U9RH9cL9(@yLUkU}NEnlzd7 zZJtzQdvy1r@CD^U6bWUl%J#2**kA7_;Qb6q&7`uOBNq+SMee^1 zA1#%UlVxvqddMa3B?)ALmRfK~fQlv^`qpp5tYCMpD?=AMME(RD=uZQSpZ&ywoLV9p zNKbgl*b8QlSlLs&wc;ciV*f8iQIL}(7&qxSMBM#}{_dxI-1ns_ODC_Jqs7w*@QFfX z802(B>QJfg6oWeiT_{dlMZZ75loS|=B(`P&#E98Z>pow$y-S07P@vnHFI@zt`M<#D zmBof2oTbAA_aH1bE%Z>^myy%G4c4CJlO5Bw?C#1)|NrGXgbz1}U24EY7O{A&(H(h( zg%7#{7%zk%IUB`QQ`~3PHy-@WywHLHt@C*3^8Thoz~g{*dy0y`%a!X_S*6kAMl9V0 z+nv2eqg?gF3c>8-xLqIbr=^M~T9*Z8zZ_TJ`+vE!mN19PBEPZE2y8!5Xz{H+TGemQ zFRs3a`ofeJ2fLcOP8Dy=jv~#%*+$_OLU+i^c6oTWb}#&La9}(lzKqE*7^nxoQJJu+ znMg+&U&Q;$lQH2i5r-(5Z8;ap$VpNDUI})kP??p3CY`Xc)}bi&4*%R2E}&4(f@i#M zRu6Q(`MP1}J>T*}nMPbvCh$5dkg;w^I^W((dv6hI`2+X;t9llXW1SFcOT^9Qe?@W; zcPS|WF#4$b!Qg9)1gelj_Z+MT3H=oC6SnSu8Q}Z&cFP}-NaY-arSS_jZ*~_JXrvJ(O24QwQ1IlM7p6OdPW_fw#*t!ta_ z&4cf2eAmaZzh!ueN63;ecm#sLS*ksNIy*c$pM7%t69}Y%sP;4abaOW5F@~kgxh8v; z;s!?keVw7#^y@EWK-+>nQZ9d8f(7UxT70AR7sY>zx2ZtsaZ7RWogZaw-N~K`BV_w~ zR{-ea`^;6PH=Us5f0OX~$<~#jZh0tnG_?o(M%3#YoQQR<<>rKv;STNdq0EqdAu-Ec zAH&5|a%r*K3T&_6oAm8#GZhH7V@89FSi<_ll{q=QQ-M*pU*shk%-4&g%%Mh3`hi?u zB$1UkSbFJQ%xL3hr`Lo|{N42@UfwsX8~CLm(?G$G<0EgY0Xe&Ujd__FyRmlB<5mrdSshlP*YuuJJ*yv&{I4_Ydm)Sat)O~9hQx7u((G21Mk3j zM3l@-yfVBdD-EGOqEj(|4)Q)8RxnbPI=PWDWbnA)9n%lw9V*UC>ubEXUl2rnS6_=x zJ#U%4y0}`NoW1NS^x87G+Vi=bEp}B&z~FkI|7u_}SO&i95L_IUs<_OknW=%Hhh{l1 z#h_%6v+iPBg{FZ9!=5Cos;LyO>leZjRQ6sJ@ZN~?UL)yCZJ66}>r2tQ8fz0j>`=J` zoqb<3x8|y-t80m!GbQJsG#q8Qcl#4uWDs(hbII{9-LJIV4(Uhpi83T6#tAF?(5C+# z1OX)TW5Rc)<312@vRZ(f==KqHiv049o6qH{&udo+EN4;<@Oq;lg{yW|H<%&M%RGT0 zGe^HHLruD^2P-~Hb#1dCPl&=VerwGLt!w;WJXk*eSeO9YPru7AtN#nenUkHpgkDhI zUlH;@+ifszu-Ze`6gP|Qmov*&nuDdAErQHHi=8a27|E@5HiE_Zk&pL(Y61RPlc9!^ z;8Si03lVR^{>+Rm8ti^`QL|Qh?~l{1@Z5PxBvmMRT#8zXG0U@2@shl-HSp&FunUkB z9VnkfHryBosdNHr8xQER-zUSjv9S?%FFn|JdNdW=iL@;o}@)tvnl zUs=@PwA4R?aoh#U^LKwMl0Ay<`2dFS1KrJe6g#OeuT8u=NfavR?z1Ow^+&UQ7wJ0l zA!{Tms$&WGhyDZ7ywRpMeu;-p04Ork&IZa=0U9Sl&B3iX+PR25CFSk7Y!yiy>OX}p(W znu{fPxACqn^BgTG0yE@rpmwWUAwzVCxC`cQeAW^U3QVJm9 zll^H?s)7`wwqQ6*@{w~-Vz~5cL!T0X0rYSLccKaSu4>Jvt%>VVVnt&%b>F_6H?%b} z`o!KS&*PjkXp;ZW%O@Z8n=J#C$6dzY;O8bOl%nGJ&!GjYi2#gud@-2E+%FJKe2N_B5#BUc$GNd>X# z|FUjP0)ZgLP0w|800(X5oBvjlA=>E1#OyZ($C?KIo_v-j43aJxSE>@-!qMNz38r`y z-pQ1vCeU#vzfR!_ofI#YnFd-}WDy;QcMp+3&FP+|u)@rfhX_dh@mBbPso=9Fn*|XQVz?f zSFcoK-0S!SR_8y|gIPL?oAz`w2L8HSoK4e!`giT{)jns9PJbfBH|=yl!vJXf>{fxp z{KGRuJj_4(jtp^Xi4?}pjcJ(MbPg=*XSy=DYl)xae4B)~iL1ck-iM8Y(>jkMo&1%VnVH^R;ys%?-KDC) z_65{O4K~WEdW+Z|;*m0Ua2f&a&w{OO!=W*qGPVCn_fv#%DHA+?Gm1$KZCh+KY+v0Y z36Y8G5|faij^N~Ala7sxtJAm3*O;B`5=wsjdT!%@tZm1`qoz3T*t5Q_PE6hk!eRzu zA;d-~2vMZi@smf zh(lf`hPAXH5eRkLBi$<9iRo#tzjK!WG(3`z!toQ6kJ_HSTC4eUnW@3L;X^`9HZMe> zkoNV-eJL1`at^)}J#9WMx>$XH1Q6HvExqR3VLM5Mv$4pG^lFYDNabrmCU9mv=@3-2 zH5%?qTWp&j1u?j3u?uI-8cLQ+y8QV-oaSNER8rPB%+^jqM`xigWje5B!S)E)DdMSi zPP~wOjc+|DreLHRT9>1z=R;t&My}%nYxuNn1w2D1-`38~##UTQD=;vf>7jASc=pJ8 zm~4g)dtqMEU@;>o%B*U{3SYHkyw>$kIB)=5m2Qvu;^oEBg|`n!9EJ=<@wn~$ylH*i zB%!-k#oMt&!&**lBZ#p#MXV;JZ`FG@x>lGc!QdNl^AKGs<$h`p- z#y8fPl&^4bLM(doT8u+J(>z75?E`W2`S~98^q8BY1!J;;m{Jz?iKlqh5U_A`=w*1{ zqt7(K;clY64z)vT@A(rc+MWTU+IJJ32zy2I8(tGASTVWfEXd!{I)ZmLtBSSdw#MR^_7)?TfCf? zI9~?9`>5U(NK;`p4iuw+*W#=_vt>%2={2tq@%G@or>Dp`75E<%WO5=GF^^qcJWTY3 zKTn(HCHguL`L=Yr=JPD*3!F24L(~lb(u7QLDG_hetv%UR0&xTRy0rT1t}=ng3{X^DB2tz z2Sl&ldp#E<2Oa3yqrhipV3vwi*Qxujw5&g+OaDd*t8Z127e_NS^I zb`^B;%2_2NR_=8(vKcSrqtclu+JOBN?o@X;@dTPbx(M8E~3y-BKsh{a0T41Ep~ z=LWrx&$*1VrTz7$hsA%hqY4MqJJl&M&l;1oV|h!N@dtYOTv&p}C1OFT0xJrV%X;<4 zHYh>vR#^B8F?VU|(&Ih>fUMnMyCCWi+|u<3HUc<41L)-OcXqr`KNJl&w$w>#RYP&p5lFbqJ7p~RYD*uesYSoJ<%*C1(ExM!yCb) zzcSes31r^5tyw6zsN~B^FA>T^AmNLF(oyoU)aqTBWMjoBy4PbW8KsDsi8yvbAcQzN zlS=!MlY>wI3UcJ5mX00-2IJu1G#c95*>NT-ukM|cSO^5lB_>+)Z&ce^(Xf|eaS3Gv zC{*e8mWnVlGb}m_UdE0oZ3eu(BgaAC;eUs?ZqkM$TsgfSYyt@L_y)Z$~t%MLxYP zxBEk;M#$pHnBe*uAW!)$7g`Rz|weNItyP86xrU5G^X7H&o-`qv}h5|5F{7H8p$ z32UFDv?qF%o+s))CvjJOy}b;3T?eDz!)K#BzWF=OjggBH{vP!NkE4Hc9w^pCbQ1Sn zB6IAMiXOV7#*?m#(t+M?6iU#OGes+|WI&&MSxuL3lHAV`{K4ijtD zckgrkZ_pq3D%=&P#-oe1EA5?}YK-KIhO#nk4idm|&*<|gb4iz%LHBpyH`li_}+3gM;W^&Y3q=yx?8jl4H-iH{tw`0V#SA3qYZ} zUeWx3yKns=xzY#DThJQQr5qIpRMTw%8JTi_od|5l*YlzDx6HkMY)SQcRzhxhqn zD(-!$#Kgp|t`PCmxIpQONik~Gq-{0i`Fr4~GbVRkj!%owdr>3NIf_I9!>%R!C^frBgw{mg4={Xz?ugW(l(E0=>JR?W-TeAQ!@R$dT1`SCCR zsSUUrL$S%-%BN~=s)2EcuG21B{PoQm=AtT|{Wu~wyVcwgsy2L8pi-CQfHl@#ispt3 zi%DmMTrH)Zo3oYwhWD|vwH_?*1`)Hz}sTW5qF2PMiSkA=+J-epU8(M#dp(cmd4JLydp;4V*E# z_F&uAwvQ;xJ(eJ9&b}(ig33p9?x1b4tKo8^!QnUrufx(Qi{RsoR@&gdnx$)bI6)MZ z*1G>&;0L0NvGRq-wOAndNiyxXg~S;YfGpyOHZlDQ>t5R9=H7RiFFF#TXrM__hb1nk z@_S!H+_Xbgl1?CSG1O@}Er@63t?%511a}WYkhw4JDmI@=OP; z&oA}`KtTP9ZJym-K;V$6NhXYT5T5Ew9;2{!+KVq1OoP!W@moy%9kCg&`j>yYL%!;C zEq~6D2DZf3|Mm0Xmyno+$wy$f*hZ) zu6{Q*GovKt`K|yA20fFQ9cFj-+S#WNRduU9EJ$-Q{W(fc(?LmMCNR#=ly)7P+R&!O*Y;LI{fSUL$tA+ zOR^a?a5Or*qLLmpuLA`&wx3l??J$hJl~_jEK9EB#Fi_o8CKgdQwSD2yq2z7HL8z9T z($-gSwdix6@ZMSe>g6reFRev8RMR|gC)J3L!WGycRK}!LPZ6%AF?J6o@L`5Da*5p& zAru~}Vq%Bx89qG~hEhJNPP#@9<#5?mY?~AkIvIRDTY@h~)Ts3y|Gb>3#uOXnIhia) zOMVr4f?_%nSKda$zce!Ir^JPnJA7n#pasDk47m0O%Iw0sw{Mx84Vo?Q zK3M}wj@~ntG{>?n{0R+yD{%Mq6R4(Z`2)AsQbeW)KMwebla$j+tJ;8x^C}(5h7g;qJR{KY9)8bP`t>&r%Q~58f?5)# ziEY^hox-za(JL9RzWCj2X+WH)ns%Bf>sls|iCi43Q1hxzcAN_E|~T+r-d!M&Kvi3hns(u7mUi zP~@4Zp{BGWw=Yuy+Fl{Bu;;!nR8F^kz?dUtJhf-8ar+WFJf9;-bY5`eE`Bf?Q$ z^-f9T&&c|Pf@gEb=(;4EN)v{fV6kXaBKS%3E8vLAs-o80ZdI?YawXZus^K22*X@mr&X#6fQX8pyGv*Eij7%MH4D5URP42v-kU{V=em20?(oIaLvxIDA?yiBLl*$iyOr`Ys34 zdxvEWUVyAPf%CyUPUm&TZ!ykIXh-F&+wtybh-eC*Yn)%cO8Xj@X7W5Om_e5WN6r>HcQ zVG^J?zH)NK&BTb;ZJu~_$}{3`uMMTgyFbHi4lik^HVZv}7>1^Q>yFD=_-Ip-T{~bU zNTc;s%R;L`qW!)qLR%Z5btSy;>i4hb_aBOFcgA;Jz4Gy}-AhHP%zmkUzu^c-?Tg(~ zqc?jG$$a<5PVY&d$azr|=37v<`31}$pT9eUHPoDT?)7bKP*kdVo}YE9BJ;b*3zI78 zEoY-P9pxW^ZANUwj`>DVcPkiV2f9TbuX{1|8PI#sSVpwu9S%V590i$jlz)7egI|ja zxd{DC7i95qoW)pbc11C1%pbc+C$8G#6PO?!>3}h>RmFImwNrWVb!)Nw^Lq2OD)yov zGBDWo@3rCM%;M2bp<9cauH?{n2?ltW*d%v<_Olrhc}JY%6e>DC3 zE1=zDKaiJr#A?uIr9Q7D3*2;e`Sq>@>MsQh`(4j>G)fyd4Uc9Z>Qc*Zj`vYk?jzHU zs;2Y)(+}&XC=r(<1{WO**;u*?$2ParU z06$XGhjGn5fPcW;vSD;%tzK03_fL#acoaV^bTOx9fcSWAuxgW?4 z>(JZ)4jOQ@jJ7mf%<@Bsn5`J$^WZ>nu+Bc$CS_^X#P#bJbRt zIB45O==*G_IEsi#y?zG0)f@X-#2696j*@F0G1`zs9nC9ro3VjIkXh3N*SLmEWw6Kl z8}WnhhzC-URT_*O6%Ai>D@LC|l9B{or*~`LJcJJ$7L^0E9q^aj^fB{=Oe=Fb1$k8Q zp5*j?-D?q|kmoV?=nDlSrKXP^m5?Trrc+rhdAmUDme3)uH2F zDWrd~-oJ7ptf8@{iXc!KSrnu1f@Nc4b;;bZI9@np(qZGTMT2YOw6s$J4oBN77Za?Y zwGN}oKG4~ftyjuLeL?b;A%WhW53qaX0l~NKHo&8^f~Dd&#{(KVR!#v)@|gR`gY;YCJa#oy|+6lC`t07xllB z*U0~xCzhgOZJv9My=0|n!!b_;$d}%R>5jkDkCe|a1q6i8cwfW~zqBSRW0!i4ZuT9I z6rkJ9>(NIbruSp#42yJ>iVW8!Q5jCIenARK&*Bhyhj-eYjg~(v5hzv^!?BZ-lj5H1 zXn7tqM83waM)3Lv(J_OvzqX~~kMfHu?WV^>4|4-9;^ZWGdM&KF-xx$@6196aV^}se zA^m{P-C>7KPu)%ezpbOQdd#Dg+Um;b*7tEM`I#-;af2}1w{p*iXK%M`$(A;0S&ST{ z8<~2rN_*Nj>)fcy9Ou2l%jR>eUvHd7ueLlN>mR4Nd_|79wmkuHP8unYXR6v%kb>XSR%m z$fpy6(JIK_eND43*lDCf-!~mBDzk@X#LgR8FcfE>%{AWDBFB0OzLr!xZoFo$*~zlerSJ$paR> zQ3H9R`uZ?W?}gfiGLcQXBHH1E`|J%LL>~#XJCl)Io2K==E^Sjp=A1DZp`Xu_wif+y zqG34TM7F)ATKsqTT_Xu5WoWzkdAw$xmY7bCUQHhrHHX%kUwPGO=NFy*|DCHp8x*kZ zF$-&0#rd*D`zEe572;U2vZNH9vNmAC!{=$Ci)X7@GOsS8WQs$Zf>>Sd-P@mcs+0G) z=IQI3iN+>`4NYn5=u8$=??RFjs8fEo3S`E6OgJb*d{h^ zsLObd6$Ba%n(Fmz0D2EC%`7zeC`nJ?aigoXmAeLmaBO4d-^T1463KUGNd7JOc)2b* zZQ=;#^;;{sG)AyTr)%beP9nLdlha?ZVUWH7K>A+x1%O??g?>Ln>6yUldS$oyR_7lL z=S1$4g40DJDv%q)XzbPzi>Q6uSF}&Et_n#I@^|q7dw5+=Jby|I57+JYsy2ldSidM_ zj-ewRBO@rvUUecnr0LTrFyd~%TfSW$MmPCocVs4K)yvR1En2^5EAEP6JNP*^uf2-V zap;TsvY&Tjv2*p-t*J+L-Yi%i9mBsBQrvcldE=$0>yx!*9I<&8%Cf`qL>Ji3SFO1M z$Bu#fN?c&2R%pQw5v|TUN5|PTtj)S)L!%Ja435! zR*6NdQgjtKOnl*^3HNPOBZ^J1e(mOFwlsoEstSDg@|88ix^$ZKe9yC->q{06z4E+$P(1@2#j8}>cO242~VND^eZ z=;-tY@`6f8cXf0kXm+1BlJ4I=W&RzRc(#YbAO0-VAr3UQv~1^D7Zu_h!Yuy?kjowu zex7Y&_#V|!inh=_#OlSh_ni9kG-eC&m`gD>`c~Jw&xd8JDzsLv$(1DJo6^-?;Ti)X zsEGZ!nXPrO`yJGo@A&CgY-zPysJ&r#ad?gZ7T-9Tf%;ppp@3`hN**He%hTR zB`y2L`v&42zB?A+tc&EJJ$4ZZ_TDS5M?b9^M3=m+ID3$VG@n0J=7~PZrcz|hPM*sX_msjnT_E@yKofKDF+#K)kd&j3) z8>>)!<(i1Yp&P;dSp$LiHPuQ_|A1_Xn%k=7Q|6ENu6g&DPL&n7FYa@%BKBe=z%~Mo zkloMfu0-|^`Pew~IemQZD#neHFrqXPz zvaF^?{m)Y<)I`KzfldHL5tHF%-RH%z0AB=ei*r0V^gP|&t#GI!msP9sVHTT&NH;k< zK8=&4Bk`_JUH!3@@i+(&E=^gc%|>j9={ea3oV3L5{oK<-bDIoCV$<{*r@O0x;|a zri<`?;h<}`5YHEya~nzQ&KmkiZQflfml36&r_jzbNb)^~WUY1JGFdZZF3EZYKTxu=CJzcT`<)*p z-i};U<*EJizQqJ^NH*SZOhvUPmW1~-sx`N zT{;dRP=KPfewi=ELbpP%`pMwpqBiesyKYt$M_yUzJG3d7%w&2$Ay+#ofg~Y$W2b6z zGTZ2E>!6UaundUJa3x&UQPL~SKj?SN)Wqw3TxLYQR45DOR)I{yXDz7Vjnz8isZpc1av zE%lgOFr17qV{<;-`xqfW9^^dj@+#;`<*D&^NeE*4D=@9+M9`TUZL z90E$~_XiA3j(_qq?7Ex&-p*TWRdNdr%$lGD31Nsu%4{l;m6zS0UTE%jzw)$)rFkMg zG&|YXE0dpA7a>pVsiqTeKcVRjx__%@S?4_l)5dJuQy@#O)(a4TQwPPc3fFr8X5rws zr|U&p7=(QX$NGz1Rv+ublEVd=%ey!o|NT0Iwz_&a=C{^jZ)`HZomg6?^+=tr)@REV$mApDfuRsOs=J%+J-?0_V%RMf^kvxx zWS~ms5Lw_XyW6W0QP^$p?925yGLBwP)34Yj|L+SX7Z zDy9=?BsP-IP3xP-M^-Ig4a_`D$?hL(He)q=Yof7CBR0mg-I67m_uq}^5;6aBv1 z9r*wvo7S_YztZu;TnC2~$+~;W<_O}wuBFdpac3zP&VB7Lj7JtE5CD15Fi{Nwx0SN? zNnbI@0b(yWrn&@V^!I)Tb*|l?Uzkh(Gb+r6NFP;9v;vt76%abqQ_pL}j&oGt?aQ?; z5(R?ikZ$)$xVB8sN%^Ep{dms(UaxgL)_W(xtg}l7{0uvZqN{?6HBOdTe zf3Glej4-gQ9t^JIe3KhT$pL)et4|&a!oA7N3#Qyp5d4T><+}rTI7m%ClcK)#F{ zBQ{g(@R;b<_)p>m6+*VTtop>*A?Cyzo zVd3qRnlY~@`o7rzz2#29d}Yi1DT-1j-w(eD`}?_`E_4TN1e_Pi&E_n6vB}DASEYVZ zfAUtae!vZDj(+ zqE~C;EEaAhuk4W+69Pe@JYJT#C>v5I4EGN9=C{7D9=^h#_0um^s@wMD_do^74&U38 z4+O|VgHxY{@!K~1Tuq3bOxR?DqM4y?`jDZ+9GvE^wWsX%wT$#R#eQkFi*53in%6l! z1`5%)1=IK)<7atJWYk?9Cw@9qjIWK1OP?>D`|ycDx>$Sbn{i#sjh`P=uQ%JwP!;=uHQEZgY-WNHL3w}$LV^Xsvp|9#Q-Y< z{1x)xOHd+}T;v=qcsw*yM?ZCGbTu5%m!INE_6%x&tr`8h7CX^_Ts1*;HUK_38$?|nwf%G$q*isMFlACD{^(kZQ82@fn<4Yw!@0ofgJ3 z>9v?&b>Ev3Mn7kz=tPh4Ceo8>-mG5-g}5vhf8cXxIB6a)pCo3%uMhra7U zYbGOr0Mvhg=6YL_|Dc6Z9QYS4VxNymh0lIO9vKR$Kx1n%N7>SY9=<;M)rofu$X)m8 z2}PEV99m=!D?wq=6JMMKq>DXQsAdSlDq3IU{?uOnmyWni4Na?vuC1m+^&52MjGNay-cdy+oB5{qPyFasYYHF`aT z>J8GC6!W&dL#BrLpDXd)`kNT{fJ5ywZm=ahgz@{Wg$fI8Tu!N%_>_ZZ7F(3_+houF`b>e+~2uCuGsCX%nCaosQl2EZ6i{GyZr z<5f1oxL4oN{$fV;1`>L^w9J0zy8i6ry@t6IjZh49$Mbypcw@@T(cXU2U@7hVu<@n- zbf(6BOkN}We5-8PLmWr7{>QlU^WgHGv@Gd&-P?KFm5<||_-ZnEn^Edl(q>!dyUkrz z^-gVH0#4eg2KF1b%4+qKLfYkB&mO+|;P^p8i2vCKdps+1sXe~5fEkADkWeiAl1zKI zn~e)ly;X8+yowdb)_Y}-SvX1lCjm-kc4m;i6VkHsq<^!1!*73Kef?IFel4dmZs>Kv zYYp*iwW`{a7ldD5I^>}DhrBMb3WF(wzcKpKkbCv1Db$4PVZt1GHBMN>lBGbl#c{Io z#XfeLbb3(Qp&V^kv=4^WjqgmfGK-6gSB;L0Bmoo7@mb^S{U6|O)f%itND{P2uft0q zJTxRnHhMl|hjJOk0KJ1--4z23+Zf`sIU8~;0FfGop>ffhCLH1K)iPT=y|MOZVoxGK zJ3-5J(lf#*sj_Tr`Q#KaE(2X{J_bgwQ>gvkIFqA&|@2S ze$@qL?%!70jOvV>6NyOAoOBrFXwu-DSl;!HnE$gO?fD82Pmb6uwCkra0qqv`dY_oQ zc%Wj?xOAAM(&ao+=h9`M>aP`N@r33Mz7oGS6;8V>xn(7|vhP!Ae=nq^l|tCs@A)b- z46WX)Cc^JJO(bmYTIjoY^Np;&!@uI^n&{H3Bl)Rr`CjkVO|b1j$I7Xe*A7_8-s3D! z^?SZQ?I*EIsZ{xIW*BQKy*a-14B} z5HCp>WYFn>COI~k_HK~rLe%QW%5IIicG(!$pI8pV0GzhK^2>|?H@XnP!`-8^4EceT zP>V6ur0_c+rpISd=jhW|f;gLM;Br{ac9jyEe#giQEYkKo1nbRWdyunNWyBp}@I~Tq zBQ;kYmE}j<~kzsA% z2;6HZ`2sSzp%fq>XQ})=u6OL5d{`+hEc-M~t7)mPWjb}@Qm-?^LB<4@)Fm~xR?cFp zxSjIDNe?QQp;m?OTn$=OBC35_k%(WWBU8(E1&lo)HJr9@$DUimhP;}c43;?}U4#|P zIs%5#4YTUMzh;2^_tnxVA+-0TKM6`!KUFn!UKuIPJ(boxUT9LBn{3naS>VRIT3rfw zoqAb@*838W&~)}ZAw>?F@b{4nr*48oE4#v6`h3fS#-wzN`=g_yi$5Oo*VAZTs zYiPwtmI90o1)0D4<)z~JV+jkVzeT@|VnYo3^VFfgcpg)|ouE$rbm5W6j%^z~TLcx1 ztqx-`Z|cKAPe+FinbFhp&VlL%B;Q)QwQy(2Y72GMiG%h~^Vgp$t)=1lOoLqI!4nnz zgF6>dby|>Bn^>ifoO?;6`h*;WbEj*MSYw8f$*MJUw!#42IieKbmcnK)Cn_SkVILG6|SP? zjWE}r%^XWvxX!KY0sBH3svECjNGLw^L5WaV0r&`*!Ts|B4tFmHHam zqI3KW4#NgHta=4*u&+&3oi(NIXh?r@j?rb{lXa$}t9$LW z9k(&e)vey89+y|`K-V5*Oxot`>As-A)*k9Nss)x|X3mtg?N#ET_uR$d)6PRSFakn9 z;Z_p#s^q=4Cd9=eOCXMgOB|Fv@^Mp0tRVC2a4-E)gR|@PYI{$7T}Et*RI)Wz`s;zb z+Tdchyjguj(qdY*jP4NUG31ES;yycjhSSCeY^JO5)7)JJ%a~`y$g2H96?oP}*ptVa zCeOhu#&amHQI;|@b>+t+6LK^Z72mpTGotc9Skc(fT8V?OYokoy$7#Hh_|%vz2@T5{ z*`~inb+6C1adL*6tz2{=;c|e)lU`BR^q^)G0nVRG#kDZUB2*tpmKz{-T`DpI#?a>Ld>3-8sGI40`b!F>p z$;}^M8mrd0l;D;f;Z-0|$(P2Df&sdJ+|yCd*HoHkrxDNR?+l|0NVUVO?%3-?0YeJ> z9s*&y2$*x$80y_u*PyG+s1{zjo#Sx1GHq9sf-Plx$p~04BBJJSEUym!<3=&b5(NkK zz43ceS&`it(DL8QDpj1Z@V`e0bm&!rue3_G&F2W z%)akqy`LIpxys>Bib9zgMx^Bl-F?S#7DkS?WfzYhaPC$LRe z+fxCFKba)m-4-W7x?mHL(D~oLb7B5^uBAR(a=R^{t6R#u-AA9;Qd3KpO zHuQ3B26r#c%nW11K`#C+*^YC%?++g2DFvZ4X3Y@D!Vfj-y@z{zF1Ry z!i7ug1WGy4fbNTkeO(ZIu*0n=+0TEU?^*cAk0KE*a6+}@)~pUB1{!+hjzE$Rl~5AV zpcM)O{rRT}(WOUoow7UQ-5@fwN9HZHVp+EOd$i$@NG6!(7EB4P+6xR@!EDdKp~#nz zHYN0)Eq}a;N=K?u(Xatisl7g1jds4QT7fCHVo*;UoVsLGx$Nj985tFmwzg}#yL)|o%Af(g@)0%G z2*6Ro6^6kOJ$Xh=&Kz}UaNF}sv0j@lfnZkpsh!3wBYd8bQj#YHS8UT4SCpN<7})z7 zx45{`QHSeLvJC^bmn3llg00z_!qT7alX4mBhfn&8s-LvuMB%wjpVCs2-^VPdK!2!^ zS6LkXDT~?oGb1K4n%&szoLDfsGp-w}%zcbm*YfZEnomTv^W=}4*ne<#{ZxqsM3M%p z1&6kRWyDBAS_YgR@NNSppt~Xe3QHMgM0z5jMJXJ+_5FX7gfxO>OgT1_<{+fE9H0!9g_lFn?kl35zECgx#I}bnfP3=?7xF>t&?0h<%F+2JqQDaVwsk(79_0uKlP8`MT zOnRM1HjK1{Q2QlvJcFI2W!9;qAn+kFoi`$e85SBdg6wdfnBxFZHm5irX!Inw1S3Pr zaxJmT?vUYQow+Ge%OG}fYLNV`y;vv?o3ip7BL#ml`Gr_;HK&5quYo)17Gty)?oSzX1>Ea&`U zkr)MZyLU%WV@D-Fs6yU^MxRneLe@E-6z8}Y1YM3TRSzB3vsG^XS+X|2SEHwKr+-v0 zQUQf5{nO%L`F%A!U8F;XAiA{GaFS75Oo_*4YQ$ZLtcgPA;&gb)PEB&; zZBZf8+G->zVu12D*OxA_*C%$brN>oR@!dml_E6F?YCY(XW7Ez`P>Rm_1s9a^jlAij z(VuX4AxOz9Ry|vrI}<#VQ7h;&BL-#FG_3@9$*P8(yHUsy`XW{t98OslsPP2rvG4Dk zceaF>q~DBYHG=LO3vRmXdO6Y?n>>D~DaMGi83PZHD@}@3)bR{APc{ae1AOj(b;24f zW1x8Ttd$fN9y>2mIG;%$rGz3SCnhH3i+a(X)bWC-DgbMax@U8DAbE=^hPg8p=AqKM zb5ErqyYp>N7^YuF*U4PU!Y6BxJ2<~H9)r=g|2j+P zeGyBYpG{5O+P3L#R$gdRKtM1TWe);@V(d{JkyS!chlfQ!YzjxlD^s#n)7)w&MT8_{ zTa^O4*Y{WvRSSyqpCM)z!GzXr!#{peCm^l#RnaMKXsZn@v_3m3HY1OqPN(7bAJa^UjNmZz3)sO zwDUzV_Yju#sgrdVG1Ak^s?oh?0$FqGDw9&S#LvmFsF7`(INXwDm15mXsB)&90V16YbnEdYge3LT@nY;?E@x$j*b`?2#i4iDt6V3v)ut^;{_=O;^Ds;Jkg zs?7TONxD&eKcrtL@v@%g@$hBwF%kBwLPE=y8XpKYT!{_F2hV#@#$m!jZ$jhu?kmmx6_BQ!?6SJnKYrInWCL zy6!XKfj*74C0yOxbvPV%yE}KcgHRH9u4bs_&9!84i?gBX-=U^x~dAiW#0p(G}*0-2He&sq0S4C0)&{y}~o9FZwy`;Xn z8|%U$ls{IjdrWyjYW3?$PT%(Z08e02NJxr|y4lqPJ9}^X7Y)z(^uUOi>uOX4l>2n~ z5j_vV^BuM$1yv`MvQ{d|txBAnoQJQYnNw7R9XopAnC+jHI1YCLAQjMtD!D!F@77l_ zIgV+QXkA+i*cKY@3bGveraC(JOZ7W(>2#nfmF8MSZLQBzU&zdxGeoV@OQ^W#gtg+-w; zH#}vzeW$3nu6JE(B8-W$Vw>JzOw9AG$ca8C&~FCC>U z3K8BeY`Bi;PLQy7#=qt}mYBi}Dw@MNV+Rjxd2i2&(A<^RrIUkZzQp8fc2R^VJ?Jn! zJGu84Zny2{8RGxBd{(ee;?!P^MWraS>=Rki>Wpt;Qf|M(6VhtOB)9m4G-)Uhj39v!9HG&kr zRBN$nor!kry_V}1GPVU>-pMimCY&UDx%ZV8+ljl@uiv}*47W%YwOZ2xAnNa1-sET% z=#fP+!?uP2-za3L8Gu?oi3+oW2cb)G?4W_5y`Zh{E(u2+b=0KEhEwrf63>dP-l~50 z`8$)`aM=fK#$|BvEZt@3n^HxhJQQr|?Os$+kYE6b)K+oLXX8KP&DS~{(J?K|JWv~# z@*M71>IH%LG|I*Vo9=^HU}V?djsfo9+n9*SMfF(q#V99&`-*MQe0}|eS>X|T%}aR) zK^@cJN>YJl`-w*6zbyD#Ow#qHuYasrkr=;F7HK;oR079XILdA?a*nA;!AkC7Y`z_L z;nHYaJt0TdD}*Xy@gJj`xV4P;hkzkih2_fbU$#cIIt+pND!A17R^ivrDcQCj ze+Q&Qd}DY1J@*+gGsGy4ugug!oeZM64gk7zY^>&+66B>H^4*b{(O?ke7CreG5{Yu` zdD(#HOpNE$`qsS))yT(utL2NlmOaahoPW8R`GUU*YOY&pFTU#?boeVmWf;ar(EX_p znB-u0b7!uVQT$-7G- z$oj4~;(4VmP&ULZ9G@*N-s#`YTCgTqS_97qS+Gl07HA*dxe|Zpe_|Q~)rRSbF)v%o zC2dlY_fXadKG!BX7;W{QH&8{rPQ5rLi9TzHet~?rZlULEj|c zA%n*WIz#*BA6VJrp3vPL)HRx4moe+1YbR8j%CEJ4uN>ZQ zfJJ8euGhV=ia7ZQFGMTn(dK_sMZaQGl~Y+1xPO%&3`PL<;6ocaw)Xb+`CbTjx@3RR zuuYuB4u$n(vBk_LYh?r2ZXw78I&qmu4xPHU7&DM@Ukm@6ieh#1m6%f6C~s05oNPJr&)Qm>^PgjXQWC#u z;9lSeiyJgRtkWx{?kM?^qB^}**d`tK&SZk)dD(b;UpVJ0h$W42pa9)R!y8qWYi2nD<2(0;kV?r&!qfTMHn zU*nk2{H6JnUnyJP13yuJr~brq2~TrAho1MpqVd_f>w@lEp7e&WCh|&kBkB0_KP-gW+D&Z0%e~Pj(%{$py9BaA; zkB#Ivn-hXDy&b;}UXLlQZ~Lj*nk+VbiVwKK%{V(-l5_X(Yhu80p z=mUfyef!Sxp-Maa7#{Dl^=mWi{xQI;u!6hwx9h&Kf9SeJ3R?c8J;Oq8!G`Emk(j>K<1{n8t` zPzAd}97lgF8eZ$>lPXPjv%S53&Ja4WiWSux*FZsFZs`jfXX|gN&#TjpR~*ZQ(CQjS zRxqjKKW8C~{uvTPqdl?zT!}wPZmSUb&`SwUP0()k z=QpJM3{XU??$i6H|5BW6!3YR{ZaCqa9%z~K1I>DtcE(>hv~yq>l#f)ppUckGk8^xVp{Iy~=$-7|E?);JvVV zc)c<8GR32m^x2d3Vt>N<7ea=wOlRMd$Q@mU)|HlezkZ!?>oLFoOrmHCDGFw|rID7v zNGX$CXM<9SzZJd@3DzxxF@=H=hOb_ksGQd@wr>uo3FAdJACt7fp+7$G=s(EPP_|hJ z%-t@&5VGX2!-L^0@xD`Wm+Fb)_mN128)@WG+kdON#a~@**}7N}!B=qcmLCsENZZHY z1Ov&t8qnW=i_7Zkm0SO9khrTX!q;?%9g%;6PUft*s{2N5Np>?6_vQuiH;`_ zanupjzxy9c=p;`6p}Tx;Y83j=%!EfzsQb|{QWAi! zT^@c_G+H}(w~Wx4IbRbjAcIx~B?a_FZ(gtI9M~}e^INi}cV#SWQEsD!F-q|tR@xL& zIWc87n!Z-r<78J`KZGUFg~qB!*XLOghP<`M_l&e20`izxIO({f!oz4b_`+s|;|gvA zEq{467lJixH69;ezCxMP?eU$_^qYQ0?|`BZSAnzwaf5;Bw*lMl*o`{dT^Bw#OQ8c2 zVkmgnHAK{Vq!zz!zBCzoU}R8}dgpbj`^mVp*f#QcoV=)@5`{+blk zocy-kS9HmK8MmRNjQ%i-4{-8wVc90_`t-MUMPo>?W+DDyM{xNV=G<^ zAPmDVKwUu0Zdm7a_R5~sT%A0;IBLC_ z(r1egEKfD3zKI(xc3GS}og3^ZqKeRqcBs+-ylIH#Y4fGU=dIt!|LU0{|}CG@u&Qi~H~cfA5*BJNY}QAb)Zk_Rn{5ijv&!;Jx|=7D+x z{kUo+uIo$=6UM?Lxot`5?~h)-TQlk)zT9r-$wy$O+`bhsnEd+(xfT(JFNK^kyWaB) z-Osz`KFc_1eDK-&(FqknOiT!=oZ}CnP&DYX-T7u`Z``2E$RiY{SG~rQiGha4SzEwD z8_2AH4o4J}W!b)>0VYx9RADegJ@K1uH+LDVaPau~bKBK@vW=9j_aDa3TeiO6u;z~> z%EyL~UOtApyG-!8cbK20y)iS00X@3*UY%8Uz=y$=PXGq1&lf5pG9Pe$ zd1NR3e1(TFQZI0!ru4Hq-<@hZn}Flt0iF{lo5Ejyo6>P1eV`-tix7RS27$GepnsI= z1-MzC4sPuGO}o;yGeaxw$)k`$kccs9#V90_OA*q>$;k~i&63M_25m6PF1XquVZXL} zz5g6JJ! zLQ)U&7n{tM9^e3|2aacQpy41hN*`AV+2eZ~0dw-5w#<5XyR_-^#xd0ND#TT0TJ=#j zd{6MSkI!e>#+jTPc2=YL<-MCgd<$#YbJFWQbk~EH`qQSrI6s29MYleCQFDzpfMrWu zPy3I^W7ngK#Cf_z1mnLtfB%Um@cO0i+7$ajFg45-MhuPYfQ0Juol|5UceVqEa(IG! zoplM4KCuCEwyx)CK>Cjm|L*jFB;@VVVcU1MFc%R;^j4E8m4<(88Kf_hvo}v5|1cO+ z?UK5bv{_N{1fKK=px@fyIgl|uIb;HBn(-~CXI;`Yj)fizqoj3N-+tNLZ!Ej`&cd3> zNy~-LEM&4^=FEaEDsb0I5VB{d%J6}l7cd=tOQLboP(T^2I~|IC1@qOav%o5MVLVD{?P^xfGE}(A1(mqVG|H`fM@>q z47$PNmGs=12A6Z_BT zara$9r}KnH&o44u4DW|%W>A!b5nmBDG6|JxGnLeO~PGn=n^dj##PW4MrL>Bz3*D2-Vh=h+V-M^z(6aD6e~y~2_4%-Q6a)0h=Y0kX!$n!3*F*}8UXo!GsMlT}jcu|thOO(A+PW11sT#UUTV1!-#!dgAT$?K2TuHVR&4*YDXpiuF`EgDQ`ajGrVFOYdBi4IPaYNvoe;| zR0jHoN~WBHsWVzYy8ziCV|~Nms*Zr>3bLFiSV%JJeom<Znu2oc-wcCFUH~QQDOnmdljBtpf+)a+se8D*?VMy zfYZVV3CW#jXPpIbuUb#fE_r!twtzZ)ToUV6LG(FK>v!a((-v^)M@yF6FFj znsA^rL4E^8i~HLd7%phKjUTr*3znk<*^Df}xv5YQw0F{{&Q91i1@`l(=CgN|FRsS7m z4cl4VMK(w9X8XzQn}w?@)&cbnlsC64;jn0mbTC7Bvz^zKzVkvgTl=Y6>mMn>P#I`X zY+&w=5fdxkSs&+7@86u+xJAB85NB*iRVI;^-{1Y*>2Rm-e3auN;0Clx=6H{?YW_U* zuh+Vj>VPPVJ>1ybhQb};>fk4Gk}gqhyle}A;-XS;=54p6oXMvRBqWkLEo5`)sNHJiE2kDA?}m+m$0J+S=9XeJTrzp86Kc&J+OReEknuyy_afm&XSW?GqZ;v}OCr}geqG;*$uQJ6SK=lc`!04R zl){xoDfr@fzG)lO>xWcfYFN@9WpPy8pbdJfo8WESsmC*U2*u5tfdOT_`}}Axl06bx zFdrZ}m1~S0;=ZQ^kF>)(2qrp{O|R@KK%s%g2kV=gR)So?aMrIj%s=#cA1A=dUut_k zV55!sJc!KHP9Pth*^0kyJXEy%Adj;$GD*-sb6klnuCmDRu0-vnnb?U=j9V(DISD7Hj(v z74vn)Lp-vx;X^BMztfRkyEjlpPmA4ipS_)#1!(@35ruouH=|C1*ek`pI!u~kYPX~n ziwXsF|JTaB_$7Gpt;5#DK3pG}qosiEF{TLaQU_;IK_-7%3t5zsS&i5$d0Jp41ba=& z3>gw_pqvev3v3@SJ`UZI#f-c1sN4 zzueZPla4_-EL{7{6ls)e^!Ve|mvy!vjwV!|U+%cVrF6v@^S%Yp=pHq2g4*5^6EHc7PmRR~ zI7w*ZRqI%=niR5apf_Ra5o82eD=Npkmkk~M(zF5=Q7&*OH)o}$oou*Ksc_nQ8X zr|W=fYHPY!QBffj!3GjRdJ_G)=|ZH}P<=`XU3v!rLk~R^X(CO!5D7}} zRf_b^e~|b6EL@A_f}3;ioik@<&z?O__B2x1uC~;oZWH;xAU+96?28DdP-9Zb7x$l^~B(rlVH zn&W6njc!4^M+NyyR}b*WkZU(0I28c-)ucr1=@;M1YiVlLl$bMr{Drwy@xA0YTKUNX zxCvX3Rb6dgjh!)nXrx!Y&>i1S;BDFgZu58~ztMIYoic}RH2i?q`}|um%0#M|_g=gt z6}joTcxm{S+lZ51&j#4$kc|Qdc|`4~onXx8>qwk4Cs*1{vOC*PI^X@1?BAZT;55{=^Ge#e8W0x6q8U~Y|dnQ{X>oFxl^9f z?{d}p@3T2dPo9`rUofrs}3!S1}~o7cC2i zjdr$1`N;@#@Q-i&KIL|)%9(B3FnRT5*>ZK!GNE92MZF*%vGk1gy}tt%YdvKrsofQFH!S_T@9UMNbP>tCp6}WYn+!+( zWx^(l!M|5lo+zxbgSB6t`uFU@F{x_0EDtRxDoLe`f{SGyQk_QgJb}>gIV?+$>z*1y zk#KV`{MIx&X0F*4)>fjCO+NyZ9a6`4!NlGcEMHQcF_7DMeL-mPx_B6Eyn@s3cW0Vx zZ)1&0is{9@q~OHC63&u|ae|73=_6b%@AXOHN0Y39C7k_8sc;}gx{nHC7; zot+)?(kA3HI3gw%dv~y_({Xul%Wc2%!;&si`&^~TD0&VEf{dcH45e|%Y{wrI7H0|D zmvy^hSqG^PAFc#2LpZ(?Z%M0mn(>^)h|Jz z$;T9jx#Fo8_3(kf-JowKK?3HMR-ds${ zVunJU=ECuvot@=3)r0xAob+ivYxHoxZGO<1`~ia}25PXdP8vOgOt_^=w`d2MiWFV! zX3^LWKkju2TouSO_!cVbJz-&xs8a!@g%2*{Iyd=^0(Z!~|H+Tu&|zp`}^5zbe(fAvLSZ zK?&h%GW8d~hAq=!b}3nDJ`x_E6i$7yz`UPP@@a3{L+I}O4J_t$@>8a3VVkV|h&Cf? zX*jq2{)lgT@t??!l-K=JSsO}GqnJEM)1z?4Zy-qM)k+ScNUM<=DkEZA=)&DZ(4N-ZuX6b_FUaR)G&}s6?`;$sbuC5szHIR&kG@s)an1#Y z{e19z`d@r~k+bD8c}R|qeR*7JV&c8K5>>wgw8XqD9odz*H_6}pec;+^+8uF{=aT%RuSF}b$xf3J`|S2Ymu!%o ziSrKSi@KY;3-h{XVcuH;iz(vrzo|@J3K7=&FQQ9-%v!;upr5wpDou3wHpnVx{V&^Y zYe{I_ffaUS2HJ;`Io5fM{;=(xVga&{d@`9CAQVfwZ^k{>sAy@Osn!t}SvVc{>xSO7 z#s_klU0oeq*Wa5hT$weVb>R6xdppmOyFjnnYficJN}grE6f^CGT2AwLAwiGP-G!f3 zQ=3MA)Tf48qOAYks_+GF)obt8UVwHIvDKERuUnt~h%;W63+QNWwf-0(dL(QeaAiZX z8R`BT`SdM+xn){k{L|K&oQC^*;8JB268DGp;c)W&kyoRld>0r}D$nXW<7BT=%$b6k zTQ;UDX-yH&`@b!cwK*a0?~#N~pj&mTrr2-9H1K%~Oei2zYAkw-aVqdlP234c%mg5N zg)J1lp|Zvdf7kbx@L|q><^A)XH}yGvED$^LMb4I;)cUA57GgFbI@0hv3pxpzK`P1K z)Eg?lY_!fP6BhmDS$4*gikUkTpXf8uof)v}9#aqh4r{#7RONAUWR+*|)7h_!=k1cU zG^7>mg;hj187u8(oeHR>i}701d;HN}LH!5zpHusiMOQ&1>q*V2DS->qHeW?kK|FPG z2px&^+SM(=f@e?BcCI_D?r7OYFfR*Zk+v*5|GlIDee_+zr(SlkYzo}tvoAX^l zV{f$n2BNRF>{84N&Y2G{3si9Fh9U2ggwgy%6IUt_I-Z-BWWO_Av zw8TbG!JzwPR678^gvuVJ-!P-CObTh?{mnl$y0aSeRm|zn3(rYUtg`m+^5)+$Tit~1J1GaC-?Pbi#?Zk-fJ%edMZD7;q_dfQxon65V+lWCiVeFCkvGr;u%PMkfdUwRL>bMQ7;s3OFJ1qA#^CAGFTS^HD$v+yKJrbSk*5B8+TOe0-L=|TXoeZp**OzFc0~T+6qE+Sbu5SPR z?&+B&#VVT=Z_P_{i|L!BlCfQR*LWY%deL(0COW0|Rg`n$j|0cUdoe%Cthy)H|y?V`YR@a%2 z_`+VI6CF~_-48emG&mXt&ECMtlI35{#BJTGTP+;z4iH|B_qleUK%%)qI4ocZlkLSZN_Agm2cj?gXOGCdCo!LREP7 zMTPV|TFUNNd2!2_zxPj~6|N@V^rQsx)b7C>ii=%+(&ZF4#8?>ZZ|HXRUqB_M4y|kJ zxQ7p=H3t5Z?MQUoN1TmKCs|vxFtZh zz38v?O(CP>oyjWMo1R-oW(&*<3>JR6PmZ_iZDM8}_v2Fzvk_tr9TNZ5pR~>c8X)y0 zh>}>XaKXW=u&Dy&m~y$fOI+N)5_=RVcU-L}#BG|uC#9^v7BDgE*&vq(bDEFC*)$U8 z9NWkXLxbw}Hz!qx#&$&O5&7O(ssjt=6Fpv7Ro%N+#Tr%v2ZcF@CRSwC9@rG9#)Sr?-QEu*5*trf6%y3EqMN6#dh8xp7nA1{P%4#6_^T-xJ3EWpqoNGg8Nk@-5r7c@)o5< zoD__I|LzM1ch5%p>uy;?Fuw%U z&Su+{m$zrV64fm-HDq=-HV! z7$ijVA`H(kpZsfVf$92WTG64^&JK93ykyhc;gz0ucxt{iA*+S`tF5(iIp9sYdiDGc zDRWTmiW!x{M&T7$}oInf)gO9QMWJT>Da`o%3ShvKhOl#sA`Z^Om@E#0{CFhw-WuK2XgsaCoMpsKA9-b>;@0 zuD&^!-?nzf?Y_)!p``!bF-0ho1s&((r~Wi;48Psj*a5MM*;W19vJ~S8QK#Y+N+(V?|G=^ zME|s4{@@&Bqy}ATt(lNo{vGxbDUisFPGPV{ofl@%FD0?1^Q%8IA`8~QufClA_vpDa zRA#q9s&rVwdHy8sNvc~9!C183969C~);#w3IL1Byk+)M3VQw~^nGuQ;>)Eh3p0kpd zf-lOZPhXUD{k>S`M&A!Hr56q5^Wt1ZaX$c&|CP-(!Z3f!2rQZ0=>Tb zLi3Zn)J?&KwU(C5rLLzUuja3FK9UboTuL(@Cwdt%)Z zme#H*K>BTYb(Kci0*BsRGepGL4e!m27|<0z=L~0MR4S{(3&wXx8IA1#59+&qo$m(-a# zNH+Mp`rvD`UEaXb44P<(*IACy8r(Qys+unq5eCdw4xFGW^BHgzZHV>AN?uoJGWyF>IWc|XdD7Aicp3s=BpE%3W@fIU}q{^qmsl z*6QuJ+h%7Q%T_PrluK@#{pW>joS?edD+W;l@WCWDUe`2N$bS`x?R$nd?@as!>1& z3=ZUkG%LKQP*#XRCb{;K&XTWD&zIg8T^+B<*U0|SI)bVbxPC@ads}K49N$Ix$m?)E zd~UA=SqwD__@zyV@09Nu(q8p9{9t;!)EYm@sW6O^Zo)xC?!j2w`f8|?hCTDZErGAFGC4pPKJB&uiU9hmX<9LvTs^~dD#!j2FQQ=-m-}BDKgbt}mQH;F zz4E3OmN?B$zj!#@C%#$>wu~RTZ!EvVas2`cH)nw>n?rMlKJCza#r@I^L1vOK2<~+w zUvQ9MN3HUR%2?hEFj8BzE_|C3zJ+@KAXvwa&QFp8Zm7{>O84A9jMVm~KGDE`rmx{n zfqIbxz24afzM|ZBUj~p=a;j1C94?6!?+cNwcAQW|j3o}pOT-~~9!&nqN8WIeM2|Ks zP)pa9m(QX_l+>H=`G)7o82&~h*|g-@np^0wQN%kg-tSF|64EF=4FCU_d4{?Vni2K@ z&^PFy8lf|uS*8a11*vx>BbZX=uok)aEPPgU7GBHz=f};y+v-k?Y%}j3#&V%M^YJW1 z_GKrL`zlMkS4ugVjj*uhK*StkU`a?{eRS6h9A4Pg2eT z)0ghlaCOQ9OpUYfIhk~CabB&K2fNVIV&lCUSuDK^^k||s9lnb>v@Qa1sMlM8)bz9XpSHiU*r`FTpwcb zK$2o#I-Ke%zl%F+*_k77l1VOKTm23$>}oVg_fK|z`Kx9mXD1P79ys?NP=_mL5mtAO zgl8LGG*N`BeS-BwnZ}rVjYI76Xy(u@iW>`3EYj>j1MdtzB3J?^wepq^8XQI1Hhz=A z6?k0vkhmQO)Ul6{P=&LLOZ+doXH2-tOF{}o=~`Lp3oQYXf;Cq<{|oXa zY|F}tC@mGqWJUypBStniNg8gU1RnQeT0m(oNMY2{d<;6OTsaF3%(kC|RpInYL=X?AkMk;iG{s zO^RE;KQYOH!Hp<&BcmL(IKraFwZ`vsr_h~_yYp4$S`u3?BSpA;-h;KE^v)7T8=D^F zvwr{0L&9pxpv=Yb{5RQA$!3wzGh6qNlU8-Dn*&@;wBjd(#d3dxJWJPNFt$ICAixY{ znam8G>wylztfaxsCtz|0T3(@ZQIuE}sTmmU-ZZ@IoJ(K=t(6$OR?4==7+Hq!_4E?X z_<*>+%{Oi&`rm*`z^UakUyH6YuOHxS`1SQaP)L|xl{)-NP?6EtM!?N2`YQ2rw0Lb% zn{LBLW@?@JKZ5WRn0qHnKz;^8Qw*J4dA`FbLw->6o?(z^*}V0%I+8zAzEih1E&>xE z2l#DTNDd$~ltKhkKJHx^PkI19ySKL+s-&!F)ua!Qew>(p|G5x>uL(RobjCQrme)sp zHa5&~fkdT5Q&5VDcpopn!8joW`XMe!{=;Ml8d2yj{;Sq=Ttm{`4oECIJVhVRxW*(g z&+*+sdvR|+m408NlI{)PW{6kON@sOz6BDgl4Z>T$aB&#wm=!5nBz_VOrQvA)L=DjF zMJKz?z-arPfVlqR#uVpJ55>8eWS3E^m{&A7@PQ>YWe$x5ML)y&AR0&_L(NEsXHY)tdhhF>Ki$5PrKatL1OVVSd7S^)^yH(+7|z-(*QgS^ewJ3;xMFl>2;=t@ zv-l@1;SnOk%te)DT%kIM816UuR|u}Kr)e{D3Xe12#3)NTrIYf7H}#~5rkLN}@F?oz zpJaVoT2_+Q$0uPw?$E9;?CM>$f8_PQEV%WK&J0u$uAA95sReeXkut#tBdr^(hJ9hV z_t~kA!g=@t^wA_|&n!bwHHR*qTs>N>N}1V2zUX>4m&U%V=MT>R@&k^>KuviB3P+Rv z-uDel3$v7yPS}f-xz;CqT&1jmrJOo(CnK;SUdJ83sph*qd?1Mn@hUKN1^~U;Rjpp% zJ*unbXDvzd60Ca-c;j4#)=~gMFPk;xdOl5h^1tNum$R} zF*7MLNuj+q^Urk;27*HW9p#zs__Gg(Pm6>u8cKF<{Knp1(?C-~AOW&;GOE;ka-v{^ z1WuWU;=NL4?|Q1Xnmq5J@l(wMx-0iC8YW}{XQ%Ik9u3rKJURzKphEaS1C*+23|fC$ zx&W`1f9o0dTZgie8{%zqDq&}@XS{RQ>wzY1C@;s;8WL;@0{}_MtlvGzewH2Gpa^s? zj}JXey(C0$Hhy2uz*BM%kq{0e99}+0Krh`;&1Izqc)h%H$?`86D5d_cUD&t|1TiX7 z`IVNsYJt+jiplE_MTp|RTB$B8Xa?}XXg5WCpfNL3c^S9&{N5f&mBhne;{w0J zRXL&7D-lb7_9%0UX1^60-yd0?K1yvgHFA3OBXH;dw747;%pNd?@1_{6K9L|;%2#v@ z&XS6*wW>W)Aj!IlIGch)l0?>B+KDulj;pe+%gN#lz!Q-!4i&t?1OdL5X|&*xrVkKl z+DZt@g!td)YoV@N<+&BK{z59sJpKSPtPp9Evx=^$s`|y*!2Wf;!r>JEd*YSnl^YQT zKq9@Lf2*w|MeTh8WEtOZ)*Kz{1mWWwsDNz!akJ%y#}y@<03zG>8fUN7cX=HDL#DbC z&MIf-$oo83#1zueiR6GLC}vLm5$mObf}Kc8hG_zc^2IM?0RUiatU z0BbHSMMnjdx~%g0dTp3NtAKh+D3H4cnkD&XE=~S!m><+A{{yBtCaziOx_zV%JPN;M z)%}$h05hzC!q)t#begK8cr_%-8#k7!%u*no$Jx;r)p7?~LZr*UMW=rY#@T(?OD77WhRmFBSr+cx3(fHo4#X30q-XzxV5FO;`t^zX0tePSxzq#95(4EN%JLjNfr8 zw)v^NO!5bzv#pgBem?6BErO+=JZ-G91nPeXvTB6l z_V&&O%%K9!5&0tu>zWep!j8Lf86gVjbv^1Xk;1sG(NX;@LSomWp&^y_5}=}i(^6oI zo&#wI{>c>>iYvTk{HRx1j?Pb7b-zv`UJ+2QB0jmhUx09&X6P#`l{P8ypGQ_~D-B{U zl>(fdErbgny1^;b5|vr@Bu??svU3MrbLZD`*7ZHyWQuXnUcMi^A@52Wr3Ux+|D2Zg z4I~Pc4^G+$BWN*^GCVQ=lXd`xFO&5e#6Cp6K(3W8BZ@M7!SQio7ZSwp{YK^Tb}6)= zPz(JOWdxYI>oD_2(3|JSocJ$EelRtt!Lh=1}T0f-*Xg=bnob>bwcK{^H8&jT*Px#fn?=K698BNVA6AJ zCm=3f_p?TfU%Vc(oW0qjbWV-{SViNc5Vc>!q zR`W3A{?`zXlg-}Lb%`~DeHc8h8{6wLIuZqN%JH$mK2X0r^Is(S>98L2(%XD@)hUYa z%5%X3H>$h?v{PrJPHSB8|YqbO15J$Q(Yuc)V6Yv78S$hVL`&)vcn%`8lw< zEz<|1MqUEm9;_Nhv%feQb4g98dX1*1&-0|SZ;QOnwcje?)cp`OR~7U@H?05gHEAri zvmGgV?LMG{${$pLf43 zES-0o{YJi3OiTc%F~PkDzeUGzsSfHS(48FyT2c9hg{vzoukSxDePqXJ z6GW`M9yOzjNiHQb!UOq`617y*=BYmYm}kf2iNf&Bg7m1l#Un33XK@Bh1B(PF5nP)| zE`Hs!XU7wTQxmyasMWhY~0vAyuY*19I)vHNjsjPCk&TpP8oHX|dWUHz79AarbKh^Ckb;5k!^ z_L4GU;J58<=NK$7x19@6dmLc6DsId^uxsmpwHj8m#dR*r!9$AWol?qd#hQXt$WNxK zF&b5UMshy09b>n)lRHWTdV>7PSII9Q*wk)4;ioFb7-gojKF>(QUl8&K7Is@b3JVEm z#guTC5-Ez++#cU%NMyb5WTvM8aJRUO&1)hRFBW9>WyaV-5$CrTUkr`C9O{DpJ*B>I zJPS;ZQ*6oTl|^aBw16y`NQdHt#Fr$2vFm?;?q+~&UVnSZFx`|Cr~?KhUiHmK5X;Ri&L**-Ud3ASfe`8L;y*8N;sM4Q)t9W?DlN6~3PdChDn9YIbUrM0%HBjK zg<6&!R(js_bOK{@Lij)g*Wuz^?kOP~al2n!}u)UL6sYS|5h0(?5pQH;KU)L=>aJ9G5 zaN+IW3&&iPj59@K5xO=wuY7GYsVOZ*;p~!S;8CV>wME^v>{kwXufO}^@+U@3-e*$y z2a>t%jj{2=P-BQi#gN^-F#n7{jx}|4#nlHtHUP*y4fsdm+li#Y#$dDG-@4GGcy=ot z<^l=%g*Koxk(_KrslOoyL@|?^ z&}JEOxwaN?A_)SfS_OsX$Nl*8;DhD+6LX;uJ|PFJ@BME`9qOt)7<&ENj3mrp;K>-_ zzW-}_I=)Ds`j%g^pXBj(49N8lgM$O&OF2QGwv2N@N{d}yf8dDK0<4E8@G<|R9tV`~ zuUpc4RfAE)`QUeRb7+uJkj$#7kr1rJFz{7GwplwCYw(GoXYNHBM-S zb?xyl^Lp66-npb$n(NV*=~B;dJzGgo`ZNl5x*AN=5!j40qJ#)FB*g0`_8BET?$M$y zg*^RfE1+smeycR@Ik!5Cymchm`%p8X@`JG<;?PR*?%l~ks&LSRR&P5t4Rz^k*3G%r zFkO07jBZyIPm+!p-W5Fz^6XN|M8N+yh6 z@C;VBRd#mSNx%}CI;Z}yDn)k07HSvkHj6YhVT(`k!TV6>0JZzQ7}?~3PW7zCSkXtN zq7m-4A2|A>sqR&)RQ-{NCk{<#`cpw(hCDAnavD1FG~2n=HN3cHmpc#UkU`gLUZt>B zIY3Z2RK0y+AJQBV6NS}g>sa4j9!M4UJREPReVB{@+-s79n<(CH{S!`NoG|QZhs`X zQ8;a%TJ=nnHW{UfzZQ0DJJ?HaNvzweWX&^NG*cl6b8`!dKm}l`++LaiD1be%Z=(za zXAg`(fM6`d_?aTSCGHd#;p(tNk4IEHFYhOdc0u#$4(nyl9E-3J(jDmz2NO&**sSvZ zXj@=0ZOU1l!>c`ItJzMa_O`bw!JW%aX5x8Pf%n#CmK{dKf)|n~Tfb@lj9Iq;i&6V#pjR ztYvpCzTB?%dX`0i6gJj$t}^xF8hSZpLh+0a;2M1i$nbhqR6mE;ZC^9?(8J}nZNRQS z!#Sx&IW>l(B<(HaVob^6Rg*aa4xA{?YjX51Dn+}UH1fcD)2`&+DQ?<3@)fh(a?$j> zt066`Nioyy`z<+q9TtWm4h#ffFr}O{5gNbE-7lb;kwXicy3=JoE5qnQ#JiVYuKE4P z!m<4~xYgKL9{b~&x^hIkS|BD^P=MSWrgGr*G0MofK6eGEe2z4N7RZ#nAHTmEw=S>R zr!`;6fw0_%zf3v_4yqNgrOe4--|;vOToiqp{n;kp%Rq*$;&TWss~I+`gh-(pV+z-Z z$)tLI*YI95$XT^@hUh{rE8Jyo$h(?GNnv=E@vj*rv8c*#xrwPqNynfKzrhn|sBVBJ zx52?d%L-#B?b?L=n@)>K^Rfj@1;Q%Mx*{5;a3>?D_kZzO`S;h&S_;hY8fq$!q<(~d+c4)OpDM)N%dq1A1|nQm(Ra*P$v514PS`8 zZn}mTHM*2@E^oM!$FW&nlqZfR+|&%KF;D7=9dhx$?JU~3oSe=I?b%=u?~d9xpZYbR zy%iV{*r(#4*3X-1>_pzZpL9ltv;P~jQ1P9~Abn|WPy}5fOLt2o;*_)gT_p>^J3j&A zlDMIg6xMGxS4R?G4jP^HyX)C*rFVtgD3xFh z9A>y)-I#{iLKGKWJN*48l0)CNtxvd%rANo+hv(=`5}saQbL9C)nl_humN;+lV$Ujb z-QQmW)sgRH&x{pgOmUUXE%_l?^#}89Nc}sghY}RUC-yeH@ygP<5P3w*au(X$rCvn- z{tYe@c`{E?e-5X-KA18x*eBHaKtpGvUR<}}YSk-?LMJCwwnmwT}>bUFyLDi;w zj2!0k5#FEx$HyPu`G^p%jcU)kt0QvVd%bZ-;#IZthS~T*LdLhsg+s(^(HAR@T9 zkA&@{9D{)+qods{jU)RnNIFQ;DDSO$#8T*2JL3?4kNvmNTGY(~SIV?RrRgo4X8LIO z%nr7@{=D*b$gt^njMNzl(SZ{0JZ!%U^Gr}~sVYvkW|1R6JK6<~ng{~qAt|`Q!nqHENp(|y%*LBokr_d3|Zlg%+%zAuJ8k~>eQ3Nx#GEM^e^2ceXlf9 zp2ncIw!1#lBM?axvhnr>I3$u0igguQg2e^b^6CcZP`7e-EU2(Rqvp^tSeb)>Pj?2E z7j?bGVmKYeA-zTeeNy3=+}<%b+~3Q6rk}u9qY4OOXX#ei1jue@n1uuy{Z(_z;kW5oYTHFcZ=QA!1IKBfjqH4c7l|6 z>{WVJOCeFPg3*6#nXz`UdQ5*8a_gE7AD@l$X9h73(7)YlT@e>w6&O=qUjF3ClZpx# zkn@9KbcX7M6||rlHAn{ozaU z#xJLtslmd7pGMf9bW|55@A;=>1$;v;)v;qipt3Sn?``a$?!#kHonrD!tGcwdej|D8 zV1U8<&@O^$g_WdZYFLU{+e{QXkaGX$e_e}y9*;w9@sm=GU5m$WZQZD@*dT5V z&`Wr_9dH;xKy-qkGycj8fS}Oy`6UDIgGd!|wm>zMjd%}u9iW3Fz&J(bA2rhFpcW3P z4i04P3GyZT$j)P5&sTad>AZHd_FWlXaH$PwK1!-5LqUOyqgh&2x60ns)6?^`Mp{~3 z{j6za=)q%95|B&C91s!`aziQJ^P5Pnuiuyo6R)(NStn)iipvCz3@`2TSP?H!)GBy$g=RlBqCPSG4C*3o#lM zTL@-NnS1{+KbcdJIBWxe5E8d5a*N&Y zZkj@DIp$jk_h-)o4pr*asYs(Lt&p`MIKd;D&zi7R`PCamMT?0dtI*8yg;k zP94u;dyiN874ByAg1Le90tQ0uFL9NoCF{73!W`$d2_Eq(P%@lq4J*{I9Rz)4q#~TB zO3QI_P5N~nXuHTcP2&j5fdV}XjXUo?&e6Zd$p9#i@1-2kfmv=H%*WKJu%1Cf+#32v zGgsETSB^WUhcaqeROrory+NTA*yow%e;^ zLEK&Gzc1k}KW}1aDr^GuWQtxtKW0`}=sCu4bEjl!z(cwhY0jfS#DD%=F4#p`PqR$E z9o;u#-HLO3n2yKe(^)~jJ8>a3M>w>jj{6Oc#%NhpPf5Y|urF^&F}td|EQ#JeGmWIo1=r2C zR*93@!n%#FfdbFn35l{H@$lj5oet;f(&A#kV|&9pG@tJjXH)0Aq`qy22E?2CvF?&i zx+%0IUHRt`LFnU5MZ%ArBLOA-qWF0-jIq#S;^6X42pcw@COisjffrGwKCP|*Lgxw` zhr=ItrYP9@#}=$3CSdc6>1%M7;#^IYibFZ9|%)vcZ^j~&-Dc&tS(a-ECm2Q5nFH^+!} zq$2|V+ocD88dHz=Qgen1$148}R@80vNE~g_y1R>lGRtj#8fkjzf7OocoO+o>M0PKlKqziT|QYh}i+Km{Tn zr7Xh!iVf%*XT1hoC4vK)m(Dt@004)L;hkF6YjDiBCFkm?Ke9gHILnIiTA#KEH(zEA z1T!=am)pcO33baRkC~tl%5bebrKW+xdgrZ0JSZa8A1~GK+ng-7ZiG#ocb`jkSv}2e zd}-__o-qsGkSN+tHOf4rI8#7+@u-)lyxE?XZ51HB=Dl0ET6e%xpkM2}F^d~JUUmT> zkhs_3>&Lgd%m}r$Bj6h~P(THgb&1GJ#SBe#Y*vU{k!?Sa?yIAo;3Nh{`fJH4J~}8w zB-t61)ZgIlt!O@gUTYlxnFaks-D+ooW0F$?#Kz_2Wpe*#5K-`s`dm{6mbTVm3J>V6Xh3FB#vghcgejE|FlXt99-b62eh73 zvh&#uk<_e@y06+`=C=mMK07UK7ak3Y8tk<%1GvHjvE4u_0rXJ`0MsD5J6DUjuvB(+ z;W!hK9LvrcF)bU85sHx}S~1uqetU41A6i#DYXZbCP=4&p4UGp?UQnW$TYX@P2yHcn zQkHUg%+EG|K7sSDys3kCklzD8&Yp z`I9qHhR-dW66@I@fC(rZ`u-pPG!?+ujf;;DE+#DexCC#BI;9zsMQVb`5Yzza{Gd>% zDmA5?YGojEdin>>L`d(OCnKX?if}+A_4G`R2eWkXYB7)GGQlwU#r~yQ{rVAW0NP6& zPPmgZhyywIiSF*H{blX~@W|@^v?O-1=a-Q&ux~~GulMAY^zv`muV3i(jZ|;2hqr)- z1dkf@4OEOBx46PgGJ*IAeOSws>b;67VQvNfJ0ZimVA>CW(mN=jmiR&NeEVsN6+W!P zoSX*UY2;nVY%@{RxPeSi&H{1h#3>}1?FA`ahec!!1`a#>qA$VyaAr=0O4adi) z3U+Io3sV!eyVGrwVf`KJbw9lW%FhXN(28qV?&cCtLicXq3cJ0pnSeeMn>h*2TVh4! z2p~ho0LwV5?vN-R<$-LQOw4<JikZ((y%xXx}0ubfp{ zPE;Xm9v>Zm*J*RIZBxSeG~@x`5Z|N1>vDSQQ48G^;;^c^^*sH%Co?p?kY31n|0fi3 zWL;|eYAv{C!Kb=guX277F?W_|6(#9{-iDKz`osGW&!eUKZI1f&8!iXsi9+@ETZ{dt zt=fRgXEzK~lq?du&C~&_?3c-7>#|1>@Cxpz{z!MOrfTIHAX2yD^ld_9JtSVp<8Zj; z-@knfcY(uBJ)9PUx}6+>nC$q?$b&8M33hVjX5byYUUA*ODp|l+c;MClRhF9n#7UK+ zw|BQq%=M3;W6xme80Wp+n%@4>$H`Ro9Q*d*C*^B@J?S{7*n)rvLb&p&Pbr>qo-Da4ZRN_RllP4le#0|4p{}|eS3JC z9pQ&nUu7k>uF|D~R4!>_Aaprs)#K#kM4u&0jNcG9dkn+-o-EL9fJXgAWeSN_W+WPn3qteoPi^Bt{;u&#vt7e(4{gLt#gkgMT>`P*o ziYS!<{ie&Wk2=_8Y#z_>0lvOK>t#!~i0j&`B$C%*orl#7B!lzaEQTkOv^FiI#9g3R zZar4#DJE8p!Y@uV`gGVfl=9W zF{)*3!WgS2zwrJ>j}ORwS#x_dmyWjFi3z?ZQVu~l{=(HAwdJ_Vk4|-+{5C%Rok|6U-k7bX zpJB(9^m{IAOe2pC+w6AK&7xv8V;l#pAaHJNwD#!efZp4q2vE*DW?C5-JeF{%KXR}y zot;0LnqnvA)0`f&Lmb&9YF~o(hFg|`PXP<@TU2tD!>_z*`HJ?LD779`;n7U$iS*R7 z!rE=*6ytYUjdtw)Zz>!;AYW#!sZwLZ3hd;ShIucl`;(K4?az-!^+j`(^3-ld?rMzF ztLBW;LnXkkI^tsW_uCYBj;6t|3N85sbBTkUUEVHRgVnE8(Ul!|8?a)RZ*oO6%F5uk z-%eKcAFHIj6NR6mlPlF;N6W(D=Kk`dy9921oj1`-Q{caUemPj>X$p{93e4V=tfgmp zY-ZR{4@Mt+9IDmbF(_eF`3z-0M?GCgMnVEHmxD{55^laD^&rvWj(<<$e-xag|5hWM ze;yxQuuIo2p@~i@6k`Cr$0Q^rEIO*EluWIA>}bNZUo&&3xYp}`fu=`GfE3j!7*6s! z;cv?H4*||x^7_>mu~USDz9qzsOF5ZeM1-E@8vO6oKU$=p9+T9>b2f(-iOO~51yO}S z=9%Ozw=;+7d>_{<a zb0q)7-hoLt?gWAF=LSj!Rxl54u>sdOwa@$C`db<~s;5{|eK@1n)icHEj~CYe%_6{+(peXlg*Ow82?1U%I&L$Wr-qACu-$;G`-2|`GEL%VKq9i7{_WP zSJnLOxA!R`yWAufhh}7M=GSHXAh%SoaQbjfklkwedJZ1JE~t~~PIWi)1O+8e7M^3XRNmo1=mU&nLxn}1ooV_`ekX8$aia53Uv9A3oY8~(4XYmbLA>*LS1 zZ+SQAHZBz=X=}!9yhWN2ifE_IGz?opawm!?p)$3L#x==W8kuNN7*-9@QWV1yVi~vE zFzzaacE!t{b7pwk&->@hd7g8Azu))w`~JS?d7gR3NqXOCr?#QNh0A_zE+Cdd*s^*eH%#FK@jPM}*oY{*zo~3uoI5e(- zU^L4=Q;6s{yK)Ux=J6@&R1Is{h$|!Y^)6)uR>>gsMK!B$)D_KSH#Pvuz8Q}y1+zr_ zaMW#nY8tSX#rcWyg%&QCOt&}qvkF+RqM)8w9~=2hAx;lp+{PERXw}LfuJMenoczH* z!vv8Y$HCk}&~HY+Mscm09^-X_t9-TPorw?pGai|3YcF}ih=PptbT3-6lb;wwa+#IS zR_HhLpXr63N@xeOthZ(8+ZxD=tp=o`PnA7TjLs^wEU^MsuRtFZN76c!2^W|Ff~E*= zSe~(_Y(&oUpDrFL5PZYT$Z4baFT+-fj?{&QbyZ0NMrGz*D1BE3Eoa4S+O!E7)2XMU zBS(nJ)yQa>CB1@l=y{KKjS`l(Ck!&6zLTi$Ae$Hkz5<_2ET+$;OSU8_!ZY^Wk$I*O8 zh`UGMU1_AQh1|?Mzp>&!N`$EW3{_lKR#qPfh>3>M#Ow4=6IITaLJx7_au5H=7q#T? zA4waI#U0p!{#rpxC&-&bmA$z{>|idA+fO8|YSz{DaN>^V!^20}OkQ$+PT<23T`Kr0 za0jsZF+z^GWHn1`rqD4SB9yly^sJs{W@i7%I~&Zl?HmQyQ$Q#&Cuttnj?Ixl-e9TQ z#mhe+mv11fq`;hFUY&IYul2NR%3TR&@yygoPLIQdH}|5p56y3;KOih_ z>Khsu;Co~AjJ2*MLsdgwULHmbbG4xrQ_@ITjNZC`wv4>{ghq=r)!s~M<#ESTsR4`eF$#doDM8>WR4_}i|hD| z$F@(Dg}VaTnz@H<`^?sf9l2)ruiy{Yht?K1P4b8Oq4A>jiSS-B{og6kFyk=S^c*vD znN_P$_f;B&xQDBtz~}2C+!MaUT>?rWDWX{CWQ`Gcl=r6k^k<6?;6V`17$`K$f|_;1XMy%v@!LSb^i<&eMsT*t_j`io z#si*QGi z{{=#$7WyEj-1)*;4iO z{8!74V7UutKur|i{TYa5yzDJ2iq{X3#g+}g6;6)3dlrDwjierHBd}6nB#aC4Xvy_z z+~p;g;jM!9#L^tI{-FmHaY6ODpERip$k{-oU@{Lc=6MhYS6RZIa!?a!oWoT1H z=@81N+at7=0@mFB$v!Z~DGwop^qbA26f}u`k(L^b3*V}qASWz%?4|||5JjM* zdf0(l02y)ZtzpQuoH6l9p)$8O$KYlNC=3dc zrsA?w0rA|g$JvfCXh8>4Q&Tinw2$GejC0cl7`>^eoScu=?mjp8vDII7=pnl0BHg|W!dWWJO_fxGbGxX`F@XDPSXJwiFeW3ndO4F+5_oStf!PLP;i&m!1L`0{2&P_1 zf?u~l{xqN8s$kJ))`u{SSs*4A0}&tk>j(0FcnzPw^oeVsFJI zd}uJE<>ly0^2_|yctdD1#}xFu?NpPXdV5rcDzj)p&NO0mXW%S`U2~_+pI|$Mu4r0Q z!(t_nc+;WnMlVG$$F!5j?H_U{wI|aV&^^qSdOUuD73b!0=&%n6`Cnx5d z*tI%z)~Zqo=`jzZX1ln#O!8`}syzMd0&Qc`;Q!JI5<#lwd7j@cV?>2CS>ZUe-nK^gsfK6CVxLy7S z_`Y)H+p&vFvXQfPkk+&t|0!+wl;O8RkV4RuT4iV~^TjlEJPz0V3Wx;J=jkz+ASzAj ziAiL-EQ))fDPp0Xe}o2ZKEV`Dkw~G6$2xl6%-kVY$~QnRk_a0~-7L19$C?lTFqYtD zYD($`ND||qf>A9g+K?321}YL-u35Jj3#vmbPWKGxUq^u`eYT&93O&zd#A+KA`=^9? zTLdKx5MIE1?0jQNJx##6C^6X%Bu4ZAkf?;iH|sSP6v1no>FSp<7*RBEa9IaZR-|^E zRIzVHkNtgvqJg2!-bEi*`OFwdrIV81&+#r>=U04RAczEM!{iC&=p(20euyu1IR`Vb zth2P=BYk!tAokG0(XbG%ze<6#uNo8lwBG}~zh;jTFxC;6?Qa*4BzY>P_c4CPrM}J;zPF$LMB$eu?(y>W9{v5E zHQe}NMcIJntQBo;$l$w*Wt?rh@;uIc*RYIZeZTDy5SP!9q>4HnLrE*5H&A@Xk9D(- zfzvbq9l2+D=<}NIise(?R{Fia^yMCaG3K&>pP8B|UrcJTU<1Kp;5sa#HFL$bB6Mq&Bk=Ph!h3aZnwKCDI*7cK#A`33-33JlgNq!l(JFgw#TfiFV(!>r-|8daKY}&Y_gOZp>El-Y4yleHuQGcIHH(FRC@Z#Pn?^g_fAMN znWd@iOp_{^g2Z4OB!*~gS$UQ@O41p9- zgy2IU>NpY@5XhHsIuuCIYsvrHnG!u6e6A30?bgq!wcSxM!OMG6dmW1vMjNWe15{^RxF`x8UNiZZX6$K9V+h6}p% zKTi-*v~LIl!Z#j$S5#CyU{;axHy5J+nLfo4ZHfjPf4Lv=iLjY+kR*-^L)&fi%|0eKnY13WekA%H)k+ zG7r1sQH}D)Hj*4yBESs9^64>ISy>_?A`|;G&xduMdF;;BRfrF6es8G&!u?>xytcfy z#`H-^v_h-Yu-PNFNi!ha^k=hYe39T$(@P-RmJZiy*A%R65oO1Wnc{Qvl%-bRGpjS^ zP$2z{kT5fAdiBg9DXnYwaN1#q1H>b+q+cl8+uMd$D!LhhX;CxJ?yrA5-^K(-_JMdl zyRla3=g*(n@q#-kfvy_Y?qOgUG983e_5!EIG#*u{kM8ZT{kb&q_*E*k=|>c(JW_*L zvq|0|p9?uTIT;ZwVCBSjT4(T{vG-0BibO6$J5#Um5Dqj;o7U>hUuyVSUl zZKEoilG<>Aa|lw~gyJ(3Mi`>s*DykrLB1vvGd!3rM@4@>=>>S@eRujw74Lo7%Uvs^ zmYMkV{m_lZpdv>8{8NT61&zQ<7&*=$*&C|9Y1G`+!f`aPDQ@{{LD61|RK4=kX?>>y zE`s1tq}Y^6qNq*p+7PB?~|3 zM5nFlcShchAl65*-NVDfIXTo~tZ4q9B$3ieH_B0jVkDV`@%(AJ+8ZK92^}VVWO%LKT|g62sgdn(ryKkrBheU zss$z6`N8TUMFIn!}UOs@mKqSUN|7Q#I>GT&<{ zUIphF_DYhf*u_a@pdkzKr7BAfRC&V9aMY@H*1^L~JmV8M-WNZ|$9b?`%BX!+w|$&7 zZ1~N&+F-h0;m!Cy zc{^uPgAM6vy;!47gHL&FCwN@_+IP;2q=-c$aCCC&-%Gb=XJ<#=WuI(I-6C5W8XAgl zg7(xG4mCCi@2B#A$;Ay3i0SF&@_yytm9bP#5Xc658vEMYUXQCFf88&yi}uSMYj`r0 zn37Drg*NaaxQKSzUxYBy!e5>)*$#C1iP1W3bp${)PVB)&3Yv)QeN3Rqmcpy`(v|h% zD!^@Thk<>ym=`N)MLZ+wZqDRA@<5ErzLZcn?aHX}Nsk?R8{(rN>MV8RR32x{J^fU> zLG?t5h2MmPQo+F3c>RHKBY8-MguYJ0J39_8O5kyyYaX zZ`hj7jnQaBrI&hgys3e3XFj6}!vtvw?!(0P#_l&iXG1Fb(s8vXvBjbGaHWxl6-fwwV`x?!L`e zzqEvPQ>CSvo13fg(8pYpFYz!>Nq3q2x62!VHuX&?``lbA!|k%HVj^+zRPP##5u?_k zz(hIwRBRKeH9HE$^;5E^Skez!VKq0aV&{*{YYfzsEi4$)Z(ZKfD0kM5UT05!Fl9=D zTfCKe{RO&yL@rHWfMBBMulv@1E1p*k{7T2urbXA^DCcy_XR>BwB1KMAkpE6D;d=G2ceR*rFAr8VwR6XWZBjb=3XKXABn??}@G-H$WbNUGd9-{6#2A@a2pPyE{1+B)JZD`)!*iB{~L*FK?b&_ioGU});8gyECv3_6FJ zY>x~P{X!N4ZXUUw%m3c%Be91-tZQo2OJAo_#;!AK@sANxoorAOiEIXJEG6G8T%?t- zX)Nu>EVphGy?=qWjkLmhhpPh7y*vb#wchjf4)gDqTr93x<)rlW^{X|*yPwy>bjmDh zxf(Q&ZaU6F2TuM%OK*-h*CvXM>-C1k#H*2Vhh&eh!kwhnl}hZ2#=K}6Z^xz7Kg8td zKJ9@LOUoljm&>2)XkGpKs8;DD?ti(;_lFkvE{I^P4klp&l-)4qWt+=)@CNyql|yE# zBH_CUt^0j+U~OpA86is6Y6GfCa&4g-k#2ALJWj`}0`Y6EeXq}tWL7SS*Zz$}rc_B> z5C`MV3|YzkI@|BuEboi@nCo7#(48Pa6&;Yv0=n*)E>7M^27b z(I`(Xg$^?C&TR{~#rZAMRIj2r0j8F>oRcF#OL>Me9*D`@xJZm%!w>J+4kY;O+J z#AA$e64{Oi$k+bJhIg_F(X;7J8}II5C!30*23FUfw)RSw zzV@+pijTAlH%(EXl~=!h`22c+TMOm)c3a*x>yw(cHlr`E9p>vDMSRMn)(K-W*fBTH zL!uk=1d--G>1KfYcIUvH{<3#&F1!M7vf<)E{{`M?-VyQjrwXDm*~FgO{hZcT2HgRp zb^Fo0_S%NCkwv3Kr|0T>Ek|)hwwXmYf0)Iij74Z7YITU!EhKuscp7ItLRythJgRkH z;{bWtr>AX2H~oc$h-c+iWY4-cj45tATyEEH{ig|rG(M2CUhi;RBP$VA#vwlA-N7`Z3ZASD98R3ihTtHDx2?`#r=Ku;96ju(6l> zriF*?mE|`&n%;h?&{BIy{OfY9=71Yv0`l;L>z)f;C5fV02cuRW_cnAaf_IP~8g4e+ zsTL07L-Cp?w9&mIz$#$Y(8rUy8rE`aVbrkli#}OGeBJY*!TMF<{%7N7i?_xEAN`gv zpJ197y6vY|>F|^=AkB@q>t%h1u z;&Y(fN&f96kaOU8LSUQ8e~UXlP|_J78S2W^G!(!oA{W+v4R3$nz*tpVOXQTvLrF<_ zzyu+a%6rSLx4-Z$AgAG|m^(++;#@ttz1ioazhr3MT(x+mvZF$*>~))~TbE>>xaoIr zt_walt#&Dquq79|P+Xjm4E=^Tn@uWGd#z_i*K_ZQZcm-=_!rSuEUC(e6{2MF37kSU zkCxszwjR~y5sY;!tOm5f6C}0q@GiEz0v3=58rFM;`HSXl>Z=AuH_3Hc;o>0 zdpxmox&ZG~a6>=F>;bgVA9#0mFwJ^8zZZB%TWJv0KzQTXemT`>e9JR8zCDt`Jv%yF zMqkhq_+Iy7l0AMm9|Srv0)>OwvAw_tdreHP+|lORK3obKkwcsWw!F36)nAI19+>nw zEq6K@s_!S|%#QIBnqZaFII_>)k5AaIk0P28HGu@F>>SzO#k<@eGxnzOy>1^k9A4?? zlA@MrdLH#z8{PJHYbq^1Ep0Y*M?SALK%4WZAH+veUu$b?tE<&Yr`k?tt*?D=%p7+E z1CEpftO*enhUQKi;2Ftmnz6fLVci??O4B15v>#E50pyNN)0*oHyYJ9RO>nW)jsM*pkRk1J(2)p$lbEInd(MXfy{ zLUT{&?})I$T?qd*sXJix0XJFI^Y3CI&8%+e6u?JKGWjo#N%3fYKI*+Y*w~q6P#4qq zTKae-^UIXoL-Y6usu%$p2T6G|V6?IOH)}pr_Q>6qy_;=pYg0+^Q4_Soiy!J?=J4Z;EVs-rFpppAm{_{`Y6=74p<8 zSi}UyqH(^p_Rut+&4;QX=r~A|mjx!n$s6#Y7aMc3J#a`eHY3O@SfA_1&+{yLsP! z-+9a*(e$Rz@L%9`AscusTUuJ`;HgE=gT1mjQGB+ybO*wT8{o4>td&vNKu}(@f#xu{ z-6f$os6iZdtuNIOwvs~If2pX3%hcKTDqq?Zap~j}-CpsE;C{ykY1N;~ZBI@=X4xFU z_Qjb3h*p;9^<>{TIxe*O3h2?L!Yxlb$o_mRbc-elOHo)|8_ufJi$w%VS&;QH=lQ+8 zI^AVuy+sDo9s37RsP44qb1wNR9G{_Iz>R5(h`5PPU0yZq)zV$3g@w&%)c^Y^ftV+) zkPes=kAvl2yE@^(bq;L!^z<}{vz{sI8yd#C2L~JuGHXoT%|?)c@PjOzwv=t&?MglW z;P%wx`mKQYBs?x6_5qrrRN)s3~MWqRPV} z=YIZd0g8!E>-XcLJ6jLwpI@J|hCYlDrKk!$Cf2Z;k;=Vss7J&Ye{&AjdYjKvIJ|jtyJIcxyZ`GRB`Y)y?zy-4 z{PsP05Ev5A6t9-ZGd>j#`l+dV5c9*F zl$1Y7FE4m5jCe(b#7K{O5bw>{w;RFI>d{)XG2em|&|`fURVmx_S9(CV7n*v{sAhit z+O$%h=ay62ri&E-RE(IXa|=Tjhau0zZ;7MzYY^(DP^Bsq=@*5chh| zg|1DP>-*Vl0I+vO9P;$Wb2(Q9_)@ZlctR%`3PY`#_RwV2jLp2V?`Qhu<6|{GV!CdD zfp^4D`>cOti+H{fBcZ54C3NUXc8|!_!H{tT_w1WXXe4G>7r@)gX~l#yb8aJFF#50D?W0!GI(s z`0=XqqsTE2)2%)UJHTq?pe_ICgnd|6aqggQh*f-rH$W+dhMT@ zkR2)Rq9uc=2FyVZ!_W78a}smyEJ|K9sO=NJE3v*zRfAs2hLHo5TWY3(!hNT7KS71P7~&}{Rb_WseZY9k2G&^D$v6B+;l z$|xESmr8b6s(Tl+ z9e7q8I7H)jw=OOoU}0yNIo;E6q^ioLjUJjSmnK2BB>DD9zR- zB98`XPxSV2W-iN;1zo^E(!WLaTAtwF^oF97?)}_!rOe-MDzYWzH2D0QZE!t}KTCO0 zwyCL!V)yZm9x4xrC3bi3P4DK+HSe{-)8w5-lPQNLW%3(QG11+y*Z(@g>j@5h|4YP*L zrhtpXRbaI$%gZg1i5{X>;m@(LvH2YGb(8{aYG0uJZzApZaw%ob+9&aIT4nhz;%%6w ziRpnLnyz&;0Yuh3{boNYt-X9kp={9|YnZp_?&)BNFn9WUATsi6EI-F*;jwz{?9M7Y zZ6)nV-w)Oyyle_SRMnd&nYRfq-D2-|OkQjh;LND}^ei70j>aP8ta1;yn;#9lU9#ZG zYdxKN*?7IV#kPI@esR|JV}%+&{==J3~E#eu5?UpPi zfau(Xmrfld%0nZiljSUv?l-#)OPnMzQWlv-mb!4$Z+`@ZmhMI`{B|}C8S!4u^IPf; zTgA6Jluogc#6-jXycL4iWDm^z>69=pST*58z4#LR^m6QvPHy0Vh{`xSMsW*E4;i>` zm9$&Jl(;)h-?*EOxjmxj*Du@jE4Q24YHDig>x*cH^Sv*RSqYwN8NGHui0*B8OV+lw zjy2Nn$8fco;BkVun6kghB4n>f3_ak0(!>`k2>BWyQ6YmfTTbNdS4;{wyI%rHD!F$=u&o(#3(Um&qI z6AJQ1p3e=C)15EJa8bmDTk0OzOLjf*!Yuy&(ViGmWS9r;%wF^9*ufFYIeAN-|LN>{ zULYsD#!^?nLTLSpUMyKf+LFv@{lLX;7B5J7L@kWfAXY?UX-Bljzm|Y!3Y~RQT z?$w}0?d&-<^XAku1*u`Hq+KC_u-1I!wM09f4JyBDvo}PjRh8KIB0pEac2`brZ!cgD zna(aQR+V{tT?Ig@$d*v8PEYwmd$DJdC+;Ab@+7dSTgRf-mo6{0qlr_?3&b7m&J%bl3)2}%%ow}46h%KXsrtmp1+ z-kneu*JYp^CEK=v&r*uxygyn8VU6QNJ%^$3FWJ3AL+#7FB@uiv@l%j1CwDtmLzITn z1e(tC(<;0--o{6{ClY7w_9Q>_CGtQboW6rBNn{1x&Xj~+#p}ooncCTH(P)?G=`g9| z-x0Jm^ih@G;`uhkHVDnoCL_x`ecdnRWs{u70iid0mnT_>$|VDRUp41=3@*$FBa}R3 zdBjTnD_63$X(g`uG=X+0LPQpy^{s;jqBI|0#6BuM`yge{y7R%aIo6^3@v_uc#)UNo zU!c}JLZ{*$)((aJEK2jjn7|)?XKUM3;yZ=0O)-7u=GC4IbEMO9|+q~9xQB-6L!a0zLZe{8%!?>U2KjCfbpfq7% zX!sniEA1Dj@lhwidU`P6fSpj&`AWi znTZuWLv7M8Wp%Z#RJ(Gi#rq;wK+CQ!#Uk+SG@e1mhMytQgt>;T&jLKCD&;w3Nq<@C z>0#!o;9H)bE|_ca;8B?TkVH}7-o|g!vzJ1jlsL6@jVhpA#_irmm%~|5VpT(E91hTl zHOwWq@W{5n12Z`(qfy(Ee$r&@>}=(ybCp$g+cfXZmiDm+vibOlA+cpj*pb&9nO^S2^;1W%AZ-y)U*|4 z4WyJ^BX{fi&@s#@e;l)6GPjlG&d$vI0+7z0+DjZnr$L@;I@HXOI z*xm-n8k>mSyh2<+euJZ!`DgU}k_W5MiD<=?Xb6i%-q;rO8f(X{kN)pTj=pG>9^C7) z`BlwUwJjWNtD`l_U|=u`?|j#P@2#P)?5LndQM-}$qQ6T zSdPcT@i3Gft8<}8(=!l%B_#K}==<>&&-3Qn)n7f@ul}v3x{;;#^i&7?_CvQOv$;rY&c$1$_*y8zh;zje|ai_1W>{AUU?_!&~M9)c( z9OsTWe}7$(RW3E^upB$lNY1)P9cwH&e!`VbwN3pTu9P8mnHKu*4%rg#(&gkb68ZPo z71f@_@Hh;8XR#V$U_~#sU`3*nHGE?cf_7(yIf)@XuZM!qo1HY`8}t2z15|(SXjr{} zBmOyfsB@5$F&UJKA31GvZ{(s**s`=gC35S-#SbFhx?4PvGz@H4Z=AF-u;T;SFJN~- zd`w$ehEH(CbNlYgSo@0St0Zb_KJ0we{ynb&`CAnEzZn5#%%&c#C)4@|MdXv~M3+h% zcYVSig2gg$R&O{p3ES*jwaeRlCzUTj{<~0S1$}A@WFP~?M(-zTX)TYEH~XIbMZWDo zfO@4YSiML+>0DcNml&lYc^#7-w~q+CK^)YZDxOn5gh=xJ$bv`R6aSK1THEf+a3|D4 zgtF5q9z%bZ_&ite)b-bs5WoCgqPyRHMfevzzrN~?bV~eLR?Nw}1NovE5l{}{xabej>GwMBCb}}( z5ztyIhd|_yGa4t>$6rm_Jv$xgT@+?d!ORmUbl+-Z*wZZa8^ZQgk`i~OYWrxm45o_- z7DGKiIS}H>xnuFK3IxUS9HP8But<#$H&-=zl6(@XehDldyh!KP*Vl*UyFNENYnswo zXOBShS=rv}FS-0XCXCs(96;gV;7}FqY-?*vF-_^lqhC&hXTBAEH>J{pLd@dx8Gq#L`7z-WbLBZ$Y@B@Kf0?HV6r8{)=M>}ZoQ)4WYKQRtlt_NgAW(xS?zX!AvLo$GhqGXaZPaMP}Y z@SE4V#>UooKrtf3WWOTor&jZkMcih-=i91+*Q!b^cx(?2JtW9;%3`iC87Ix2Lt_nQ&$MZD3Z6 z6K~cx5ry>eqBFCzWA6S^PWd2(7FGN!J*FTkee$6OQm*XRI?a3x{nzB{7HYU)9Y?mr zymG~zaw5SK50PIXCrf^0f$c0vF^uf{%bTnz6&NQY4WGc8S1|Q^B%1_M)Rm4Hb43nE zWG?s(SH@2LK`Zzcq^thr^|G=vvN)VhlvKiOGL0N2z@+UvG}9{<O#`W}+$hjf{D4{vz{CN90YMjJ{LRNN&yTcE zz%7FWO;1=r<3NV11=_%63O?>Z^zYWn*-OoZa)`y379L-vP2Gw8bMAI0^!*@skiLWe=>L4`Dtt~d=^Vtj6gaNXT$X{kJvtMAZthvX%ikV>;^?zdcOryS&MhD7piok-dTw*6;b?mYhS112%y_`RigfniqU zvfL8FZF&A}{eR9m{J&5XO)8)q9KBhPOC&?=f536%R-}lPX?Zw;1nB=0zN1pEDcM1h z3sUso(U81FZlp8#?^fb}GS>eq)e^bwU&n5(CBT%heOAWuoDw*|E3q!k!JtQ6WT;E z*4I(SbUoxK_uLEx3Bne~GLQsFGN$9W5h~%WcsN78a^ zrtK`@53RAl$aD#RsB?9sp6UZ~DNrzTvXf@d?SttjgXV-q$RNrD13TYZrYkwg()+b8 z849>uD1AqU5QvFUEH}owJU&X?N{>FU5~rp$O7yTuT4G3tU)Pn$|A`wbU-Fvmpy=Sg zlr5>NM-39x_)Z##UcS7n4DkCT5bm0qjPmNl(uoX9XOE;Gc2`Z=fvVQo@9v0$;{O<2 zH|=sQQW6rsrNH$Z&&7bNT?hW=sw({O#{{SnRSgZrwwc>ax$7zLRc`EO%2**C?hB!z zp~b3sx7+Qv+qKrCN)vwjzdAcRC9bDT?T}Y>8C03|DcyNv#9#BIcgq*Jd97q$?(jghat|J3lRS8NT{T%R|2$Nm4XGEX>Y6RZfaTkudS}$?c~lBA^sJ z7LE6xebewr+Ql#}vPQSuR=>HZ(QPxavB7ht4+mcJcd30e4~q!NmZGD-oNj2VYieS% zK8mQYr=qf8kWaCcz=y(NG+3Wux@3$PA$wOamT=S0tkL6dnp5kXMCw_lN6G`P<`s=|oFDK3?OkN__cig(?&sCY0S>J3=^%YxEBSoRHr&|>tg`c2E_3)tIl&mJp*a#=2 zEOo(&FO=J>X$hO^igM{%LjwQyfc7q7=>ZWEyM4X#y!+eU;&;>6pSNhwf5wV^;`g{% zj$GPmkW^Vh0^eaiPP{!7#^RP77eZ%~DRcUFYy8l|+{x2ZTkDUc__xcs6G~%0m-UgH z^CZ(9u&xhwOV?`xm42)2%~w|usnW2|a)(3X%M%flui0uO#1QVf=ZsMuEXosn%2?e$ z_=X*{YVk7JV-!!OgI5Gcw|whO{XmgU8eioBim5t`1x*6q2{nj(-RJM!*_CRY87sCt z+=BCUscL&m-srkMNIy+xFNh%=?@G}tyHx@6xsah4J5{v+G!+o$Z|YZ4Pj zEehVjk#b&Y<72iOA69BrrPYX0I{8l1*b5D09$7T1f3eB*xb`3u0IFV)ws%$dR+?@o z`sMr#Gt8q|8TJD9LblqoiTKZBio)$C$N3Ptojp;6tI$M^T;fa+y%K(t%ssl+%;BPK zbRo_8**SW8g!_Y0fq6$YLf(Xz93-|m4-r^+jerB@u^Mo`|NG)-J&Gl1w83HCYkJzf z)u@uzm*PDsFnj6>i3Kk|0fJ2JtM39^?rOw1-5(g_KZ9I<)i;=gStU_m1r#2)f)Vmz z(BicwBkae~2!~c|kwLi@!Mh|R2_ad}z~D8{>|0%dv#boI@JI&v63*B1UQg3W1G~u2 z+eX`@3)K%qRTB%ivGrrE=K0VKb1@_%=#)yfRYD=$%~1H9)6Qy*?!1Er83|?>;O%n# zi5fV&IbX2utIrx-KkB<}t8O2q;6Ob0AW}l&D0Q~1;ih_OuZnF!sXtd@B0e9U$1VBu zHyXsX))d(eTk&QMA8Hcavx-$gdN*}8j1UL@c`?!NR=iRS7$L9{ho{{vR&Q(Q7+?mR z*7{atm|%vLro}2rQnawYVh}l2pw6C_WQlYbx$B!vi|(`CuXIuwqhT!3nI%ItWh`&K zKdI|}hH`TDIfWe{^SrDn!&XNZEwGZd^(Yu|_~We6mw+M&HnY;u&izVBhFwwYo-E?z z=B5btnOu3|wQ|RGs62pJ9aMIF6bD7PO%>KWt7VG07;bjk}x5CI%}`Y4hm4d$JmnciC(v{$qX1JCE=!W4EPUc4LAeP-;*MBsgOaQ zP+BdqkQ>{7$(pjwZ8^)V7Cn(+utrI$-ceRt_q@#*N^+65>yf2OROi^d@a9NSsweK6 z5fhc3q7z$_3g)njn z{A2}2dQedU{N+?&D;?%ZP(Qt9Lp6Qz7*ztFFvPhF|DC+4HF=N_5lZm7w*>w>i4Am# zYMmD6-}l=KN=jA)!%bi9{n?IQ_-=>n07;yx-!-fLTmnA9d)7P|H*0Mr-ia)iZNQx1 z;o+@tp{yXojAS#zG*dF4Hd+*kzc#z?wwpjY8qftEtQvEb#R12b7kGOCiq@Lb{%p}^ za({etNy9@}h-0Ktexm@WLs#gxB%rL3$S_|MLgy?RABl^Li`|XUU8RkgSwwy_?!G{W zF=LRmaXsq5PuUoQBB5hoz=yr^>(|GE?P%C}+qzH1i!R`ft9AS?k8O_w$e58=KY2wk zcn@9!Re+I2w(XIJSGR*)aJ^$zkuCLO*v*Z9y|5UzWSf%MC0+f`5JN(g$7yieOr~hF z<^>}ioq_eEl9Hx4d%e_cpSHaiSywv~b)>mgFV}**8cHX`^uksIQ!VdK8`@9&1D%kc z_#D}R{0bs=6x~DVQ0{t2Xe^IjYF%@)K4+S=8lZ1n7*s60DUBXdpZ3V!&@lP_Z@4mJ zK88-0pIY1dpcob3P%k?A1lXH=f&sY5sj(69;Y`e$F%%<;1>^o{Q0sX>?Uxb-aDOmE zSkT&N^$qTsBS}uln4n|HUjpAk{_XQoZfu16^HHqs4>xJjdVEK)$E2Vjxxd{)5&jrU zwBLoKWJ;^Fkfml1L@a`zF_@7}EUZ&@btO|JFqTHY#gmq;<>k|f;<8E}jF1rra|tpI zbZ_5diFKkVIb!M58aKD=q>_>gzfKnerdt$Hbj6Km0jAyrjXufDtvq5Hwdku_Y?y?r4_ z58ii%z*v^k9+|wUGL!@tO+OqoIMn#W_0#xvT)xbAr)i!PC%%}{p~4LLFuG3N??TmI z0~TwBMPzziM7k-LnAM0;)gcgRp}c<^H7j=Wz?&xp1SNBT)%_ zo(u=F@an=d?f?Lu<(}m_j?t)vGn0#d;`VuVnI1?U+dcEZBc3IC?2m?~rdm^;&pmS_ zL-u%ioh1skA*gc9z@#-3mXLA?h*M9RgO{joczhlNc4#jFEDfq$Q7`?TZZci+aNk1? zU#Y|o7r?N5^r>RoE!hs*Fk_x-aUE4nywl@k!que@x=1W|0L#$$k@QoaipT#EBO7+N zAEz-3@yuiUBHM7&0UwF{v#Ptd*M#lC0;f%}=yqh`7k;^MF9onAH8o48wo=%&VQ1ax z|1P4D_lc%%Dim%}&49F!F)=Y?bOmxP2P8&+Tz2db^Eyv_zvmW~*oozlq6F_6=i6n{ zVStCOqqwbf#O^_C-A=YN4H31C*-&{YH!m+1_~GFpDC~-Mz|Ly1w?nNTUnRERzv9B{ zGT=nKX%N3Tp5VsD3JYP7&n&5^r~n-?X4T)Ss|md2$%v5fK^TzJ*M^3Mz!LQwlTe;w zgjm%!0%+aboHb~nqsmIE*fW#%RFo_9i4?I+QGs3Nnm3Jpi_LsJgFHGq$LN{U&u=c9 z>iy@rH{ehBolprRWvsT8)Ew8aKA3?wbYxg})e8Y7`8ZuTo<*+StzM z9vvu_g&A8KDu@Xu>Enc%+73%s;`e0+Bve<$ekmFqnYP`nvkG!xupg+i|O z>%*~pS*hccZDaG`o)BjM=Ianfu2jWFl@X=`u5rU#JDIL(qVqFEB1@d$>{j2#%7n&U zsz|G0hmy))%mZTT%mOzj^5E0J6*%e-z^_ROc1t!wM@I)eVU6tUS*Uzqh2M>tZgzwCqLcv5S3Ltcn!1oe+7(z$W?}Q)kVH{&* z$#K02J(W`XzWR1Yzsh5Jg$?t*bQfVC9%zpF@aDdBGoz(0zp@76WMN@p-{yukruA*3 zl2iyCF(&FM-FvqPGzq$B`pWzByY+ilz=R?#x{kV4t!`T}HbJ%fyBa8}L}a3K2+}4R zwXH|=a*ltAY!2%+d&MMoLwrPaJhYCf7356;(9D~kl!N#$W! zoa5|R&JvC0h%~gf?=^9@E91Z8W_XF%C@=-xNo$z%&qN-3+)93B#Fkt-v(z=x(-VHW zpE$u6tBh}{^P;3gff&npTgm?7tD%Y?70lr$LJlhy`XN#lE@;T82GgyCvt9=pWtE0M_US~_u)$~Ea}@b z98DEu>*!Wy_z9vy(#M?n_ZWWXP(#Mq^G18MxZas=cpH69BtikrVm0W+eOR3vc0T+W zGFr*2uIu!%+;9FZ$&XW#t8dHbP&EEIez<^J+MtD5Xo6Hv>Khw!N1G)y6=Z>SlkrD2 zwwW#?oM*J_v9J*qA$7UbS19i^?myphY^Gt(qJCXnw_gM8AL`*XdlGlQHNAih<9?p& zM_auHGlD*3igVL4lZo0fcDP=~d^cZ_DL3%i_hAV452e>+!qCs?LC5OEVTHg$#I02I z1E~1YT6OK!=Mpw~b zO^E(5Q?cjr@&b>+jH1-rOKMMW)&2{}1AYh)y- z)*6B&9%G;f>Ffs(K++WQoaO@l`32WhZ-o+#N3yL{QKD zFOy@Xwwi9u-l=OXpLLQUjVVw&xCPI@PP>|kd#DoJ*yg6DooD{R?N*xh)=i z@FP=KBYsbyLW0}}C$=PiaG31tX+GE7H12to;9@$0YA5POjFs>`U1 zoBE0@&MA*5HF13(&zB{i`11rh)>MU{ebDy+bW|2-JJ_*MHerRBND`OIqVq~SMG9%N zv?y3?Us_kdr`OKL-Wn#ZZeU@`UIvnqJ^L4@N#IxQuN03G5oB?#L@h@(m!+^ha<%

p!Y?rv%3V5%*&l# zPrITdr3J~#zM!WwgH7xX>(~xZbaVeS(sxxXG;cV4Wvmk^;QnN1=TCjZ=7uN}nn4Cmj7di_ViO3G45k^*^pY^sf=lu zRC|66V^#a}-A5@k1BygGq_ovBaX#-%$-+M|$ahm?np)G=_*q85X?$}d#Ks3H*2H-s z9S*-4>Eh{ALv~!gwjaOeQ#P-C3p!0v9t#UFHPzrV-3Qm_%UV+f9Y&ce54NNl@zI6f zU8q-iGE)Ggw$y!^j@e%eMBas{QMW zBL}7|_&SW4SSH7e_f5Zx!+e|P9-zYu3JT8n9m`=zPVfQo0n%v{7Kv#As0+RD0c|(7 znYNj`9?esB)KpYt;RGlW+f^q!v$aGGI+Su`;k{;Rnp40h1IWde;s#FkX1q{w=Ug(K z_@CC4lmM!@1is%=rB-PO9TW=vR*?m_iV)EVAGE5?Py*yxMSFXY%)*w0^Wk(y{&mCr z*Ta3BXzA_gDS#cKRmzC*vQE#^RfJKuD6W=uWMhB-RjQ?KDs?|AF=o+hs-+M{$c+_m z1YP#$-+_NJobt~<0KzM1!CY_3aF9`(dMTC%w+f{LW!$niF%=ggPp07|EDE1qz0%aA z8ycn#c7{MO`;dPZVEr(&gfL;_!>$= zHSa+so5&!aO!zl2b<4tn31;c)^~F%e4M7tGTlrXz@o)HH3Tq(Lj!8mJ{t zCPP#rLv^_A9UWDWE>1CsV3Ooj|M4*k{ZG97Ca$zks%)( zDzInkIpoz7k1cAQbnx508Pd_$P#53Dz2QdoXv=Z+S4&Gc8)}2V&7~`!D1i#$LM1ZT z`L1F++|*{CnM!^1^l)vpXjc$q5E<~p9A@?bx-t6qrhMW{dc+Zm#B1V=t`Eworj3&h z{P9Zx3Z`Up_5RMz9c}-jYJ|HajGIA%xO@LkPuN)J>%vYGiRT@n2@JEqin0K&jK?6) zqpU&PTW`x&a|pE7Pi*w>vA=O514+`@9B23_T`Z@hMV6a>YHwZz3rIAy?KKS7Z-0|C zXv8ZH$`b=%X+^O2r3AhlzJ+wEq}CIfsjx-^PLCfbF&##%atWcVO%?qhm6`^BMuCHH znNdV-+d~hw%s9{o00Bw;Ak5t-MUfy2k6Y22nV!#OmQ(-qYJx(QVPrYMl ziI1D)4F7Nko1-P21Ad{KvY>Q=EN!7;+9g-?29bMf zBy8gf9C+d-H#)OPd)8M|j#U)#R z|5of>0pOO9FJP>|&{136_w#EIyrJ3x2~N=z$)D$NU8 z#Jza;=c|<`k{NX6xUql{=*=>b`)54kR`|}&9O0NDFEpq8#GG_f8RS7q))F+2FQjJ{ zu|{`=yaHNC>^L7#%_+vCK5#!iGK3Bzq~oZC4#Qy{xBEj~gsBY~+Wf*-qssLoZ;6i! z3qGGdoBga&x26w6m#taac4zXnI z4;o1zd%5$sX}h>B*binyxv{DHZR_-gt-zluaNvjEuhD@LKFr+~j+?i8zM>j&08&UV z=72qX&6e`=(?=Es&NOp((>guJhWU6}abTVh?h^PQVg@GLGg&otc7Fayw9Cnr_>cMkj@aSH&?ffke`3K&RkjQd)~da1qY z9Q?J(+OhSH^YuBS>;IrNVDf_gj;O_l=1hUR_QqG|EAcDCKOT6b-b?2NMqURh=68KQ zrELVPGl)D+tO*IS*5zgUnF$hDqKj<*?(QBGvqyK~IxROG1gMGGhcA6$!30H-5AfB< z&)IOtH%{U{$C2$6O7FZt3r}5Lofj|Ug|Jtyr?d0N?aSNFV8{8LAO;fiitT7w5I+L@ z!jNiBMR3tJN&^xxa2}9hVsp~gOlgHGf&|&Rckaps*6Q2RsV?EJ!NjNy5at2-#u?v( z$la4xV@ru93-@7yPm5QHsgjt?I;2i{FOR7;K}T8Cj~<4+kSfEs$dMWIJ%9g-AHjqz zS)cjis3p95&j<9WMyIB82hbCMexSNae~tiD2py^c0vz8}L z#kM~0cLD2zv4G6WCI_@nFxPpE)UenJnj1uhbdw9K~X?_g1!HNfo zMZm-_R40&jad+38_}bkqIqKg19%#a>4|Y1;!NE$u!w8|U+&#J+D7*= zdk?Za+n0xjZ$G^f47_cr*hZ#8Gi)ZS(H&@T0>9gfN#OH=q5?tFvmVFoDxq*9~NICt*c|Mj1L^WATMC(}C2 zkYE$-?(WuVwJ;1vfietpAfemL#cEDzSZPEX!gWsu9uQ z;i0OkY&cL0$vkZT^3I)hyDbR9mtTGv|D&XjuIurp@p`d5937;|v2g+bm?y1PD+q$u zUw{4o{^wuc-+AUZj%^&QEG=7>#p=9s=gxVaS1cCULc_(yMb_cDxVX5qw8XwFl}bcZ zEEYY_D-;TBx3+9Ht0;;^|(+dWGKw4YPDF}HJWUmOD>mdwOZ_ydA8_~Kb>!=t*R;!6$*vt z&!4lCctt;O!=TY@?(FOYK~OH2i^bxdJ9pTmeVDjo-P7nG1%NdBmw)+}yLa!t{r1~o z7?w(Tsy3TV)?>7{x5p;VD2hTv zkDomyqFgR_`SRtRot@wR{`U_bKIBh?i8~gAj~_o?TwJ_(@gnOW#U7*pkT(1K`#=Br z&xz>u*I$4A_1Cwyw$|3xY}@|)^Urg+oMl<;*j{#8Q>QQtP1Dpg&G-FAqfsuGec!KE zt52Rh+1S`o|NGzn{`bEpqTl@HH?O_++NDdE>h*dM1er`` zd3m|jY7tQ;lVLYEo6Srn!#YKYs9vwjvh4f*XPUIeCDJP0Y$LAtoOh#&+2`1I3H zKmGL6cq`0{E)yX63{vd71^@tauS*aT(eCbUya@mRU>3ogpVITX2XP7 zRu2F(p;oKKn*dJIF9-nu0OsBaLCA&)F<&MM3+e#?=1J1`bj+6l0D!sl{{sP|VlLoH Re-i)z002ovPDHLkV1n<22gd*a literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png deleted file mode 100644 index 2f358975b94914b94eae386a9355efc5673ee30d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 110077 zcmYIv1ymK^7w&*aDd3M1>9~}1BQ4S?UDA1h3kcGUC<0QKZjo;3F6r*Pgmi;+!yEj+ zw;t=VV8P7nGw1C1_TJwPey=2rg-MJF005S(jD#uxJQ)VRr_hnXzo@VacY{AL9AtEy z0D!;<{Qia{(mJaQ0F;2N#9MVYgS`b$FA~dCw)?|@E!O@xmhQ6XxjKg6=q|;SK$yxN zt_KE7Oq_`o1Hy6k>7lr*uY-1v&L7+D^4WG)k~n=ITb;`cE{65_rS*GB|4oA0DgKvu#tXqL zMamaOLC2iz?5)`5grS`?8J&5VnVGq{LG$M~cl-PMPVqE>FT~MV94(X)>inb@L6|R| zqe8vxt*w(9M$kvCV#vml4W$2jy0f*lwYLYUX)-umZ1P0R&25wffcH^VS|tj@ZoEWX zdWys|BF{t4W@d;4E8U)ceyh8T3bZUm_>)k90^|c{$E&AzY56MoLPqR+O9~4^=l^;% zdBplxX%$s1r8YwCe{=ZN|HdM!eSDWnvjkz7TANWM+3W8IqA$3$iq7^!bQl8K{@mZ) zB=Xudg*!b84;<*7fF?_oQEON_+b;~|Cw8#sU|#H;&@~y@+t@G>*8O|dw?qNhxWPB- zbxCKg-g(;2$%TbMYyxQrZmiiH=V&_q1Cwh+h83u!W5|oWX*!t_aY9_~$$z_<6{r=Mq z$h^V*rrgOf_;`pq3H8x|YrkY5KjpD`70!36y0{pf%{H3i=QINF9OFYKEhdkL^*1yh zDg^iTaQ>|!#C^P)BdU<-1h8ny%i@T&XgUZ*0u^h*DHc%DdOY9^$&N;7a&;8`Hoojn zBIhM$_xijG$wBpKn9W=`?;L`#!kDnNpEtogwn(gnXl_Nzn^|? zdxC~-WQy@9ju0<82S)tsIl~~KDS4~HAmr=dU5!IFjJd5f>`~OyzAPx>@FJQ7HQwTE zhd>FTU}DzR5I7FqMIKI*03R^2V$@Yx91cpMLGm+Vw^HB=HghuDk|FIkV;#=H`flC3?tkzKDAW$Nba0D-Qj+92n#aItp@KS5Zkx38)&S z)AC8Oj(6vkU0q#U^OXD->ERP)f@c`-$R!dOJ;(pTW~6EV-5gUl<{~>M^Ua7|h8{9n z*hq%?1(cSmWVv$-k(8vl7vCEj!f=O2<|9jJ_lN`UQGq_1Q!c-`n4OjGpZZmvo`*0gpN; zqZqIDdmy%&ixy&v^0}?PUZ5Pyr^PVd2k!6h&to$cV|F0QFf^M^*FC?!XKw#qquDs; zBygUN(aX#W1ps#v$;iseY9sldI>^TF$&Bi}!puF?xZ-Tujt>bQbHPB!HP@A%;A_aQci(=CHSpejlaxi51zQGlJD zo!`ss?&cH6AsdbjTfWA0-|!&eTrvW=Rtj2b(k{rK1;yoGSV#vFGF4>3UgHMG6#P<* z9H;H=e`{l7vkXP_{H~s(PQF)mO(fSz`i*2{=GCFLfuzwmL~s%Y^$iy&$0M2_6$jUn zA*rzBm=^v~a;YPhk$$ZWAF8K6GxafdGc2wKNo;AH7VF2MXD@En{ceGwTB$BF7`vYM zg@j-pXXg$?^9sMjK)t~Iz4vWo#bW5vYHshFqj^YW@c|XbyGoX>ZFtxCMd>FDN6+~I z^x$OZJ9>;2YwnoBD7iY_xseaH9#1c}%qq)&j#*TVMu{()vh!1C(U7g0Qu$6l_g+dM zT+!pwO_EEm9&~Utd%d6>&;1^!w6|5+>6s!0jMP0eTDWO-9^NeSh#4M@EX4Fx? z_~jnZ0tlI$x}*of(W$Zoht@eOBjbpXpmPU%d+Kas0Z`uo!CFhX$Q|aqqvFwlqmSgQ zFFRH#W%n*sV`U($L2MP7R;;Dn^419A2Qlt3rhlSeh-Y_spI4-tcdIi0K?&wAN3>Zy z0c0SQeke{($gpXb$)bE;~eX=q^K0}`GN z>V_Wdu!xZ6HV%2~0VUz66)=cxvZjFXe{1b48aC;VRYCi@FN>&t+S~#o(=T`SHE@#f z6vs{lqCTlWO+U>!JWq%KO*4bG>vxBAd%!9ffP1mXEblTazI}3bHouyzQ>9mDAMapH z%o2w5{4A?WeD$&ZgAFlBf79Z@w1FvMY~XbW*AAZW(b3Vjp+_4jK7xl&66z-lQxi9{k5~+w_pf&&S}v&@egNDW zy9D`AxKh|?B$ezx%<(D{1uA&>L0dO9HTBaq3@@$*>Nt1?lFhK9}j0%9@!MLQUbM_DS%Q{$%c>s4Jr^L>Hn-MDT#PEHQDg-t^6 zw7$OnFPYC(tYthby*1%veRAhJaUXbA0Mb3}UhM+nMnirw!E=Ux5GFAw1FE;6m!f8j z*wi!7su957G4Bd<1!1B`y_ue#p3=on8OQ5dN}}flmRu<{VI7+%lZMU&Ky82D26K;B zZ?9x}@v5t^saKxlENu{5BynAMtRuL1nU`JJ`_%`v_&Ei|#W-I)65HTg+uIzQ zwtjP>td!+7QIRQwUv2v=p1k$5`ZQ{3BX!($$b67DD9!roosR4~`z|#B*)iN31M{Hr zzA6#@yDC|iN4?@iS{-vC7lv3X#Ht7t1E)`dV?_lA_|I# z@8QT|{G>ykCGamYixaHZ_GZ#tJv`Nz%M~DG^4bC+6M?VC`Ol2{Uik=_+AZJf-mEE?>t6hDw37TBgxk;-VPtfX*ycJc0OjzgGJEHkIqTEJbI zYgy*w(!?3vTz;TW&`aki+RjZ*O;xG%Ync4AByEqc5*SCBb}Ig> z{hBdrl8R+a`FA)mE79{YN5`@YW4fLDlsfqh8uUmR+Yb#>u!^_TNN|b!Q4^QpI;XuF zE3taHf0_uohXLeHp-HwDjOtBu_?7HLt~}faPQBlyaJ)5~h`j|dD3qX%Dk)(-JD)B# zP_$!@chO4M>;2^OuAb@7BZfm~G4D)`mgpwOtx`CN4s18xkN+_GR9GK3#C-&=sYF4H zf{f&$PhK?B6O{qlSi*&T^>#2{%bjwb$$Z zStRhRz_M>V6%>!;2magf^J(;eeqKxExb1k#AgSPJ${>D)vsXv_x1RKgh122& zZ+ZUbm=h!spPty6#1oeBo{h_@5rkccOj%J`l|z26L6^CWJ!VU>f3m1d|5lzCX>kQ3 z2}8ca5DFiu-nC!LPK?{;7F$}rw)p21sXia=h-tdn_}2%E-#|v5Itu8^7o-Q054$xj zPNX#XKKKmG{@ZT4w$IjSA;?VS{$f95@N9>foI_gS=mo6o+ZQ*X|J8EcDF|WUKCZJT z(CvL{&lbxb=Gx9LJF^Kog)!x^(NUGg)?$&gj9>OBRDcY2Q!n=8wREjd#Mp_L8ygp< zrljqT$FPAEu4O3X1~B3H25P~+NyX{G5I;6;-B6s*mm9#M4Qd(3B7=^n@pA99h^YxszGae}YN_#J*U zHKh(=%*5SDE{qTDN*noBBkf_Ukv3AT>eMXSTnboDLT0)u*}}aJsP<>=!)PUiqu;ktS8p zWBa6p1Aa~y&A4_7dn0$BvLJfmBSFDJ0{9C;G*PKffYTr7az}wwJzX6QILT`c|7GAN zDI%_7YbJ$pI~(E@nF*Z*^!K*JBW?aDC0EF*VUi8pxGYg*BYoIa+2--c~~UBnT|yYuhYd?EDYRGwXbkhv72*Njcl z*il9O)grzze5Rlgzmpl2?so2WjnSUzSrF&w7GHCyhv*>}ObZ_yGIX{HaV8j5>2AMt zX=uvGKmtgygMKpH-Q86%<(O(WxacpuK69~9)mUd_azbjIn3yOt?VjnRb=;dNo12>} zD0mIz6%@=hx;xFmo}nNg`dl>d+0OiN7)aZF6)a)kz8-6MyYf=dWsh=ISXek$IX&&J zdcLZ%GLqya>xYC3DucchyWBwwQ`Bg|`=t3_AJ84O#)QH*GG>H=U40F8ot}x#^+#MV z5fsAhZXeZYb@ra5r;b$JDK{{FyEw^L3bB z>6Wj-O@tub&Eqzzf%C2&ylzkLU`2>YjjxKR=$<4~*@t)h5ZwIoKwKKWuP8apo>I+T zoVl9{RN(V^qnGn7AE@@bAj86zXG>P#XP|3jo_Mg=*Q9TkMG6A%UtGl{3 z4i2Vgc;vD&Gd~}&mQEuU7fb9Kht!92ruDUkFH~#6Qo^dT9_DMWNr0WW`8O*&kCIon z=<75O&+gO@UNO&Q?-3nSXw1I1EtFk=*hh_igO>d-EqG51k(B_+pGyOV&vozl^=y{k zl|pozO}0G}l0!z?eh=#Dg^<-RB_L;jR@L!TcR@MA_B#@fIE$-0)NY_r4;d(XchPWg z8Gbo6YGVIbLWh#`h{17q}Q zvZZA*){W>_3GOB&=e8Ls+alG}tAwUCDC!hLkxTN{97AKy-=c;oz=JOphbj)sibGRU zI&Lkc>OYXX@{B;-)wpQ2OGOaw%JRhdR^ipl|OFIp0dl_&7~dK3x=Svx^Oe~ zm!Iv8c$GI&6n0`SC?}Z=Qo3y2SK6ZrP}_IuMk=?5hM4{5!cBHmoVgddSSjlHrO(4f z-JaO>nQYu%-eTn~=1~U?=(1RB2z%;0)4|>F)Rf0|*}TS#=A$J{2ISMe+)$9DML+P5gX2)C90zz2YP3%XMdM|mLUh6u@TkK#&5_?}m%dnxeAX(Ed{c# z@1+V;7lpMmL)54TE3D8?gW8)z!Jx21nsu>_7K6SjVU3@$-K_) zl;@k=2(m#jp(B~uw4kwO9b)C16Cu%|g`3L5M3a6-T!Ncf$^PiQ0Q}$~U&eDhshc#a z-mzb4>C8QG+M!ESIZtPaSRyR^H|_|=M@26d;B>IUh8nfPf(__&c<0a2t;-p02>uQ& z4L8iQX|cY3^3yzIqCtt}#x83K7dvQ^^)2eh+OgrFcXA6FJUs26KO2?L4AM#wETW2c z6&A|vE*A1PmPHJuT{6IKDJgF09TC?-zBJwl$H}jksiIZno-g3z6r@P4^mrH^B>0j; zktX^3a0$DVx%;DSDoOW7kGs_Ad9I4SN{cVA0D%9$0S5&qMxGvh-%} zRju9!+He}a`bI59Ho2osB{r|qk5q(6eh__%AKy1Avl9kqnR*&AcitBK1&s3z=+#9! z!Yz#SM^nb_2ddbIXPGK{X zaSCVh%5F{XbaE)Pv=M^V5PBVmG$?I#MfP8|EaJy&`zL<&jj*qIWTBF1sMi1`{!VIx zSvZdkv2nBW^Jqp(Jf9ZPag@!Si2vluYhH%c*Vn&i=m_8G2rNs+Nk{Tq%MqT^nsCB* zSaJ4bDfPxdDV%Wle0PN7*qh%Vtj9uNgGYcR3cVfS3!*kxJvMFi&MV3{U&y6svEFq* z49U2Z=xo5=d&6;ey6dVXGWoZ}s(+3BT7 zQszDpD)2BoRR_+RUxJP*O31{#g!_Q-iPf!OKx6o~vD|$lc5N*!X=LiK;A~+oRns0# zy^0(TFcC(@isQA6ZvL-62sMG{U3vXz&>N5XM6Q6} z5Up0d*&JDWl>EVD!10=%Qi?!J(GiiGt-+@q;jK4+j3MHc1UXLsel9NRXC%*kyHjy% zp0WAymB>wWei{YL9*-6EYBi#FQY*r?;V@ZaeJZ|%s<=hX_C9NU4aev;b#aU7RzcUa z!R5-|b)8ucQtyW3}?p65s|rs`WA6qe^g+#h$OcO(<}Z7yih8YE#%o87A8 zc}HZDp5;0yA^P3}!RIx6sz1gq{Ror03Y-=}H#ozSz9v1EtKI0ub)n61^X|`llk)40 zc?2cQC;~2Hzt8|-@s(~hPgh0UyQPnW7r>^X4uzx2q{IiAtd zu+|}?rsgFO&}KyW;)myCy5l|xv+eHC<_S{kP^w_q_l0QFOxi@@_giH5(UOCkK=1n zj^)aNlRU$Dz6Oh1;ZUI3em}3NF|n5|3272e6xS$t{M9`#50P1R4i*?#cQ-fU=gU#CG@gd_sVfb)9qkLM3_3hul#z+eV1TZo_ z{_dDMwJbb57v{-O+|^|fksI>rlYoAgawAxAh(4jLfgz;044DZ9-H+GeSoC@Xz{V`Y$xL(89bJQN15xo*T`iabSdvrjOjK==pGZE5x{*6cxJUkPR!>-|##v{g=HS zQS!pvlRU|7MZ|^svpe5cceq~p#MK0zRpf&db(90Y?T|p>a7_vs*p5xNuQT=+^c=G2 zLTcUq6dn;l@y0Q$u5NbUrF~$)Poa@_6Wfs6OC)`GlgTALSipq@Vf-_XO^=It4uX^$C z)S}uufA&F#f4yT&Xpttj80!M906hPxnHibfl+Q8l>usu&)^y)Y zWj-HEFbt+N*Inn3F_H1F`ho0)5>)Y3H?wVSg2j1WTjxDaL)b5d(+BeSr3F|#A zVs{(Q15)I97ERTlL_2Ep!7w@&TT*VrA!-b?$Ryc<#I1*Qf`~+v?po7 zu0_ynZR#mM_Tq_Q-0dMD_}X;WNI8~IW$l`!KVI(*&!YjzVvfg-D^rJWeB4+VFtzoM z7H|S4&2QGF->A;80`7tkj9^XVA}6+#$x7`1#|2onNtnsF(RcL<+VER5;(J3bW8E;8 z)!dV&lCCMah_SK|^wD%ehw9A?EFX&hdN*u|2*l5E3pX+@S;NNQF4E2tT@yuZvbIJmhQuP4ZUa2!rA-=^I2ULNpIa|Z|)aPG9FanN5Sdda%YO2+4nOO^=Aek zsNM8lXCdFvvT;{_O+Ie--Fdf3Du)mCs%d2)mpWU3m!{{CHr5vSlOp1n?_k06WTaJ5 zx~Ge%#c4wCH)#-2%8frcL(UB%0}VRh78S|T3uiug7IQ__otIdR0)V;idP=j&MWx@y z>I)fn;R$N*IgrMXFR2MwSz8m6lk;k9^yf=vRac8VB7>914vV?px1ph-TSs03>>xB$ z)U6@ch6NHnyDUYzwT?b3?t*?D@0~cRn50I6NWh{LVM2gXNLl+doLlP+isR0*&_Lp^ zN&YvotVE2HEi^~;=}$t{&Pz7lu?5>dz*Vco8SQ1}Pwih&tmk~~v=L3Wy=M4J*gxtk zJMYnYy>d5i#m4VlU3lo%IL2#eV7YYc-)ra<=M;BzU>>dPqus>)aRVyfj!0#>c$HW^ zsk-!^e7`!vG%bvyH!gB;WGq3?_9xZg%83bYW?+z|nY>J6PWmuWN(CdX(UphJ0#>%D9j7>Mp2QQv2~G!L!e5=h&Cslbpp^&0tq5`C-k;F88;k9*WP0eH6JP_uY>GE{2ypb z8yC-amHQ@>S8E>7i|iz$uC^lg|1QX_Uthv-oQ}#m4(yqDBit4YfcF9|ZAV_~FO`r0 z!{*=RUKOyD{U5Dc7j|*grteXif8)pJ{JHVNC#DTU2J#uSy5;IdphySwenzhpTLl~j@$yp&oe;ML*r zlUbrJpdosBrHByjv?^Yyb74qjj>3gdLetup%XRlPnE*eAuHxIhNo+~ka$V-=BgXf% zwt)5vs^s$K+tR7{2LhmV2lXRo-CgNr^Cr-GeN(FE`*4=;88PE~0`=K~01i*O#pGrv z9)6gxDL3v4hNm|^1L*pB1DGScR*3$JO6*lKZO4LQHh8j0eX7GmjqwAXOBu}F`UApN>nNW@5|PM^Gi`#SwFMRpmi$cA(Z zbyF$O7-B?>^c)`Poz=MS(s1X~B5=-;IQ%QX zRSE3ud>O#VYbM9SpUO^^YkJro(n31`3x8mne?kY$rs6(*C8{`y$8Mt@L1-4HE~cr9 zp%|OkRvz9a{~Ez{@mPTf{yqw6?^pbga<3Xy8!Ru^shc3@WJ!iNbmsPT+grwYZGvy6 z^S3yR{65HSdiD2lA=ATk9_cp8UE6+2r^?kAwJB%5Z2f$yxr}yJk9?wqdu@ zq5ocU@FsurGQ@+?%jLj+q)&CS^|8LK%P&V%HTg*hKT#2(FyXUb^~RW+6np&G1*F$l z|M{FqhZf(jp{M70d->6&tYqvwGO&Go(|NFe{rJ~AV)g|Zfw)SH`UlX9$V|{}Do#yL zM++-YXWWPqhGIQ`ZuEP~&iXa2nl%k0WnT!tH}qvfh%DZdOyGTs*WHBr1gtP2g_Mj; z9`D^t_C;h;9FQL5FcxF-aWL+}QoF<>d3Va&6vx+3%8Zud)u9I|kkvNcs%O%67(mTr zqE5U`@LDSvn9@LkGG{?@lO3}DzH#>gfVJSaf83OujXpoNZ>+|l$p-pQ$0T6^AYqasj_`g`?3Rnkq9BR}2~{z8On!dHS`QI`-uEWYlw_9-JHCC{@l8Kqr1I2`5vd$yiZdZ`Te(cb;V7z( z3F)xl*k?!Q55Ku}4EF2b#7tsIB*5I!qNazlt~%TNOzCL;f@$Ex+G9&Xmz0^E z&pH>TPB}4dUb|q&$wHQ298iY!-2F7N!(F{g7AQm3AdT*vplP`Ab!U6~ z6)EZI&E08KL1`&S?;7Vjq5(VcNJh3os2{9f#q;nGJoU?9dihdgD6LKL1H7W4Our}Ulc{=vk<4i!#(fZVruVLw~Dn!(mlknDHWuUaD)_k28G3g2@3@;DeLxuciMwi(#BOevEF!UV?z>Kx-hcqz7Jr=ag8V){SR!N zD-@hg*AvdMo{ z;#dW3WtO)w^p(2P!X+&&$9D5-GM?xSK10a+s;QeqqvJ6Q=$0a)o@C3qZz6AZ14AZg2MMP2PcI7hmLZ7u+XoN ztN;B&a&-`dFf>)v_kL?Mvpa$Uq&1ypeg;W9Akndqf)ON1fz72Bi8?t*M@B{z`00-i zVlyPCQ}Hyo8_loSRANrbE3UQ4J@ByJDapmxlPtd)S9296XxTUZ!{1MFuaU2f74Yt( zCX-V7{)i>y0T$wV{^}XfdXk3Y<+>Mz6L$aivzN}`g#4202R{8uO}bKrrepR2?gq8< z!lh)dU0N6X*7|dg$1>~I^ZpQv7q)oHUPGf^e1$cL7D0A z>0=LvkCcbL;ZI90ae1k8kxf2#9`LtdH}VXYm!M^8S~0$DB0XN`nEh~hbX&tx}9^CiXV z$|@Kj6y0`TKvsXqd=R46Di}LopQgk1`F#@Ay|(OhycWA$YX1jCZ~f&kwy$@l_bQ87 z?B8aB^TER!{SzNrV$`SehgZ2Y~3kmFr>dQv*QAz+ejIo0s%jMJsGAn8DlfV-A^3A$rbfdDQ+!Xp(f(MJg+J zn7}uVp_K%Eb8CetyeXby(}y#WvWsu9aadXdMacbz|7dQ@KtmzZMe~qW2^@78UBd^Ys61KKpC z>>vBB8^#&arBvK$XER`SFP^q^h=YRMrCwWc8acADmu&AN*ueZUpBA>D{4L9*Oj~XI z)Lg`fPIwbDbe=dYENt{$Hw;mdet`$qW)@(-jO*Y3aQjA3FdWU`y>jPZa5Uu%K?C2% zepePtA5>qjlnMbrOeM$iB@!U16z~P+u4VFH*#$ZP84?=QNjVY~K?07~2xy5ng!{AG zxXx?56@)HsPy3EkhV>uP;oqM)M7PvY04ayJ2oR13r;z4G`iBBqx1 zybw)mypKoqnh>{&hnM~RBkAI_Ehi_3dR?VTK^XEh4JF@V03!O&U#4Mh%a zOK08vV1{B@oA(#C?wzZ&=f12tt3$a0sS98830m;M(=UhXrkI{X`IG}y{4Pu zuo^Lw@;&b*uy){7w&d-7jX(m7RyKVV?FIEjSG~G7rCL0rFSwu{kEDolRcf47<ANRQu|c{H8cqMfWgKWEnL*707lI%KXf>rl#D1yVau2PB-jY>57!0RT+D3^(hOE4VRFKu-wgcuiJp`5JNPA*WPu!2OXl7H zq115lyRh)#JV`0H)y-a5y5`@yV8?XyaaTj|^}|N3+p>9^9-De8$=$u@Mv2JaU0SI> z#N#0CUg{r70aFevvCYoPUdx8K)@KdZ2$43=FWeC~{9yMN^Rs=UGJ!|^>NL}D<;%@P z1--G|TW`kkySmCA+FVl62K}Q6rhu@}h>y|ny}$PVT8gDW@EGLY*?+&)?;q2MU^dpGTEU!B49G+(yZQ^K$!BZ>F?wJ2nBc^Fb7~Vs0wPo(j_(Ke1aK zrQV;72E=ZBUyRAc)s7l$TIX95pD4voP~!%h6)cQN!OF#tJaV{Hg7nV_zC3?- zQ0k%kF@=F$3nX$~g3PWnI(uu&pmO+bb=kXDGR@9=?={P7{K=9+(ef<1G_2&Y85(O?i3h0Jr`n%vnL3*MeRXtTRDWo3JWPM_Lp0WR= z4M^8iVmXzv>dg7z@^DG)pP$cm0W`xsDO%FfXi(bjf#Uysul-I={V(;0V<6TiQKay~ zAI3^JAvk1~L7c0~!y-ZS^mIW%Up1aRl47`n(x7_Y^=7>{vLJW3l~hGfcs>1Kx|}g^ zc=O35MvPyg9v77tuUgz7WA*R(wGhymWOPaoS7HH=-Wno=>m*N9tB6|#4P@y>wF(4R z9cOuH8U$WO6*x9(+zdla^&wGzsmPrMmQCF!EJ{Y~Zc*0?z^RUZgB{Y|Pf6i*M*{!j zk-NVr(qt0UOt`%KLTF&q2+cp1kx z;c(g!1?(k8xD3IJ?4TXXomNSngkQ7od`LekD znDgz685QpMgcqixM1ucb?A3KH4B+>^t`u;Xo|;M%@lMju=eL^65fBuV9~&G4f#CQK zQ)#0~TA+aa9Gz0Si1+E%=)}On$jC4Ela0wjEt2zuILsUv3p?yFT+b5F!k)BlkLU8) zFDeAsYiPt8`zOmHXur?xki+3%TW>U>I=C_svFtFSdXb};{N3FwEC{OiOaTFI-g}o$ z(8oCJ&2TvX(ZtW5Ia?5;{AJvZdYvu%vwC)}%1I6(F*kq(XlQ6~yRbD6g#G^;CBgc? zQ4NBGI476Z&dQ3x`j1koe-?ybU5s*MeqO;Yxj;X;j|PUv?G*9-dsf#$r`8TQsPHrg z2CkVwFx3(;iyY&`YU^z1%BoNKpt}RrR&b^wX&O=W-VvcUgv&m8m+?M|+y=ZFoPx-z zg_3L-9Cz)WRoB$)roB}&HOwb+p-Ki@xFCI?uRoV>z=G+?3m~hm-$}~E73{}Eu&rN! znS`&6O(6ye^q;1D@2LC0>QaOrGTk>Iu`dG=KQ3u*k$gsWxLOUH7EJB*_;7nqP*pVv zya<-~By?&dm&-GuF;&-;{v%@L9GD!N4mPYJ^RSH46-Cu zNJeKnlaOVwu7*G$pp07a&t?@ABnk?(w$4T(;V$-vua3>j#(77VmeQfv(O*>m?|D_C zSN`=%|M@G^ipmD6V%MTyK3m%?60ZL>ayi5&4w6|>QSp~iZbC(GX=7E0-BN19H9{5Z z`DwAvcu)8S>;FQQp!JVEr-Vohg^5BihicOlVqJLp*HlLLa3r^@OuHASXJug}EMhK} zOm(x6^g$y{zn%1;fo=QjHSo*1@YCA2(Kl!r>h+T#p?HUmj&5cYAGEKKpOJF~?aMPD zpQ>bia!(~$i4LX!(_3ed}C>TRGMIgng>Efz;s3K!!y~fpiR}c3<14ySp@txpon1xLr!lb(!&@g*r4RBdnsB`#0Eeu6jQdMsAA zT2$+bC;I=_3it@-?8m33Hcqarn6L*1CKXw6@v(z?DGiv=sMMdUentVNmUIuHPOr&U z+W9&GzuODt^j}8y7z3XoBFUZtzn}X1M$`A|HR@IRPKsFWvRKztRgEG* zifaLFw)!#a{s;4V32b+h5&VOTo9!}12rkm|74(dNU}c4uHpQ;mIO4bme?;sUwFD#p zx67Oa0jH($4WR^uf)>}{_wkiqo&}t#Fl|r9Dfg>>hVaO+;Iu}S4qXv`uBv3vtC7o+ zPyQzHrvroEi zys4_{jF`=-f>LfS(TveK_cvwui?J__2B^TUy=CDvTC{BKXM|~)7im$}gd%6nnDKw{ z1{>k&;nDDF0ZTkSJD1nK-zn@~#5Q!sd7sl9+dh1aQk9<@78Rwpe1aZgGN$%s6mEhv zIq~Ak{Gh9A+b&3mRepAIlIIYgmM&uMYM(odn>U)d7Vbi~gQ3uabzCNUeyeEwLK+=P z&m#jKm71rdOqN}p+9kiJ9+=u?w;!)JkXq70M=kB9E!dpH@LA2R>A zos{K+we2>CJ<}Fv)`J1Xdg;Jt0jq|j`EQa1jx{d%V}wsd>8}sN53iQKYThNnU95M} z<0_+OwZVZ+D=)Ctq&V*26VOJvKMTgqoem0gl!>UkHIPl#GwUg#r4?^2I}}dg`*Cwf z&*h+zR^D77rYaHA&&R5%64h^@7L%xKwVSmHV$M3rT?U!zE>{p@91o zldO|U5}j{g7d+kmO^M7}5pPIuEA+`F7% z3{H+XfogS{9zwRj?fb)QuS|Oi0~v@^z3BGY{ootFS_ILLF@I8Sp;9FT^es>~_By%h zRxQQf6isEM)3TN*^V)y(mQLZ4{Bf|wV}s5NW&00I4#>s`!q7U!@Qy#teT`|wnnR|I zu15N^HNV;HvSX`Q!X{G_WRT!(&?%3omxh@js&^-|cO5P{fjm=J>$#zrejZg{lOIP! z7XRsqz5U=?5Al?R!%c9@efIn!XTK?bJM@}Nx-cX5WF`c(>Cv+$umFftyTb6r@3G$} zeXG<(@paNCv-F152;Yl2iIdDBriTV?*OqL_*(#eMW!~~E{k=*wsi)1{ooM$tO*y*=~KN}Qd#csNnC{6ps= zq=my_$oI`*{C7jijl7>(Z<)8|Sa z0CMqw9|hJrrmK^m7{#qo)txG}RA=URV|6W*u#)n@kgveh4-%Ng6R|T5{=%-|6pTtGH5KoL*xIA5SZ5#;y8Bldm z`Y^7{mo`_)m_nsxwRxggWZ>Pl`syc*R!OToTU&2*#jfpadHX(V^4*+*LhQ+LwCk*T z1MQ@5&%!6Qt|zzPfG1sgl#6wrMTJf=bci!CCB;l??CY^Yf??9RPAE7YI7SUyD&Mhv zeOB0lR66mcf3?+Zxo=z2Z8_+-=0OdBmLQS204*+dHHpfb_*%LKHl;RU8H#U=~Wf{ zz`Ta{x%WJ;MI(3fBYP)94~>X9&RNZ9jAOQPotdQ?oVc6M$C}@OD#{A0sCtJ$oW#xM zwiO+ea4Ua#&D!x9&4~y&2kXX-Gi-0qHD9sj6iV$H5{n|)Enn$_Z88b7t3U`e-Ay9% zrbv@*_=%WA+(~je#5q8;(E>}ClpSVcqF_BRp$zX`TVt?#7H++>m@v^rB(##7Dha~D zPa^}tuT;gI;yRwc5_ei;2N6$T;GfdY)xCg~A8PS=XccC5Rn>{R+t&79=qrfD>g7LG z{k_$EOQ}-phDO3Y_@wpZXM&oSOWXhB0@x&V+f4nC{C=}%DcT=y9_KM249?7dfAN!n z4!7>?)%bJ_h@sg?GsC~`94TyF&)rn3<$F#&yLwY6CnzfG;y!@-%?Umtq!=o@CVw_A zh#Q@u>UZ;2A`Fs&8d{|3bO~-Px>;3O5;nl<}JDci@N-R*4 zH*FN+sK3^TX%j2xg~^o-4Gpc!c&Gd4M^@c{t(_fJium!Rtuqf07MA;(5x&>g5f&XF z8*qNWr;a)6i-KNx^;Z~%Ibw|A=4{4}_o;(h!xi9SPVU?Ak`>Y68r=CH5zzLQQC* z@5(YybovsL&33^_V6sxhcf>(k&;4}z1`-nf(`A@~hF42+dOy8H=H!b_id8$g2u~wd zh9Cp02KM&)`ZMdtLyh9sclT3MQ_QLKU-+qH8{Ei&DGYJ>DS6wt^CTYhSB$IA{bqT1 zc^_Fd;MdMuIwzaPfv~RGBAyaWnPds;iK(NfGJt#u=Pv8-)q`tC+Mj)zyJkH*fDP>tZg|@!QmG zGR;i)8(CF7X%O#(n6#yY5r(DMAk>wWl_9wKrKKRbz$`G(p179BU_)wwDs`Prs0Fje zMd6uT{!fr*=i1WsVMxD0o0%B%jPvs|;^1jTMa4+d>M3~cf8z2e7{2vpI{G65e0jR{ z&{R*4FY}`nR3K|%NWcD*I6OQ>2t!%;>6}u-sYlbAdEAFH>cbV+b06FdTNxR{u_4hE zN;7eHkqlXL4sceZ-58u;51oJ9m8vSsp%mHuHKkDKwC4Yz=_-Tb=-TDr!4ouiAh^3r zLU6amCAhmgAxLnC;1b;3CAdRycXxNY^L|yA+JDr}&hDJ^NI%_u7$pC={m{}m4U84D zChPFQ0RA~t4Sr`XY_G|W)vKrMn4a3u8aVqRydlT-l^_e2yBnh;{|82(0FWOk8VZwTXMTCdPbaJYT!`#e_ zF^#RM?VMZ~;xbr(1!ne|)fb|=r!yh~d*iM(-*yxAw0`kw!ORwa5WZs3(obb+(|6Qr zZsR|L`!_#Xma#6s)$@6T&XjnApc&Gd=t95!LSbK8(+GwJXwu)3&7^FB;crWcD3t z_wV}3blRvX>KPt_$%I-CDR1-9&%SIMPkcG|#w|p^Ed08b*7op@IRYR z4@>NfcKx&5g-(Apn&khg6OH#V%52wU1)TthAh={HO<$e$R*mb*w;#f)QGotfNpI=J zMPnwPv-ykWel}PjCcxC)%YqrD!`JxGEwiB6tD46>P- zEKGjpa#E`V)6gg7?&;aWdx6`C*NcgClbGbmCfi{>R!H;?HYFuRNyvhnXK7$=7AJ#g zFjavi+Nw=hwU`1Apxs-ourzv@mPtU)7G5^3n~Xd8Evgp3P((g0acuZ|Lp~}%MP0#~ z+9&~j;9F$S{Adq``4?WEPSaab1^G)qaWGvvv1uryOtz5X+pJzPtL|vt+w}bK6}%UI>F6$?(U?ZU?z9|GMl^p6HBXh1|gxV(9 zXJg==tA^ugjQa2u`?ij4RqO9FJ_S*FGyt_)DRs-!OYS%n8gKzxpn>l{uQz^ng8n>+ z#Na@zQEPiU7XX-xhN@ls@MB)g{d007TA*9V&e=Z8#8(eFs$#nbRwVmu!TQl?4WUoU zY%{zWIyBqtDRO_6Ysfy3XvM(&vgzmx>V`AgP?>LJvvo(^NbQ1`nonp{D13GnprSj1NTL zq;R+{vj|{7xWic6(zW0=_=t#@?_`tfQ{{YNgu|rAn4Zm^wGW&x0Omsp z$9|~qZo5fJKkFAbDq>B}Y~yw8Q&w2@cls74mLYwC#)_{ILkH(o`aQh6@t<$qi9Naq z_TbjLZrN`nfb-pHO(+1cq1m%73cZYLW!;TGL7HPW!YdpT+B8za8Fnu*+aHnJ)_0;D zTr5|gRCSRa5J*0W?0^iOTF8fM5n}`Q_AUIJ4RV<-!Q6Ydw^)&`&G%B7>lb#aeCPZF zvHTpycq9p8U7^&m=vmyUvX>9_vkdZL{f02OxxWu1{I+I2ONfRKu^P5dNwo1YYb$Qm zY;_^-GqjOgXBytlMqa{%Q6f$4znFQRbY`SZ8o}W&xe(zlux=5P8QRUkj}8LqoL#Fq(rqWRP0ZcdU(4%vcH0c z#=^gU%sf2q2a^<{iUU?uoT;*k@n-BEJ42uoORNO>bVrv>gPN);$T>|K7Ci-3c%Sd& z46Tu~4F(vj_kwwNV)JVaU~S-eRP*(4Xg=VOJ@rFdfM~}{g)a1uFLIvUm1(kL&02$3 zGlZ`8Cd?dkbN0)eVZCLc!+$~@=#yaq=Wf@yPj1|dbC;YvH+mA(a(q-8e>s&?sx`A@ zlz_h!H09)e(B&VW;@D=O|KOkjIXJ(N2uD!+qopZ>nyTEUlUvs}2PHbJJ$6bkhWc0z z?3`bHw_a%a;ft32*Rkds@avObsgSr-I8Q!3^OkLAE_fC7(8=-NzCwhs^_yU_&;hO17>q-gJR0@$Cmi5p z&~4mPRnOPEw-}-t{24Dw9tB1F9ej)L!|*@L3JOXpDxLEB3NPcU(-pL&Fw6kH)u&b0 zHIJkD1Ue?6muvZsbGS=GF7GcGFEvk`R~(kRtwDq_I|;GV`wk2pyD9Q(E~$HqmTKkN z;Dkp+5gZ{kIUP(MRdo353}IjPt<25!Up>#Y-_~JL$?@N>{{++NPm<^Ln>oD>uLlPJ zbS8N?koSF@R+hiHz8+vhz~D@^23he9D=teBT&s;PCz=gQL{a@9Z#BdB^?@qW>vFnC zd2v|l-2vU3tHFucG-c-dq9=i8AK&sTqdf+U5UeL$5XQfpAZYnik(!*@N zw8^n+#fq-Bh{2kh`si1@$<5TCr$Z`zBysp?J9ugGRl>8`$i4R(HA))Fk2M$?VB`b7 zsDNvZ59)hd5>z7w0OUH!3bToJgpa*=;=5jALUUQ{b-54&L6GzTcFZG#&*P|zZo8(l z?EEb&c!C)Rsi}}_{kx!jNlUzmV?4lMKNP@mZ>1ET zwB|)HaG95c9^#ElIhKjjAAHcj+~q=JmE>igP1~2mgAGtS3KQ887~(wWG)%wjm?qk; z^1JU0?I;&e!owf$?9i><*6&7n8I6|f_};JH$vxlsCQ-$~j0;c&3KQ6Ntkf9v{!3Qm^nWj=-{nE*q@7t4FnP#0qZz$KQ+n<(}mZBna zP!*x~IGN-nxb|Oc>g@b_*{!9i*?!;4WV6=p?c`M3(&G93dscOIbyL#=)7vGJ>&fEH z`cE+HxkZaP2863z|L2ZHYHT%m_O*qt^?$yGVRI{A54e#-btgGHQ)Nkc2mnnt!4p{h zK!tH$;pplJkAP2Xk)l8=p<1u~9{FG!e$dzUVljANT!!l%pj|u6tlU_fwmJNVABdNf z@((WjEBlVHP*qNJXtEnEl7^YUaK3YfeA_2=>|xKi?x-H&)WhCjyDUR!ddYZ_gz1vmD((q_ z0PhbN%Smo0G-kDGrrWvoS?GFn@qMsp-@uWS5`0=5Z*Iwu4ZWZ_Yt$A@onV7(T4HvE zR>A>pod#N34X4VP4z`O<551FjaBOc$zC-)?Q^z@PGU<&3z+?c#W& zdqrMg#_`_nB$44XC1sdOp7?D8{c~H}pqtl{9{CWhG4NXfs7|Pz+H!9%Ewy?v6;y81 z?>t7i3+S*!nE)czJf0^ret^4#2G(CG--V>Z#UVc8V8GpU+7ZUvM!l5`} z#=W7~|GnAuc;5c$q(QIM?V=Y~&xi{-dz0?8B$l@@W&tPy%?JyV@R^~ap*o;1Emk-S zYGpr1OOMSmI^*be4P9-8=43D?jc^kv#t)3FH|7v#*eabc`0PX!-;4L1beCY}vdw#7ZvlPFLrycFwbs6n6~ zswttkEb9O1%kdX3{FR8+;=_`s{{OtD+OoL(K0!LVKRc^IYy(e=_dE|DR_{)@USEHR zzkUDyv|*VP++WdQ>1AgwmNGdSrcZ<6U(8CoIUE*q9&Y~!BmXH}wCNop!#puIw4~PD z&&=BETdG}3oYfcHr3bF5#P`5KMuMb9wR*{ofA{ z|BK=08{L4e*F`T#*RWpVgg~I!IXK$hUY~@X7REu@9n~-^NI+P1+lm00D&QD4BZC-F zExE}KCSGiIK8hgV@_C%fY` zByp*RKYUxJ6z*wcWK^doEDzC-O)*U`r_FP6nGiCd2tedX#qQrRuKHofzc$3|BAN%u)Vf0<;AJkiJJ{y9*;)utgYt-9SL)SOfkkGRaXIlrH>)_y zv$n*%hMqFGBkF8~V~G)|XT~2*uDj!|*yakS;lWV_Z=Kic$nf3kP>01GxB+f1TRGmc zcYaqg%b;x}D^ce#6x9pTR5q>he^y)q8R=VQ|x>GR(@^HzUnnOL*)zzi0=>wLMMlDBN&z*S`;Ir0q=s}kH3$K4g{+OPx7qa35KXL=G03u%zEDzlEu z{T5FlsVl|9*^^<#t5|DkMjyt_kLryhYfN@Auqh0v0Gu*%@>n~~-<8bbxZA@vHtAu< zh{%r28gss2a>f4wFO>orpdu%Um~b$hZT zs(Ah2g)VUYFGIldx?c`&P{$yJI5rGteC8t%I#+mq1{b@gwRA!)o98m-235o>f`_DjgIR{`F znI5OsIwGJnlxwh;2rs#OZkD4R)y440tmNs1f1_P#I(Fggm42oHz-`4s}e3(8)qp$DC9#;%^* zy`SoB*UI-VgYiKg&xF~uMcHPTe~9ECb%r_}!EXkB#rm>Yp2cTd7Ws- zC4JHyRsBc!Uc^tOM`k;bHSO$b?1eh;LHgXQ(99w+<~osKj0ZW=lk5#rzofAEHcm5Z z7;FriPGVKX>U#gQ-#XsBu+jPn3T;6rnl7-`kV=z=Zq{2by>2qS=5%xjeME`WZ6=S5 zq!cFQiQ!I{JM-O+0a^U`BrrW&7bGwH;{4-BOh51L?v5JtKlT|^F{3!%9xn_hF^T`_ zO$EXuBN>^FLgQ0^mtvRX)ZgI64$&>oq|wr-gy#M0fGrDD8vLFGPis!A@sObb3DsOI zVFxi6Lw;Ysy(RV8KIXeco-jX+3L{*oN&p$|y)>6LjisiZlVnu*0ftle>iZ7_sR94k>Bx) zi}R-tI}Ntnko$LZb*7g2xFa{*f|8aHwupd4SY&;Go@uM&*;Gc(sD5oeWCg9<5!o>` z0rxYCUuK7)S4kddLfvua+0kG=m49(@0a`Q)c^~8@5yu%bP~3l2n*(M1mn1RWS??d8 zp3J!eRv{2)clU)2yH+rryq%-JF$)T2c;`JRMJBiXW}?K&*F++t1w;Nf4#nq;{zqHw z&3>(U9Y&LuRC|}`!c3_XGLd6)11dw^hj1b9zD%Dct_ufSgGL69<;3RwSQC1w>|)}p zp<1-T^d4g_Q=ECuqByIt#3l66`S!qp1FSNf$?cQvz*ZQXZf2Yb{Ti;SwCG>rxlSm4 zQtyDoop3qMZg!3*?skbvsX@)%Q*NyjaY_+11X~PIm!>7r)Zxlo3uK|WjrCI1avI8c zHgkRoG_s98xW3deFP7$|g?736xE-L8&>|}H`kpO)o37KQfrQsd0;`wg?Y`f1JVQ25 ziD{r(HO`{41*Bze3z0=-XJ^~`T%|s;HG)w~E!J40-Tf+`Tv9MIYAltVMMI7Kb-vhq z&5m39r!_x2yVGV5;)%_t_y6R**uO_FQpu$iZet_sZ6=#$@Hp*9+r)WjP_^HLexyJ7 z@1l^1NZR1rpy{=|#m8a)bK|dWs#xgAUAWqbYX|R%@9ecw)ho2>&cD;YTfp)bKNYst z(N)J4wM;eDwol!X#c6W0Hc-k~YC}U59VS^T{)p%&;${B03m2sC`E*vba7Fo0O}{qP zF>c|Qr#vjZao|K-OdA?22VKb{0Ixr4FD(BiSW+h;Dxc8l;L>bl`>W#c6Xo#a{moQt z{I#pC?d3g+Wdj(xR_4m72Pxb=plV3zcs%jqlocTA*nQ~+=!IQ-DLtz4F?68->+EO1UxmodZW>HGZw z^+d;JE%fC#xZo*1`>mISLAn6y(AZEoDkwKCPB$&jd|TZtV;QU4eCrm$iN%Qu*M5kw z5e+J22hM(#j@RvL0)@xnsO!QbQQ1Us|Pa^B}k!@D2y92^Ln zRWW(z$-^-{OK0mZY(r~alvnfCF69g~WFbFTvZv)vFXGm`!o%fjj6pm&XJmXlq5bpv z|8oKO(#OCWvSCSpj}LiW=j%MtJO0O|j?oaZ7;;4{wX^|lc6KZj__LjV%T zYiepzpk`-gKEH_aeSW+-T9ll%X%Kq7-}O!pV+C_c3A?-xkNgRW zqq77tL&hyZIRne@L@}FZkW<0Pazs5IxIaI0-&$I-5&Bt$#?i3{9)&;ZG-Uv1xhAHX`$Qy_Qzq+5-j#-R^g1?Cd62 zj+Y$IDtL4lHvVA^UyL%Wq}F?TnOs&+trQE?2ygG~DA3j&+j+Fy5`{R*%|#^d?_=L} zIqe{@Xh^LzKHl!2zwVTKXSQ3eRa~|jI~>EL8oD3ps1|ryitm|f1ZAc^^@8H&i@UW! zeh~vm*WUvZ59>5l;S#Q%hTKM;B&BO-&*$y^*I3EZot+&J@UN?>xdNMj7>VuWCeSi8 zbDYa=PDk7FXu9R>GN-Yq#-Xj;XDSs^qpFVBg0tCu>IEOZmB{?p|4sDvIQ zGxpZp_tHUok~&S0yKuiS?o;2^_HunNHCLfG?u&*Q$B`3bp=FEBCGr;!mTOcUoai6j z7^E9aoMV*mIxB6d&b&_Pp=M2AN!HoD<0wh>Az&w_q zyox(}pmMKFj-NH3vB}!;A?Z`@z4^<^(z|aOu}h5V7*%mYrWGlr@Tc6;rXSbDN-@D& zG)JQIfuN%OnyWhP*44J-PR+-V2S0wNc4pVX(`zDcfo{*&{&hq;tTPqB;=xXDdOc<8 z=rA1bPOV>Ao2j8|W-l4Q_(;j_yLFhy1%4D>VqOhH2w6WFvKmt>@w~^H&XW&E^TC(r zWzS0?Z>Bot6@txgWJTL*e~OKGaQGh%T~!jSmc91>zVr{Q|NL%1XxgyQY|O*UdpQ}U z_dFpVr8i4#(7;OnGZ*6BMz@d=U8jiZcT0UIvBkNfWNt+DX8MmzBe@bmMtvVt8T zNc9OO@!7ZI*3{A>@wwmV?Ck9A75)0YxuwOhYQChR-Q)TGVmQe$bF9aR!Tk5)tf_=* zTCqA0m~TD!IN!h9=kQjn`iK^cno`YwO>u3)lW-F_u8nP+B315v(jhFJs^s3@T4=6= zs4r|#?4hG*#y6-h9C=D5;4?{r&HIf%`iR4^FVnn4m$QS75QB;ZiP-@}@>E+**nk`|Z5TGAw&A-IMqL_1Mt)% zf$Qr1(^)GoADi4-M*rZob9ET<9993y#=ijiJd_=1nl{pQuAV6O9pT=!EfBX+T++m; z&~5_vM^_iLp9tB-td{M|jNZ#kf#6LMI1mWU`7M=argqz~>T%@gzkYbEVx(aPnzvYf z4gfunk#QM8V+e0s2`PG<77%hJi}{_NKBHZeoSY28w%0c|bqx*3{_A$!n-}+kaa6&< z!QjYlrmBiX^YLGg(TV=??IEm`A_`tCud{_BlJ`OvIhW{C^)!4Q^GK7(N@nlb9WH9z z^JP-q4RlFh4%};WI*En_?#!PuDEh)fa?*kNXfIW)3YwuE-J+F}+xrlvQMg36HZmHE z=ufHSG^G&?^LLl^Xx&|l+}s~pR}WJfOiXA7Lo`O0bS3Vf@9RRY3xoMiT2URAJPnb6 zlQLqRXsGAbI{nXwIoyrL1ZvHh3LGe7Vb?=JOrs~s_3@9YSew$0t5{kaeI)_2c1Cu( zPW=l>p0*mArJ99YGIy(=4eNisxD<=MEg*VIDJnjGthSjryIuT;yf!4%UZI6*1zC}8 zLe}g2wCaO!X8MHhmL?;PY={{)5;T3kU2C086{JYfRQ;rzWf) zQSC9dPDzQH%VN42WGaDDI?8YGtr!-SwF$M<_@qN=3&A@%i8qh~7_A-CD(hYeu!ae( z5xvN3`rBG4Bv$c}h{gg_>SF4PA?)3as@j{dQ#+rbEhf!WhPrAP7OeW-h{k-`2e@Xg zRVP!5CRrJjTG2+tU=%;q**6LM2?`D>4Ud3QX8CIGip3TdTk*E%nzS+ae=B1+WxNL8 zyJ&(%HtS4uQy6o(QsRzt681SOPC{Irc`o8je9!`H6wh8U^`1uteQdTA{(^1z5 zO_`;urpvN9`1}Ko)nw4ofSOKBd`RUjVY4954MyhFy(EuhzWQU!Vy+_JB7i{Fjyiw0!V|vRX&kyh}R@Q1hnAZBsez zRxUep0>hts%IccC425WHH7|uaLlOgASLxgqVf*1ZVtz%w zxo%m+-H1baQ|DlUCZ5Dm<%e&BeO}g@rb?BE_UDLHV~6B^PHfpglYX8Pdd6?F{1usH zAWiVs_W5)T%1pLe@heAb;%hoEPm$;OcD;6pegg))E%6ptxVR^+SdlAo;zWVID~@eR z1@J3V6n!^P;<+I%%P%OXV{$U=7=oA9(!L_;|ouXW$7dOEqY$Nc`Cf;2u7ANp&WsT6hJnKQ!7RrDbsOBj~+ zSENc9Sp=>0pFA0xAWSGb|2Ta(p1MNXUYMe-_WYliog2$mgD5KpWCi6n;o097^AVZ!2&gJG+WFJNYFy9uuHY=>awUi z$bwnnPL?n@WttO7ZWFZDE*!MpZ=LO}2F%KpwzMY2FOW?p)en`H;0^hFjZd&}{xLrb zqny}6I|m31DRT=lJ~}dVUteE?RE{#$k{OGtsLrcx+s0kNG!q~L>yqQJlj zFFLTiqp9FpnL}95#0ZHqG<-xo{8~{HBNP%`ZQzt^g3^i6Ho$448BRAk_H(!>@q8hf zY&2GOs1xagaIf0U1xc1bJ$o504qKxZqo%K3a)%nn4O6=(M^)GHQI4$MX{#>tMF?2N zAb4jQSv!n#sjn=SVY6Dqo0j~?p7uj=|Kw~|MWcI2W>wrfq9d$7bYnb9JPhULHb%i> zJHrkgpN92JJ|4dJ)_8C6z9l6n!~3H5M?cA#D=!qg=$|LQr?cjx!=2&4+c-{4^RJMi z7ZJ>DFjQqT)|C}FKxqJ=&%@6ST>E3YZa98Y^CX%9` zCMb8VN?m=UZR-qY6OSyoiW5*elg?-Pt+E!%uIcGxhAT&dBVo54MHG3l=4HHE=)&f#dt|za)OtFsEy-y)QA4Wei-Doc2Ut<$3Tz>7F(O5+Q ztnQGge~U?iAnQ=-vMKfs^Dy*z>`*5FU)3zFQ)f{@_l|0TJ?>ZT7QV6 z{uG$H%8!q~J!Bpvf5@xYw?K5jjC-VUk1P%7!(R&8e}_bWB8=3wN9ClLPz^441YXBD~XXUlbzAG3}!|d$f3&;wFk@`Yo}l7FFR)W9^mF*SnjU+H)IMG#l?C z2U~(YkSM|=<%0^^1OCHPL1Kh7lua7UUtQz8&!Td)U4{_8mKiV$Ol~eb1_tf_!kO?P zw^^n_{mN90NYA<)rS~}CnNYb~dFqJGIGp-)EXKt%BlQh$!Vq`N=-O@>47-P{~ca*zv*?VFn6qS=(qH#Rm$9_xH`R z2WI2s3K$acF*`M#MBGHzSGRyl-!vX=ss6Au=>RoVH46ga&+%RRzcz|(CaM=W{vxIW zQXy6X#ntq5!#lDzeVgm4d^^1~9BneGi{aoGk{vu52nbxT&{pM0>Dq%RzJH-buTRljL?$&m^FEk@hKmKVFP zEX=Rm4msO>A)P<%hXaDXMLMR!;Lcbdl1ZUA&N^%WjnSM-ew4*VP(|YbtK@umloc6@ zC5IX{ivc1Ibvlb239k9)l;%_OPZ9eRvC8LPmzCZ;ASmnzL+)M|d66}Mz-S_WcO-xLN!g&)D z6G36K8D@X+_qX4@Bv1g?7#^YJL8D4RRhzlZm_-f5r;;YG2KmqDAPK!5n`2&8hUq@| z%A5htEQza7c0CnGzg?2s+E!%9p+$ z)ztjHn`6?;`mg6A5%_(ta=6Bn0hegzne!@V4*zOp0$*twiKYyYTHyFenM1uCd>ci3pt}yMg5Dn4o9t;pm90 z!PM{PY{6{<+IB?+?#Zaou6y3bPr{ctE|*N@RgFd|TPu5C^m{gs7Be%bUJHYGQ%JBW zSeMqAKwtii1=jC7*4yryQX|7T%k(*o+%5Pr&XVirvHK`l)C82ILu)|dcKrGbto$(& z+m_Pmk*p}ph(W+a*K)r~!YmcbG-6Tm)!z72*amS_!82AV93-zGf-$jIs;?Bi3{|f+SUV)QFFbcT8t9x%I0fr1dRk zHzb~GdLow-5UVV1E@J*H>+sz?kVpvzap$ksp(EmspS|dcLJ{isuQqtH)~QBOvkHw0 zmF$TAGY2*ei)pF_{TnCmQ(Id{Piw4Xh@UoBc9ZA&eRp$=2{`n0Y9^an9m|R96M*}`> z4}PzJ*C}>y7W4lqyA2(6<9vo*_q373Re0%> zl#qGJH0279T(;Nit5m~r>nJo^3Gf9kN-AiZY+zcgUotNtodp$D43AX7s)yP-g55+|!O7PvK;;4^d&Q02A z!7zT~d*B&%c`~Q?#WC@lAygS|udW#d4J3p<=d!IuWyM4DV=KFjhF^-poPyk=S7)=67O}=wf=bQ#3>Bf*y=gd?nKzO!dnBxv zsBddSgxGBq@#_7#V`u!qV}d@)>szl{&e$-#WuARF(Y>N--0jFtx&e6RaRqPiLqgNxTH1vRXmx@Pnmr# zLN`+>02BhIRw2LVFv+OptFx=qxlUoMwb2(p;7ctR>M0rE5lahr5PYFmtoxU&^N0zO zkq=Ji8>(g+?~2KaQ(vl>V;W4w4DVJ~N+`9aZ?g_#qRk+240Roe8-r27QO`5GiF)>g~&uKOP1&&L~^1tV+5O9V#M6!dH6pTjHMPg**d(p;(=ItP%$!Oq^ zWV$r1;!36*6&17*dGTD6WA?6ZhLETTPj0`q@d*`qDfY6pE|JNCROy-hzAeYKz#a~B z$BH1Khq{exIniT3$c;xndTtEdqI0>kc2y+Cn}okT^wNadp!5wW(oeSb?1XwbY>{2K+IF zm|?RSR(w`Q^G{sgp2EW}S;F^Yqs#B4)0Kt$Wls5)$?f^5njRup{X%w^+cOx>zZp!n zm#xtHS$o6j?R%*bDvKsXY`y0lNdDj`tx#3UWYzuJ8Q87o`MP!O68dc0PcO81kaBZw zWfY?E29Yh=1$9cODNhZZB*zp&yF2IHYVv${!nEUYzkjm_6pPA?_T7dGSmMiZ6Xp*I zzJJFLPT3*7D$6!pewRwA7~q+r|5}9|< zr~Qxy{b{}d3ZQ)v!R}h%yj(>SO+m<_XoAGT{`K_0N%DzfwAX6)=q@>qpm9trzDYI_ zQU;&$w8*=GOlR|&ticpM<^0JeW#??}eE&vv+lI@#{h8-jhB}^d%HwG4?>k`J!OBe9 zyt-KD=v<|oPk~L1!##nnazLr@myki|FD67zjN!@8$vGg5t8}cfr^!9&h+y?)eiK0J#uTgmzmi98u&;QW? z&m$bOe0Rt)PWSk6MAcs3=0{V8!LvQJ{Rra7P5gzlIuFro345SCj~P*iAmphAPa<~> z#^H?c3x6O;N1``sH0oxT3V;P-lfJ5+U`J*-ee1#2HRxqY=r6({+Wr`X5LmsMwe@Fs z-Y2@ziHVCX7_*}XU2iRqp=smcS@zbqDM|?CFOlh-JY-7L(ga$*h*A|-C-$o&%>0SI zYxkuOm7=No^xT-vI0&_YmeO@-<{3s19U;uP;u#mzJ{Nr_BM1X%o-d&%J=Iz0^Xx&f zMvZAZ&4%(G~e^?ea&9n_VvUXd9WippNzCOZni#l)ObN>dja}G`}_y5?M zBEZ|761EA*3^0@SyS-L^^0NAZbi0@CrOLsp^b4y4_AjUDXYfcYlkW_~zbbH6<9Id> zOy!HEF#baOyv$5jrAng#2xanv44$XSs%?X01p&eWvS&(|nl+h4LAs$VoIZqEKZ8-S zsWC3F$JP?2Y~K>;Zkh@w+dnl}VKFuRCc*FV-ceYPwY3~tGSP$mF~si3uc(osPwVid zXdV9h2PXHlHP-U6>JI1c()E`?pGQfPpCUmB%jj@=?$_8awe~g6&E@_7w8(g8$r7&OpNe>N@CthEJgaK99X&C67_g4j0pC^pd`-jcZ<`6!^YKCevt&9T_}nO8udj6-v++8EhSNtskp#*ypaw$FcA_bpb= z0v&bcyA{cnJH7}EbCo^}l9V6V!i(SKlDIe^^jWFMS6Db1iDJvnYScC^5-}M0?|*TJX0IK;KfQs)`E%;Ge$tvjC?Emdp)hhT=ktcTiM!7@zDeB8qH(_- z2B{;*LBo@-WL+LtL}&~*Ox6ZO_VcY~Br|EuHFTlXr!sS!vfmzQ$}na7D3^0_BJTq> zRA2;SlBrlU*ou{xAb3ln3@62#gs5Mic(Qx$>m1m-TUw9v`NUHNLYg_aB5Yh=mPGf# z0uMjj+PYqRdaG%6RkyGntWz5a4@KVtZKOU|vC)%(c5_OmxWcHmG`eBOyXgd2oY}>F zFzndNw60ujEj5-_i*)e_-%Yh^_bi_nr08 z(ECYjofV6BxL09C!KG43sZjIf>`zYtGNy6S9EQ7+GPB{d(=LI1F4+TpwBq7Jf8Kc9 z@uvkXdeaagGl88LNyFGkfn#YC&J$&R881aAkZv!XrQP=6gBtv|`Bm|u%^ivX5vZC4 z1~HDYY5d$=Ta}-LCVi{t~sYIS5X}8 z^lfOL3r#u^3jA>46-Ub3-Gb!j3g-q8{A;>ly(BP$3yyt96@j7yeaD^j*dO2Jb`4`t7jNXB=_L$Rf; zb4TMxZ}|MVLK!0(^#}PBFm@Z_&85@=+%FaIDsPI-RaH(ye;VtiS}{Rbh)ytt0C>~F!fU&nkOY%`zMe3@$6s+k<;F?2uBve%!DNm&DPX>u=m(oA*8C6Q?t1*Y^v zw}s~toP*$*E@~f9&Js;LrRqXt2|mhg^FUNTofpgL5}4z@4GymT8uXUyM9FMZt zny7rvpmpRYKvLwZ%3|O|4AN5NxOzNGMX5K^;jFT??3;AL-8v(NH1otxY*53jUXjAT z3IW@?0;SMJgRL|!9;WU973?npDNmrvDkX^Jikz}UB+o+Yo2^ySpmO#92Ujg4imw2pAVboPjQSD*!x9B|y<}uYzp8smA4$9@spPG?sP* zemRcJ{$icbyouWREbVYB4#d_}HlCJbhZ@50Nu~T&34C2QscoJUaU`I({^kVROMh~y z?IgK~fJlE4bh(srdE2~UUrfL|ZS7s$c|LoG;5||^Zu;PKJJA5o8}Q}b1uBxwc7(0v z>@rBtTV@;Q|7Lr{SJKc{L#wXoF$+M z=EvVDc_AHktE>NUKr8wU(#jS2^BfGdhNJ&=|HE7$3rW}QF|O+>{+x2>SR!-kio?1S zCr{xSee90HbaLu7y``dq#%)c@AVZ+jH>yF2r7!ZPuUZY`gl`tF-_u1CoA+Im&+;fB zenGI0#q6I`cb$G$7onocW4$fI!9L;^S)6mo!O&4Q0+&almcS?x#?`bI41+a{>GOfW z6iz%t2T`b*=mMJ}riEJv-(z*V-3Hjj6Un|o-D6ryLPU;}W0#!etQz-YQ{qYqth6#O zZ|g>gr{o+{cEt{e2Lsc%?G5U{AHyrYNW$6@JX7@>n}qd4Gxh>jN5}Zy()k!)!QI(f znAU~kq|qHH)4IN{^#MQ!X{5Dr5N63f*^7yZS-{ofr+@d8{%J9+NSh{hD7U`-Z~ex< zDa!1YPrOQnH8sFI&kSbz29(ehJoKVfwAx zG@bu0gHfd1(v_*DX=!*>x4KHZo<1ZbMAF&}r~A;{W@uee$%K=)_Z*TNlR zON{qA$W;*s)VS{C#W=P6lD9T!f5~Q*8DIe(QV0MY^^jdoZJ+>oboYcZ!eEE4{&Amq zCh)Ot!|uK(1oOW&;gPtgRe!wNXfMrA?0r(F1|F!cQ|MjD5fmg76chyNXtSes{(VOr z?LVq(B(+eoo)Pl?Va+=`H_y)HdKavAqvSb4hu)AkMDhy?yerMNn-~^?2%f|O(%{{$ ztyi;mrWLGn1-})@D_TUdr^}&qose!hPfh~@5jB$As<3ZIn!7aSg;siuC{Th*5dAI!n<6!R7%}WvtdIzo*gf zK#9VmSG#l)BiJc-_+zpnpupbbZM{ zLq%EMap8iIAW!_+iKmF=>A{L~5J|)bnj@C^9&56)u-Jo&yUcO%HHO}!8#FXD3u*Qu zZ)M2Yp1ZjO?@}hurq&tjt77OS9;qYczZ@%Y-0#xVe5xr?J39J-M=lo*_`vsnG<{`I zoK3Lq65I*F3GVLh!96VQgy8OONgxDwcemiOxJz(%cX#*ue&?LKwY5K}qUzn*o}TIM zN17JsBbGF|L7aP%PNNi%f~L`rVwf1)a#k%3ocpp>bYg9X#Y*L9jEJCKx2a~?Lo3yw zU4K{M)Zz4V=k{fj$KaJY5CK`eEPVxiY~5$YLfHYQzkDSh8h7>znNA`RWUm!Wh$uNV zdRfX8Ww}P#g?bW1C#Y{3$;{?>EFBS3iv?R5H;$%-p4ewzLKgp zJb0u2g7`Rg`+yYK}9d@Ls*O4k*K-@$4OR%0F)@wU7tu3IK2I zAGVfbbIRQ7WjC-_jHmPKoyV1cqWjcv16S>b^?)pgk%}piYFaj&$dZfI(3LWUCm!nE zkstTjt}l~kG)dbD!Yct`Rhclzq_!&7-f%+K;YEE7S&&`vO3%2J0c>EInqE&rq>5zibo#W?#{L*&Srysz~xEmS)=EHBi9^2Fr zZc>EA2ttU3d!?QyNtvo&3-N*7eA=QHigr?mKx_$~ep7Y%s-IY*JM0X+&qzgMfvJzd zzqujm$A=~{!Tf^Y$=uxP5U))Xk2+!}gP`)6volDr1z!mP1(g z>zvZ!ex671j>w~&-AW{A8U`0 za8vo&rG47)wqIv9O*Jg8?)r_|Km^I_6rK;hI<~igOdOc*_>}~YrW4nMy0psru7mZn zn=qIF00+w)#mcS6Dv-#yC1(pv&1`-nnnJIerhd_+0-_I16fFvR0?UnT%_MV>=i9f2 zHQ{NhQ+6YbN^Ul7*y8*OrYS{paW@_9@?{OyKfvCGh>g~gX-Z5N(rRSoV*$m+DvpId z>po6$6D*wW#JYCv$#X1F(> z+bI|^Y9KG+gq9Kyr2<}E2N6d;<_|1a1J_*ki<|gFDa;3tw}00z--7xZ46Irp^d0A0 zt2rx|or?TCDD1_$&VQrYg&e)0fSyKeG6uO*q}|)l73Mp) zKjmkP7RJV4=vk$_5$uQI=Fbdwe=SL$u9g9$uJX6&V^szJA~^w7jj|@fVF%qKATfg6 z(|s3)zjYX6tV~$i;T5Xjs4o9T-Z02wQTvK9(wncd0HAd6lAu7{n^oL77_c$FZwC{Z zT14)ugJHxt8RrR?G(D&Y^j#5T!iM zc+?3FPR{&{pj83)DZ*ccZMI`RTXNaH1eX%aW zI5LM$;a}{ZWdK^(L6^s~8+AZuozz`-&NVY%NO4Q>dm_E zd0aE4^Ff<11*zB9p&ndQ{<_X>*ONv43m>POMFU*CINoL^Uuj($>3RYKqRsg#EW#zk zTR>+xeZaUm+|2qRHF-wrEF18YSC`#F}RNxAqrI-^fMV*kZJLPKK)m$>;4O z#@CF}4z5oGbW6-0k}&56pu@%CVipoGw)b~A)mR(YIseQZ?t<8fn2^CI34tf51JujA z(cTu-YA)zSv=aMp+JSdO+mew(_gnB%L9vLkG3_T$-_V>??>74?JdsPZt_sWB)B5n{#Gch94j^NAtX? zsz5h4Z0?#Xtfd1V)HzOCO=W1HkD0DK6;f*NPg89Ro)kiC!T6)vOcqlZ2c~VdQMBCX z)u#95f_?3`#LR8O4W_yne+vrA_sLKDic`8wi{zaeB3g@r4Zcv8c%)&5cu7t&$6}q% zq-~mE3Mq!cyM3qsa~M=#D?7(smJMkU5KyeQ1)~Fy z)_p+dwJvor2s>Ll5nIx+4SN=@%6$CQ*4B?qS6QdW4p&!K2t+B{?63)D)w1*JDQD{N z1;m@Lo2TeJK+?b<{2H*Dr1aR&iJUN$X`c>hqb7Tq%5{Q;gIvEG){)@-6x_^#7c7vL>0UPDiS0IpE#yR=0Wk&Xm?3dpW48*E z@Vgcd13$jOL1cb6v3a+ZsbtZnAy&EbpvL6t(M1FO9aLA`^T1-WhbGDS(Q&{qz2n~v zJ-a)aG%wz?tlCFeFq5w{{datdi3K(ZaaoRyAa z(;qv9N*4R}B!H|5%!@vwlRTcSkmzq`wJnm>d(32zyE`Z5ppr&JX%EyD4aOY0sIt3r z6Wlt8*zeBQR+mp^GJ9fj0oeu>xY1_*YFgK4{j+bV{Si?A%uViJ=N6JW~p!%NT)y)P_?7s>%Tb2K{D0;_JGLqzBXl~k5T3hXEai*Ji z!nYjq$yLaNIk=1i$5AtE0`=`DZTS}Op5I&=2-NPFk~7?)ee@RapL@FN2hPuzYxn(p z$5Yv5z|9Ik`Vx8eFn7DVB*?Z$5nyKryQCJn2-4J}7RUfKK=Gbg_ogoeg}Z+93| zmk&Mb+0ME^USp;ORoXBsKi2IGeBiRxKYVl*>nI7eiPvwA5Ay2L4~2vKa4U{*`soms zhl%WKPPO7=pLM0=Cq$6qFd7Vv^TZtzk<9;yCe!I^OiY#Qks(22bAPTC;_z3wOF+&x z(^^u@99^XCml1m2GCCWTm2m~TANKV;HDv7ntaI2d5@XLjEEMznV(_u#^Apz|D^t-8 z&83DwEg|OounD6(i7SgqYCcuHp);eqn`dyNUDn|I_Ktv@f>jbHI7C25OMo{V@)znB`JCXVS`Y6Q1 zcYt{QZv>7k@np-8>Z65<0{f;B!o|>`pEJYE*}%1=bvOJo+n%ze0Q=I+^oQ!l4#8>< z;pzuokgoIDxs3gCYDcWr=aBKXY$ik0R=bzE&O+5nvn5o}!l7WW=_*b$xi+fJ-5N%n zPSa9_VHLYGj@ua6PR~pJK&cG0G#%KGG(Ru|)i~04$JCc*JUB9$^BE1~$&swNAuR6{VnS0B-%CGN~AgoUX){P>o zULCK|XM8TSb7}X1m?%5mSn2H@2;P4Pc=!y2@J%XVKsle0^;>BA-vfRl)CtU`B)h7P zWv0jhgAW_kt@A(L19r(3hnXv8PJEgE12BUtwy6WC7z8Sct7jPxRLIn{pce>KzLNeO z#@NT#ELi3a2j6L_pt{R{d896=l2vg36Xq=WM%&g8yE}0L77APB`w16%qT6tu22_Ap&nNvUWU@6YF+K6_J!#gD2+-`K;}zug;nET)76Wz=(q z9&ZkJQR6r*<-n%9_4PdjKxOnrQMu`F2;-IP7W-M6z&zh=YVaJeHYu`|+P2}07{+~E z*ZFnHg}2tUn#mQn^bcn~KkKah`Aj!LS<{O3J8+A(275=Fp6~GzEZwmy$f)-O`ZNmM zR{ffWJN}(#;&TRD+7x5&dOat{!L2^IUef$|LeAozmt^!WEm_Cc3HYK5+V!@P@1C>b z1*^lYibDc#YYwc6fj5kwesoflxCdifx~_i!^?Jeu1c3rf%o*uHyvBX?GGvxGped9% zvrRR%FeJlpn?FV9O8EEm1sBkLM2sLMu03TWNdClqKf7W-wyP*!6}=W~cqkOzxmWWD z-nv#K)*WwH_`wm4+3?A`%i^axk$)|zatff^9`M@)=wQ3M%AR%MuOL<^Ivs>hA+2jg zb1)7Ol^1C%P&-7r43j@~1g6!w0_Zd=T06MeFi}sZp*)@ri^6a^EAYjCQ~H|{Kb89b zJF+1l3Mna#`<7e!)J%!`=_*M{Nq{-&Xh|lILbBX$?Z|TRDxr7l4^~#JF%7^B-#vrE z?p!R}Mf)}?i^IJA#RML4RMt)4$|ixWlF$#*uEN|GuWg3a4O?4l;DWaq{n2Yo6F^`BnUApb zHSx-+pkKn($JCohTj9Vl?a$?;(T0E>a_wN;f-b4~+6po-W}?+Yj+Jtqapp>jD{P|k z1Pgkh>x*MG$G!W=m^-%3I z!4D2UihVYxT$O)nYT6q$EXn+(w=|qX!U%o+F?8V6bEgp^xp>MTX7;U-ULE`Q00G<@ zDkT}#V)ZV?6yd9T;DEvOFq8*OuU#nTlA&ZbK3w33{@k>6c;Jzld_ zV$hT1hlIGW;vbW(U?Ke>pJ?Vr95|ce{;4jfeooKKoMYhuWI5(Z+gx^sp8fm{g8=Tc z1UYiQ1lN?pcHS>e>bVwyZTs5))Uy8N@PN^s*Dz^6WMy%gbQR>q#nw} zlz6BOKR*0KOffam_WEo$A=Cvf=4MK(&57mg+F^NK(Rwju`{g~@v=M5Lgj8L`ObOeg znzNBC4XuzWMOn=4WXIskaIFw($A9#oG!)HADfotT6`!&H|C=85*VgOiT_|)xjAz7nEMCy zDw_%&inKUf=-qygwwjQu_)KDT$~ht?6m@$Dg&UK$#+Qyh{)#;;Is&U6a;&n6T6Bf0^ zYb42mUp{e~nWP2fYMRj}K{gb!hMO34snT}RhW_7qgGAy=6_#wV;0z7Un{{q+s5o_F zuc!W-n+PHAGefq1B9t+&wv@wJt~}*oP7|OfeGq?yFFQ%N+;Nq!-y%Umz4JF0<&#tR zzEEc*b799%l)=!i>b6zQP!}5L`d|Z}=^L56d~O%l#Ohxj3%H%eWACDm!TI-(u7@NYKNX_*uV`QQS6`d`B z)sA@*vx_I*3D6AJV2&04aK0oiH}~d5foXSd7qAN%Qu)g3@*8u(?SgW~YO>*pvI)R^ z$@V8qr`W{MTgvc{Hzn6wnEP5_79&M9`k? zEg8&^Q?k`8NSj|+D@^CRHmfg*U1CL{Icn80`D2~rPd~cw7NP0%{kL^!ZURCE<&Fc- z@>>4VKCG8*bu3B<6rFGZY-9b;fS@=!uFz2XC}>A^SJ(XX>+*pLR;IANT|yzA17*s% zP`$lC6~Y7wY5JV-Dk&u)LS(*`N$?zng8T^Pa6TpVKlWNi!Z-(|QNIfIaOix zFFOhfR9IaFgeMKcQ=QiNUJcSgrkUw?=H!P#h$(VclyQL*i>h_?pEZ~qt(@TF+RSFA zzSzg7kXUYL=qu2%G!n{)57`59bJI(w?BFyFqQ_y16yk=C%TUFz$Q}DXWAOQjvSB=3 zzis|F%Z=j4UddE{ils)XZE*LzjF_s9!wZci~BM~98Hn1kr~GL6EAR3 zc%rcJ0*hu1S{emsnZPhDv(;Hls#iY1BwdQ+Tgyv#@G1M}{27%B4DpDU>Uah729vWn zuSB{ydX<9o8Ux#|HVdjJnWv3b-jzh;j;5OZAS+9ct(l#%-|!c`pOh!a2!`mtKtnE! z<>04#Nb_VG=`d2ioI<={v9h}!-%Tfu& zzzAKCOYY7pwAEuFs(OxVo!Ft<8OZA;|K(PCsg)?8T>@`J5Mah!6tj4&MmI{@D(vIZ z=k&XMFEPK+F|ax&oC8e|EfyU@V zNqJ9mjjXHzp_S#J5fd+M?p}HR{>Mnix76Gh9&O>~EYds{O;LNe%7w8uOz?Ci@><*9 z1D$Aln*dnY*Rcv^w$}_RXjq7ujcOg4#3oJY=vx2M-7`m1`DR%Lusai@PRG(coyRku zw=ZW?^)!~@89Ov1WLtc`>vrhQtyC;u`8|p7;lqg%Ifi0oebI&(@YpM; zC5Vke^jOqmsHZFS%5}MI`bce5n!3P-qxf+DupKq6OF==A#H>GLsQWRO_U`5eRHaj1 zTB@X=fCtesH8bl6rn0ZGfZm|jc2dVnfuE=Cfk^iFzOEw+K0D>pDZKWbf4x>KKfb%7 z%G>!nKFupk01%}!3w~FB$aSiO=shqQLB9v<{-!z7Ri|3HJ0ucMt|ABg8=RSH0k~(a zb~a}!)0oUrY$2&~^l>+hbv|M`?a>ICGBC>j=rAM`7D~6K}6F(7h>si~6 zdpqDHLTXyot2|-T=8JSzTgwa`?IXgV+y>5MG^3{06RzBgmY#CC4M)s=WNe-oEyTBZ z>eU$rf2Tjwk!v1{lHSk5lZ|#yN?`l)7R=aj{a$;2CuWy^pRo^Vne<5O8U|heCNt;V ziO%IDZvV$=Iu&p7lyAc*;O2Q4F~6TTUczwPN=TE`RvNdxEI)UAb=DtpUs~fT%S=~b z#B-s2R)CV6sRqR70049tya-^dx!qpqR7%f@1YJhCFXu3R-Xyh~`0|816k{ zSsisvqoS~~tggRpJ-_&sdP%9TtITRErp=CsNEs$YmA}{iDlJZ_+x!sLWwb)nnpbL1 zD;K^UZk~=XF0$v;$7|>M<9SeUOn(zQB@UZeLOz)=`4oKj_qZsZIU()TO5GNEV#fs1 zJ;44U;AgSA$i7Z0A-+Tsu64xHm)U*ju*^ZfYflCW3%ef_=HO`ou!)^z`JVgAz_mdn zbhbtY3$tOn0@VOfjA*#`&nxreS)9L$)Tpzd)0U1jab4j>w)U>yp0PSaONx^p;|bxD8Nw+rHt&?gx`Ux6Imu7&pj)aCVc zSkM7Im-_=oG^gM!Ib)$=ZdhMM|c=R(da4+CKp^g{?`N-lC@KX-^VG@kCfziNId+#}-%mX~!* z%E&Mab=JiBjx_ae!*-wR?`~5RW7+fQR&0I@=*uZR{b)0>@$zRPQpucSnC3s@d{ya@7VF3WHlO>tts4 zQz59EeDaA`-r?@=J^_UUs5)9w%XVqC-L1kryZ<*-O?>ZOagW6su}!xusgJ(tQ320u6?e zC3+#gM|jIH+f;$o!m>o(%QLO3bqP};)2Q2Tok4QAb8Po*ZL3u;4RjTwfItnke2Yd8 z!3=A|VOOM?jKvQ@r~KkuwiW##Q*G<-``?ya`eAHMIEZ3ZEQ7;~`q~?!|0HCSGEe zHbwkg))J`H_r#=kI~E~4^qRIYyeBHFc(NkwJZ$e)h4>WzZQNQ|%j9%)37V>tnSo#AeFyH zJ4R#-^UKl#+lB!hi%Cb?d>UQaA7`Oj%Jt!P$hWq)8u9$eTIQ?`nDykV&3nQW=Oo*A zk)=PF%iDG#r`y@1lxz)U;|a49GR=si;qu&`gMGXB)oU&%fpcv2g~38O zHqc>xc{#3r*nS%Aw8efM$IuHgL0y{BcD`n&qV!2xL+S%7&Vrps^%>~9?8!E|;BHpS z9R!&IBz%y;x1#%zvAQ?1p`xGWnokAVp-j3RgDDqq>DXGtXf|I--n9Ib$Df7mf{^!Q zqY<+9Dn}IA+gw^q^0W~Q>fQF*3wC&aedfTsr@H05XM%;WUOPBaY8bGX=;$q2TBON7 z0|fg-Ab;I8cs)3ne1i&*pN_O!Hd{g>jgk2ZnQSeGy0K=sh7d5Bj<(9`^agk36kG+}4b|MX|X-2WR~wV_)<9_G#EnPN^);D^@XC{}$_i33=2S zXL|M@wSyt?4}7BBG4>(r{S_!B{m+b3f`gIj^IkW@gZQdVAmRVJsJNkJ$oescLkN8O;s*cz1Zk}xH4uf7gp?lC{c5geHaXYM55J4ED zW+YdSp!}Xqz180Vn+^+alTnUQTN`zKuYe2}n)dj9_|XDGTcTCLUW!pnh$Bwnrkzk=J>`54sZDG-?9_@{RiIvmA}x~6;f>;t+;A2 zpl&Wp78#23eqICg7I`nEHvTd*Km$^tK3XJ$0f)-*mE!&FB4$llml&)(f_hEW;l4zA z!DE)zpLV_?kP@Ns2$Jd?*`&?B;-T~tss_z{)oh^z#3n-hDhUv9UXs>wm@D^A$@t->FdbXYl&v1nP&*`peNqafkeJh6=#W!HaVSVf9I) zzj1HQ+^_3-li;I2z9)~JD^gYlN9&e7<}}CavnoS@);1kk+d!fUJ;N-~fg>;Mm?=(P z-cC;78;^evx|MBG`wfWM!Q*fG$c_cJhr@m`Y0X^Uv8bA$pOfe|7qek{w(Rkiy*z6euxI zb%JC=`lR6DgU2(xds=f~+Ij(vY2#%PoX7Ct+l%)fxWZ}AlYee*Rx)YYMFe>SU!-_n zUarUU=npg$?~?s&Fb%N}t-Y_Rj#SjAW_<*i>~vjY{C9OfY7gnrJSWRE3rYwvr0B-# zidm9Tobqc=&2hzhgqSSJ=|a+;Tv4F%c^ZRA!lIDAXffh)m(-5bNk$S2$!SE+^PlcI zHQldyj|+O!>@fbCG+6SJF{v8^+Rfo*nc*&5pN~LS(&BPSdK--tp%bUmQkWHSi)V)Y zNX3pu_5yXtX`S*Q1396$G$;_BatO!ACMnnUem%6r<)#i6CIck7F1yoCyVEVySA1Bg zbkGlIkXWs7d8SaA<|;sQup1US>AId1q9uqO7w~-#ADb?rL_BS^D2<;dmoR_!Q4(&p z%J?qWaeB{ozqn!;Ap>f^ot6eEz`Nr-KgZaee9e`j!~FgcbEZPvc<>HY^QJKRBKek$ z298ThO`g1)f3_T(*aJbd`&?PCx*=s*ricGGhoi95*z33IZkghWuWRJJQ+cM&rDWWg zOhukL%#AQv$BRa z>2YXay-X&FAxkzrTC~kvw$9l$6~4 zBkq3{E1GFAEojv!o?EP5un_c%TRWwt%Frj}e;&lY3?X?b-Cq*#c-X(JE?fTgoSWO+ zfA_{VN?T9p)rkd$VcoBJ%W`)`1wmU2OR6H3T`|R3u8K4&I$||AOT8WkC&+J6)Y{>V zeLjtdFNgp1znL02YHN=-?1Q{AD|lQRAyFzFrN#8(ADxEw&;&N~*tctdS@i zEAxfYHSUTvciV^rm*j#%W~tJ`oPIzpU_ z1!K3r%*8kSjxwv}SK77z{Hw^TnoP<52(VY{{!AWmQz`s8c{^QyGpsPo^4m>FI(XT; z&Z>WL9P_2fJDd0D2p&%Sn-vqd5Wh!Eiy*H~GCpUVf9%}x^ZbSNmN&qVFqv>83WO*7 zM`YoUQrK<_{1s^*CYA3%*uXKC^+(^FsB&NG*z# z^z5C9^{Cw$T!t?|Z^F&*@cQ!3+dJF?tyiOQMbV^i9ryCZ82CAGi09P;XC#&RZO zND>%N*B|oE9_=?;O64NG3`K5k$9UXjT%{M9-xBgihSUa% zBI@kXy_lBi?<{m5o54IIN^e;x{Zh})7vXdUJv+240ThY$eGW&sopgx#;jtE$te;&6V!nv z2z#g2_Bn>S4wV(M1idl+|B^su`QB;k{OY^1Z3l{f>IVN0x8|`h8+hX)Q$?uxeL%G{ z8{NF$knCKdE!Kh^bBb&s53{axjRhiIK?Mz>bee9s^_>3B{S$LfC{Asg&o9odg$0+` zR}l6=zhlwMC11%nANVgjQ&~P>AGm<5T>YP>Ny4Nka=u2}0rIa{pqSOmhpn0TwR*_3 z-mHo7O@*GDr+1*d*dh2UfpQ3Ctk_*nDxoORqEI3hylVH?{`v|1aUZs$?X_Ht^Q0|i zu0xJ2&QBVJ2^s%}#^J7{ihO*lF1kH&K@M6$a7L&{_=>Pqs9p`dv0643Rzre=3pFkp zwml7PuNOU0TxGSdZvmdArZbf#Q|1LEk@4?j@`(*^fznNQ2@;#UR0P`tMi>cM1M<|0HIyb8r``b^*7AodESc^uEAK`vEW?fCmv&6u%0CF*oxwUjHZV_io zTwW&&F~{@vc0Xrde^UF$Y=`s_CSUH54E>Zj%I3_(g!)>RhSJSPcBsk>Tad3z<|L@I zQGx*Mi6Fbj)gR=uL$|lp8<=g(FN}t&T>{%HUw^>pNMRax=Lx%s`fmFus@wjQf}DG3 zyZ7r$4*VA(cL2A0yyH$uiS6Ko#_-l53$sI)4&L%NjK3b)-qDOvj6r;HweQPck7iEg zPs`huY{|Q_*d5N*Te-UUj7TvbNa!x|J?>I9ad!)Xxg+KyjFQ~E%lDS7G##>&otGf} zNO>~`x5dhgCG_u#kCR5SYPK?pkgN69*dgvAm>CoE z5oA!QIbGM(#CJ{HxwWNWfBsdKMJlnNuMhv45wtOpBMy*VIsx6D-QlFsw6bV}_zK~) z`7ci*?{OSk3x*#4cPtN!L#e5N*t6Di_fk*}^7Hm{)_bTY7o~67qmQ49OT3@qg7OWrJK1lPLSi)5Y zj>vk3Dj2-Xsx4AUo}98q3nBr z{DM?rZdjU`4YpB|2gWd6^yzKgMRbq5r;rm;eF+{*=cx2>TWhn$OYV)J$<3nmT5zE7*9WJ#5C3! zVv8@0V7mXU> zJnAK03R3j;c64;xA8XrNT;fauEPM)gV{gLQFbJw&J(h%gA*V74zO1vTX*)Jo`m(BH^-F$EL!$60fC)%; zf2xU?5I|Rs(Kj+-lONTzmjM3&e4wTG_RDJ_5%H4?MWCb{app$PuVhfzYFiez)1kKd#&-eT^}v#=PkH)GyCcACV;V;sxb{rf$yxGjJ0 zAXh$V$SFO>1rLK;G=8-5N6Rf2JtG0{d@tGjP7&8(cbi3yOq_vf^7G>yf#4Pu+BrZW zXo+SIN zm`66Y7eUrFOYqS%R>Tr_U!Lm1t5ce#ahh;$>m2;`scYccfgGq}QybNA`{{)- zv+>HLv{CT)WuT?0%Giue-fp-UBd}W35knCcWXLDd;ZAk^W<#CIGMBXER2o9!AugPJ z6VB2CDbSb17irEZn2S-H&5{8#(47L><-));SE|JKXr@F5SMWb^64KVIA$c{o%F1b- zuOJL0SlO!Qk|IFwZ_!suwK5Uro_MU@quGG@2K<#@DAw@0#9DZk;jmc{jN#?vQ%8ED z%*l+%6^l_qB-{bSfpxl|W2cMOJ5Cp)f9v|wQ%NzL7ZY(jagbR(n2@5=xvSr zlAt6OL%;L&R`WHR&IfM8=PUz?IN<7w`|3TPC69>`VoP8L$GW(lIW<2_?3()g)HhLN zCjHBIv*0Y3yqvDZz6e6&yjruA#zg({q@plxiyM}b_TKk^Qtn{0={Gq!CUpetTQQ1Le-%Nh-qB`#LOia`Lx{z+is_2l>WW%L$*9SKyJZh)+6mY z%gjVVv_NrlcZbKt-R>_}ykwqnj0AL;F}50c!j8V$er(;GYADd>OX_!AN%&z*O9Ml- zR^TL@@=483cWD==%0|5pz0*TZ@4n2%y8X`^u?u-y+vb$TiXfwdWy~k==YX`YIN6gc zZp2G0^-jsxkrEK~1m|Yr&}#hu78V{OM8c}v&;}RKuLo8*Mg~Td67vxd-!@yzlOV6Q zaPBkFo#DR!geIMR28OceNj+8`b=8S{8K78y-nj>*3wpCZ)myw~O|7h~09jSIa$evy zwOKDLC6JGW$)4tJgi=Sd-quw zcfOF7vu}8KD;v%YJ5PfC938i-w-x`WooX(~?qIVw=WVKWbznJX>q_5D_koY%om4ae9Q-CAklapG$m_ayq+b?2i%;RnVtg8>cwF%I{~FnCUCmV9*| z?5N!?jg96<_4MCVCjrQc-O&qnLgHY>(uWA#IOT~J4nkk;T~J%giL>G1Y5UajYY+5t z#f=;EfwqA#r;y_G+Am3(EvG8l&$@RfTCS4FUnmEllVvwsO1>~me*7RG1zgU5Q!yQt z@*{o%0kL*5e7CFdpt5?R>#WHF93TWQ3!ot zHJ{d!a$sNL)CKIztnX7%ui7=4Ck;3#;Oop&r6~9v>#o;0XY>GtGs^RSDG1;%^GLW6 z?hmrd{q??D{r^~i?QmZM+7erk;m+zUtUDKCl#?B;eN%XB!*DgDQBBP8KONclqd3q% z#3KWd;8N3=*@*-0Ut$|HG&Ch2fUe0c)Bc?2+v9#on!&nU)Up?lmiWcRyPGmPY2L7`DbLHejjB?!8WT+6njTrlqfo62wkOP)%1N< zGT!}>EddzM6xlsmd|$H=)4DC`h);NIoy#rr1uouGKJlVfQFsj;cqnjrqiXZ4h(SLi ziO%M^ghW@N-&hAa95XA`b9?_(KYL|NQO)*q=QvwaeY4&vy>-C3nU(V7<;H!Ks4xYL{fQ)UXSC<&-5eG;-tj3o*bgym$oA+M2J+I9` z$m@048V(If15DUG&6!U79wo2UsPum@U&mt;i>pGO z8doF23_|Q$`~!hQaWgy&mqjJxbw-uMeeU*^Wp<0B)jC( zhY9gHI6JdbE_?Z*FF6`iy*Vyg5-!HgM^W@2Lv4rAVA%T!GGUgWX6u6iyT7M1NFC1< z;T|1>&Dop*_qANMmW}%;6Hv5Cr=;=|hM~r;#hLWw*Y?L%T1y(+oNwv{=VYd+JbOPJ z5yyeL`Jn2#ICCQZ6;g66%mq6@&YU4=h=mpf%M9X8ZSr=YU!ULU#?)zKKWuFEL86Gf zM+Ao#O4SaEREv~U<{yEp&RKd>vJ52ww-b-k*$N@a(?n&exxlXnNbVIjtmqqqXF6=a zLBv7r`0|rVv7u^7HB&pi-QT~_mj~^>_?u6Wy3LK2-oFE@tYyM(t%_JKGLt<&bw$p= z8L<-rqr`>gVH3+ZkNf{AN-ZHW&EmBy&fsU}fx=!$6XCC}1*`w^35~L!Fc#8>q2uXkx=^3m$cUhJC7!9 z9o~Kuvcn^7vK=ZcPYxfreR{kjI@3{HJ%+>qUhjJ)Qg})7!v9-iQ@5MDj}|z|Xr^zK zD(v*g3kmhz!j)=EKR*{HdG~=v|0eszWmxs*L@^UC#f7db}^R&ayzoN`Si| zWd`Urg||ciF&867i{-LnGqo`Gs+x`*Fp3=)X(>-9iux5Q$Y(d(=}BwXfr)%qLeYid zLnQBgeR67Q{^aSXHtk?z8k>2P0t5AN5~^ePyimA7SUhJ)s(Xz6^_8 z;n9z)DKLK$#rCA>Yh1bRN6*RA6}SpmwuVX;2ardUWO%Qco&Z><9CPGKDg$*xLqd2} zGn)md<*31gOeQkP|MQ?`mYaDJEeeVm1-G)FH8;2u)`j)*95N4~XC205ui-;$!2!L^ z)Z}R^YG_DB;})OQ(CD+F7z|#ENT6_klrsct+58inwd3AY{yB++9N2 zN_R;J5(-EoNH@~CG>bG+QcH(ONq568wRD$sEg_vtcfKE==li?f>w-UFXU~~)X6C-{ znd2W^wDr$xM4PPrcE&Hkf#@IC(_Dpr(RH`iX}xiJ$;(3I3|2+NuSQ4mM*iW3h5pIY zfVY2GcKMwCPki|^$kfPZDJ_?j&nM+;z#F`#BcmXJpP_co6ciV1`0A`;EP1alAMP&a z4;{Wh66+?;xH%%%S_~GKdb%XGU3m=1)3zjoAHA>BEjFNLWsUlr)Mfq7OHvyiyUsj6D36LOqLxb3vvSy9aIz1x%Kg|BTP9H!8e*pLK^zG@+@8kq$xdPx78 zeu>9Jr(g}_0^K6g$P>CY?M!_mqD6T41&T*8UEBMlg#+B8JagYMvFh7$tSjm8EC{SJ z);Yr;Bo(0{K&JYwc}qQ%>0te`I(mEr^r$r^jCHaC$ZwRDz}ePaz|=^M%uz6=Z_p8t zG<1?O^gHGqqGmXu( z;DY+y{d-KP|2ul`GjXFvBhnI*i(Q&V71?QgXtb^%#Q4W&G+zSH2Jao;bYY$N7r+TV zA;j>|Cp$suKG#+qiLg;ymy|Esz*3J)OYHb(XcB{JkLhY7Q2N44sBvc#(!(cdq<5&> zw}s7>;B*#lEn>W8H>(?4!DweznwBbB#(23i&CLOe6|X)m!|9cd zKYs<$c@L$@v3X3)2GNi$dpU>RIoNKu*}Bvjq)~b~49*S(gL?GJFfoMv zQswCt=bUZEP2hi>{cQYf zDft_!hUMbaxUC*C@$zujVv!{E7(%Qv$A2?%{)=;eEYkV@}*B^n#t+&%P#xiT(Ub`xE8Q}$f`LLuWl+QV}Re1u>V z^zCd-`Owd4FXD{Q6M$bTs8k&ExdDbN`9Hrg0fLn0&%(lLmwHoHcOq+hOmpGkFOVolq%gHy40nQ-N*&9ZQg$!o`a_-s1wK6QkIJEI}md|e>cRd!6yhw`M zON(%i-UsPMcs@SK_{c6)V?6dk)rz*}O%q0UcL`$CMty+Zh78$48}^L@)Ei39zWdtj zQ=j`CI$Ym|-i936M>dWFgi(tPNJO*GmU6p2>)Czwn+g2ros3TsIVN+efqwIIjz2XXXtk3ks zc(Z<@(HI zDy#aO+{!z$B%6$Zj}fTtZ(;o}X9Ju0>)8RL$&hmU!If*&&`4$Z6yB109rf!L#`1$N zEVt4TU=R2#PN-uabKD$|emW|RCkprN>JYvcf{s)TaO$S^?qw(9SRE&vTrObr6lx?E z_LiyrW_Xh_PoLFfY&$ZmR#NU-Nd77j`3a;>GF;k%Z;O9sBVDUFmQ4ccp%oa zRQD~V574a#WoM*{Q(#CdjooAFe(`j@Da-4}CjLL|R_di@wg)7SvP?9+i>yjB;|1wA zFY23&K=)hCXA$YaZc-(h@4PeHy2ifh@Lta{w+I13hhnURi!p8npzVCPo{BS)*Zlvk zJR#O!O~EzV;jnPprQaJVckGsFc)`%g5sGp6ne*bk6=EE&=1Q?9 zl8W8>ayTgVlA)xWQCl&VJ+ij7D9GyH`_U@Na1pE4nC?-7-tij_O?DHCRy#4wSIeJ^ zcDHH=7RvyTttgu|5&D|BHc@7{la+^Vh#c9CBfC!WcW&=|+{iJ~^0kuq;2#%qgU~m9 zyXlnFgHw%cEN$lA0_JmIe%Nr2w>+iJ?| zGCN~^jfl{#1O`9Mt*1&ou7C{ps?AGit5vk7EE-!2~tdUplJV152x@c^@ zW6Q>0XEV*@r_8i9v&djxL6^ZrrL)vtZidt(}JC#wqRUpgps7AYxyB_0s+0Ihk&2FmtoViK5m)*ff1Dl-ZhKg*`3 z)^foY8j1#hyLd9>-=k!B44}Mee{o$#LC9VRMlJ52$BOqfJ)G--C^Si|c1lwaPgJUW zO6X2v;*;nGddXv=O6)If*_I=5FUkKGDRno~9GLnCmI=v=N2x=lC9jF7zG$lG)0c?8iuhUP; z9*j&~BK`i-+J}jDFU=N1PEb?1K&ZLMx4DNt%t9z~~=JKB>t zCCBkq{dmT5j>gb#Fb=40#)^=(nQK#>nR9v9eQNTZ_T^crz@2x9Ck2NdWJLh4adPsib^oqhU=^d|#^qjR8=E7m4#n z1!a|K@A~4@Y+*fQiuxnOz#|~(yqt-P#DtAunJm;~s(cEP{OZ3|d=xKoaCgc1ela=f zkD?iFMa#Ie@6^3Wa~d3@b)B7;GY)im0aee)!`)7ZzJ(3FYL|UZ*b)~R zGB21<(gF#udAe$~(7^!a?28zkVZgX~@rKS#f;Z&vR{(D&Xc}bQ*->&PrB1BnQiAFx zoQzXgwyQ)pev#>IVx0|sDAk)N*tPnl_2^*As|~HKQ9fyu;Y_bIhczRy8RRiODU1ol zFx1A3cK8=$7XaqW92sAkfV)XL>*x5%Tf5I302J57_F49;Mpboq;rkqLMiC&t#m*oC z?U4j75qCKhqF*%n=)SDL@bqLjIW}Cn@BjPj`%uN}da{HDkoo{;DHs_!(c{+P9vsLX zX$pjIcJ!gR8WkVUhF|Et4ZKNMN&TN!lVuE4Ejuk;<0`R;kEaVKIF@j(8}lzd!0nS{ ze^DgVm{|sTsV*$%3E;6{;{IcH+4cGkkX{$&S*8cFCGpxBkD^LLoojIe5Q;f0D3cY? z4inrM`mWn9qEq=SN)6-DAz>w(0(JaZ1|wgn&1gJA1i+5F)}Ec(*`c_Js50M_N=i#U z5TI-%5@jOuyRPc&xOiD>+lubFfuuRH?FXad)Ufx<9hRCvrL%rYzxOfYe)s;rc6C^) z&}wsnp|MF{XIL-`f3Sz!TDv+c%lp5h^j1FIw`SoLZ{AtTr5jl~V^Qn0*>F>BBcGVA zr72Y4;p6MeLh2?bPQX6@@Hwx}pvSNbIW)nnfbmUT$nc1F$;LX+DnXGSBGBbD{Fq$+EO$Y%*A5eg)HRKwA;LoWgvrkze-9#yHTy~V@#;Tv`0{g(BKh()?&V$ z-qkq@>W9Q~Nx~08ihJv-Yl>jddwO-9;Vk5Y=Hl%Zf5K%gmZcg65(L3+cU6DPRbFIT zJxa$AAT-1I_;Shp{@jgc$yfMJU~NC-0-=#b%RrO6sdZ8Wu=v!|nqK^@wa|(pU*MLn zbhQ*w61Ux;DIZuLRZp_Br%<7mbl#0qb59c97B|985K0lw*PHORbb7XM-@LeLUTMeM zwCzk@x<7{FuCw!t;)-}vXt;h?YmS&?VbLG3)2ISo*n58EwLUad-3QeBE6o~cP-~ME zk{KWA&t=8dKy5fzx;vrc4OW=ZV-*ByX8k+-o1lklhX+sE#S7ROf@JAPpj3Bm@^tNr zs+hytHbns0YToAbH?61%$qsPAbWCM@-5wt@XS!{&{629Bc$^Gg>dP)T|2(d{Mpl-i z7|^U`HsKQKonB&IM^aFKd|9Bby-?J)sF8{7(sgK?vl2o&k2X9xaFm$HZ)RP@#--)r zSv>lr7Hnk?Ct6rEHLiS7IcZb6Q_K&Ojf3!x%M+ zUs$>f=MdTZSY2(elNlz1>5Lo|3wffRm@Qaa9Ld7H!(sI2!f7lh!8g0AhV8gU^+1Fk zbx-cd%vf+{53b2yLvg=AAc;5y2o#%w_>;UyLA(O9&$>MP{8F)Wd?s}2-TVo2bn{*Y zpJ83R8H3W;*G-Dnv&b4F+_c#c7O{+87`>3OY|X1j)gHz-O|-uQ|Fbj!SXS)-Ikl1k zr^g0yUqQ-(dx~LdD!Syzb=mh%j=M_C2|Cw`RUXa%l=ZiHU*Y+RoYxKU`7K^!O7zSI~5xyfQg};x^NDw4j zrH`ZFhMhUCznTysz}>=wKM5a^(XPW-^Y~);VJ6PWsx<`>JNWHcs0aLUxShTB+%FhF zJp)go0@8&K<{{@!1Pt}6qu`0?(8+EXvxIo}O;3%?H^Z~SH4bo~-7~?A2=nUidHMK@ zdRcMIE!X{#l%bJ(JQ}`w}({2>r~8%q5xNz?=pFESt$99p?9rnjCq&ZYW=a_bw8Q-uU@eoyatz=N-jQo^KUUUHShml8 z{AaKnO{H~u(Lh+9H6`)Zb5Q7^2z5fpA+GslwrotlP1j}Z7)nFVX;wum$=(l(jz5uu zy;(RzFon$^pDY2Z5SOWwbn_Sb&2hVZ%dX+R%DuIx&u}>rEv4U7Dxw=OIvy~(s0ey~ z4sfl@ObS(fqbQ*S*uT(wSO&3;nan>qtLi@)2(;NSBoTqPKfKVi0REXtOJ@1MvYwPp!V}lmS&Wkd$(H~*OY@0rC<;_1H{n{2PF3^;FBCpr=*e{bLI=C6M;lSKMy*zg3a;g_sZUO9GK>kbTG-PsiL{&^+isMU72!^Oy<#0IaEN|;Ypvq7m$wN?I?jM^ zE*-P5ym#RT;c6Z2ENplRHs)KAFW?2Wvo#=GE!6>{dk#75QLh?Rug^ZeOQ*79o26`$ zGW;XwUtMxZz62BnR$2J1x;7?`E@Ig|_g?Simm24Ls>}_vM+n?O&9U zs;yAMDT$_3f}40deC=yiets6w=fO;zmi$-o&tYxQyiqWq+u4+QYb!HLhFV}PE-xo3 zPog&14o^a$VmlBmue^K~Df+O=Q7m4ZG^6&4F2df01_=`NI_2y@c)=bknkyR?p+KQf zNVot61GmQ@WWs@UWZL}LOtJf%JH0&a^>&nHjQ_n!)AJb81*~m)vccoY0eV@Nz#Ur< zU6zO;8|fl{ZT(XhvV&SE=EmX)Nx11PijPr+B6vyke;$QZ^r1bA4$OHS&x%1rIP|R8 z!$Vj6<83xuywzUgsjW7%r!#87?L*yr~S!Z&$_+;Yy>&=9yHE&Y(wQP!db zkmwX7Ln<%|?=*+@_VxnsMgRF#TwL7JveZ;hNXlv81*lbw%u?Z`KLzJO|36w-X$ zxUX#K*;6#I*^g0n_T|uN>hWOmh2@j~zH9c!Ub2`i&4d7j8a7Ojs`uD;0bvkiiG=ZX zCth>(f>*Mj@BK!_Yl|d)bB*xnKD@5UgEbB@Jdj__QJ&l7KZW$hUhz*5t-YavFNUx- zuX8gzpIgYyi2@aKu4NxGul7OVhqe7XSON0+f?bFR1DVzTX#u#Kjf<`=2BXzHTW@-J zL29z9Xx_}PVubsK`Ht2+7bZtztmRXTBkbI0Y7~#z7sc^fbu^P!(*@I-NsNJr&^`5m znZPrJ7Ms3MpBkGbFH+>jwjjT- zQQ#TTbP}tdW{7U-XOJ)4ME~ZB;d}*jKR(!ruo%A1bNAxR%7;sk-J95We0Z<=PmWM@ zsal#?!k*7_<$5Ot%GM-v1ZHB_iT9Y8B#U*7E1tQnJzr`uSQRDqOv{zfyn~r6z-}1qEE`vJKa@X^)>Pf2*WFTK0cmTgOqQ2ywM4HT8~M3tB>~ z8E&hDN`p@>OSnwvHQL<@!~{S{q0O% zRuO9AX$0OfU`+%H*0s2==hEmAn$tJKU^3Ag4f=Xqffb;uH_!mfu70YbVb86u@7n14 zB;3D}2J1CytH-7ZV*I~7>IH(fU}V2pm0ax1q?$TwYX<%%A09curxQjEaHyW>wVq~0X}zb&S2@qc6cdu$&%o*H)G$TD($ z1i(BU3JGKl@>75LV%XL+{_eN;?)b==Thw2HNr2I_1POx?R;}!@GJYqpvY7UP0ddsY z*&A1hx-Dvlbo(q*s|&k-eBY*nKU$3Uc%+J9f;x?#^ZAlpu$otoGt^o?Bm>$7O-)k2 z(9oxVmH5>=74Jszl>#Lj+&x8oh~DP6KC^ru=^AF}8t9u}thGJeuPv+^IYX;G$ljRx- z$5fp7-)C(!)2e?&ut?cx1~p`Pc2<;uV|{1QUWpI^;K>O{HO~Ut#LRtrG4u@`-56r^ zgX=4HyWe%USV_-$$ENdKEu&KSjrAzqnO}{@1`U77{5OeqL2n6*eiYSyw(dSLELavc zCk~f;bn$h}wdl9UD6x8XqehTrNF$RRYpm3+sj8(b;WLO6!*>n6Y%91thFtCy02!WaQuwy=87}f3V=mmB2HdSjG?|^McxJaUPF>krCR>p9YVgld`jq z%kh(IA7O6sXefU#vMTDx=^E9MY+U1~EM)i-Jc1y}D|UN$lb=`iIAA$AEKLfIR>R$( zZ$NVuYPB6byI-2{`nByU1!t-9I^{u8vW?;Sj+nC$=#^)6Y&qx)!-><}o1@Fl4C!iZ zdU(U^jsl7j`uiRt+LO4M8cCJm?u9n}ZnBg?Qv)CFt4`@Bi6FXLpUXP|l6x@M z;mx{8kp^_+66^VT47!rROy*dr*lUbV865Fk3fvNa)QtWuf51;)J=R8FS4;={I2Rxbm9X6^^lTD&>&O`O^)ygk2 zJLW;EClL^0JJIT|^r2h~jfRR1aOE{S#=PDSW089oO2%6p>t)s2`~YZ9p5K3K(eAVr z#d7hRg%THLw-NzU`P$|e7h>kMh>JfT#uX^)JiYp?=$HSvlKT2+*(b#~N zgV7uJ0t){5TF|~@W`F%HXkqcVt+lEg%EA}(BKuvGi|<~*A{i+3EX`EvR8ZE1Y<2E* zJqB%-mwL0zTJhy?Ez5r^Cn}SVs;Jyr_RH@fA3aRREzggCA!d|0BHl%5gEy;YKS-PX zpr~>?_yDS|hWF{Kq~;h$k&oQU>bBF-xhv%ImtF&td_EPEG|UpUq=%G+vXrLeTbs;Z zIUJ;OLYo^FPO#r&@S2dirD#pP=8k3mVPX5fu(QQ`A%}B~x8vC@@?9H@ad>ryFLwUJ z9cGp_iUtam44XspPriZL!NY;Rv2jP$a9XrLc|O?!U)w^<6s$NVl`clPo*uEEvbU@r zntOIx-rla96tt2dz$U7wr<5-L(=lfCf6*lQdl)owdyj6!EZruJ#v8!~A1VkBntSr+ z_|Ivyi204m8g_| zQPaD>uDkzgD79`M*Y0M|r`;=w0DrqB;1`O9g+WWYkKJE8%xv5WfOh;+ULXU_Q7A~l zECZdWp$5Ejrp)k5<4-@s6V~eo^;%zrm}@Ofm+Q7W9r$ci{UMAc8uMjGr z?O6wGi%gp9v8{n+{y2VJ%Qbb6L9jnHMq#=*)xjL_G4oS!Ai>}o)7_FCTaYxWoIz$D2loz07BXju4p4IP0mDZUVB2|l{|l&GY>tA8v0Si! z%xl3}z(1~SnBldthd~ydg zAeylxjQva2vyt7W=+t=j=#H_)4KxI3(g3{|2p6n*QOiBbrJ$nERDsMd%~Np3%|hnk z$lhUtEdKBMS7dNLkc6=k3OTs8)@5)Nqb`S1^2ll`jH`qsjMv6;-THoIA`}NEYgZ~% zOm4R8MI5Y;o=BJh?H}dPP$6wX-q_XIP9&i0vvg{tfm!;1Pp zvUCMxz<3~l<6g^-;x}N{!UO=E;e*)#I9RY}^3s%J6P=trhK^|ry<$LE7egmH@Rivo zG!ILIJ)iip6kZkmFGwPq+Um!2DM@pdC|cm158xo}Mf=CSAr5f7P{n&qAPHxBj&0EL zai-zji}}inwjhdisfesby+5;^%C>{6e5Ail)e>`v^(t+qe=FrM_yb@hFi|i$h^&Ec zjDq>Vx^?yJM;QS~=4189n*8Lo9!JvVO*&iuE@62n^1Hj}n8n@gB=NCF`N;?M6Zg0F z>8c`4MOMyPenk<<;R8R+)dYJQPpt!_6lx#XVoqd@ZNu+h_uY2lV%cV^eShR}IIwb(Jf%t}kaP_XAMpk!qG=lgE;hs&peG5YT%2Q_*JLbwquNq^Zr&8A5v7q-;YqOVZe!02y z*M;I|-=9j26}nJe0ppc`Se}>3(45^#jrj|KpaLDH@nhK~kEa+$Zq&WmfSzd?DpkQy zx|reWv9k*5rkSzJ3!a0jPlAn2&Y|G;go`rJKTiVQLH1ry)N1V5*ffYO5Ca)U-Vm*u z-U;G_EL`%t_q^Rn1XYf)O4(o|QaUDaON(IOvB6>nbNH?yBndleBHwPXnc<#8M5CtJ zpiGmgp-Tw9L-4mxA5e@wa?LhABmTUIqM0qdIWnrJ$B%UMHOYjbDm<6aPSl>Z{Pu`3 z<1;AdSS7!n<*FN{Q!M$ERi#hySyVavry4Q3bdaYNYRy}ZE^1O`12JHpQtJ5j!jQX_Y4dS1hfAw2EWwA z75e$WXzY$eK5!JZXi)HdBhw|tzN(Gkf$J4^?_S`eYPd4L8=I&}2z+G8y>OYmXjz z=*U?8yUH6yGnGSds&X|X|NVFuf5X!RF_=g!+!f;NM{rZ<9@e(Sr8vMTm($Xs;~>I|PKOP-C zHGheZh(Az~j0l+uyv{@HS$m?M;u+unprC@Sc-$k4u1a!Fac9yTyjW~M)0 zBkOCpYF~3mh+w`xK-~XPuQdCHgHuS(9f~#&(Y>ADiCeHF@PLH(Y6F~e7V_P*Yn9J8 zWU>1ygbDuYOiiMVZU=cL|2yXh?9D3%(mRY3+kugR0KbG^#$5lD-aCH1^QkiCA>JF> zOq2G6euxP+ZZINjJ$+D*6v278@-eohsI2A~4^*1Ctt!*ooL4mTmj8&*sx`Aj;@!l_ zewa|5;Lqg;=~Nw34PDV={+IBYym`9x4x8TfXURsA4BepWkn@A<+Xh3&vQ{S3uC;dP z_SpoMpK=Afn04*KRiIHX_Po51K5u$z%63Dcpc41bX%C{#a%Ll5OZH2?Hy-C_Q|1FA z#D+Gg7CV+8XYbai)c5opOYm}LFxr+A=22q&Uv6W|fK^^kjMv&4?6*I+`SHnWdbTJ_7%EZ*k!#vug-yI1(iK9{YPi`KVYK^z0%?d z-Mqt_gg{ILU%Z6jfTvkx#K{l{bidVwU4zBuO581aY|_&dceZ$JLkA zw=_`Um9Se{i}f_3HBG;JG-DkoJ79~!B&Sy`Pp6&xFFs+*^BC>rV~{_^P+Ijqv5HMQ z=shnvpAz@}ySc;Z)ZgY7<@$*8bN7>A7Lt{5?4xZUY#KK43cho5bw!< z?T)C=sjKUSq8w6)6mw}~V!J2w-lmcbDhM=u+wZ2@Ol^AGx;>6R(u(Hb*Zsj)jE^4u zw_t#kD+ZK0{lxb^DkK&B1412(%uhV&do9;d(yISd*6K18Oz{y3@*_0mx#N($;LS{@ zQ;jaWK9}!VJ4;8F?H%Bk&=sn)q+A@h{&WI0U2}5mxD`PUiZCT5*HjxDLbirfm>Q1nZ24!{qLh0fzL(v(=gs^e(69WT z=CGRcjilc;-!2C0ZTkP=#Gz{M5jq|e{ZCxz;$2W1RRtoaac4it!@-F(@m`tw)NOju2{=y%l(GE@I%0)<7DXE za<826a^K)e!hB(iv%})yO51@C#}(>#u5S$`i(be*F!ox}Mz8R7rQO!h_w!#VV_?tF zweGLwz8Aa9XrLdTKN4!Hs!LE*ebG(m!x^0+6{_yKnYZ_&DuM z?3WgM9RBvrTl8Y1bgK7qV16;-!cL?gX7SRQKg*tP;XDhEQKS7RB80aXGl*=c-(2`| z;f?%~c9`Ylrxw&cIZ?_eTVv`B3877BPDly<(*5uHT3irl9Io+HX3!#>;aj>n2N-{F z9HO+Z%9<~=+lQ#Gu6~IX)~h-+1^h@$o7&kRuOz*et37iiO9@ysZDM4&xK`ZQDr-o> z7$oV^U8l0e=xIV9SJ#)*OX{43g?L?eMA6fG6g%FiUH8o95c{mWZDCK<8kfgZU06s* zo#IkH(?tSnFN^=3BbEtt6coEV1RK*#pKZq=5Xch}uxHoLNuQ$G>k^Vh(TBno*+S+My=)GeBlBYN zr>x&4b7pNXo|0)ZeLdVguGYN=-PfoId=9GyYaB6Cvfav^&HJI2Az#@7+7)sX6%^66>EK!eR!x z=!3=DUOK1c-4OGm4(TUbhVI8GWrytMqUqjrw^`Sl)m|nsV;Bq#L|MMK$aG-XV_aiQluG&LS`DJzupn{*-ld-PyoNAc zmeXdYgb$Fq!F;xdaao-W=VysxzGe$Lb-_xNwjpk~p_HGcR`OhscCWOaT1{>&o9tHr zi}6S6lC^$O!L0!mx!j*n46OM;L>@|1Dr9s&0Rq3zaJbx9sS0sXa#D(K)NQC zdlz3c&%*w5)s42fOnz3|#mFlz4dRqY(RG@9jZ{SOLKSO^Ckx7M()u~!Rf-xzMt?|e z;li;>{mb8-sgUuK%Ou@S-i~O&3 z9JF{APW0p_eq0Nc)-}AmEOUf3`TV)oI zF!a!yhJ{$9z;~~b_K+LO2Tv3L5;YL^|kUE+mPQ+kcsB5Ap}c^9w#X8=vKTj|>!yP5~KP^D(b*#>g~c|6%*(%+dT6G2$D4c0x_&qy78%yNUv*@#IBx7b7?b=7 z8O2X6a@6^3%#F{~t%pd-YuK{I92WOeceq#My-!6EVQ)3Wd4zj%)9AqbPnqoSsaf zSOz{$$JiQEl|dGdH#FPO|PU zY>t~J4fA-@M4_+s_abS`A5UAHrJ*VH=u#vLrTH6IQ8nOoA4j-kl}g!ZMz=YwEa-=0 z@aql%k2F{B9hfKmc0kOY!LJ`eKfb^^P7#5xS$!++_2e7#L-Td}=dpM)pl!fr4vaph zwaY_@5Ms+!S3cWMfPvj;=N3BR=B1w}zD-i|sY~ta%|x#?pCm+J3KqE_tEeZWkaNLM zIy6v^**kL?Rq?#7JlMp9B*$N#Az!!57YWe;xg2 zFjUk7jQBnFxLy_PPUa7BURe`p7V>632*-_tNNh zyvV^gq$)R5#>wrpCT*b5EZ1%%u2b4v1Z?<#+|}R?<@vsl-`gn>BXbj6rs+nM_D*_N ztPh;zKHvYu-c(4j>D`{bz1~;~{>M3Iq}(=4U24qI`a*gKWNCzifLc$xaGp}k*|j&3 zWqeI_Nlbe?d$P`7T%>FC-2I_j8g=1(QdOu=eFr9Www)S>jaL-Tm5G0Tk`QBOXjN-y zPMzxyQ9?+KgRl3}*9?l1vD3sIb^{O35kV7iX};2?y+E`WWz&6z{3au1FRE8m`w$vv zx8GQR+z$mKfmNqBmr!xP#7ZiQ+qA%_KRyFSw|ybPo3v`eq2 zkJ1_Hkys8e3mWQU4)C3P;;EpXurr%9wi{^WA<9jHg#@0zeDchO#uz3J z4X)Ri`e-UvAQJYq!Zi5b56pVbm4bG1A+`#M9mqevx*_Gnn{G!F<=eH=)!TDi&C9u& z=x27_vK(lL;Zr1ZS4+wlzxKCda8WI{Y?IFDd}gsXUX&YaS3q5edTKu4Z^tpMNcfbZ zN>AX~>uNRZTia4~0jOH7LxWCL9z3P?&fImY>{92@h-vQr5%q#iDk}v|)pMJCl!vO% zuf4#hpw`gZ{A8=qAIR>Bt5;xTE;7t01=Ikyd|?xu%&Ukf$*?2W&@&hrQrI@CQ;DMc zgrZxap;?ZfDDGcc5N#?Qgs{=kkS!3$s3_Y6)u8;QMp`aq*XNS!UJfVswL)lI5Y1`j zsFy`_+e- zD7FPy3dmz%aXPQWDyG7nlWZQJoW_aOj2$xnJI!NCD0Adixg9YeeqFF*c>4jxN|YEi zuu)I1PghH{xKxbbEL*AV=U8|G`eHXYhPU5Z=cQ~lQti>%ha|J}G)xgeDc{zHXBH6G2XoqnD_ z`J-uC?W9E3r-n;N2DYIf+-_;41A!c@x$vVt+{VD%AdrdIq|S>XXI@PCW(cbC8{VSw z_{oUfMY+=y(k!tmyJ>43whB^~yT*=u9B{2hxl~qGP+EX4Tg)R6=&jxTKc-Rq$Sw-G z(GZc%g_d=hhwQMf;q~OKyda6HUvRN%p(J*Gij>ufIIV9t@~mP-_6KzR41P|=V#~V)xHB+VRr)S??MUZd?K68z>`VGC3o&}z}B?!nRHU1 zHI*q9s1jf_4C$eZ0AIME6en;&&Eo=a{11e%n$6r#rV|y z=iXAtqBAOTF^z789K<_>uIo7*K<48cgtka6$eXUR1eS8ZDFgF+r7E@%PV^FWd75w< z8XX6*g4wvE3k->tJ(TRe+-!i^FVHKR)mrKHzT<`G`ujxzTl^LX%Z+q&@;h@y(XQ#-74uCwLa4vpVuQiAYxGCkVt9c=!Hh^@F+d zR5p5K`0sSG1>M?Afy=lm%f=k{tr-ZzmX83vs^eFdI?<_h1f>e5M9 zq{vTe4A7^4vJW+O5#_rNo71`i&HLa#WiAa^92yqh#&|vdkEyQ?i|YHn9z;bHK|&BI zr4f*B1{6j*q#IPayHk-?kdg-JZWy|xTS=LrBqfGs5QcaUe!jowdH;e3X6`-roW0jx zd+mMB?e4u`eV*3lqV7Wdo+d#CVP}e@u2aLM`)$+J8onv_s{D6Lm=D`xS0K+v<3_F(?;?-q|VR zbFx}hA3cXwZ0D>K_0QC)i)h#T3S?~z$H*wa9`lIO5I|ngOs2A2HXl4DZ_Ubi&1}N0 z<2pfbMn8Bd^*7@Ei15VQVWqr79fVus`H?Au9!-1^&hu~EhO{iS_e#-kSk^A00CsLV zxY9sPtWa9;F>Z#(VV}min^o=HcL97N?9R#tYL{iz{0br!WjKG)!6U!QnKQ+Va9#OE zp~h@ev=kv1-H7R)ckD~N$8yaxHBw`h^}Zw!$U?umXaw{7*<#(ZGGBrEGp+Q5XayZ+ z6SphenP6)w#zO^Dwl{8B`+-w3D~U>RvRT8r-}V>zx1N=N#*LG zLJ-T|Do=LP>n3k$_Y*XAm^Tb;t3^C8tIN0e;{|eiLD}$7&Y%PCqh?X{fex@Vd z=du;JC$F>6*k`d^I%z(v?d1Yr+p#p|VxB%jTFYH)I$GR062fsCve+-_!1`;_7WaJN zj^F=s+saRyp!;eW#O9{+2*xcy80R+J02vuX^fxBdQqc@q%b*0sc?dnJt)v%jLTb;I zm=9cgo_W->gx~UY@j82|g)7bXAdpB^xte?wsg=QQUqI;JO6+f|XA6dPXOL%5IHqov z+Vk$LWXiG8Y;mfbR<{jQH_T5BDw>m?ar2Xsc}ylJ87Q6iy~}PsfuFiuxz+O$WOT-j zp)M66*LRLCdu&&3Gv&Xpc`**&oHp#V1AYM)Qy+EseGh{Qvo)1Jg-vgrZzFWBU5XsO zFu5?rA>nuNoy(E9KTgeI8GYaU&;}$L%4}{{tY~6GzX+hWva8umildrEO0xMI&Mlh0 z;omoQc2)xz`R3WP?^%*V6dc(rj+N;8jRt2$f8Vb%enn#}otv|JU7CY|r8-SuMt%jY z4Wb(C!vS{t#sAuZX7hfn>RXZHe_n)*ZEI6fESV^6HE_C+a(1+-H=Qzb2FD?g#K<7c-4nrf_qE@JHl?3xv|cpYH_VwErHrRp z?uO@Y$!KLQ)DWYC{zOS>Gi=OGOX<++;MVSn-IdMNue4KZynmGG{`@9ZA|DqA2Rn9e z|2UhF!L`bPhzae>Jxrjs74upOW5UniZdbt|6ea+HP+o_@+|ZMfcE2zPW_kLD?z?lo z;7El@6|(I_d+QSR{z zSX19b7&$a^X7^+Djx1Orl}0yQ5HmL&3ceztGYoU_i#9DD+YB)adV&*AX3ID$XZW5< z4(sjy7cCd>)P2~*aD3YXYC947wIT$=7M-di9UpOIvTkN->_#C{gAFlLniH@eNN0`@ z2l7{B+c=!^rx{X__(g&|{fW7y9WuSWH6F@ai82vTsqCy790Mv2XNkM<5&w6{#fQ8$ zZSPs_+g}||W&ntp?_t`>d_Ry@4WkfbpY>$6a2AdLN7 zc`?2)-BURA#lj?X)@G}^TygY?k_hniwpo6?%`eLIX0>fMBGVot&If1y?iMfxj0oEs zsiAAh`!1*jNSv`DYg6fFX#6|9_WvT%;rA0u?;604sxN+?A~UIP{cuYQYY|yy`}^Im ziM!;gm4Afs8CW(~%8d|&9R$*2Vz}d&M*b%OdH&syd4p}b)#Y-`;^i#AnhH|(`a#H& zLSy#Fr?A4C(S*$F79iua!Tn1b(^%VnbyP5 z(9qOEoNX)AMb6uc44cPX)+V)ynE3{?l1Pnb9UVYw^^u{Z_5-`IclE{o;z4XesUe~;XacMb7rSInDMcb)`{!EgJ>6M1(mh((MV+4F9#0e z^{%VQVy)@vX#$!Pg_C%YnFMRtgyE@_ZhURnf)nrDdB){@ZiZ|~b>FAqF;g0I6U%6G z*@zL|Oy=>7=xYn_j!7ovUh!d>#Y^-8CZtPy&^b{Vw95p?T;zP+#3C#V9`Y!ECg8o~ z@9L@nbxS;We-jdL`au7JwK%4$bxZJ$f@T}uI^77lJ`#*0o-m+sZB5n2@Md*+J7fg2XwBTzM=`CQH3wwz(Y+3X8VXXD_RXChSdg zHH*Z??>wKxj;M9p_LG3+5w(g}3ru}@<-N2}yh{LqsO?4h{ecJCa;;_!abFNHJWJu& zL>xd79rU<{W+rA3+@yPGP}M(5;E66#u`w_^TROWi*?Mmouw6_5$#`VFm>Piesh zDsa@f>#>iRKW2|bjjzJtoi+jOSzzdMmT08|(r6~Qzf-|*}pH;u1Rn>S!#7@ zdd*z$FAK5d8c5r!@%OBJ9{GCfeMw@zf~|9xiRh2hqC6mBG%F%$tGq6KF43raWY2TP z^NGXM#r*Yz-a3i>UBu2!G|37gMy<@Tpeph*N>@;xe|Ko|=Jp(xXdnUoo};`a!Cp_R z4elP?i~R85M1!UUN;Jc>8tXU?S5d-pgw0alfxO{o(9>0z#iM!}3;L|O zw@|BaO<{(ZFgpL0Uk;^91Qo-2VuB^I$_rgG!Dl`Coh8AJ^_ZyowaCxv35?U}B63IH zfhBT)xalPHSgS-btr}lw{0^gwB8)azhV_XrX4AZS<}w#ND`oi?mS8ihte~Z}D4q~f zw$CXsO!{^Ak5+ULtv;*au5|HovTSU@UGFM+%&AA$?L|hCOLm}kQWa(b^yGOlFnnbR z_iD-N&{-qv+r?PX-$GY5J0umWMD)7!V-rK;Vx@jfjF5bo{L)|`5SiR*h`bjj)10dz znJ2UOZh%DS2x;!?dy!q4HNwJplEjic_UTp^mQ_XzdhOs~ zb>!FW?;k?D-u3I|f>%trx#8PB6tgtmam<#fsR74N!j3-Z-z6Wbd$U{+X3k_i)~Jaw zzuE`sf`Yo6qEO2D)~_+~1SM4hz8dx8JsdlOs`z%p36I1dyU#ahm=G;@(zfIL%ZS1o zwKHA~ZAevxkIXy~N{ejO5yl&^VY{L`rgK+)|Hw z)qKg{S=;7)>D-0r#L%ZiF&viGqxptp(KG`c=I-mX@`MfXR<`D!TE6}CH%fWWd@U#u z>6Rg>U68-D+uTrto6KtwAQRQ4O_F2G{+$#0@%vlCur&ke({e3}|%rMi3 z83^UBghuv!qcN-0uCdc@vf+-s4@$cAPC*S7rz?sKvcf43qb=y)#Ybzu+xIA*(bv~c zjvlj3xGzwJ-r>(XaYkoPA9Z0jGa= zZ=|W?wG50q>65d=U9)Bv5h_n8RkZc!<6R&BANogMik@a)b>D3=mml4Yf*yh)a9RB^ zW9CeH9Fx^IzWIpL^5T1vcbNLKriwQS(Z5RG5iP{qVFup~qX@ugz<`Sjuv?>1wRU$M zC??LTAIAs|%CJ>>h!TadJ%7%!Ow6~Oi;S%%qtQS6ev=>arbh!~7cS~A$1tC~o{Dq5 zh7E~3goUWunBwB~Nn@T3-F%BCi$}R};)W=6x=8Nd2S$6~)TeBGEJ(m_4b`-nGA0~l z@835Mp4jGB>zE4=y<(%zaN2;cm-5G)o$EiUV!CXSue%rYfg8*~0GH<%_$zw1dWtYL zP7*o#STYVJR}G0#FI)i@pHiN>7QXkv^s#Va4FT8PsOyJe8+3U-f1`D+<4`bKj$s*P zi}VifUjAvJPnAZWXBk!1+B$!jeFp-mHd8rylB@7i^3W{U?muy(BXHeOG+L(1OW8*6 zL*{G7*d((J_}~=cV)9Uo`3V4&BFQq9#`};&Q(SwA?XJ0d_bcu0GW`H&*B+mrZh!x- zVoDDOi=^gVVt&%)$eOF@RAXcKOo5lRKBCwdxs0|>{in`H^e#5Z=IQsCn=Hlo5F zgeGj%MuuX!kxFA0$3%m=-eQ<^#|MVvla6ijvDNCk`?c(h`ojb69C0@xi@$1x?cWiO zPa=~RR4#>2yi97}veVz5Ho=k1?4A0xyw>igp(j@yIR3l8OB|%Bvv)4g_E&IW{_y!+ z4R-0+Pb)LIMwnV7k$M7URM)I#Oy7{b9f+))0*rcZNQ9d|?mi+;AN(F;laIY961=a$ z!FXw|mihY6rOvgt?P)%rHePQso@hKQJMGY6_Z9fk{2!sTYtUDs`mX-CgXt!|5E z@#F+{%fwc#SBvH|RJ|z84*QhX`OW2FtROqK(3_B<5`>A_4L$dHKKIe^&<1bK(KZuJ zBel^-8inHpZ!$gq0=bcH$aZ?O_Pbr?EL#NQyYN3%F}gZK&x_Vww|92pBur1lQa-LlC}n<;q34Yb>ZYS{y9*x+R-f!Rt!Qn%T#Dc*$_7C$K-yd{~k z5)Mt8oGvNwGc4#44&!Su8-dz~XF zq$HX($Atm{d2`om;^|Rkb)A~sR|a|_65Q~cun)9^4Tpasy^2CZw|DGr2NL1Q3C=1Z z-v>OB@^p8XhH98>%|o;GBg1dLlAtAwPV5U5X`vziT4St*#EJgxX6NptGYw>cu8S^= z>~o;Sd~Gd`^xDZ1UX&8^H@dC~+u1d#mWR69_WC`&2~&vvHnGWP>eZxKX%{ypn-7|Yera-7h&p1{vNvoDLZ@4vNi}_ihf&p94za`#; za1IiAQ+MroPUp+?5@)@t{EzboY>cPT`{Lge&y@EsYx?vT05}1pI6)#N^D(U zV^9{)Fvj=Pugm%=b(B^yEo~Z=F@jf-ijc7MumEkWN7vY=lb@H0Em<46!0j!- z3ka}U^#SwI);(#ZI@6Qj!TRorwz#9VxWl{^K9-2M&H-G#eyl^y6QbaYHYNF{-%fob z(aBPNF9fu;{h6?&4*5tSC5Iqa8crhF`bK zNCZ_%|8QWSXx8*_G%5IOAJKArd~BZX+4FpkdUG70MC|w-8K_0Lj66^2%~>jkS1?Wd zId1{}C#-ry%1OF%#L9zA;tO}RF-G`SxWU9$^)+eo>jOwrLQ5RGt^RU(?qpGy^w3aP zcI6vR%SWcx!ac#S9@@Ps2mImiEI#L;pn5+t0ZkZ<4R%99J}x-f14cFaY6l z?O|u$BHSiZwKb=v(C%(%eu2^k)K?k7Bn7J8)FWud&|Qwn5KIMF#{d=zVcUqlcV>?J z4${$=q@<)|r21)X74?rIdnqQ1p2mFc%^we6(cX?{XnJF}>&27ON=yNoqr7K9m1mou zf2!O7QzaZO&Y(T?f4u-g+;WKY0t+_&T9ggRj1ta^;w8`GY9oaz(K@w0G_}C?D$r&) zah+4>%x90KuUf~>XeNF>W!Ej1@zT-D!6k&WC%~l}-*|u0hf8*ZJ#=aad(!0NZCbbA zLjygdB8*0IM4XRID_y(<)WeGi0%6i{oO$4H=R?c?SV~8aHn(C12jKR|{)0x`%A z$Y0reLVWMC1b+w9FBGP2IlD7&WS=A&Kt{a+E9EkK4&V3@`v?=j57}9mi>OT^Y1CvO|Iz?-W~)ssFRQ<94TvLVfDfE}@b`YLMGr2|fAo&=Fzpwgo(9H2 zQCu8VD7hz21W*#f$&!PD+f489`&BO2QQ3i_mlA%P)KI@?FH=1IMXp*b%J>eX{o`yT zW|zGr`EX(SQ{hwFlj?X|jvt8~Zr%}mer}Kep`*EnG-Z+7eQ+rq1|4RS2~cDrN@2D1 zjUyX9()i#5zYT=Mr#ZHS(bj2Ms4V{hnX!2Ebo1QCJ`f!ObevVk-1t*8KoPHf`)3(u z*~`gZInp&+=vo@zYm1G6WAqMfC5Z?zfNgzRco*CN#$mGJ4m@jSGZfj zh7ED3vS~H*IrysMt4M{z$e4rQo>^Hat4(#(g)Z|sYi8kI>aKbZRUP5|K+En5M1P}G zAJ)Ax4>#O8*L4HulakO!2dWOoGcR^Djz6hP)}U<++*qG<`gfe3Ux0Jt3$qi+05T)( zJ}|^U0zB1dIP-b$0-5AtExXqx1A%${$#+yu3(Vip<+spN+NzSzg1tWaUpKM+9Qt#F z0jo-_`J1x&fD;Q_0x9b}DozCfbIpkttFDuQKp_!ECV_J8H3rvfwZ&e;a*BeQq`~};N-7t zrxSg+;t3PAzfCia-W@DGff3QFD%|(jnw6t&*xWZXKb}ZSO)tF(GimdxN>1tcEToLw z+S=l1{hK9>=tf9zQ`|X^wV0S!avJ0vmwGZk23y%k+bc6xJ2JL+Z1L!#{lqO&2Q*WA z^BI}>d!aI3;uW)&_<1>o>jomnMVg2!Ux6thAxy$ra-r{^eXr7Twnw!P`;I@hBja%S zE9dHsW^3D(R?<7_-4Aes@3Uv(h-E|xj#dgaePDK_8i7tmLBD~DooSMSE|rtHh()k* zaH!9f%VAV($b9yk^Vd+y*|G>7?%L#DOYe>^iNE)a-`RbEds|G$KI-9k6{x{g{LU}c z%9ly6E>gFp3|01Iir2Z(X|D~=l8vuF)T&%=tpeJsOjScBp zm$oSgG_A*&Pf2u4((BS_mFds@($ZgZd^_UyN<+vM|d$n$|OnKGkN|IOU zn!P<*KO+-A;>aK`lH9Qi>ltZ(w{p;07iJ-EMUZ>eW7esF4f7J9jdK#k7riRw20{NHTEAbM_hV#L6% zIXbd=N3a|Ft$RPvd&t%ACDXQkDs_A&^fSmS(C@L@3|rnW52fom^v&Wv-g$qh3zLXl zgM6X7dI%?2>9UgT`||*+A&}Rp-)el1H#J=U2iCwrE^j$W!eH`O`hRBcZIZX&d@aje_f?1V zJ|sYLt7jSonlyC)8ZSTLWVy)=XbchgYQ*Lbygn0cSw4GUW3$Npdi|lo`tsbE%_k7Z zk8on2t2Ew2Zd9P-9ZT=|iSHB1*pMHRpfJ0Q)IGCvSRJLrX(2qeQI;Jd7(?rOJ`nPV z=de0=z=E{a(4msDJvs(u?bt8P{w7s-WL!usI{QBqKKVd;Qo`QfR2g`(z+o3zB@N!j z(+J9-FO>nK;ml^NBy1%0RP)wfi4+#g^ZF8Id$e{D>tR+}1}as~>}ikn1>mhCOqP)L zA(r6VZ9&7yPWje*r$q^e`-#|0%(hXBRGk*LU>}Fyft5%{I$q`4E;8rX)}@!Jx`IV! z-1*m2eg3KD{vvF=u==Liqxc_**f}UHivk=FXQQLx>x!{7ED(s8`m=|i5#(0Z%zl0K zRjL1F=UMrM(P#VF(p~=f*8~82$;$LSfm0|w8bd>B!%uvDcDDVuP)oq6wwl_u1^*jm*EE)TBH{x#o z$-i`(NJAc;Vn7}6JFXm3{pGPb8|mazVDH*0^o5aFvCbdH(6}nNV^|L$i~eXL>tY#%>PUEAIG7 zA>3FsR=q(3C2Q_jnJ{lrt_m3y8YKVLehziV_B(vy_0}Zwss!FoH4YE%^-w-}iT~q| zep~ofvj?!Vm|>G9CfTv^mQ>IPVz)4L$N@5WN}Ts$Pr#D}5NC?$rNo=Z6Sh0&fU;e{ za$RL*8UEYnA1AOV;WS)bS{KI@hK3Gc$B>`JzCi8KXi}3o(tX?=yFrT}gFBVX3g<#~ z`|KdmE((h_2PH&m9n*vbIqV^Kh^o>QIv8syyhxhydMk7urq1x?)b^A^aGx?H1rVw`jEEHR-@1I3wi z?nkfsY>{JOTZTzbGxk%CnjDgmaP?Kc+Jyz*6UXCS^a*G(=E?Z@%A{$dgKr-s4XWDQ z0>Dh8SlX=R za}AceSG2auKUCg(6wZ%)H+LV}qeCgE!AvTrM4seFwNg%vtMWbIt}$yTi8kj*T4;L- z#pMimEAys)nmoX=;MS0hnn*Rp-{ZCDV`{p)$uZM8V&C*ln4<)4tPfxj;%?@6P)dMx zwXw>Wx#t}p#?JaqYCyNNEHWyaglqGqGsipK_tzfTNEZ_ac+DQCi^%%12m%`vb;TY| z&E0w?r!vs;(d+xV-g}M(0@lEQFL0b^nTZGSR(iN*lj&*#I`%Dv6+e!)m4d zyLR$R+lk}sW6DfB6Q;b&c%M_F^WG2+u%+YmYX9tlYkD=6hO!uaHhySdVBgCkza16c zi4zdbAe>YHb0vb$F-)RcFI>#8^z7>l;pK0AH8A2M?9EPpK&Q^4WWS+Sbx7_1VtK~F zBJO)a(GuutGsbP-blm{N#IU4G=FrxMD^=WHbhZS0%OzKaqP1_)Eo>xruVsN=+os|h z&OI{`eA#S?-`@iCH?QWIP+fP~rdz+J9p62tS;KxeF#>&e`8&xk{Vcox(60EP6t+~T zhjbD~|NIyZ=fS!T+wG13GE$uHmFxQqoiFL^Vu0%|y6dXM<_P~u0x55Vrh3SGSwTQJ zvQIDXXK{l4VsJXKVkBDgd4gKVq8`BVuS$h<09VHUbr{GDp3K?N;|wv5p&g&?SQp~z zGqUC@Z1qS4hIs-akTZX(zjsb_dKbq7-26ZEE15iHOtW<0x(5lc1ZnED<;5Q#*DmY9 z({o?fJD1W3>Y;hIwYapVb;5ffdOwmD^2*Y3TVg(>q){%(TU$N_mr3=h;WOr&_PZLc zYNDhBURhpVUMvZw5&nvG$1Q@Ot>CO->OKT=-CTC3^%WxBoG^`52V9^x ztOoqqY{VN`BG{Gs55JPo62pV|%~HQhr|Nd#t*+C|&AHSfb`%tB{3((-sE%ZUf?jY3 z>PJC!N9XcWw$Llpt&ygXDC~JU+tKQAEWcI|179=S6iXV{fAdDWnZ9W04!W1WKsF4E5w=pv8FTxoQY84PONs_ueQWjeNYnJ z{D^r0Z^ck!^iikbuO=M|G&RIyfhWJRqBPkRIom~~d^&lcUw#RIfi-3t?%uk?6o z380DZ-JWsOunNU)&*J0kW^_5TZOlEp52^0t^f0=~$$H&mc{77fY$Wq`|22=}2Pjbt zL&VdkU7blKl8ZnB>@`l#(XIE6Kzy^|P?Us%S^o5)1{yN(Qj8h|GHE#Xd&2;p|Jp__ zVPLBeBsOM{y->3H8*_|$Zvd{44i&_FIPJndS3Ft-6Z5$_BeJ=S8hk8Z6hzYEg>m{a z{K(yr%ewjJt><-B_|^8-JoST`R{z(M^@TUYL*%gOnlE>(i$+9MmuMfo%>Mgs zS?IcBi@0R1t~R>+qupF+?bW@|)GybT<73Vt)n+?{J%)bs`3+{0`lQT`jmq=FI{&i0 z6*IYQ1lUHmBVgmH7XP?_c%|IIuj^C+6({Pe>4wfROzQ*vEu5|(Ko7+^jePOme6lE# zgIbP@Z1xj2=C{&KiywqQnC+~HG!pjLMtHq_N}32m0|Ska;ON=I z-eTXnYO1JE{d=h;G+dxl-KT1?`u>jv)b_7d_20u}z}4|I8)*j5|O7A45(+!~-=XP+Hz4{dJ&24zzSJ~ zJA%coGo#e5MvzZM2BrJ=d)9&MVWcTwT?Q%WaQrMI6AQu=0mOTJtaMu2(FTTRvLIo2 zz2y4DbKKKi;rI<`#FU4z)l|w6waeyj5iPkt)^|LRbdWV-TFL+ zD~igVS1=RXA3eN-tAVjhIqJ`eiyNc!U%>Y zfhWv*;ou1FHn!2^wLmhkjkAheQ|T8_XJltvK00zZu2_}18=oCwGRLDn&^r0)c`HLB zi8o<6w&fr3Kv8UDP3g1w;}9_`90gno34aGjfd50uHM^WSnHRF{Ep)qbm^L*2rf=dp zY~(7}O_~ZvR2m^>wlVjH^SSwBoXJUfgXuw1>rEN2AFgE{^7j(Q@Dh_C*LG=i7VBK9 zbuyfo=^Cy zawB;#m=cPmbGay3fsiFcQJUp3s3=rb?qAkga};Dtj+I$gF>)D<-ADD~She)l7tzwH zs!D}uDo`bxj`G*m7~i&40LrATO+nxu)fn0VXhH>&JcZP}uX4ya-G>aP5diiA$7^2< zefgMw*oE?GwvvyW=A8Wq2e+$yi`^vR)-nE*mflBP?a*L5hJ|i^s z;h}RL`sr>=qTm>ub>HlX3211VBLG#k=ER2y^z<#8QjMl{uVByJpUJv;U*!FBd%ZHju=)H7dy!(J49YD<8=pwRWv0HTPH$uBPVJ$m=N zi-qjGMt2JPF5=NJ88O;*QbQGjsNd$)wIU1+Ku~2P1#KNL;89_;wgl@^d9I*|d&+M4 zv$)rh2+$w~>YDEZ;eP0|O%w5ANwFo0!zCKk__IUp_b>g03)A(vx(E)C*ExXf1CpWp z>3%C*^!2~EF3DtVhYU0?Wf?nMb{(BoALWVq3g8$2{^=c@bpi|-Xv>8je}lC&WQj6( zznu@r6xOjsVrwGME4dRFPpIuG=Pwq)-aSPjE0{qIWg^vT5IVVx9@_B(;84u-rSmUP zsRCcI!-Qr#m@;gu9T59xMvw4A;T+PQ$T2S?#du{e*M;vMbbHR zEja(wx}2$ky|Wkn}XkaG`td3!6t{f{DtC zr7K?IO<)#^!+2qgv=O!6KK9sAE#bAF6<8v3-+o8`r^rJhaWQqHIN)W#cq&DWyXtm%QEsLs}s<4%DzIlRxC zA>9rWog9*-kwZY^PL0W%M%`p&(>Rwit_wu zwO-8!v`39YJ;|7qjmkkqE_Y@ghu*TIiZQf>e~BOC&XtS!2aI@6$AA(*U{fvwDo1-` zV*`-FriC`3_W4d~&^W}bI87^z+l{GU1h4TiSSLmd5Xd}hyxYI#nH(JJvs`b#l!e>) zfWh`BJ5hg)iRbGL6*HNG%S+|~#D*x`h^GhZ>RNLnYKMq$-L{x1%;|fgKi)Oq?zMpY zsz`E=Vhui58Cx75Jm-+)a@^{Sd`^>-a`7ti9B6!$O)1H+SFjii^(evPpt_+b7^}>a zlOiv?JrYZAnW?VB*Jo>UsBj_6T$5SRg3*YQn|6|^V@}M%l!0$c^Zb*q^ zE^(~{F6s^0HjT@cSwf#+PfIlo*5i1g>B-SANu<_$5~HwFAzml<9<-lx7nc`Gw$n$$ z4J?19bZhhc*lECR0(&y&)Gjke=57rS%G-lyibzyO$FRAz4tdDMwn&CJyo&}CP`zDY ziM+2o1|L3CJw|_4_(9W_eqH#%Z%C?r90_*E)}NIaC}idCdey%^(5&!v6w=ApCbMN? z1$lvvYhSJsgY0)aN)k&-(_agCiqgMB@UEu4t7y7nr9ti;dDE%fDr|b_URFG;xV4a) zy0d9{`)QbvYt3MNrxViwM_lv?U`RSwb@0fA9CJ&lTV%eU@@xYWW)-ol~~ zQ9{?Nk@@M(O=Aj*%_rwUHBfrzM3ZgRQH_{R;b(3%e4sL}UQ(9+lw*mW&bH~`#{>t( zQ$pNgX?zNHgs!)&u9WvjJ6-R)qT8{iz>JReh!tZtA1!j^*t(~h{;&&|4Zb@psS%@n z8|o+Y25(0lEWep*=IcHaDFd5ea!G_+ZxTF2vF9SmSSv=`C}rwlM~D$#+TiN-E(^04 z&F#6me;-;Rsj6d5F+;Wl$@V*z?)#tF72OnN?c2(zDc+|wghYW5GE@@AJAoV@s&izSJfdgYKLgkM@Er%h`}`BISdZ z`P{^zd=6VEXB|qDso}Xy`JCv;JSS|AL&$~htI7%>tp^=gQemB|V&$qK=mEX7W@-9*W1QvLk1iR7D zXc~(&r#yUGgiaR@jtw0(w9}a+XLt2* zc|Uw5)_h1d61{kd8EFEDu9aC)ihm#MTJyJTNs-^Ch4fzx9l+>v<4Pjskk}5s53)2mrAn2-kVH z-`+syNl?e}>ie%3FA-~dK@1cD!2fala<}*4wumyBfxw5KU-;*ses>js4ablGYoPC! zZC%cE-UYNW?zo@VMe%U)-gRN(Uv?@)X39+s65%hy2c&q>#EI~7!WuUJGBGy-N8%j6-*I4ax>g8};eob_FAW@uk_aWcq zaNeK|W{+*c!3oKvfZ~F46dWn{h%70tYYS$pI<6M#t0RUnvTx(*VKT^0xgs#UZ~tWk z={Z6jdqoVb<@leiL?$e=VuX0bswO9UC!YQdHzzYS)34OdVI~J9lS0Ke9Q~lanSEZ? z;62q?oV#naFF=ry<<-$WU8#u+DtQ@&3Y1Q&V`y1;k)i|0!~?<*5lO1Vgv@X76aTLl zKz0YmOUjUS8C|KrvtI|pC@Wl?(6g?sNjy13&d@MU5T8BEJ1a$3xTO&AO**D3fOUk) zmI34ofpP8ec-8n1)!Hx|i@EPI2uD>MG_5^UL;irlG%3wPn<+$&w1N-*r^4mPA%a7{ zzzrH#f5Cm(9|(TEyfxj(|7LeS#&>4_?UOu9Tt(ItGx!#u`R7Y(EWU-H$D1JC;_@=7 z$jd|23^DP}a3s6s^}XjBH@GB;qyPR11HCubo6bl&MnDrj>+T~d1NtI-f*)y7xvaDz zhn2&zK9rNZTlr1jKo-|7y%S2m>cZ}@5&NTDz<5(7WP5&ZH=RLk=h%aex_9|=dtnhH zt>WCWbg*(XJOo~1*+!0EoK5}8gkVykn(?6W?YV#HSFh~~(B493z6&DG3zWsJcn@^jxQhOMP{Kbs4c`USgkwrxL?7q#cQie$A(iW)h zODj!d=fmXTHNC9w!HG1|P50wthM5#mpBP1qA6hBv{-boPK$Y{|Y* z7T976{Gr$`{kYeOCBSMJFuRUp z_8$x==b%m#jCDZbsiuCiuzo|~fzVKC$nD`xEQo`(@v^V0g{YrR!AZBGlYk78shvA$ z4bT%6q0N1~xp>wi&b>;|X8`&iuM=gnd8vWr72#Wx`c3*6pLkr3)Wqxb|NKvjEhxF@ z!9iYY>FpOk^mFlt*Auxz3&oJmW4cD=F3C$t7y=N4j_rOI~Tb^FpEy(8Ka z&DKVYIcW)fLf)K2e^@Y7GSJvqd{*?B&x;odo#VM@SvnZd^QFbmI@h56tNTUB)!yaP zk_!Jv!C2Tg@Qkr&s-E_7Hj9Wf1wgG!KTr03)%-E3#$KzN#y2-PY2fazVW`0E$s^OV ze=hw+!E8mvle0J`eqofiD3F6TQK$38w1EGy_bwqJ;pcQ}$|tnKzM{%9o=#hOFc$^& zbpdtUiYG%0c0zF5SDDtejGfHIpPU-1(e8N|sy4T8Io+fj?Z3+}fYTFrC`rKP3KqB3Z^G;{d#daQS9 zFW1VsBa_Y|!WbiEiO2Qt4u#8n95+Lx^6ies+#377y~^hRgl1;(2bLq93;4Eq;dW%J zddaH4``}=bIF+BLgagwy8Me7B5g1+A)Q5!kq?FLdZ!h!w2#bz`$(o*|5SXA70<|b# z^33afbkFkL97wLA8b?QP^joIEU@+vJLxCXNeOHFdgZj%U;hr?)28mltssszX^#Pcg z>g@QwWMK|kG7$A7&=Si(vu2il? z;Ymfeae7{5L6hJ4Jd4N2|M~Zg13j22;?gj#Vp{^3_A+ChEtq)W$z;gAUYFEFIKg(% z?41_%XSYJYAVUB2CBnnN&&Xa0hs779WcD{hEdE;yLP9FC|GsL-!!zEIDVg*xT;BU^-=5a*7O1xLgE{Q-+p(}^>x#6s=LHLg#CM9 zB{sa;`qe}pHtKl{tYVqvv$bK zi2n^x+QWp;?y<1~lA|OP)5!8j6CE$IYZ&I%F;4z-4n!$YaKV4yz&v9FgcKTzwe^Y^L+MBLB9HTBR0%|6@jvPD0ONy_We=Ad9)91G z7x#>sot~~;{P8kQE*Crt#eZ}7^Vyk&ZU(mcFoz{ggjr&Be!+T84vIp+?&kF}SWt>u z(a0l6`?l>kKde*v4w$L^&b2F+r`;T2gy(S-8G7k zimEE7{iW_jX5clrhXmBpA0&N|bh~cxT~mwCFO5^N%t)wldHEn4jj0v40&3{6cva^E zd2Dp)=|+Z;yn9as+Q9?%ZaNJwDpVY zPD9jPYBSs!ANSN;%;Ir7wr?vfHyDsg$nLuAx92>d$}L&s1OrbjeAH5N5g7Ky((~%v z1B#4k$b;+LiTdU=Q%c{Q;^`elZy@Wjac0KMgb>d|b$Un-pprc5UVO?oU0POCE4t6- zIWJi&8A}c>RUJL7bTcF!SKQD@PoSc7G$&>+oXeeM)0Y!fq{A?4aP@!yARm%0E^2mQ z;2`Lp%`v6D0utxPAM+_|1U!k<0c3Qgd=~e>TojR=TgI8hb_8LX-Z>DKIi4h5< zT84m%h+=suQIhTTqjkY|F1NO+PKg;ROIusBi!$>*7)!^<itP8;i8~qjPS#t>KdX&z}RFtDa!?_kNMe|Ex;+zIvD=}_Ye6Q zVI8o3>#ZJ~L*=l)wSo!E-_pnbyJ&;AeBW;9YX_HN?&hq6uZsq}-EmK`Y-|=L)`H;m z9?NO&^YB0t*TV}F7_UuS0$#e z_utHn_7bn!zPN}K;LlxnHw1nCmI5+zBYyEw+A|!VcfhYgBZtc0VxaVwu>Q)5iQUI1 zWaoZ8Wk&uYg0ST`HtF^NJ-wp;vLlv*=IC7RfOUWE`O;kK+UdQ!!9Hz1$AH$Uuqo%r z=a;GrI6F+4YM(|23ONTakYS;JKI#ao+ls8G$BF-J{fTd9DO6HGwdP)zZ58jku#CzP ztr~ri`#mHc;Bd|(Hu0+7JbvuSy|riWM-$rKGX%^)i?{P_4IB`ih6Hy(i1@irUSlWj zn`HtO+?!oZ_MU`?-A+e4jBm7;ZiAZ%CHv|=DWobwtq9^V%I#FUis;Nwn;zX*CVm0C znJ|d=07`Hf$q#W-F14j8W_0+H7IzUA`dQ z3oAL4a?UV@cPG6w_Szd(C=}wl(!FO%=(2bH=KZ(&+~hAxX){(~{Wkm*;2|rvjITd- zgtu*;wIX%AF-;lA>CYorV;?w$niD;~Aq)i$ke-wTg2b1)1wUX4Aj;c>UmSq97c&bIKVDl?_tKJdM`juuDjV*r@bNUI$J+VKU(nje zdgq0T_pfTm z_v{cHeFk4PxFqyJppJb2Eg^(rgHb{m<!!}#>tthMbt>Dj< z%U*1TGXD`S?fbfQCyC4r*0`shgM7+=1f)i%%c8hjWX57>z%+i2otdK>@N}P68|}99 zo>jjOCeT569CS3_$G>)AT+Uz1jCG~(xjSjId;gE9ua1iH`@SAfB&88SLJ*|{q>&bo z?rx;Jy9WHw3Mkzz4MW$Ef;31D0}LtM-7)Wjet+v-i{)bRhxb1Bo^$R#`|fk@fRKX~ z-cPBN@J%<9!slboMVhuhbM9sqp!0T_bG5B`x_+lfos_?RNyK)^Kr}ow^cOE=Mr<_p z4y!ykO;zvH3|-R`iU%jOeg|v>{@&+*aO?XESI9e~RSwlo@Tg13ZT9aJ9>H`?Z z9eMmPmlKWx-??3O6%P3N@4Z6uiF4z~!T)>?TxUsv??_{xUnzLLlhEMl#KR|AIKU^= z3+%NU`L5-+Gy>HrM=wugNHzGC*PoY(xpz;JSJD~!H6nY*YPQ3H=t0X5M(#S^iH827 zzQ4pnHc%rq59btH{$>qM)Km)-77O2JjBpLBM5ra^933ecZEjy!plTx?HZ0BpSbJcT z>2;e6l8li3NEdzqp_Jt7on^$n|yw#HfvGT&(VQn+Hs#oOgXZ`3v)_)!FEYG7?Q&c$&pw zb=S=1MdB!<=a+Gwy>fM?{E4l<*ogBY=eX@vU^&t2Qe*D3+RJMx=628hUhD!YZ)HDx zLAd9b*V+!Y2-%s*SkVlt@IYZ96)QK(piNzZe4p!b`>v0O`yf<@=gUultaXcpdk-O; zPxY_IjEJ1*G&K|1^gnew>HkZ6s?t(Y4E1qv_j7PYzRfyfZdItNmimSZwTheedh7)t z=PJM_1H2o0O!bGdf-zP+SMFV&3YU(VS+@p6*G$8#V4s(M4A%>Z^t6_RtONuz)cpp$ak&lGgdIOJ=9X7@4)O1KXB*{HcvjK1)z|QeD?`zI_$56ZF^Kq834!YU%!iVm zsSwEBiWb}50I!k1K(rIB33$zoye{{4r&}_A^J573VtvKv8f|1>GS9jY0pThyP}AcU zdyz|AO<&?+U?uxJ6JHFKj4X-LoAo}cHQ6JuJCiYAIV~dgP}7e}TU%)6fhsuS_61l+rk|uYnqQjgg-^7hDKHOQak3=Og;a znUkiIP^xj9tD;M@R>N=+zvNkMBV=*K$Q&5oX#Ts{(7ev|A9_Ovxo{`>6cxShNJW;k zK25FE>b3a_VSLrEA7d@(R1!2M-f_?CCWE)Ahml&InRC|}-N>fhUD$|0WRrlyf-qAt zv88qtb-|wab?>s1)277rv^#U=h2A+XQscqzs-6(NW}k$%rXfEqAKd-XYxi<+`GCPC zFx-B7D=Fs~s+qVjeaJ<|iWCqj{Gf+?Q4)?D`byMN`EUdcttZix7-X$9=`BIz#I!rp#tl>=zmot|Mq zznNR)oGKRXpKXl?A91aUV27>xKFi^ahn!^Y(?%K@2=4+WfE_fev`#xDNN|2 zGYmkUM4U|}9ki_stw9ZYZS;m6^6pd}_VWbRZI1F68^EV>i_cW~Gg9LY2hSgvDkdkEWu3myqS|)ulnO{;mG}&cBE4K_1@A&RYObXM4IwuNO!IOyWZ(* zKfeQcU>iff3=CpmE~So&sQ;|{0H(c(%4)sEJ}~sI7_$+4D|G31<-w8k4#)JT%*dUH zNQvd22IRS~YQNZ-415n2UrbOq;Ehg+90spl%k@~s$O3fSmyPC!x~!=5`-EZtqf6JZ zLsrG~(%G|WwG%UX%Zt0TfT`=CWk-vppm1N7<@_BEgQPz65vtig zf1*4Wym|R#P5=8BzjI%EB?Xy+4r4iQJdN(Q;Nx)CVS_fUMlH{hEo~nM57tE&dg0az zA+JlAE%wDm&HORp5^s<+2o<&CSnlK~fiUn=mQl@CL(Tc}jtRB(QMfw4K?O|f>sfJs zjj?I&Tp7RW2MjV;vnG6WZKn7t(PTbMLcPp4Fbnja)FVMF+3sWu_>Kaa77Q@lvgq2}YX0N9FzvGiqwzw9kDGtiJ;c4krU{7m)o<&-Zk$=pK^)>0Y zfnb`Bay?d(Tru_H6gAttul;^$2pLT)15Ia0Bc5G>#JYc?*ujbZHAXR%ySIgVJ4lz@*D|mjBLn z+(}JZ_b&K@UibogVDv<>yG_XYwUk=!m_1*nDJ1cP8yhs*UhLUSEVk~_BxXGCv1{QA zAfb-<}HU1Bv3E*4$J;?ttNFhMZlx=<8elhR@ zVk@;W7GWj{bu!>pXK3-*ak!1^W~=xOKA(ckN>nG6@`~3#58f5aQ?`Os@MsQd&Q$B| z$ebK8Ti&ucFB_|5BiqYyx{}k=%MzLIGx^<1&20Y2?!TU#-1a$=xf^sn7F&9j)qY_H zWu@O;@*QXVrAYW-E@KuOBTZ30Z?Yn`xJxHK@SRIG@!X8fPsw|1&BJZC8Us=mxi~hT zZ}DZ=G-J`cZH5IDQqlaHuW1^R8$2lyGz=D^+8dI#)$-mhc zN&Z<@xASRg<=}L0^F}_){izrJKfpjVki|e2ML%vJAS8sQ1V?1dpbuJ7mzB4Hm(Sr9 z*D89VeZvm+W6sUs*9e!lA~tv$%{L^DOUofL$WQm@F5oW0W;;F72nk{2>PdbA{Z8F~ z@0Pp`%j-PA*ZOa%!U}%x+?hWP!#S^$5g_c4_DCwzWd2D*PE_`nvFwNOrAjZY|vAV{w1Z5qRQ>-CdFK zsNO9;{!2c@o;Nk>Hl=?pAt59LP-e%9u~rCA?iJ0*CNteTg{|*pnrU_5;Er2&{V&%K z`I_XeFw!7kDRQmd=q~WA`DA^~hG|{N_VmQ9cT2ro7Eu-I`=MTHZ^?FPf5y%yFGjoc zH8tFDAb#J%waYSZS-Z6=F}xdv0bcW#`A10E7jwO6d|JE4Vs+?3kz((<)_iXlFBsps z{V6Ei)7MC?wd@xuqFp!x>(yoHQ(&WWO*yV=L|oe@WVrRJXBfL~-P39=V?3B4G9CARJUT*~{ZcE5T1Ey?x%n(jV9ELnz=JW32h0Zw07xC?wf zWy6XLqq{+v`bCH&=NT`@jmFpC*297iM>5 zNwW{>V$K=OQ?Dk$TKo9x2)b3Li>Rk67b&Y{2FE_bzvrL1Zw2>Ju`)VRqwv^HdycHx zUeUdbwXGX8B5BY+h)^uV#!#@?a^ug8-U)q^k1uAW`t`YmHg=&{e@LI)=L^Fx=QapS zJpr?$yyTRvas%m=Kg9X}M-g5NvR$IH69};_l3aUAY?hZ+)UR)l8u_2?Ptt*kt;x*_ z5$b{XV%XNo1K);%UIfwj>b>^;Udb+qAqeHz%F1YO9bW``BIX`p#D9@gXm1g6wJ6w` z0l5{E5eQLWy;h5m=DL+!pIu5cjvBSl$xtj;i+`YCH-iB#$0#mmPz+ree3qccX28^A zQfH@Vql>_?9583dw!yGuHYYVaXXhP8S4)i02tPQOLodE7QPX#2;YG3~ydcnY80C)7H8s|W&|5Cxg z_i{6*z&b%&KQ6UcD)_%0AK+|xuiw4EZ0T5PhDYe}5^Yf+t5o4N3eL666I~W;F=@v9 z_$oJw`s&gs?a~PiN*W0UVikk4z16Idp5&g2*Ujc=g&y#ljUGqJt7wcX zHl((DfYy5uMX!ObZnXfVIDDz;x7os0Es6xf0EC(*L^o~p8~g=VU7I9sJxp=1 z%NZR!MKvC7dFKn1x6nk1HGxEle41Kfur1Nyk1k)jy!{HYsL^Y~%JBO)Oxe?sP>FV5 zv&;W9OH*X?Y4V?qyBh@fIsc>{fz66xV8Cqje#V}E7hm1|Nr||T$yIT^oPS&BzR^!v zIyZWE|p<|dK@xKA&(PU?X_G64Q6kYxO4dTX6 zTI889UxOI(=c4t>HQ}0?T3VX?d$>+TZ87%oCmgA4%s1vBf%7j2-Z%@JJlX6Mv>oABg4qQdn+b9*7p=B~Ek`eY$Vw0SngBhW<2cU9ak$+QnOtUR?*O6}S+T!^%Z@4i$cz#q)sy7a%SF zpG{&1q1{*d%J_D;XRNK6FE20Op~F;*m9dUgOS5H3tnalejRHj+F(CW)e@U?l~K`^tZP!&}Si@-I305|N_ zvKOuJ<~|=z!0&t^%IDGC2+)^^y3QG&|I-3UFJH?MbVY`(h*T9kd-J;;ymb~H9(?Ac zjrV9&-kw$nrQ;-i!&_ArWL4xzf4{y|F06D0PM4$r4*V5`R*B0;y^-cp+Gziwxgr;?T>f^gtw&P3Sg z>?OW_xm4_w_llc^5LZq?_Os^T7s=tJVFV`1%c)(77gN9DR0T-v4bz{zR9nP`-RG<{ zUe!M1i7#C|I>iXoZJw=1{Px>T2>S;5b$`49tvUKwPG=InNdW4XW+KKlCrnv`t<}$a z*cT%9c*=To?aeO-r^LRbHDtN`wN@?@M@(;p&932rthYnR{b9T?R&S`Pb@@b7%h6gM z_68eY{T&^lL$XEg{5UrYb6v@si!|e~0>yPrp6tmu=9*!vX)bvXfpushlK8h-cg>h& z?@hz=5+AmdaKnt$=DNpAopFE02i0D{o^skS<$sAXQC0egqxNlcSW-O5qBxQ3W8S1! z_wB6Z{I@&LqRj;|X^BbhoPeTw;z>OE1e30fWaGaCoQjWJ-_M2bpzWVZjELxbLA?7RX`0-sX-R9-irMo+rq{Cm-p;dlGi271oiQaEj6kb< z3$nlgW)-4MJH!2EU!Ei;Zo*R7FPpO{yIZ8|i<6U+atrK^q*9~T^FNAHVCy!5RB&Tri9i2=2p0ISiOb0GLLLinQ54;CdrV zEFO8e;9o4$>l}Y)nd|n6>M7MLeF}2fmKM zUu%=B&wNcIN7M1%{qXcdS(%^tb7Lh&ga-=OElC}Te$mhIS>Ppdz5S!7x%H|AR4Fo< zI>~%lJe(S()w)Ji6t=#7&nQ11uFDPD=p~+Qj^&|WP~YCqk2pLpm(8EEsavocNHll1 zN2m>)wV3#}>O)W&G`}9Hzhx(RY95)Y@y*k7^MY?cqQATQ1#EkiLV=w6AF5?w`Pqyk z7>vH88}KSk96Llj#z_M1UMw@bUn?*#JuS_0kw{B`Kc-z4k85+? zHB+kC?AcM3&k`}o%6neq81mgSZ5L1$|FQ892ZtAy`8I|DO?-LnjoR zeVI0Vjb71uem%wMmP@&%R!G_(_2QNhps6KSJQLLRNu4*S*et(Qq7P>XWYNX-D>JPA zh&^)*5I8YH7F;^sH}_Vw?R7lgea`tFhPWUQeZyb%&Kbc@o2EWp}9F3 z5ovedsX5C(!-dw{H$ym+!x_yS*ND&rxz5mQ*l8pLseJQCZMf5hH93Ef)zr8GZo+2N zirN*I$%P{>!_9rl5@nOST9^g?L;XW_YX{!s+BeN-VC_4Yd-}lj+BuvLBAyQFYBSmi zdB2-?kP-!%9ACrv$CAUljqcZ*YeI%$;zLDE^#B&#Ri{JCo`USh)ZB&c>NSY8p3PY9 zbe}mi?C{mEKxMs4w1%DmNB|}O*1+-c%iznG)TMOd&;oP&yCm@$*Aq+24a=_O?;GB! z@u`p`_@D({_1Ieyx$YM38sfdXK9w;c5SetnLzY+=vhP8!;K4bk6k9a;Jysa_{~~#gbf%h7ymT~n`8Y~!i*LzEo%0P8`fD}wZ=kA`v~3)b-?YBWtP9@+h@)5 z5K{!uV^fwf|M5#ZM%q>@E(WQu_clTJVxWeCTzuLD**1N(3Q_dzcpGj#10eE_b7wg5 zrANN8-1u##(T1b~Wz%+5;94s$Sa9|~{}<{^2{!4yC+2u!oCAcfH$(qZ&AhmxzW;DF zp;QZ?ROCw58|pHYcfm2=6bopJ0dfs^A${#n^y|G3z0$?%E)>1)2EFb=BPVh*Vi=71 z?R^p7(|*oYSYBMFyznCC-p`7-a=fwmiJBc~QA5TN6&$lUwHrMVAu(hp=xMzF->Fag z8afdx$n2eO?Iw3JMZZNXyUUMn=?_;UctK!75GkBD^f!fQjgA~$EJ$z-cE9_r899i| zE{i^%B%v2h%lsN*3hG=wRCO+n=sAq4w@><#uP1W9d%lP0RvjCe0l$7Bdv^2j$=;%< z)XNr~p#}L_aXC-yCCT4qbWcHBx)*!n7S*01rPi~O-ml2H5fGBEzoImqC_7#$#y@^% z^~TuSSD)hS6##^3XNSWEno0KRl<8i!`A(yu94xf1gqbaWk$g+R{VEZrNTM5rZL?>S zqx-x}-b80l>Ra3G>4XwB_^JqI|2}#Jnpwz$5Wh{|Qv=uVynL*V0j^&lY`k+72VC{; z1uJXA?}pt0$!-S$C`4SXer*#tKO&%xdyPKVSWQLZx`<%Is{OInu7&fJJYuxWBmb8oJ1J zJY(4~1;++FFM6d3A_5;fz=^rL+->*@+N8vwf!=l2i_D2&;CG0-)?}?F)FpELpc4{JG};BJvPXV{mfk|cV(R- zpdtN+2+Aq1v+XeYVz%jipb?-v-zN!pj1gNs|6X*?4gkaQH5ntNizqXPvod08uKMg) zxd58^om36+%QTrD?7uk@WrgabA4fosi0~d}k%aQe8B|7-=~nJ1T4;UH2{Qk=TyklDY)< z9~R}Nwz?W?X~C?XXKaV_J{rTm$s~Y3BbwkV!UJ9-#F!tr>4s3Est{~JF5O)$B5!|_ z4qLp6k&fq)4KzyC3}g!7QYv2NsN1wWxW_)Npq{Ki5i!4rzQ)u$`_Jn@k!C;bdfr+M zMYi}#fLRev0s&=v`}A(vVCp!=bN0)t|Elh{W8@{12~kV2_m!ujAYGthdw^r0CFoBA zTJmz=nu(wlqd0Wjxdulze%O~Cs3zii97l$cKV!f1POAGX3No)Ta1vj*Rh?Bcrqq2W zX-{)|yN7p8CNL_5isBadvvV2@-Iuce53BDvx?v^U|$3A(b!h+!>qs&&X^G%}HKSLUN2QY*keU4i0c#yh4cQeT{9Gvs! z_xd9JUESYi_v%;pjwEX)w)h|u9=e?b18Vb%g)qB%gnh3o{~jwy^^R78tv`T=Oe4@9k#qo&8Z0f9D;-wMQ#P<|Ky(*No(*sf`Lm*c42F5q&Hc2=Azfnwoc9siEbHq$a#EOUn>FSRfp zpH{O3zQbKQbFMY!;K`q%*sRa$7;4u3y*xgvCSk+g!Ybc~^m2?0ls(&d(#{s(+5h2| z3i@33Os|V3*y}m>{;2?Wky@*rR-cp$?}@Su9@-b2%6^H-xxPqjdiE!p{i-S|A%U=g^$UN(c8ct%+qbrm=b; zBO;mVa&mKKpSkXdg9dyoR(Xt%8`j)8j#ysscMeh6b$-O!A|xz%Xbj*$g1w2b0RdSNnI=^a zie9x$`E8D}rtv+m`KFnf5LawAqb3ed4;~ZA$M3>t?+w5v&jN`%9g%_ft$ae#b6vzs zmPb?~(THb`nNl;MHlda}8N9h+E8=`{Bl>vhLMJaEgu1F> zeFKG?qTw#rlg+@f=iuJ`J_jG~)of7B)^}qos9*WyQM*Nh!y}9^@fo+-N)FHfBVO1w zyQ!4j8#3%ymp>j3?(-D@qum9GU&J*=&)aaHsdMmhQ$|VFL|{IBXU32;Y@Pb%$8O=) z0vlE!KDg)EbBWDiFG`$Q%8utgTN~E-^%i@EIS8a~D>ktM+p4V^V{yOyym!T%Mn@3a z!J|?4uE9b=7$%6XWP9b?WyllFAf`#Y$(~-u$^iu4lg1apHk$Ng3B` z`C>ON2z&Rm=nW8)4wHUHn^|KH0dUFz(SYcGABwv@dPfJ@;ZxLNvKK0DnCEee(XH^x zOqDk0Dn8SbzAm3CA+11RXdjt9xgKjWI^3VHe*GD5|Co72Y{0Oq0r^Ju=K(5uyeede zKU%E>3^9S@DMUqR!<$0QnVi`fe_}>WWwh4~) zs5)Gc`U;CDo9Y}m;aDp$uj?G^J3Xz%zw5pYB|KS|3((C&>Vl@nhxUwCGy*j3ZzFB) zhhD}%y6@S?3Od}g^c*=698p>Ty_9I4Z)$$0la+-p3f=d!&6}|HL<=skrY(rgh`^(T z3|#0o_p5t- zmpSmqDZW-~ox%mlo~fQDCdL}hop+r(QE8o*mK=M+#x*LuVYd1zcxazLsCiXL zE+{REvIS|CCRj}pcaRnX?+IC#+t;SnTZ(^>sQjJ==MM!a<5#mQq1cXDey=W*AM6cx z!|9H$WI~6DWqyJmgi~zE!(XmBp~4eCptN51Q@`JEeV>w{ZiZ!iZ~$y^zS02N^@e3^ z8lZSZl^R}NfG1xvfNS`=b-ygQY1-N-ACFzGo< zlaUMo#&s%WwoiJ{H$Avl&4cKaYZVA~DegLM*aW=L7%o92#^E%3PjjuE+4^I3{)A_$ z=S(v}Jl}@z?NLt0oss%TbKb>v%_}s!%`7oSC2v{pAbD0$0OUu!s_a%p5hZ4rYg2l> z7zSCC#NvqLfQ&eZ9g)VsMT5_QLvRH71!4W@D`KEejH5W$U8df z5<^9_(Qp`fITT%##zYb{smopJ5Hc*ylN1Mbb+720$DV05sXvs8Uqqr{zz&|O^rVVJ zRcrmCl3fAa-tQZ>C2|nsDXbrpKKtE%yLC$$EYX#mp$EZqKr9+%ONP2)n($1qs$#mLDq`!@+&Aj&G&hl|r!qwMG za|uaS5ms!<`gvG9RYdSedJ2q7;WDL}y1}=5cR045x=e@x1~d}97e4*7RGWS&j)Fn+ z13wkA6PlUPXHnCn1u<;(S=+8Fg#$e3fcHQlx1tgv>{|B$)iG;&g@;ixAJ$6{Qo5+z_3Z5{gVOvu?#Y3VCLL^4*Wa=cM$_dI&;;i^&Q@lf-b*Er!42T-uY*Fi*k5VdYsITB zmhcWHl&F?iOM`s!{MTf*PG%_FTHKfEt1dg*cUWk`u+PK(zl^f~pO|B05dhS01l#9) zbv7M;A_PM3gKlE5_kIt}{*fy+SLs0gB*-*dPl*-6k%ANG=&>tVy6oM`J0rarH1rgN ze@A-HRzl2qd&tts`#Ug<;Q+I={uh(`?(+Ds{R?mNISUvpZcG zbEk9vD42*t0mBQpc?JCH;R=4fd;?|a+f9&V&4IsP&QZP)wO*rD*+NpPpU8Y$zBj1g zWb4*VnChF5cXe%*%5l=K^Bsg327F`@h>#pdm^7evdSBX%l=Rdu=}~SrjYh2IrcFP& z(~|I_L$wXC#pLPeHEjlq_^}5MP5Cf%D0~PSF?276-%Z z)Jb%Wg@j4efK(Dl2UPnV5WhEEQz2ak3skd@2oEi#ufKk=N`<_DW)7|yHC+!RXc=Xu zXGBUW=#WZB3>WP!P9iO}i*-)%hQ90AYmI*0AN{d!bk%&~jOIq3VU`14I||Kf2714U zI;!=nEO#R4pZ&YMcvU=^Xt=Q_tiJFGx@w+tP%qry(<8YzC~GM1U3GrYv|~_#y+of# z3_@#kf+tR8(-21dP-8@C%-mpHW82+m7k9i9R+s=DK#ys4Sp!%t(2(Qo||t-H~Wxp{(W-2H999J=U>v>a;^A|F0}yQ%^dF!khV={u&kZ(>hXB7YUPn(%R8<*O#t zz4Zzc>B)W9pAn8NiDKkAqgSrjaEO5bukY_j$&lTRt$W?qt-AGrvP^b+BwGeeU+vy% z*(ZtTe8(4q0}Z@{Fm{kWtW)+LD0J9o-orD=t&c%uL(!~}KsYobpFs!2C=y(RN_+H8 zZd(J?w?7Xe*dBv?t5qOc{291`S{Vz+FR@Cd%BGmz^VNm3;9LsQz=JS+6vFM5hjlyf zy#Au^gy2H-zlvy4b}Zl$#3+Y36#JLr0Fap|IYw}HLV|EEu^D%P~U|9Q6K=pa;6(|RKVzU&HEqYj52 zc9u)Uq;7yZB3}(z0irCy5j~bNAfn)gRnMf8MXXvL!z&C1*IdOgIL)58)CUO8#bqSC z4-V}6q%<&phP?rj9nLk^1O12xy1V0t0>yfq?3|oxnIj}bq2&}HQsMR&F7hN~YgD{T zto!ui3?iQ%a&i@K8xc&9w-o9nla8nT7SzEfFC}e$4pO~Pbi)|n!Vv&ozP%lqiJIzJ zDl_U|(EUxdO>$&A9yHW0_uNP83En?#=;*o+%1>9FO>`%{4$^aecx=E|Wyi$DlAUFfr43$KkG2~owg6$R`hhLpJo6b##s z>n0_}k*NR|(Q9Oog$9bSJxbpXRtIx6BXIm4qRo{Mvb7Sd#0T@E2u$Lr(BRrV))S}&Sl@irei2}F zkqg)M+A~2R+ke+>yF)|r=wauzS-=!n)c2xYD5Mw@QU)bL79Q;E5?`I(A!+tm zdk4_%VVKDC(>VP`rUUa|`6kL0_6?GY79 zS|zY;NsSLMepn?{Jyg@p_qA`bQSL%<$}ha5Acl7I!7BL)VpM|$JqFUmq{Qtr=!SRZ z1~<9FV6`yV_QQv*xGVU;@|a@$ssDj*yAVa=d(-3hDdF~tc{sD>Gis`{vZ1KfLyvIeFt@=-sP zdR^u{+pVCc1MX3|8$zgo73SciMQPmfZWSu2DFbFWD#C=NR*?*GZS z<{h%eji@h&nCna#4%30^yRB4+m;`Hamo$TR9YWu!TlDDSw9p(SMR^+= zSEe7TRCZpFno0FsTNqI&)PRutJK4|hUxCdu3oDqIg1?Lsa7%X(%A~+qr7>!t zYMkY&^$mz7 zf09dKf=83buGw~`{QENw_X)fwM}^r!tbr0x}j7+SD)mjy8Gm=kVf?mwbLNgF zJrR^KmG-gdnh=Gh2&SdHu(7;>R<>^;T=W zkAXPR65LM~|IVzHv$O?qS!#k5 zSO>}-tsb<1GW;+piRCmMz zi4C4=bpuU)hO%VedWWSa*&LY}^3{vARb^qvNBt3VO`5nJ!+sSlt^Nu}1XyoXI-l&X zxaw2WJOBe{?9({EJ4MG2wgThD+`E-jDEM+8xz*G%(enlK_2B?DdoWuMvu7;6wTRvG zuzTZOBGlQuC{KtL7Fom^61XUb%7E6q!T^W44cBFOzF0>mxY+-1FR8(EE)T38n#8ai z*}vi{JK+JqzrW=o&P)kBw?Qd@9?UYDZdB=*v>v@67d|Q)p(=~xFVQa2e{$$ z$SaR8(OrvgYM1^bNCkc^w$s_jDOlZL$SFfl_i{*^j!NND&Y!u+rcS>&aq(MYo$l~i zIyMX^kXnBFMG}P_A`iTZDi>e*`Gzlj{IAN8EpizgYXp4(p%Vl}DYl+0RkhD9teP#f zcT{LMciL;a_d37r#oCFPA3$^kJ4;!Bm3l-7a@^_QYm*{)hDTgL@Eio>R7VnjhK5q& zQ+Df{mD==m!PV6*ExYwBYsE9SbNa8C>@k+!m80N?KvNextt5{z+H z=4Y9;YGG=s!0&E>m?akOL>DV<2f2VBB%a5sQWgf~)FDIBfI#CcC4nrLN4m0{ja+DZ z`Sw~6BJa9%wPlM1VOHF_bsom~pM2~0W`-qQ-&4Z5Skf|+ox3c%&4DV`xn?b2k&hI% zBAAWEH|+l^hN>E7lvE`x3{Vfa zqMij<@8vtLI2^=ATdbZ~3qH)l+rfb~H?3HGmMgDc{rGq?-;R$SG24?@J>gDa9@a$z z+fuYWxmWl~>eF5fG?rX0*zetVF2X}Dz|0J&SOK8P&b~=cumdQ^i0b>MajC%O+bSSq z7Qu`ySmYhrhcb&&a~&|JjQY2|Y5D3>g8_t%9#TdrfGthpEkShHa8Zh4p<2J2U`n4P zy%=>V^uWr% zK$5OkWd7l*G7TwP!I@-PhZuVa`yioBkN#Y+oMdYM}Ldh=F1399Q`3rN0?f` zt>JItLQ9~4q0ktOsD4|x7i@m%cl~DxLM`t;$mY#=4<-ac#LCZqmW>YBd2SnMQp|Z;-~I~s3Z6dXfsu% z0`~NkSt`521jVq&Qv^;*Xbx}(@!dLDeEHYx^~`3|PZnyrxn{Qa_eahbalj|W08r?;*|NA;*vo5nr)!*_PhEn(^WTHJyXEvSW8Bd-g9vdCUZgD zl_T1`^y-W;D+bj+%BYNAh-L79R64e@wcjlW-UeFap*RtZPXFF8E;-r>`Qh{BBqQ(O zK>t(Z8pnL4pAA1qwA`?impljGyt$9gH=d)vMB@H(#U9bn)T1Vu$}G#1wvN?MmYg~I z#lsMO>P;Df-|_k-#Ym==|4Ngo!=&tiXjU+;`=b60vpo?|k7D-1pxHyn=bfOR7mO%v zuO7$79TeCY*1mF?5W*zBn*Jg&Mg9i}$T>kY;gWgF{Ly>7kFn4uVbnG9s9d@pS9QX5 z9xZpuFv+#)9MiT9YbY+L@7>bp9I`LDLuob)Xe+m7RXLCSq(x@^lH~iCm2SpXa8G46 zl`j-(>x@W%$_6oMHQ>JjEh6t7E5I(CciKIsORqm+Mwg9dqQ-EQhn zsNI?yyr1l65?}vN<1zled}U9qP*Wq07cPX)Ss&hmkU1?MsgOvMc{{N^axPU7qZ-O_ zYSV^4ezXlaFe|syYVq%Eg;=yC;!!#_%+Zp?yd;vGb2Tu4qlgC6E`7GvNiD!;6ldg8 z*t2aM>Z;v!@Hf3QneG?HEHhLQ^OP4(VL`?M3xF@C>u%BFFY~4OrHy;I@AKoA_cNqz zE3ZuZMu(Ea8wKqoKXvHC%X!H?3-@~_e;uDCsGLG)vr1{{W-Ej`#Js^vOC5j4329S9 zF)<*gk;(gfzqN!g;hsO@o1kh;B)-7=PZx%l^@~+^bd^3IW!#Dc6dI{X9~NKdjl>O! zSfA$Rv{y5R$-uKE@hPci8zTYWZ!{%eOrHC=az@w+xYnG&D~z(zlbx`lzc6)(=br0g zrc9<(EqnP67k)I4?ZA9)+OJNCg0BL93U_ZT@%fAw-Y;t)d-*#iVCviu=rXwI!SAu~ zv`k0E<$QP0ZDQ3lr&eJqMzIjVMgSN;gk7CnVrN~-o;z-fw^y1gY8rgCitBv zgUnGW2o%^H9rz>=H3uW~{+y`S+0xQttShBSN96Qr7se>uo$_Uu^>ReX#!G8;Ws zHQ2br4#Mu=b#zYtx|z$#>65ka$aBu8kMPq+$K;3W_e|u^P)R{PwjOy?e7O{k0h}G( z5?(v-mQ82$YdX+74j0HCmi-eyiGTK2{gnURLK|JujqwFJAxLmNJ_&2_dWM_vW4!=k z5$zxQMLe!2o%6s%eDKtl&QKT5^efR&OcrIYYkSo#_1Ngk&PSVVuUQ*Nvzy2EpT> z9hd4&`c3XDrRTgAjpGM{A22hv<0K>{e`kmwRa`k=DzAf+ae-dbqijfyc@;TeN_K^~ zkqv2(#4Zzlb+=*X^qQ=sK_c^tKXOJcJ;XgV{j3@qoyyt;-ZwjE19W&eb4A%Jd}pEd zwe=0umx)$!o{mZ*oquRS*_c=i4x84AJz~K9dY}_!;S@ud@n!6p%gqhY(>j-60X+2; z)zk8tE@o^D`=Iq=Q7>#xv^zFxZ}H#4>~Zt^c>CQNo_c-lL1<~>8tu0CS6F?fpX(0s z9&rt@{mJ7dE&J9+98fe3y*oERXdBg)s zPSh#a1hMD5@!#4B%_-UDZf8XiBXdI&=1itH7;&CmZ2F@=#fBT=qU=$oG%nE{DupP**0CUkCJ~}@OWtK0o52-x!&kzP+@gBR((J%bprxiv3oBEjMMdp?4eDBm`-$h^SZuwe z6db3^N_erLu&|Kb6#a9BSII^bDwhwD&Bd*S>M}wc6KKj#Xz;=#G6OivZ#%#*E@Hu%>q1UcOh7GJ#3otMqnzoM;bGLyA)&$kMH9gNFH0 zV=CD69>i@u3;aq7DK)UWG5iw?ED(;&`O<^o^I1(pyIFt zEo9tAb(CSskH7S1k>3Z^Qx)rr95Umdr?<{E>6c`%kGo;jZyW_j zJWR)DW5g(u>R~?C<}FV_UPJ+ZhDLoMq8wwG|T(8^xlEX{?m$U#PF$t>7jNx=8q?(~z1iHVJk z%~{;)y-3zKk$bN*&fs1DFULz=3>Y+e;q2~KRv-{ZO6|edrY1mZBUnuK-BJYwguZIY z@k#3-`;;iiFwGDO|ALO{yZY10v?6GRPK1yt+<_!+>!{7{IaWexfA;`^ zx*($F?g@x5dPTs&)6>Dh0m7VV3l0aU&TG}vM&`t?Z)R+Be28G(H$nCwW%{HnEbWWh zB(e&Tixa&?=sB!ZViZO2JJil(weOw$7bKke$p&^a!|o6=Fcv|UT!7c*b(UPNe)-9{9yqGqTgE9K4V&Kw+jlz~m#i!DEZWAsczj4bMA;uB(? zeSX~3hXUoP!NrdXr;oCj=^M3XOUAI`$w`~=!JRH%j{Lqy6xH0gSU<)uuf{#18(wj( zE_hnstoFx^J)@FE?Bv!eoO1&4!L9O<*3Cp%+S zO@T@$e z4Yg5S$vAEu<{-J!$v1S>6>Hlm<-v5)lB-y)!;c_P4nCHef`crmVwu^R^~0Moi7tn? zENeRstxLpWuTQmWjSfGg`V)%(qp%RbtqD>9~JYYwgzlWav ze_zndLhg9+O42%w#_x?dsEC+JDpN?4mxL-*2SFm{_CEI$LsZ$b$Di#H#bzb{ucoVj zYU=;u4^Rm~rIe7435dj0Bm^X-JCu?VknU!nl)z|^6r{UEYLp-d!azzGFghKKk{t1W z`15~ucFuOrdwXy9d%yR7?&scjZ+)q!sk1<4z|re?!>+pNITU7ua8+^8Fg1LP8EQND zhm5NBXjQt!gku7o(MEMeR+2@gw%($Ne=~pe}FujLeIJA)yRNEJ97ZO!09Ajz44-V5>- zb$r2bX?AQt$9X(j3=W*908}$Y1VnrqXw;;Ckz1t$OYsBWP7?xmwEzNP3ErkR>a z+_{~K8kX3nqxhH;yX_tv_7%yjd*o zUy0l+Zpd-cSx%#cl6C68q;;$(t5V@};^mc?@Z6mE+UQmBb4<^Av@bZ7=}>lIf3d%V%uU4i;#Jl_m36E2g&M_oTcC!M+=4l;61-_ z6mm>#CNxc~gK&1oF!y& z7E-*!&%%ia7Q0XG45?KFUV)Z%tn|a7ban9X;};>rk5Pm7>?v!cK|hNC(Fch@i3349 zpC6`HU8)=PwwNJNsu;B+d6%?W$OMxT$)>v8I*FemeoL7u=K_w4ojyBb2i60PRIg^g6T9a* z8S6Xfcpn7Xx;6#&TpVY6EI6{ubqELTlVJrUL7{U6UY{yZpH)d$`9L)K50wKul16r;MLI)dI^??7nvl{USs$GBHI_>w`YN{z=3=p5EUSYw&V zfm`HwKqtR;o}fue)(^D-?Sjqh0b1!RlG@Z9*93CMM^)g*_kG^QYLc+zUkT(VRdM*; z#FChe;0p^+Qsl7eHiD$|sNKAIx6y#f_WV7gtU=aNC>J1E;GsJgnq;Oh6^lFCNjN(T zJCs~00RPV?|0N5F+**~M0fEOJxIgP7Ro;u6EAQhuvu`du+%>WM0ah*$B7^lxqq~km z82kG4I}Yr)yvyGd!o7*mO?|PvI>~NY*Msl;PzQszPl?PN%x??UNVJ}4Y5#mW%lm;_ zXw~8VuiJFbo+dtfSih2CkZef5JNethd4~h+phxpA0ya2AinKZ{sjIVq=5RhSg4kCap5`U2o|}YA5?j&!1%r7 zj6L#q*VpC7R^^`UE~nKE?)PPgY74KU9@J;P4}JN5;x~cMpP{+AcV5nZ=^V04FOvcd zR2KLlmLcE0IkRs+3XXPwb(x-=i}pj&&&0{$tI;L}2F& zsLxgaGo6cLh?(;z!v|rH$n)NYbVzL+FV=T-_quSmr7#ukDL?q+HY>M!I}i_KpH z;rEi`bC1Y*Btv3jF3aI{zEc;I*{>@Z2p#Suuvh`uUP*@$0m$CN8-|lDun`Xv6B8WA zWhAx1ULJ;SKA1d|lM}awb-hl>NPFVv)ez(kwGts)&7!a?!pk-nO!eammU2|12^Cp$ zFElRKp|0Q$Eh%9Zv?$^x5qwQ2=cY;~GxY_}qK}=PeCxtX0>-AD7graLR_GLxCZ$B_ z*N74WA6HWg^7)*N#wzKB5Xk9L|BKU((LvAwE7*-f-f#5l5(81u#xx8@0jHC;l?0Mt zBV?+Ysg0%W7Faram)TA?JoCJgQ6wgf9o+Jq#4MufuJo@s6J`>pIKZA4Ki<7lqsHF% zE|Hjc#P4J$nb)8D=sg9++u~0dk90yKAVvsN9&SRJ5Z8euulofUAGa;G`+8Ezyn6Dt z@W}JNSz8gC6NUHO8qzK=LnWDUv6b5zy%CHHw^|tTjf|9aRe%>Rj@VW7Bu970@af#S za6aF{!cHi?C9~LTpavW&AdJePMt^vadFW4mbE^3VW^XNwGBK_-3RQF%Em z43aTID!E?q^Xd7$yj{B3+v8i=y(D~E{XTszH~N*+Tc0) zVMlddF+Y~%d(;c$o;ACS`^K_1+0Pndi)9Ib7GE$lnGRFq!UeUo<`k5qjBj}_!}+Nw zqPHwKHA08d^hHF|swbg$>P?GnyM@uUqogdVi-6_&W0i8(8RSdRtt%N}Y3b<^oU@=< z9aUR}=zIwzG3aE56u%MB%4l*Y4X?ZZR=*Ue$9lgP4pZsKB>Dm~lQpyS_ zSuOU3a*qpAuin}FGU!5_NvqoVSeby_(v4^7hq6J%LpgTV=i$Fu!;4(mDmXxiXF$85 z>uyavo4HnmAXgGWyV?sI+1eAcslorr$zuAqWOi83Dc+F{Rszbj-mamJ@`=W2y zupm!)VLLDruYr-qv6Bnj`$qp(1>0Z%Vba6EY=W9;W7uKfdJrVJWCX0N*7kH$V=tRNBBB5bxJey2 z|FBCxeE80lvE{z{J44T8+e5Vig?qgX%6VnAtKQJA)R5uk_~nW>gGjwHhwC?X`?3sM zM;d1Q&I)|D1L7b1a=OYh)^DQ?-D`%fGhY3VvfsdGpm7W{ook9NSciUw61;;;P+a#hS=Cjh35^yre}BP2X$55Ji?>wqFiHL--a_ zo}}D;PD4CZUHH0SH;E(lhODE$b>fSj8~Xl{lu9t{1@r0eoHB3#;TDbymb zbt3?fQC`*pc=Ym}2oxq4Uo~yN`|FN`^>`+e(eZqaD9_%OyaqkcfzktJW^>xl!u{iQ zk^N*<20ZASbsDSeS%dPKvAP-N}q2H9iF}K z?M>5Kv>~E+)>*njA1S~))YW7~G6HkPgk8t(<|H{CB&~piuZ(}nm+#HU9ewcj%+vv( znY2nC>X~Q1ai+3?xSTXsxiLxTVvh%!L43xnh(Y4ai?k(Eqmi5u$lAg1lz4y zb?4z>-3G8}H@&70lm|n?`%$hJx&!j;*FtEhzS0MIHJ({04%cp})_WhIz&`Hxf382K zxBhr8T{so%AMTnxVo!uRc4_>m%t;0mYw!LZE8SFcyf)|>68PE5BsC@VF2a4UxV7-v za?a}9S2JL5EXB-{!F~8M#hV`nyY$PUf1F$S^{lCq=^{Ba%50WNcp6KfV=4D0yy2J^ z$(VV zm1xo%S!)u-=`Z!aBEArweH;=A`z4%wqNNQBwFIJ_p5x0;^XI_Wgp{3s%!h`BhM7t! zbMd5iGBH_V-8T_4kN*N~#NH|&nB0?N!1B86|6UFX>a1)%!9*`c!Toh!_FSBD=`h`v z$Nr*MA8$Jq8#Md8lTu<03~QPb-IH=wXR4C+b>_NQ|5NC?eFxYs-4iS_AQ<$o=lKYI z* zeLxQa%o>A!B$83$Jj!$psB&Ml2a2>6P5gF*S#cpIPclga%Ms;;WNP3o!1HXA@?rryrn9$6Ju?mKg|4S(Xfb>M{yIo+w18PymSxDP zbVg$`kF10^iaQ1pN*P#x>&A28(eqKE!}%)ur(W)cCTIPe)@b9J+1n`~lW^(wE8I3G z_t(CHd4Te%YYn&C`auV*X(lWv-Zp{KbRgc=3jVf2h>et+IF&xbE}cPFg~r9B(EnT; z&zI!flV09np*WSAm4e@E)+u9rD3>D+{6H}-Q>~Z{+~U_|*>@UQ7W)b5WweOS zS)#5!DMr|?(LK@WbCoIEK?LOTKCr`g9Ua$Ag>0*1CJG~6Hrje`GipU2j}+z#3S(LDvUi<@1@lhu{0;R6O*i&*6>&~#V(4*pRF zNe0kFS=^bb0Fw;cZS#7y%a-0#!w@|EVrK$7v$^OK_WWS$I!h5pzA*&X{}1j44>nAj zToG4be@S#t%~1-D+kbl^KVDu2%n;D$2lV<=aIJrky=#2}s0-N3{(+$KbW1UR%Ud{x=zH-{3E;iy+<-gPrVrp$| z8H`_t76)SLQSuv#mfqKz?foeL>t797*1~g`tNUZl{#>`Qv2h2|vWL2l_YPHW%>G*k z3_Qy3*3-39FM1##KsI{4?<&@QBLM&sUnUdaKgaRL!AzEBKO7irRvK1!%1_1=@%n8Q ztq^BUt6l=CmRDeE%q;>}tOb#i=L35vbe;dE+}X;CvmwBnJC@yFnDdAZ%Z1K#_Tv^N zd3eT+HKKtu$NE-Mz?iQ{esvU-2^NW>Cx3?zO_pRYpj zl(5alDnCz+1^SK=w5?2v1x&sot*6(^Cp>L@JvOA z>yy~FrY{79yROZ8q4kWBm`HgKz0E9&S5EAcyua>ZU%yJ5eAN?7{(PkxoCnf5btTB>JryrHtw zGvdT)j=9GNZC$gCZAu94oP?SAz`TAmZDL*TNmEnPw^`h$kTLm5Y%|wmI-AN!!9!h;KKiRkcJ_1FiP!B#;5MXvWp%C# z_eiq)5*A%ME}QC$aa%CB-0DOqIW{(?3<+5EvH5phXCWLru+15vWcz*d%JcE^`puk|Ck;QP+FS3b9`uEti)(>QLqU%!T6i(WAU8?x1Hy# zf4yOajD!a#IEo$|3h0=#+gigVjr|qpfpbm&#OoS%6yUUa*oo2u5#!tUxQp=+v35>B zGu^_>Bk!CJ@Z-~Je+lCt9`an;Eu-l<^B~4 zP7y-jX`8hqr19d+!gp?lg>Ccu7#)J8de&U%zi=eh9slr`{WZG-h3HSizaT-$I8GD3 zqCvhA(KmT#4fi|<{vGz*U~Z;KXS&=!esw$wbh>|d&wV9oUq$=xnNN6vFwnuKjau1| zl=A_$MT`5;XtLF5Ug|$q<`w|5|Hs+TLIkK{w6E;_<7Z`-y|pWP<|^en-EF54lPA?v zemo6(xEeub9s=L3#2+mO)PGasew3hX5T$GwztpJP_Sa6e=8fX q%3=+Oc+%qcb7hxq%ZR%5Lc-^!W*UPxDL7UP02E|ZWh$gzz5O3V?9r_N diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png deleted file mode 100644 index fdb75ac0c6eb8bcf93eb3341f7de19e2b6123da9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 183400 zcmY(r1yq#Z7d4ClDhdclgG$3t(j6j*%+N4HgLFwZ5+b5>4_zWd%+M)~NP~2zbc4h& zH1C7{{@?e$vv9GHxp(e8_nve1-se07t0>9g;ZovaVPWCPzmZYH!om^3!otS6e;fFp z-0f>c;M)U-H`>lvSR`+Oe?hk-nkSX9u%2Vd%e>U^FxZ~;bfI4JWIC&^nk(TSWca}J zAm%a4%ZGPk=qmZJyW`m-euWjbM$u0bF0rUaoro~2?kXhKU{X>0=mGb>UQ2VQwAd}v zk3y=(pitwVkaxoork;ch6QqoUL=_*@VxP#D-ipDZw9Le8*7`kBW%q{8t|MwyM=viT z@Cp7v??{v2h8Nx2J11Q`JndYFpcZZ^2n!DnkBsCE9ix2u^!WVp49=YHA$@I!euRgI zK0f9NU2yPlaf#C|K#0FT_Gp-!oSe+hXLU=tLqXug%?xFELP4SQx~~Q! z7E~V4wt1Pbn8kg@KL(^#dwH~pL%=< zb>KUS7-DtHe{LA7{LF+fI^NW3WRX3b)P5shHQ}i-7cg}mM^T#vQhh2j?CgxDmrInbxO-b@aHS_fQJsjXeP~Q^iRwie z!?7_Bm-M!o$<0ErK&Jf{f$ZUL9lGB6MTDU!-CAn%9faPc)-(dkaBcPw_Fv=Ck~=kK z|E8ECz|E%9hsf=(*T{K*zfM6A?HJe{-r(e9cb#^Q4kc}TGF<-m3SePno^4b7&^m`a zOW;sZrl!zLiidHth5vL}t=)h8a^GR}F20#UWf+^R^Z}HyeQC+&z;h;DaR-Gjl>YM; zRwj9;Ay#IDFjtYZ6+GH;RfG_afFLp~>_w;wj*a0xsRmHlH4ABE%?zj8Xfq!bD1ciD z`H9>578X`XY9&|0;~!X9LUD(Spr!d#s+tNgzl6loM>yde{)sgPI40|FM^V(wJWs>H zTBAXxwq$DIp&Q1KQp?_M%>^v1w|>A!V_|_;O1|SFpr?sdca2xQB(T-UO|psZ-wpAu z=YIX*?(H1r!svYyHr1v3I9OPeQGtYE(9?(7ls|sUJ^_wa#7Rw$pO5d;5c0OUg+)@7 zbXtu;`<8%-se1ZZ(Ax{&rqc1UH@;0x0|^}W8G5$q0M8+Qct}>p`H^)A<8dqKEwF%Q zLZOWQvGO-ZP>##X%U-x2A7xr<>PYdEx3+gpdY^Z{54X7x8(_KX?=2By7E?e(ccj6`j7pGZ%#?GlQY(^=U6|PfBviW2Y z*-mIEAfIId;WjrjGJ4t9ErCHw($M+=#>D!7!%R87g_TKKQ2>5V6-?56#www23=3L6 zSn1hTW98ZCJvtxW1_AHHlDgwOv<>=jw%}IIR;66PzRf%|QC|86!DT<_&WN&YI}6bm zi7iTSeUy0fZmdk?W6hU$w0Rx4SMdWSTNA5Ztb`0&j+~IwIq?fZ6cu}oU5xyLhDs+E z;cUG*2bmd`ir7vpOC@4?kB1ol&cH&n2>QaBnr^AURjw#G#;3rl3uV)@{taCF-tNxM z`{ionhZKPM<>chhY{<)JS1;(kG3FK&J?iXhv z>H7BebOTi|)JTCckR>FF^Tv2sQVowg+S?~8N5|M4RPpfexM!gY4igo6h;|@|J4301 zWyUaC8$fEf7w~d*;PmoJg~c?3YsfAP)4{hI8ULrUq6C8D-`5AM{m*vqBWX7Nc;vVO z?k(cKtNjpdx%Q_e5&ClfwVd3SFJF>SXIEFgqJACYsw_{8BcObgh3%!dyAuoO!derb zTjA>F2rjsjF_RhlDW7@T=Eg{4enWl|jV^G3Z(d%Nb~x<8+^8~nE4aFXk`fPxzi*SD zrRDvOfj3n4*`-ze8pArqch!}H;jegEIYNe%9&m&pUuQn}H~csp6&CO*=)N#SzP+O( zoVUvB{rf>8OVi%h9Kw@fc%S|Il+4W(m8>3V^s@~|s~z`d<0i-~Slsw@h8xc-DC^%_HiH$HKyfhb`@G}hregERxbXPF2c3C}CYdxX ztakxyar46KiExCMR^Sqkv6;SmAma~jKk_z#v8&26KmU2a!^WSnxwn@~`C0u;3fBs7 z@0*w9J2Fk+L@6NpnbJADQazp48L~6U4SxM?v{U_~s9OnygsqIb1SieMng>B5 z4_(5#K|a8BS}M`hGke!V2g$vU9UvOSLL^*gUCEu;r?T3E-tpmjA(pa%@-jB zoZ&-Gv_%n>vT)CmDjfc5?9MH^&AD25P;zq0J2U37V`7d<%*4b9W1=GG3B_08RcBXOJURQ9HVFZ4L+K&++G7SH~g0c#>$ ze-UJo2H~Tutgis8H^fVw^Y-as&M(7-oo5rHU>nahh8~dLzgt^vXKQU|V4$O8pu>}& zXZ%E=;D4Y0;c}9$h?0_$2M4%w9);G+@y+}D`+)o8G$U^Tn;;$nK@Z{M5AqNiQ{7W9 z;q5DQ386z9>%EU?Q~wsDHDGZegjA*H*Mh%tEROToI4LR zcQ8amnAYUr9|VLU3k&lKQJnt<3$>jAPyzvk;^LFzO%ng-1c$_WCDXC(%I>Y z$Ez*+{WT4J(q{*-UO1;2QDU^D^v>l9PMnY{2!s|pslHZbR?}}Oi?u5PKXNnJKa>7` zE>@?a+fJ8&th)7@&LWAVc%1Cf?pso-Rsg+~XOU`ghq`u=$H2AUf2Jy)WBZ|Ue0W&STpl*d zn^rS-9~+iK%UW)XSDi9sSYh$XlrAb$l^Xzy8WUjI9KzMxkvMwK5O&nvhYE;|G%+sb+-l{ zS+d)I-IT>aNI^1vRU060(<<*$_BU9=VfnDz`8M|JGT#Qfy5uhj@pmV_HV)Q$T{RRV zWPN^a9d3-XeQB5aZ~0$!I-mmY?u@AG-lo6ts#yTu-+0w7k&uv(mW3k}8YoS>lt!vZ z5deZNZ%?A^3v>i>&2%e7=7!2RK%8^Z#@PR+a#P>>-pz+9du0XBL7_y6gnQU2Z-~sD z^xOU)uJk*SQd9XN3II~`l!C&DG_A+u4C=c}lA)%0m5F?$QzgsTuG>DuVF>9-zjJS~ zlwA6M1`bGWhqlAm%jmdDNOf+bL;vQPPP_SU2jt34xIJef1W0y;{BD@q2I;?rG>ahh z^~_=gnq}yA(M5x_f$>t8#y3a$sI;u)qVOa$B&fZ;ee?JFzvzNBqOh|F0O9T`Gf{DI zpPP7BN(cbCV+>~eahNAek|)?3o_)-i7&ELw%SYGol2-+r1&k$OL&(Jdq$Qt-s3O21iNLeAD{>?ANr_9XENhH&oo0}0beLSJA#k+e%TFnCkD$gIkNUwP9_I>`ps3>)r zZ+F9J!W6XtknvLU#PY!imq-QUfCmxfE5XXtkY1)TD%!mNTqQ4k6F7r*mfVV4oBZz} zzyHS;Ix6oLO+LumI}d&R?M(4ew#I)O;8$t;-o0V_!7F@{=#7ktiAnEcHsHOKa=8GV zL*p%d04-6Vq*eaAI4ZoOA*jtvJe6W2-P;`i93bwX86hGE7WZJ}KoGp?U+yFSTmHKu5RiQ7?|=Cj!C9#0+0ZEd z9>4x<^KkpKm*C&nn`Dmy7~T8n+}2~;+Aqs18|RPfOb48 zzW1Mv>S%NK-9HG6tWTN6TvEAB<3gPH{`;KHj<6Abp@y&ySswMc`e;y!^8vxY_f z2h2)#*&|TfGdPy;^mGZj5ShN$-v;?bdp5h4m$OS59UL5@nhqb@2hCQ%oJK4w!W7;a zHoVL|p@)@w0qpa?g=xu=0{KQ8IvWSGQuv}Z>f?f_y8D`rkf~ydOT4GryXq4zla^+i zscDp*I}f4gC~Fw^4~6YJ$1RsFl0t*z-_MFJmy4Go+3*BSc_Zd|TMip&1ezV`yE z@EX=@qQT!eNK|}5fBS~81EJr#g#B-ljVBw`rUGEa0INKwTji}p{8GBC^j7zvH;M(u z{a1qKsC+tmdKSCdbbTHci8d@2l0MFV6Ht~j6?F@iAvqzax2C41uEvPRj@gic5O!ht z(uXU6I|4rA8xh`5K4|IUOKH@{PAP;AzRxpY~n3UU`P$W2$AmCVQD z3WPQ|5lSrpgxtDi&HsT~G2lP&m1zzNK^=r^7Qa?9g15C!{GKG)Q7S07V-Q-23a~e z#Q?wgW72P+Z;Y_q0tjtPEAk}M`rW&CrlzeYFFxh|vk_K=x)Sf(#{Erl?a@x(?MVom zJI;tYF)BKm(7d69PWL)%a2>eJUSl^LNq0v@=Rc>%LV%co^EaS@v;WQIN@XatQp(by zN&g&${vN(G^FXmYE-c*pjZAm)gZi<7t+_4l?W>uv{8Nvy#Mt=C!jmtySOzU{t07ZS`LZd}vo?DQfXRtEnTy zsj3&NK6tg=g~~h$e=Ya=^~7jpqOTJ$>+GxlCUjM%e)_a8;R)aN%?MCKdV1r(gDgv! z|0<@fCIMXAW=}0KV9cwR|BXR|kIpZ@s&r~`jDA=eWs}c8I^Gukvx(|2N8v5ePhX1L z%%c1A!dkn@zl`p8J>VyPghL;FzfOlnvCwu~P5Y>3^kA{2Wt-%f@ZSZ9pd(WC^OGb7 zM6h-t_j)fQ7(#=xczk@k`n~lgL)|TyxdwK?%cTdam~()S@dyZ*KT-}4do`x2gB@>a zYrC_tAj!0eC?)<)Bm$c9`8`mPnozRp?14Gbvi&ee< ztB4hkZ=t>J_)7sg@b)%4p`xN9VAuWqwjjT^boUuwz~+F--NUl?5WCgtB4TMPNtK~7!$>+5tJ`GRA&s#N1~Eg)oj zd7X{qtA~b$PGxzCBr(B&K=kU>E9^yP;4C<>Z{MPuYVvDJ*8NpBZL64}YxMmuWcW~? z_XCfxO<4@lrUvZUSne6&1FG6UyxB${g53VJH)4n1ukNHlrd%g@|GYh@EH(^BjofCl z4!gOG+UAHy009Od!t(*`4nbTE)F0ATMeIdTVV3pv)uq4GhkPh&suqdmBR(dijoZ6h z8k~>sXA4}Hl`n$A|6jLqNPTS+IQ$VgGE&}aV8Ik&cC<&#FL{)W`8{~{roj9BsliD% zty;=0D3GGsCpR_Rwc(6sXKwES*fOf1to%&-Nz|lVqZ`1C(8|gvC~&^c&dwbXH0SGb zlGa|kNdh>@@vx+;$T3+4BJIQ9QsPz#CmcRLN>(ICC*Dsp2x|TsLnw%H<~~Q-hBNaF zfw(-IkAuc|p@S)@#!C6o5j{Fu%ah=#Vut9~Mjs9!Vn5t;t@mR5_=Cn@in%V?P*c+# z@JDTzJmZhZPUC~ij1)~-?uvaW`}+OYKmyX#Bs;%f-rmgLg!Mtkn((wrN-ErNY5)6@ z6RHN15On|F0w$s)@^rk;2+deO_lE8{1VM)FbgUyWU4W^Wl(J2pMIyf@l34lhib?Jqz3U}7lN(~^jXB) z`d4eWmQJ7y$vf$AL(Ja1vW%>f1%_X+9Kt_7H~94`^k2-`{wAe@7!qt{+{~lud;f<8 zK7E+zvFa$t3_BYFb(3iV+M0t1Wrco%l=_>SQ+bB0z1o7fj{>E0_M;4hsITls#+@YV41$50 z5}APq?K}(HXPqc)6Zd!v3Y#KwT0oI5GP|g!+vq5^6VyspLW7pKJrs-$x^v;D}$X z%3_tPedd7gF+~WA=crOZ-ho$UTDxNa@y2|SeCK_lekJ$bk8epm7KyUQLy)$aP`td4 z0#cuU*+0n>z)GHDQbS-vN2|<@`NhR)24(Qs~HP5B4TiwX-YWzt7A@FA|kwvsxaK=k{n za-SbYnS)nC5>%k(mr5+ z*RxCLQIr8rlqZW#{xQSLKhY^ci}_CoN6VH$6p{2$!$8cP)`uooxhsLZM`pU!8Qba@;J<^b%UpBJ6y$uu*8!6d1N{3)!v4yHm*!(af zmlfx_Q9o3&F73^79H=>xtvjg zuBdO8=mTy&p{f`hSr2_o2!z)UuQvAZ5*qjz|Hd`sc!=vHt{mH}1NKMIH$?8UeUU$Q zmX9Faq14G*+GTrQ*iOV$pfdO36B+r50S?=_!YdYv6;UBi4!J0~ZSIV@l65N}&;aAduE$@ScuL*_|jhaRW9NSg68i}p3Q zgmF+}SjQ3s(i8eHC=a*SM#Ed^$~rPTufL<(69@uVMS}rbYjShVU_$&8P(0pQ>-C8bzESq^JE5Rhs=n`0^Yqk(qiLegbPJy-c& z0UjP1aly>G+f3R>Y+BX(UHj5mrw)^Ecdgk(GgLFw1hd4-6RL6#!W*G43>!%7Ht%6! zp}PV6QSw!{fdO^?S!g)3J8tapTI)wjb$Bajgi=8P2eFWm>i>EHxVjBI-DiI$F9K=s z7b5gB^j&n=zMN6cAkm6^LL!L{4F}1IAyrRY5DPz=ea$YGj4ladFjA~}vJ?AMT#3Xl zMu$lB?8vb`uYq4ww64BBwYV7!SRV+rfcv^tJ|A|Gf5s6^ z3w+*`S&~vM0MHuFX-CQzZF$psXd{?r1W;2+~0{cfYCoo$FNq%{QRRoU5H- zDXGujAgPT$_y;peCaGH&;?TA&froYDvCOLdm;;;2vvsBS5_>b*3gxK zExSDOyb@DKl|?9gV;n+2T0Yw~GUmZlihS<_UaLr!L_*hXkUVrx9{5GyEKF@xSD9V% zoAn3h>Wz7Q*9Hx5f4FMeC{m*ikdopBarKIE010pb?KL_2G0ZBiaa`Hw=LxxOX?80Z z4;hqqtWC0pewcFB8bNg$&)GLBLtUJm;9P2TdZ2OK!Uh(wf5|>yH9C6!l6E3Pw>I^` zwb1(ovtvS;*3h}jjHPLT@-3OT9@ZooyVEl7jh*fDVo+DsXTRw$XAg@7nml5<%-r%} z9)oFJtUPit>#nL{K|}e0rntnzx3DN9;-|9v(_TbO!npda4{b`#6#_u&I&6Aw<3{t1 zUzYkLpO6@siingV9p=$x2{}krl$vTpSv@k-U5`YoDH>TaYvc#tK~A(=P>yU zPBSh=;B<+iEBPJqMegwscZ`InqO@Wz#?;Ig6Dxe0u4+Or4;ves!Qn-?WLgy5CWSO2 zX$|JuaHPQB0Al$if72_+kU3TgV70ZiwPVy~l@Y8YgoIonKW>fVVM1rCANr@I7N-RX zMKDM7v{|gMEo|3h#Z?UCRok)vnIK0uSq(jMeOquHm2xH z>#sVvhC)}Xe3zAO5Sg%n$`IrL?#^qGuAJtrlP-xmS2AIJn zpz)wga3!vsprFNN+WDL+j{R1m%ApoIA~q~bc7QzTZ=5HkH>cKaHVk@<=I1G7PjVSH~~TU!`gazK;k;9bvTzSgH=H=0S; zH_LAK^!IdC_d_zF2(s##_G-I6j{0K1FoV@2 z86t);#C_sC>3>DgGiAet9xwO(97vr~dTh@_y6Bm%uVbW;&y#<2a6w0iSVA>&b;awh zdhNbzI&f~Zn$B5q4%W~~@-*`FyfsK76_97SEN!bJ~Ds5V$WzNl2pU+Tc}20 z0Ek3gR|a2!C2ZtjA&*-&060;cJfp4MNXYzDiS;}*ejKUQlgRD3E70E@aE6;>Jj4j+ zHld^QysEG8tR8#R$=98~?dGL5-H^us#^)YO*ua#E^(p$I-63z6K;67Qkk!@I4qrpk zITk-Sjh5j>1rY_G937qB&_uhhDl7mU?JO!P(S^yHW2^V{^k6GVy2g>zfn{W@J)aW> z{xs4}i*L!<5AJ+#HR!z2WuHBN)#$xK!>_c+P(0v@I$w>f#atw>RegcCdSB#T zs|WWNp8Ww#`QsL2O`_+Xg}05$eLd!#@1p$s6<6F|N#$HjhQjUML`p~Z(*!+_ecK!M zc++Py6q+QG!|QYWKKQH$fS5wm{Mt7CP@XjW+UhWtSoIM>7C#vTxN3%{dcQBxT^+Jm z#(a!J$e2>)sMuP$_oV)ZTh^&5&-+t-IwFH}qVpeU=}E6QyERP1t;lCO6uDO>M# zAFhSpA_l7ebyYjg1I0K?**oAoGqXM~o{kckO-)TcN)8nh z_#1|xP6D}kG}i_xErX>R{uWd z_^)TNMRm*xiOLNJm@dr-)?iQDZ!z+wT=fiw!m=NiC(kJy&-Lr;pkvI6_0R1l>0M^& z43oi4r?!qgwnJ5-*;|rvzDv4b0oNTP8`ZL|cgvN_sO#Ugr{7X@6=!@C#Fs#5f}ZwF z&@=Spuhn2E6Me^U+4eq>DigeqL48A}n=flfrVjsC1wjP^r@iDg4L|Cjb?!T*4&zcO z+a78ZdRz4@;VL3SRKssSTp};V;QXHJJ$T_4ryaq^(L>J92=i~j8gg9EW?*&P@c_=4 z7$~$4a~(hpsacsZZG_t6&Y_wLM$5oR%q&;blnt4Zv0R48P^UK6uZP2X9*vjX1tX+{ z(Z?9A%RAKF)q4wz0U$-6o0w&3)j>NuxK^;Fa@x3+gr8@puwtfQO3F*Y%QSR3DfNDw zoVW0FsX$^$`+a+NX%hc+)7xiB!6wFXhAUQeD_!e~`6`P}0E9*V&pN|@_Q_3`&m?P6&CjrHui zQo5%Nnpp>;1XFuhgMdh9CSZWZ41wR`9va)5TxfLd*|zz@j{nd`T+fQRCL}@0VzJ9b zB#n_Sp+7dgQB5dI?WWwwLlMawA7=Yu$mTkV;-o^u5L<5Yj`E9_@Q^wOJ*|e6gJu)p z%Qapr={3oz9nez+p{4?u%WcUKKN z)r;n`$&IoxnPg2}f%$VxNXjmVVbJ#4D@F7Zr$y(ti%A_DzX!nveWy=P$^!E-BH%=U zJ4A!q+Xaq9QNF8QX$XxQZ3{Y$Wkaf=`r{uOEZ0?qck@|+25>sxFc9@ioWEmv0$c{* zFytbr^9?jK8H^6?8u=3;?PX+!K(;MUfr2^7#G8%^B~8bJTREy9qzU#oTa=M0gYpqG z7n8k{WZCI=il_(}!Qm(mf9LA`MmII5nvRo;u=;{4ppZs(p zHV!09>d0e#wio#+R3`Z&^ir}%uK+9N6XfOA=Kx$b^mKPi*u9Yl&;VHo;f}Kg&w`<5yQy zyx{Pkot%^xt)D=jm*`@6*uMJQTeIqso$uk$<7?P5r2PolZq%Rn&MS@%*lv437xRsbCpW_# zP2;pvFDZQ06nDgPPMaf?PAu*XNpP9H)yT-gWzd^mJ9U3_(gmV-sF8e0|4&kfb*6`7W>)j$ok@&(KO9dT8KvN+IW;D-=aR-PeF zb(GiY`0JixzgO}ci4km|OuK{RD!ItDp{|(5b7ZaXZ8N`1YhyE`aNBTgr@(x164Sz` zGwQY^uU)<34KFlPO1`Fa8G|}%bi-<5HsIckGQp3&#^iL$$m?_C!8N8>k&VY}=N3)) zTB7fIS~7ByOaCb2M@U3hto>OOO&%Q&2h_t&CREmKAi7lE72xL&l>X{k-&dS&U2$uy zEENnr&);0k*_uR@B?{~-Dl3z*6oSM=d|X^A9E>X?%wVY<{lV#a-UjkqrPE_{6?>2C z&VrX#Hsn2b9}%*41-@HG&$M9E4$#}x(I4(cPDIi!)>GZ}t6sEgs9HXFup?fywdYRY zO_va4K6h$#oF$I)z7V!t?kq7yeECtf2|XUCWI;+A59n=iVBTSg0nDl&hXi5>$X1%H zFCz;(??e(tpIi{Sy&~MCFI6*ij@wsPc@_)@blB}9Q;Ire*XZ#)f7waHYk<*KhokAamt0{huaRr9)8>cH3s&Q#Agen=Z^UqGc9VftAaO#P zFO`f9uxs70b$ZSg-Juzs}+ei6nMN*Mp-P0I)%0(zTV9+=C z<6EGdb3Eprl3XX1CL>X>dajbIt1Gvw$X}(WGriChUQ&fua{Q8nq=30>O~bVzo;3CW z1}M`m#DR-Dc~EZ{j2EIQo;~A=B1a0nq>Ip8=IhdSo7Txre`z#~chDC6&h%qkYHebu z>`?C2X!)MtO!Wnr>B2;k$H|An*>WGal!oxr4iEvuzuk85?w~Hh$N=a)U zZM4m6pHhRJ1f(_COkM_&H0|=j+3VfGuLETz0F->a{JibY+zs*G&WtJP+5jBg&!{M% z71_e(1_(yhT3to)biRwM%&;*_&~-awx~Ev(R!QBSuLaGmp5hmW2&!WSTLO+NINVAW zPQC@tTeOsq_~o!Gz&-GDnZI2nKU*drh$xUk)k0plWYS2?Sx-;Qo@QXv>v7G=U^vWZ zxnS?T1aLMFi8}zLVyMzKLx&AHr}Y`Oi>-Ij3$%_efpUtG4Gps%JG1li_6sWwG)L$i z^Mr1Is+WH!4+kn^ThK}a_0hti>FJ(|w4qIbX7H}4u!sodO%HvhmF4L4&5P<0j*Vwf z+z4G4tI|Qtx^Xp0Yw%O6Y5j}OI~&!JJqgOu4(Olo6YtgDM8PBNjk9y1$a$eU{d7Mr zvXnte0%7IQ-}A5Qqtee_UVORMZanDQ{4yN~Z8BdzJ%nA_dNx{#mOGsu)K>!Cwh&pF z1osR3q73iPvwCz3m0V^7VhgRUV2(m$)G#p$mrJ`6D4+5;otG?!==%&B?o`xLg4hey zgaykgHv36H!+Onq1r03~$3=hmn_1&8Y8zjtOJ?ldf0D$xA{wZ0{u>k)pRNDJ=lm%r z`mDZ0kH>Bll}XvDC1{mW;LDRw0cgk++;~4@48LumMq0s_`?Oize*RP8Zg;cc=bHoF zY0)ba3O;LtnoCG;61JtKrS>iFrg=kUY#2~|Ed&*In+{c`sv=AA87u?p7=OS1YFpaL2(GsUKAx%o zc>%#Y-7Tb0WgznpwPJq~9RTwF(u}ZAj2Sc2Q6%EeND=#IDq*PU$o*ml2!Mu#qG=|=)KhCm9A&@$Tr;2O5jVKdk+YFMb1*P`!9-)*4nGW=WJR(^9gvcOuO zyosMuR2e$XdwG`ObF5u<))*W3{?4Uu)BIlXulsJNL(^byrS)2<<@}G}r;NHIG>buR zHX9P=OX#aTxXDsr%P3a)dxV6ntrqoHh+~>ve?$IuXk09b@GG`wF}n4M53X6tO_~NA z%hz`MIs7n^6NSW4+n57sTTCcg&$hWDYQqxbxn(ep0dW)#Ex+?FG`>;L@$8T9Ih>bo z#*8|;b2CG(nNpL4R^K0aeAKVvhk#K>sU#EH=WDoSXG7IffaJw((93mrmB`MvNDYuBq#1nnY4txZ>r~m%x5z{!G$V=oPQcX{nRsGe#aG2bplCS55Hy4CEPy6|34pZ;<_iGfBamY~yX5 zG=BP++ew5g&-w~kukNXEd@K1wowv;2>{WUk=BoGZYdi5=2s44sIV$^@2r<8)!^VRw z-~KF2ocQ^>$h7v`pzV)I`}>Y2JTZG8=U;Z)+!={fZMwdygV`5E-}Vo^%tdYi9XHVM z5X(XyHXVu|1`S-VyBgEE!>?j6oCUK~=pE7oq;|@A47# z;}YUE%e|MSkcY$eX)|J(e=cJDQYsb}^YLaMrr5oCFKFsHcrsG5Y~39+G@X7geafLB zvFEXB1ey7ifT8t6^ScQQxt@%I^PZ3j%pHq+*S`m9h^H4HUUWNPu4^`V2?=N49k;lD z3<_$TuU(nLo1Ve=ywtB>8DgD%wa$?1w};d<^o-G`^OAjBQGKoYRgzjrf%#ggI*r9I zqWws&x+?xcCR*7)4jj8v({WjNZ*mk@2vy%XH3V`p7tIdTB(t^+3^<^C2tlO+AxJCY zm(WTI6b~o@78HKg<;4QM{Z&Q}^Xf#TG0_Xd>UkVCR)@h( z&mAwmB22fR9`ZhXN#?lu2Hg~vep>F{IP8V_mgP5%>2Ems1qcTFHSppOK|!(gyH}Bd zKHE*s>0|D^`+k5XLPtki5_?!dg%KOC4ocaeB1(SbTg)UPf~I+y<4PJtwvI@Z7J%c{(=<9Z5tu z=#yjB=Q=)jK}J{2Kord^AXf_gGFZ8@a8Abgcn~ui<2%ce)aM}PmlRZ+uUOru@2QJ< zN;v4f9V7OKT(TOJ%M11X5f|GXI%Dg-%;;8X^rjBKuDD6?%MvsnsJ_#K`tgoKtnXC3QjwJbdSJ*Yt=YR^NU)@ckELZ^UCN~yHPGu1M*_9*6FXm$_QdQo={hd?#DcNr`MX;A z^>unRKu%89_0G6-vF;ol<$5=%==9m+rFPAOx3|Dd(P`$V z?nz(5A4mUoazFOG(@+!2Y?w%W`Cuhz?KDRUvR-cNY;iI9&F}PV+-YA}&B^7IBcW%h zam7DjwLd)VJlH!J&p2e{czr)o3~1_et?XZOlBr10H&_uk-E=%z%xyaRu^y-!d7W`q zSUi6mbk>e%qquv9kr_AiIlMQum=r-(Q5~Eo37uLgp=>84v{hY;)IUV8ax|qX1RIN% z7pcAyp%d}xVYa|Nyv;4%Ru^0~Lu+pq31ft60_4Xn{|R=>cRd@G{TcT{zCMM0VH!e5 zvWPXDiR__1T+DV{$4gJVy#p=Xhp^LMq#+vKbn1!U9dkEwL9AtiOS&H$?===Mn6uU6 z^d;`UF`@=e|Eil8C|i{exnL}SC-2hrp~gFrSZjFXk-@fR$bq`G0-F8sEO|(n>MRn(Y7Cg zWyGFFj$WDj<=|$6j_t94N@6eGRoHo%furuioYcdf0+{L(Pk~gC{py1i*8H`njy-mc zJqAh#QCTdL8g>iPXTSWq>d(LRCS|O~7e{5i8K3=G?P6vz7iFQ$M)4}+F4rGhU2*qI zd}gmQGNqvDy~QwbJ8CYMIR-TKV}adenMk6HekEn|Vuh}Roa`OizR~4|b4)_x={Z=S z&G&gUdHtyC5-lC$p2P(P1vE3ecM+FGlg^DTbQP zrHr+GUKtpGn=V6qi3uG!6jPhvLB|a0qDi(QH35Ff+8)>Kh8N>$J*&K}5@iSNb&8Gi zHnxNIJcxJV444^a2|tD+xtc6S61^I-g(mHh=77BOY#m{yK4~8WT2+a%2SH$$qb3+=KGm$4OU zI!3fUkhEoE4i#X{RU=u~{)UElDwwVHl>#jSeEgN0vd04hNH%XMx*bJk;!;Ss4Rn)| zT6_d60VJtfETzFi?T`IZJ(W-wLCRi7b*j>S4-JY-rM})L_EvxXewWO6?H2%W;a)hwWKNI-me?mB ztHBS+;`Cr$W-Ac;+<6H*o!B-{9Yh)?B*opLFU(9y+!=lRF-Cc&KIN|F@dc!2BJ8UD zBbY8(QKr(pM?IWu>!D$OTPWI(Zg)!k3$2RH;;CCgXwaKWL4uXbQpv3v<#)DU>9X?Z zHpnx@%{18(DG1^qmq8OU~+?Z`;u1XJ%WQ}{j;?fk!gK2!gnoa86Y(nlS z^^d#iF~FnLw-w#}s#;KuIx#naxoCN}ZhlHx3p$$jd1;12Y0?KCxDut5`a4#_y`_b| z#Jtx?nS==jcs;xArlX4${57Ot#C_B-;w)qR_3mfqF8hBRo?jUdMc;taUJ#($7tOr~DlMxcyiP~f)Lk{+(jDP(J?6R0r#az65tkRA zX;M-0U9HZCduDx2ak^nqyL}(FP&iy;JID1uIxFYjE)?RR3Mm`j>+!%48~QNWw@JL? zNc#~RS2n|d-J5(>bwCV@6|v};DuzAv7` zz@JGsge!oj!VHWN{kJyxfEMt7e;2@R!ZxB3=ti4zSHGnBdQG9~UX}grE|!w2j-IRx z(9$XwQQ~*xHqeW{ZTmr>{x_eSp>@_^9!*5eL}R$VPAK=Ikk{YF%%$L3<-JHygTL95 ztdV-gdra<|$FWT(AwczM5&M{1W^q;D7_$?nh?u_s?Cn>W9Ul~QSg{gc%tv$9zx~Zs zNIAu3?aRq=`ccY!Up*!ZCfoMFuF)01mt0==uBB#b6PyK|(_u>1-EBE-!;*@M7wT?j z;bp{ZKzR)iS5QS9D2#D~*?vnBulh|pV}lcla-K4#3>^iPe@xhw;wHjUQvRn(1#}bk z%`03jb`p(9fXssSR-+=7xTVIQaR)_ff?lVy*lDb^{xhBoDg~7y|NI=+mk)+Zcnp1Vht z1gwF9<0z<4sYJ#vS$d1f(GVb!4mal(cH02TYS0^x9mqBg6`R%Oa5C`or-xjk>-V)h zu29tOz!TUW`L~g03@UhIq~k(%7${8NPs9GZq5(SR`+PB|mQlEWn> zj&B?JRIq_971+Z|h*b__&vk_FFdP_$r>1@6^s+kcf z)3-T3J_|gY(|FTB9}yltNz1|-V1;Emy>9E`aum#*-sxU0UD?~s=Yyi?o25fjJIs2p zP~co5a@FSit@nB%)VQSfcEFT!1kr$Gyvf2K(hk?KIZ^_ zvgx;Z#p%7GGP})#^#R!%+68o2n#-ou^s!HcG~x{)GrP&Bfxm5m3q06Q#Y+Pfq6Qu! zbCe-T$-f~Sg>gKSV}PL>TSLYKD;7N*5AEEqi=$GN8V}+CUpu}fl8Oq96$6S^3fb@; z(EcfuO~m^g-|>)BZTa0Yzvsg3I^hJU( zVtP(Q)Fhs{@tvkzKUB{*H z^7-pP)^Fc!c6OvoF&^yYF@C%@vqbpL0p)6zd+NnZZ*)iq7MAM#6V0e7Q5OkB8#MdB zSuE6Hj3@GkWav--D)>=N0{eJ&?H%|&j>^7S+$2m{R#+)k5U3ic-kRks417)UAT&q~ z#K=OTSUguHN0+N?B)g(klYktLrqAx(=@PL;ZoJ|~&Q`>l%qeHuXPE(7e7-Jc!9Hj2 zt{Sgl!ck|Z^C)*9jyr%91B7xZg~x;^31nHAO*AutfOIC+AiAFpY=6dgR0wf5 z<%q@BDk@W)ZZ`4ZCgB9o$1mkF8|C*a4;xZ|&ub<82ntkf`jP(B`mi_qn z=%)>>=FIR@_(;}wFq`^zZh#qDflo7A!93Q?kl0H;O zog>FT>b<~wG-%y>;%5sq2)#YjC0~D5Uvu`cEbB(c=9DBweXQuL?0QpiwLmz&C37)w zvh_|~BCmT3hwWbbbfco_E--&*9G)Q0j75h^Qn4iw6CYuChe%DnwcHWmKtrrv#bDp6 z5F+1p9e-86at{9;^$YIUKE<^ya7`XTxC*}wv{Vuq6aM!3bKY{6HQzZopK@BftQzay z{KKDB!-sgmz$E{4T#b0Gr!)6GbPgO!#eptVQ&+~u|2fFY48P~!txV5vZ(j*>hT7xz3;*j_GJ8X+FzH{ajUT@e`LfJL zRCbug@R70g9&C}}`mWZ#`QzucWftnsjZ8=J>G8Q+iPxp$ZQ^r3-uj+UJGaca+n&)q ziXA&{=?PPX;z=$9BsaJl+6-l`k4Xbi?Pr1TX^kpvr!1NGp~7Wr7DF+O_oe@FkF(DLUspOQGWK4d`?`NKwp{2FSlF?l*|-(dl8_r;B9!h z`fOmQAjVI1X^M_b%FBQvbIibt4=|>!AKQ=GE^r&SZ_M`N{~T>DjmY_=@Ur?o=3mFa zNf`KO^6_06s0-B{{f4UV5)|Q=5&3}u8ks_hd?}8LtF5kDb8e=a!)GpL@pG!$`MA_O zO_=m4X7}NSZU+yFnqw44D^jH1DCD@FezB0ljh0=UjoLyl!=Pt`N4B22+>aLi))7#r z&BmYZQaUO$t(Tag1etSz}3mggtLjNsi+dO#*>o8<1CW!f&?J<=u< zleM0@NPNVvRxwlUp@~}4wh>=1)xWou2p?1g$SgkxzcvNOEf5s8=_{`|05!de`OeeV z*Iqy!efiuI3x#Hx>>G%=k7H+LWn~jz(8aIk-;_DBfud+lOPy(>isgD?`ilSx!l+}C zx}m5zTj%MXgcQ##Tz-f1rOO{ccAG|+&0$_V&nb^uS#YQE;XQytfY{#&i+-j+;9~6= z;7l6+O%>q%CGHZIm>zF1$|6<%C;}-kWN5TIB{alFoRwV^w{O4e0y61pE@FL(EwgN6 zVF_$-{Y|kRcZ?9~nk(SR=4>tL^27gg}vi)20X}RT*vGv{Kd9mfhk>Fn2#hS_0oAhQ$SqU!7z6nQvO<7i;zH{dm zGa}=C!k!}VtjuAAP2TZT9+mD(DB0 zX?#+zJhyT*D-3pH+EirbeduQckgyr-b-8q}7<~hEzX`Nj96()*|Gg25Kakv zYUJBfL&tbEMLAVw22+uh zIvS2g!kuDrFNeFDl9fE+Lq?k9s4?0;xTeo3$)SFh+tFiQypCMvefWMTZj0x~AH~W| zj{%ZOXe6F;0!K7_L-lT_Woh~Lo=)kpQDcp_f!e^kj1PBw=@PHGzq_TUSUlipm6e&$ zqBcgs&^Wx4Mc-%}C<$>Pw(g@?S)j4ori}Jlks6(4wa0vUFx!&_$E6W26as>1gwbg3 z$^Ce}`n;^=` z-^mASQl)?-!E(1lk!OMQ6Jx+`#5-qvi*mv-t%w3x;d4=_HHi^*)r2~v@E^mA_F8JA zPc~HWjul(KEG!;ql-I| zr1ssWo#dr@k(|8bjsCp>^)W!O+U!e!;P5I?-#0(Ga~uQh7R1Kxb3TL=-(45i5u^gSs6CB5Dpm=QGweD_Y1?^1n$SkvF{=fAxGJ!BnI%2SYzWs{3A$uG19 zZmQY)QMphQokAAeJMS;mb;t`G#*~olDkCS;kDtTtx%@*gAXD>H9m~v#8r~Hr(;d;Q z&FJrGi7<^;hPw7F;;M!rrJ+i&L{j%PO>Lf8e0oWW1ZMRBDO-bs;QH??;?+-61MSM~ z7t2c%=Js#ty!jk;Zx7arXWOLsQa&eYC^Q|CIiDTw`>yTOx1}{Yg{-4**{r7V0Kun| z$1<_SO*@m!&%D3h+BF5AA#)Z!zDxeHQ>fysNaA|b`pxHoWIn1QKAkdJbJf+PPZ2Qr z&O?VfyPzRzkuocjEfcQzQ@gJd5#5Yh$=d?Bi9K=zgHa+j4BZg6?!1N3D@olGM zi;RTaOsR{Uk~*t=NS?5TqS_e3*g<=b@B2JDY4wDa7M{2VMw)s*8lj5{8;GO?pv3d- zB5{R)%GW_x%PAaonpS3@risPy?-Nk_E*$UrE@JVJT2d)IP;77-(=gj?^veL3qh1+> zx(g6M6C~NB##~vdyp4NWBM9_IFsTPD!Tm&%GNzAF(PdxeTm=KTtWv?#4Pj4M$qFFR z3TyOvhgtUd^YBq>A$@OriC;I1Z%g(V>YMikg>6}>*IRn$q-P+SG&K`0&9u8I=u~{p zI?(1LP?lHDLy3cJJ}Jke*z&!{EWJc~!6P|d)_g2FF24CvhKdGzghg)()0~bk*KD=> zC3RB;i%yv+ALW16rqw^#5c!$*iA2MFlfQb->NQ;nRSv-P;}KzHXZJ-HF5(UX)<(m+{@yN5a?VlLsI9xPR*I62y|d>I6G(4P0bE@l*;Y*> z1i;D7K1*6!<)-t|dw)-2tWJJ{ct@dD!y}p$&!p1Z)97cirI@}x(ssoq&MBEkFZUQz z%T-?(*<<*h=ey??op94|WHbtMb5DJ1HM*&SJ$2z%8cYWyHjETYzg_WSQ^ZH9w47{g zoD|zq6#M?(*Ez&1&T$7gi1hUhiTWQWJ~(=ECP2BDb2;s$>Bag};?{z-WxsW;UeBML zk}oY_Pr&6o9f;nu7^c-Jk@mfJ#Nk=?vi}fUZa?zz$^onSNQE(o_q~yqfyUE#Y?KugxC{ByQ9!NGKo?$3D z1E>Iq?9(>KHBFeV9l=a$gPjIM;j?-k&B2!MKOM zchEO5f@mk+a|UL#GOcKL6m8{%Q}P!8UrFac14$xwuQn#SeAP?m)vr%aeZPNmepcG9 z-}3lz!x65udH+5l5t$>S*)w45)km^Z0%tYP|m82W(QLU@?4e8gIpF_|E-Qt z)}v`%o9l)NP%xZcc4T=y6GM*yb@?S9aRk?m{}z|v8gca4b~FnQzTifPo9{IkV|yUh zoqdj;@VK+Go^vGd>Oo$(CF^LAkd-T%zn3s6p>j$Wu1$J}Eu%d{SSLv~-#9WzJH;ax5G4lHO3n)Xe)Be zrq&e*vol(JuBahRX?RkGvZ0ag zxU>;)%EwAX*{E>1nKnTFz`-tvl~dQYy4&1nBw_GHuKKOt5CZ5YJM+pd_Ev}E$s5e7 z-&m%uh?M1YaQoY(S=aiNxAUJ)KZ^BWHg^!a$T~eq#jGFzml)RirjZq>0dx!ex0*_gmLDyTcv|e&cXypeulb)mPc-v%^E6 zBU@Q{Jxhkr+w!%MIYG~6W93;x7#Rii%||wKVZVsH-Y4V{y-3~w;LRC2WV19eh{`|RJb6}F+c_76=2PffM-^OObjrH_# z53Ozgi8VAf_}Wo#djKg&28g)X{YbN&OG#^D{(UWbc`A|@a2j|bKz8!5fc9niZBK7E ziAd#v4-V1HjH{ScAjQ93Tua9r7`0Nit$hgF=s7Xw!$uNY?`ckvhcBOWR4ihqE5Oek zK@^^M`a6e`VrH?D2N}};F(;H72peBZK!1i)xNZlW7cH|pSkeL2Gc<})+<*#VHEdJB z%*N1mv_dWsQNs%}-fIrp$h%3S#;04g`2w5>b+rVieCY^_tH;4Lsw{PUzfTvsV=`_v zb@M`y-XIPG+F%UbR&f2t5&5KoS`kzb6OB^*i%(8pn}duejvn+c2Sq+6ZlvClV#4dn zu4Mbfvl5aE2-Q}`ok;MEy~wv0~y`kVDqE6aFIvO1{Mut zB_>o3qp;13oND)dY)|2XE5;86rR%2TfBv6DtqxAx=KoR=H4geErMyyzOpSRxM7~`Jj$21OpO9t8yni* z-aMXr2TSMSqGok%A1fOZv$pQv=zZ5U$b?!*izb1Bu+#0nr>%3YUhkc%X(){%Py$LO zoQ@p1{5e*YSR54cBUKmR zlIk<5^y`77E2i+seYO4kBbe3u zuZM$&nK>7Od^`v3+=1VE;Kt9p52FY}AJY>ioxLrdeOAarClscx@z+RgWQ=ZqHSrJ; zK>aQYxR?8PfjuY3@WjUR9RBiEUCepUzz{OY|LyoWK0tBBj8|mP47Ix{g&A3e3}#=C z4;}#opO1bC&!!_8!`@kW_WWRy-@*R*LaFV5on)VO;O4xsU1Jq?hr2=KVSXWmA$8+S zaTOT#GCnfF?LNSc8lZ0gvoiHK+VVW>HxKHU3n@T%!VqY@9o?TklD{fvdV4zIwmA`{ zXGOlk*WoGn!X^5z-Ln^_XIRdD=D!W?xKAELD0UP#DW3xmo)D3*F;3)BBXP>+R*u2Dg4|p2uS6)QH5um z?X656vkcYotKLl$q9mP;n7{VumdQPCmmia>$lGc-8O`(Op++yv;?}D`&%986G{s;i zq5M{=dKs@ji6b8)qa8cbD=wFUANSz^wSrhPm!ns;?|D-Ymi6It?E@6$s-gLk6%;X2 z@*C#aDYOuEgG|~TD0N2Du4m0H{D0r>H)eCHMRyR|Ql={lN|2owV@K zyTf>b9KVE^1<*fmOZh2w!)+^N!>mr_&-nOw!H_2)iswBhKc=f0*%{-+!P#MuP9v3e zvi!`6`Q3m@{J4!ChVsslCX!%$5a-oEMojKzrUl?ja+&No`U#p*4QZWGbLGHH@a6PN#DSp|NJh$oZgnhL1 zzghr4b+%UQ|Dtxv5^&CR)6A2VvY&kjfN$C~J0yWSA%=vGu0o27oxm@YvV?^M1@(Rq zHjC}px$jODcN*UJEDeWCj5=coefcx)&^6auTKH1SK&e+oZRNXNsM`_$XX_^oQNh4# zVn^0H`7A_SX(VBT_yA0>ntH1h7|#8kvPWuG@574$S{KhzOV&UEz-AYQ!MSgC+m!)} zK%CYWu+8On=I}8k#)7wV1}-0s5}4pV^R)NdvUV!9;Kr~2y)U1bRd*UtdEjEf-c_(N zMML6nn{L1hnL>URHC*N);X%6c_m8N9@HIoPY9WSmLs*7hmr{Is!r@mO8>vhwK;^}2 z16PnEllCB{`Vk^r6Jv%mF+43OVt^C2@!D5gQzexod99?!5WS0c@8(#z+&P(3v}$N# zzjnViS$(UGwa3vV*kOhcqHBn6ws-SwEqjdPl_7AGQas^I8BzZg9xTQ*ld+{zbFC1( ze@blo*Xxhk_%L(J(R5W;CctAM3QAh~79;yP__y-I82r&P@P=!!Ip%_U!AH2ac0bvo zeAA(=c(~tm`9q(y@SfLoJ%Bcg>M4}cp__CKVfuCbrll2f+r+x%30j*+v5 zBO=+3T|}C(Xl~dX3}ebxTa+%rtXq{U?t<58rSJ3RNfV2?Mlv4$(45SqT?MA)H~e`uGt1cHAmfUA4#p4?GeW^u zZ(KZz9mWB%^TYuDO^I!C!SCeFzLyL(Vp&fxybdMESjHm4mail93IW74w{!5{O}v19 za9?Gd`-FzqIDI_H&DAsYmaxi#IgzMF?g`TY!s;OY{kp#|}h0qMa+@N;cVqXWqQ1b;Bc#u?uZ7K%7h z1@jU#7|yXvTln+m`y&TXc#*;9+Iu!!p}v+v{z&=GB*LkI3D2fb+C5!~P)OrVqfS4p zW;n8pl-im8VNGgh6n!PrtOXq_xrJy@ksJAte;4VYP>DgAdw@A=t?SFAGMFoFUC-uv z%+-_a<#L}^APIYE3pcd+CW-g4sf9a#Sxs4KB&z$j2oKQK zEN)Sb=;3R>;$2Mr)oU>Np`Gx5Z&5qixe?|UCc@2amK3J)aXM#g3h%`09$@6x_yW*% z>ZMH^lbBx5OPF9@4J*dG5O;1g|pU-;Wy@(HZyxFQH zEOBshVkbi1UGcO?RMH~xmFMKCx4$ZERn8!A%+$T_t+3KnwCBGiyq{n)9J#-aY3S9z zXungZqTOt(;tEvM{?75|GI38Rgr|1kMAqj&?7l)r4I*2XVew5#PgX!WGQ_@x#v zX+by-OLbpcXM4{EK)e4>-@a|8B0`sKbj7o@?ybCK|n~gvoK{a1PlHSHW0%k1H`TF-zc^B%U_q^KFR$JCR$+ z>k4NZ;_m_R6q03KYGNfA1iF=iYo$oh;d)7*8G>?rWTtt056!(uOs{@vQvA>D|Df0n zwm?G$o*o<=Y%@}}xT!r2kp2rjW9Q+4loh^xo$(@c!PZIGh?z%-(cQ=$8(jY-~s93(ZyNkfVPwk>k1_d$i&o?nWrb4kd9DVO%Wqzb@aYP zBugC?XPiXu@*l510MR6oRLdjd{3mB3F_)ba3J8k^|f zajI3f2G@zILWymo%4B%r8t*aZG22}OB}RkOC+(^tdf=<{pj-oLHT$v`5rCZ96R*nW zc!~L~g727P9n)nHg1%veY9gbTVToClz_J1VWi*{H*N`3gsQl+@ujcz|WsczLQs3^L%W++?fp66+pErTkO}TZjbQDZqIMivXK1 zl&6KhTcj>QOwh>bzgUA=4a`bm?%-8pfJFP=o_~%DlMaj_)49M6$|`;I^>la*y3c}R zj9hS|?fn{5{Q{Azd>XGXXlC#vFZML2u2oaUx6_1SfNrXxnby-op4O!w-?#I-GXq;3 zOplNS+$(z^1wELKS=)Y(oxyJ-23>=M%FT_1bmEjH91aPD%svhNGI$BX9rt#AL5#|bM zrqe4b;EDZWtMaxpzc(D5FPA;SwnDiY$3PXBWo^z>$Y>1cWpyk!e8iwR5wjg8EU~n& z@0`KxM0w$I9=&GS9YDC>c8#%X1#yv~1OVggOGwFVh6UjYL^I#!L@r5%^4`{v^bz2- zITv1<2sz$w70w-M^z+Ld=dD9}K0(|YF?U_a-3r^(6)M389p3?A!h&J%yAyy6`Zqph z5fWv>-Ld+KvBjD4R3Ndyk&xfTpMm;12?w&o335wJNQLBdbO+Gb{kb(R`s>ut z+)M%jvN|lxKh(At%aKF{$=F=7n?mG!e%$(SDYeJ#mX_uLMa}3diAE&s4{@7jQRM%Rjl5{IMwmvNL>Z`#|1$rP72PC z2?*F?{a-w2zZ;8OBnV=H!m{x}g3j_*t)r$^wHpIt1FMrc3-Rz2%?wYEO@kdQs7p)j zV$Qp0G8&XuG65n8L9+&HW0~gLELbocv{l&e-v;?jj8M4@k-*HhCbKYr{m)n~LL1*M zqG8a9Zt6Oho}-+R9xA7#s3?_-JLMI3-dxk4X}eJ(&80CDnN1Z{Hq3nNi}2kdq4c6a zgYipAEb*5T;MK;eG3Oe%H7dq{&cY#MExSuMiKZIy>@^GVMYAt^PQWMxS}AIC=;9G?cs%x@eYtcQ$4vvD0iw6!54Sc4kD(BAo z`;mQWs3NWJGO|$y%fDe^xbZCj$S7K<@f-uB<^R>15KE)2hOz|yeR@M!1&#@lv$e0$FL z^tn*j3{b*yAK-FM--*bi@s{~>NxD+uZ459`>BdhqpSg#<5)eW90xQWe_JZJ%*eR`k zJG!Yyvd>aPT(&~n?O@wK;p3WoW{U$)oR|y=2e_$6SXzu4= zV(_*fB8YX~gMsj@#7F4$lRHDdK)V+<3A&gXM+If_Aq8bmC((+~6}HC~NV^;G#oh4k z@i7gZ<1a#uRr2`*1U)b9{$9Nn!&kA979ZlD?qbT9`JS2tY zLUZ^0_`cO@l9Q1Ygx7^L5`gVd1_f-LoUkBKWq?@^h|3fd4DhiPNi7-fDH(z=Cx88A^J&rU`|MKc5$CrJt5;T>T z;QSXI?Z#t|lt2=+X+F>=H@AbGlakjT2W(jEjGym^i&UmVKYlD_B(6POFtf6vjEMjY zS1Yr%gv5oOAygK@Os4AR0A6P9*VD-gNijHIixE;zDZeiTzm~0fT7iUW*XR35&`9Yg z2x$1b5s{A285IZ=21$E04c53^UKV77fTZ-Jo&%yE8QqxV5x7=JJ>WBmw&V zu1b2XVSr*mMAhYQUVs&f%Vq$&Ua_xcpi&X4 z{Oj`M+#QSag;9;}gP&FaEhF zpXEiFrYzfs3+ieUz-cX0F1-&3?>zti?6Lwk~Fxso^>=dYMfUumnJM8qR30 z1+O31(V_->(3A^b1MjCc`ic4_fg;z-1km2Eqg7B>&NE_?3|&@Rp06{rlIUkDW%-3CtI+5pq>^({$*- zg3Mml4&3$@Af)~Zg9wpcNjn9GQG`L>DH#H_s6}e&(2beEK4I6nV!@sYx6df;GSLAM z%fb=UVUe&y({H4dkTwKtor?HX#;%A@yJErSRl%W%K<&`(VaswAqZSKhHXuO1#LWr5 zDqZ_M8vW3ISq3sf`m5?DzK3L@Iz3}_t)!{Z${ZzErIf*+|4a+iQDqxlw7CVKW(KZm zu5&C9=!>GpEk+a|Uf>?C3Vy?T@4YC2rz_|oywNcZyEHF1tC0jFe`K6SYh0>sxAR?9 zQ?fR32ZYPi@FabNsNAYGKaohIY;_yq6JtqU!yt1CP^w_g@{Hi(Y`@u;s@rSvo`L z1aQ8;30R$25g+5#tKG4bl4kOn>YK!In^vx8QCXOuCBZLFX|;cNgc$e4Gux(Y7+S2U z6sw@K69QONqo!RT0WrwZpsbtU0WeYY<`6oyF;b61zrkN!z{=h%ybL0F0mHL2zX@Uv zd@Ny7EKNi#$=#nx$FY)C#itZ}4la_i6D%L>D%~B_c?v2ll&h=X*F=CZEV#iO?Ce+( z5{bmJyRV9!eBE1%e%T4ThZ%8XgQvC$&ee(ms)mZm+!tj~x?vbZ8)DCi);`>e|LrMu z!5F5db1_^pT9pJ*1+F3pI4+}uB~kP;#+_|f(M$p;u^-7Rm;)~ z6kdm@9&pk#Fo=|rWM%Ayw!@k;)OgDU+_;6r2;9qz!rnorpA>fOqkTw7NQ19bN6V+( zjsX8{DhcZOc)uqd?H58e{RyISir#s068Gf7Fqc?y+g$$?Pa~w&1{)^@rhH{$Oo%e3 z2XZauIf;-1zrm9Yy?he%9r2Pou4f!Iu*6(u`8JlvKN8PDnGH1TD>$Q%l&vE^8PE-g z?7~grS_E37CV%%HTY;zW2JgU`?xt+_eBg9W`in%Uhdaa2MvNP?>Z`tZKuxtV;=&i=!+@2kwGYrg_XaJ@q(3V8>VDR%3;wVKO>Km%WJk4^Hx zlBQ_)+gQM5HAxZA?!f`e^{G#;N?CR&IxbVIivp6M`)=Z;i6EJX|80#&UgWtpG>7yq z8&7V`-AAL(F6{f?7|pgKx%`y_pxMn!I08g5^%}>HrVNF2hm(HE*2XR;9AZom29wms za!rfsF*zUSfhgQJz4=4=fox2;4?aLh@T9-9#FN^}pH2M52s6ymzMF2F`23KfIa?!i zW07yc>|oy)9GX$Zd3O|{i>PO5`0?%ov}H1NeAn3sK{TQ(^R`d?a8@92VM5H&EW>0} z`8_j{-r;W3#>MD_W@(cr=5HS~R{fm5+NNgDP%(4#JS;|Rav=JKf-*~D(4gnW|6McX zCMa^UP?=Dn)P^OO;l00APEqGWY@wK3Nq-$gOCyvAx$BR$sfC5*Fb-4Kj$PQt?*n!0 zV`BM3a6<39j)(7|TpRdd;g*ZIP}`$6->dreV=53mOQmh+`wpWAUYZ)Q86U~JqgUAc z+{tBUsHM-60S%qCCNxq!l|DkiwAx)abAB$dxKREp_w`Xb=E}`0p(6Yj+;z3?4a;P= zsGn?JVuIpi)&Y+AJvoj@>jHyHV7>Pd;OWIk%{kgZ7>MF^#_`R)g*qa`Z5?Exro`x5 z=wRo9^&$b}4Iwk4K4EnX;XelrbP-DNp=ic1DrJ+}W!TAkRY*P&aibA$;TZb#3?rTmN)P}jt=z<#=Y6zsnztvDoOlI! zd1Wxl32E7$e6j_YkA+2n2sBR`n=wr@(BYJ8<=~=sO^AytSFsno`!3%I7>xtJ9|Nd^ z(;vcl3J?{^&~ek=omIY9v4Dn8?v$?kb=*_M^>=i1@K_VDb8|~zB6P2vSaCP~<&`4u zwA0F*lf<$+S3wYRs7L#=RzgTVW1uPEbc^(4uvN(H6B3RDTNPrcG^deS9rN_vz^vFbp?#q5ZCsqzq;d`zm?+ew)I-M% zkX#0`vRk-+b!I1;(k!;S_Rnu;08UZH{Q4??Nm?iD)bHd+*&lL;Pt3o#xF&h{ZmvZ( zgchax)x_&P51UlszqZmqMgvEIo)^p$$I4~3GZ*2_mDp5qTK*6Aw~^qXA*U0nmYdB7 z?A)Hu^P{70&b6$Es}Mgin~?(8;CD%gijg@}{h}f!aI9i7o>;|hZDVES`HKE%;e8=i z)%1@;JuG8CL(WIaul4S_H-rvNr6QZt$)KzLe62h4;D!>XRe3I74{gu|ckpT1}iWOsG@F z?)wceQF7Lq#?{#J8p5so17}me*?q5}n$=fjMyg=JSA=W?^f0PVecw^-5r{OiZ8+r( zW>#F^fQ+meRzf%7@-)+*Cz-A&B*y~I@o7En zL+Chd2%Gs{iX{7 z>?+YY4jOAy3XG($N|yQ0j}-F?9bdo{Gk8?j0im;MJ+kTyGG} zhCaqNlOiPf^!otJ;y;S+<;XQYV4vuL^%C>eY>&38Lyq66PDN{=k3Ndaj8T+F_N^g{ zAmBzk6EZUa=7Hh$*zw34RtDV8NgDR%JQ-0bApVX)uCZgz1~hU_v1AGR>-bid0^0c^ zhKVdj^HeyotG_=Kh}k;xvm6>?q4S`891+eU2LT{(T=Q*WGEXd`B8v8duM^47{+B?6 z&xZjl6Zv|WQ_f7*DqnI#dPAlH7&Pmm4k%C{p!h>40PN?JpJhy#ykUbZiVOe&q^eTI znR{m6L~|xRM2mra5xe5(I%*&uoK@HdP}(~=jkCX0V`gC~uFXZxS1Uf-8k@|85IsRr z5HM`*JgabPG-Gm04g_E;VAb*prLdlTzJ+~lsELhDRdaJPS#5|~z59AUok^uN5c$jZ zlT_>R!&T8I;(LOk)bD1Apr`myJDa3%2;;+z5+5S-hMu@$#c84;@pEu3&z-Wep%M6R z<{s}IX0{+v@=#4s4>N`;z$%VUtkbHxtyqT;=E)XVn`mr;92&qV@?f7z6Ewr=cMW0} z6fA}B)yhJxD)*fdZBfTq53CL(OM%x74J2v1vc-~8 zTEyxFzsR=V00f*6k~CPRz^x*{NUCG4O=g6gFi>taRkE|#oG7>K(%8GZ%epgIVUyCf zb!(fW1<>jP_CqBObrvHN$Z#-|B7o`_muF`+e+&adsI-YRQ);VNfeN*boykHB@=@AU zd@C=wF_Q&YWt1Tp&(5~?9X(WCPB@=5eEKJzp!-ee&5d`G`3FKigaReNlGG(Y6uDKR z^$L=pjy^^oW<1(=Q&Ozc^4e{+=W1>1iU&}fm~r?#_O&txKEBJ3S4Tt}ePk*xf*orM zis_1~vboW8-_#o3)vC}-7y@MN0G%%$>c-2mbR{|=4Mdomr153R#V}%nVw@K7Z`ZjT zZG4bKE^fApuQ_U|=;RDg7fby*L(7*2#v;d=@9}M+!#D{%#Vsd9q0YLy5}!R2YovR_ zN&IAPGizKc>YQd__ds1`@i_`3Fw1681YP;PMyHv}3Y2N;PyC7q_N%@brKOX*he2!| zj^zqi5vR~Bu->S?zk7y-D6>E31Fd`+7|RiZe*gXrWWn;4D3z^{H!D?nN$c`D;|-qy%iFhvj5Dqe_cyaUlo}QU zVd@s_U!S&Yqqy^-1EN-)jbB8$=6m$j_W4>>3l?hreSntEg4Pw2IGDNJhcekW$+$)x z(U-TJ{Wmg$I3m?9Mg%k)`qMIAmddE zDOhX@I5pZi-_YEhH{=`rSelCSxf+gDC86pJ9oxzc2X(Xz51!V$d;PB#;J||k{+$5h z{Kk(Yx`Y`xgrZ(trmnl^1VWdJ)H;t0!E;qGQug$xN5+b!wQEq=%(vK3)^MW1R;&C} zG>vvlS0o1cY1j$UdXvEU>OYHtP&K_WCo+-J6Z}b=lzn{kMgbUCCvXtvIGy-3&B`!5*Y^YjCgCw zo^BfMw(2JkZQqe{f#{2DmYpb%=G!ASOU_hV6=S(MO9CAR=9gtPxIDGYjn1tu&$JRT zo@w1?s2u-&+WKI&lRGfOu5zaXn93$dcC@#bTLA*5^%+!ny12Ob=`Chg&|Ab|2x(NQ z*_1L{&S(b6KPT^r`WFDTMJr_DKu zoMzgF=H5Z0!H*(X!+ap%sbG~k>D97UYVGgOSEFE(X)J0MFFAM`8fGmXJkHd&N$NwT zZ*(BUu()o(9CVac`1Kr$kMIXRUc8kS{t)8;$gw*UiEG!;;S+uUiK_m}AW#;T#qU07hb>f{1P&ufmJNM6;~AQN zjv+}Vj@IAHU6OCAx{_gRzO7z@(SL#LVD^ZZuSQ6P&CV3y%WrnuS-&0IxAcX|2WUZkLOePZ~bRx*5{rj-NBs<`CrYmDKv z!!)Cal;*-HRaIP;iPX4a*S z$dnGYrwXg^5TYqs_{lJ>nq+UT-BsnSA$ey;4AL>1peQ4iHNFnN{<6nY}MLz z9Z=^Ihrp7BjzrO6*m-2uRsEX~#*4ix!6E!ymq|MHi{7!&&PrY&?rFeaoy@Zv!jkMk z97bDIiY{IP>e`yC9E%D&HA7}BUEqnEBKg4Pan7%$ffz#q! zf3%TYvB?7a`5iSI0~pq&UDDqzM~?mhSrTt1X*8@^-?fdo6qx7=6=$+4pmh@N2#|7nx4eH@0ULGX{|mft=GoY zLAibOh#Gjx2S6pDxMQAz;P7ousYJr)OuS4J&m@C1Mao zdw{hMCTQWi!W?@`4WDia32~zn0EV|!-xh0}KAF^C2f(aMSm~J))Y|jh>Sa;I_o#E# zXxmx;2a-Pxfyl?v`Fr-WDN91`QfcwaDj#*F7zPrvpUXba3|OtBv`4aL>3XmE@fR`L zw$iuSRW0k!Dj2$&3(&yVZ?`APanPE7)WDjetL%`vuC+aaW0A#*L{Nu5r6*If+jO^$ zFwkYvDGv&=={G%-OM``mZYYH>I}j$?@28xv>qfwDyY7}#NM474{B3cWm|vh9ndLKs8m zVcaBjzu%g|crvS!*A{53m97*o!luo?Brm9rkzdMHEjAfyI=syNW13?6rUbJS;SU7} z$Y~8uDMJx9jj*?r0>l!Vvt_t|roJJE`R&T0IkB+;&OStt<>^w&L-xks$IH^?^2fzv z0jHN8#lF>_Y1^?u@gQNgs5=*yW)?)m)07@-m;#Ln*Xesde{ZwZA)-70motFB-s`del@oauH^sYa^UMH+7LJb_d= zsnRy2mB|$5r@qza9j~KOoAWj^_wbG9`LrD%he4YT+n%A82i4!<@_#L~4-Beyc)pvt zw~IkVm<*F?&Q@~jWiahjG7I!EZ7mRg$8D^IIO(~v;4$ta>i_&dn!W>^>i7Ns*ds+E zLRR+Pn-Iyd$FcX!-h1y4Le{Yfna3X4Bq5HGz4zWBgz$g*{;vP~>bi0X)%&@hd%Rw+ z`@SPi9TR`wJtl&_=VwN0(+wORbj;&bl17@6M(+5OOzb%ep-Zj$7`-5p<<1)BU}vXK zmcQwrJ^_cY8oYT`-A?o(a!ZK3f6hUGWVCJjUHlO8^&iLej=aSxMD>;L;(bw(CUwoF zz-kBi3CY;biwTMva)f$+7gH*BRQg8$BQi>?1k?9^+~_; zehij=ue!ECjj8Jv&#nv-dW#FkaBQ9R%jP~ogV3Bj#kpOD>+$Lec}OY2P1bNlLQ+8D9}^$jP8Y zdy!9zr?3h6ZyV3RgtX*ZF1hjSZ@~?Z*f?(1#1uno`j?4oM@<%OqwZ8N_t zwVcrqI;6s%u?IB97xiOHsrkh7fI@$U_I%?#4~JkfFcZAJwrFO{rBwW zcrCX$=T9Ct0RJH_ZrAC$A=EZHqo+MHH`!2~pYLRUxGck$`*dZ^;dR{TFiJ4VSLT>~ zL6HzibAA1&g(H+;AZ~z}WTHyz=kDeGz@;PF8O3(G&XeosF5D77*x!ET>o{~q+=DcTueJPAqm#K@1*iny0;LXZ9bXyoLx;N z94OO1EAM{V*mpBrC#=E{`}o^;3+gP*&VCboh>L{4I%{SVC-Ec+UVVY{GF&pSj zZ7sDfDs~6S9UTcXQ%mg&&Ki1pq;1|(Ll*09Zl^86QHq}$VdR=+4YAQQ;R1bss&#U& zjmtFE0=RIWTX1l2NH0gK26jDw$^_69jXt)OwJ zxl-nk1p$QmG#|HrfI1gg%ooPeOF`ph(UNM(s$~M3?t^(M*%ne{xI!p`B_$zsWO$X1 zCV?tvN8i^g(ADt@m5Qg4b!dOt=|&|I<8ptB`5AREi}s}4e|Qx>9T7A2J0wj)KcA># znWZ@-0(W_#{L?eOfbo>8bgA1oHy>ny4hSwaiT{`d<$VKCH^UhLXuDXVEvD`F8kS9g91!e(es!^7HjI;2`OD z0kyS{k1$!>$mnRvgdO~dHCI=)C^Ii=&t_F@aXlaZL zt&UZMD)R@>|M%g;&o`FIL3iE%%i`AN{iCwzwFX(DCL1Jr*opbc2g=mTG<6Y26}}y6 z8mJm&n*u}SG1*sGjYOKvaZbpR5Yv=7DytP!2J99Zd9^z!y04{l;>_5CuXhioM;S?j zHd)B%gu8##TrOxw%b5e8=CDOING+$uK}HEL7kxLq6m>y}{Z!jY zrj<&~<_lAtq9lYMwpj^<)FF@T(Uxc`x7pttFa*HN9e>!!&BqbT!S-5$TGi&uLMOYN z&rAUu;&m$Hftmt>=sIX@TUOj+m>*ITU#ftLy=z8oD{vskPre&gNq~G(b2z?_84IBp z#iC8D+UO4m2#5;^uyzyfZ*lWs!LfbaaCYtQcX{}NlytVU&?-=JGAOrai z>3aPnV3Og9TR16P&gNEVGoPXZuz)Z5g(3VE3*%K{MZe@(yGoZg1zU0CxrW%`_fm~r z$@B3GRR#tDs`C=Fl+r0jhT+ZFOb?LY2G^k9O%4&8`(a8vtPdPQj0Ns~uH)kH4DR`B zJ;S6!+RZo1e+UfhLM+AKRwrYGS))U!t(*fd*VoEe$==0>mnJjKC56h*q#|*+E&;$)qS#B#ej=n zQ{m-+e?qIahT2=%Hf?&(#acXw^@)kI=d4OtzCa6;i)gdiY8VR{&a|)1Kb-98fHmKL zV41G0q~a^f=;6bDG>8V_;zTNiA6n^>2Y=p=*gX}>%oJ+M!g^1$NlG&?mB+(6 zU%vG-X2+*%W##8j5XQ#$eor9)_R=8&9svP3SX2}JeRGrUj@O5ntvu#`T9=1_-IJ1P z)Zn(dc4M4!t*$1KuP(;C!mOGm8N|}$Z-OMW#(}_aPCru}84dK1{C-4G8&U|VqiR;% zl%S{wbais_=HAi4HjA&61F5WNz8mDQby>D` zkvL`98_Vty4qg@ShFmbY57yElbHpCBB8}o45~$tJ{ubGLmhbuHolqGU{C-q>+szSepn&rwL7JLmKd_GSfP9-#l+5lTNc&76(8k%T3{?wcb1<@ zjSV%}au=zeI|PRl^ec?YAA|_)DlmIc`ajc%x_qz?R&W`pJAC)-h&93k2#>8nPGUV* z$cD&9Y~xqjUZyWNt)Khht5uoQ#%kT+` zQ(iC@-Pof)VTD)T5Un0;iVlapjbT$&&tUgQlWi&+bbCZpv~xofFKT=yY;k|a#7Kjl z9z3R&mZVr#n{wuKgt=8yWf3!&)PT3~Sq!Fj5R+_FOZ?}}bUznGPsM=%Ak2o^*=}__ z<>3k+P!*t2tbO|gQaI}Ut}UT{)yX^NnGQzNTal?x^~h&2+=CoTw>Zy94B^qSrg|P8 zF!G;$=gN_4w{ts?0?13sgv#1PH=*515B%xX+Uj_8lwea-wk(VvJc`e$3w51N3HpI^ z1q_;Ta*&!K39eQ(NwlSI?hb~OiLMq=uLW2;)vr;OqPdG9&n$H7Qnzu zD}QX@qTW~j(`L*i#o(8-1$E>Y__!7o~vyxV7l{N&Rg26K*6$b|RkU+9?WLUcB@Zj9Nut{LX0 zlz(f~m^{{{{qBOHqVZIEVUf~QiP8!{uQY#=txM|t5<-+S@)CsG653C)H#oBP~v6Du3rwP~^d^p<1MlTOp$B>3F18oum?B z`9h1g%wvo}Lmu;QcyrwGs(7LI54ONT4M>sd;HPb^Hi;?a%LXGiHVwu%S&9NDZzQo{ zn8X~PTtE481(Y86G({8PwcB%~4If>ihvoLYjhe}FZS!f%+46}r{g17UPJYnhy9G~2 z&Bxq4uc1-vooyf>;}0sc){VBTm&nu9wzjjieQ#&(Ez#7Ro{^)p)Si)%p?kY<{OoU_ z{+qClmbtO{K`uo{7q#q+)5T8q;bAH5w4YO3rPb9=HfuMxx><4W2x&e$KHN{2g(qU626xGgbF*JLf$J>>FIt+wJals`$WBQZpps5s51Gfrp?%F(B4y9 z7mJ-p&zz>LkfG>nN(26-F}+D{ZlZ3&9waDVt0_e`9c^9z+=aXp74bT`Y+DkLT79wo zeYvBf#lSsK;%P!j8eBa#_NvM_FE5=-v5gI<9FIJx6Ubl?!gSmAUjj?q=8kfopzj|X z>dHh&Sg9=>={GaeK!;XOVg`NHU{2c6`|5xw? z+@lbF+}RxVWfjmLkKm=y2aKA}IojCvt{{ zhUVtx0RbKT8!jR_gGvK{9(QF(mM>C&^ytxGb#7J`(yG39v{B}V>r^xXaD{vMQxtlB zE(i2lSxsm473U~wi9^dzQ|2?Sv|nsJDJOCZUrgK*i9CHu`08^!!HMlGA1AW@_co+8 zH2{^ZZO9G9XUmbvQVQDe8B_5wk37#1y7ipR6kNU-Z@9+3X>Z>Lfb}dTo=^l!&++M> z%&Z>2t1rhZ#w*j?kD^{0Rj<0&v9U&*38X^V+1N&hhL)STMMcQ&R>R746ybEb_4?8j zI~UhxZJtw95{EBIYg(3SqoZ3Mkw_RA<+l4wRJ0>TPO4WLk+(nJIG~~7^|PX}MV9w0e2hl6Qa-WpzoyDdPj7QE zzZ^^*8YfJ&l>V0LK+EE{%}wwN z>*2SGAOmBWUWt}`Xt(`d{R2d&2XtWodPZ2v88a-QscB`o!*8a_(6(yRwdK&Wt!GV@ zgs~ zKLl(I*g2oG7m!aEjsin+0aNI}O)oY~k{Ix+8pnXAvqi@Rc2k=Q3krI;#CaNH z>a$VKZewCXP4R@h^C{B;dueE+L-}MNuAZ0Wb;W=b?*)5yjBR609s%S%?WPC~<1?I5ved6hhuI4n>y zL8<00PpE?3&jtPdkyw^HHOcY?PD0 zE1B2HlfzlHm8By*^ptThSxs6e-aK15VPenG-u=(rGW@xhd0|P5PoTelpc!r20D&&1 z^rnIGpp{$3hm?UI95c`)+5gz&T?JU93)tk<|NTbTXM;hRM778`GBvhQP8(BBDlG&V zVFQz1>g)U^;p9t>ZKK*V)6>mndq=X)f>OpRnW#2E@La5M^<@}KxoL;+PpY_d}NwCKydtOvPu=C|_VZCy-2LTd|t)&xdy3 zYn2LI>%jF29;GInttk?B&?4;f#)0HKAYb*o%1}H(qV;@C&hX+wpoBLWY=5hr{3dN{ zDmAjDBjtSKzr1Z_%(VF^LOLKoNz@B?w1@7iPLeJ+tUBEc0_5mlkXc>M&3&IGO{8Pa zxjbBCo}7BB%aBCWgSs;At)Ra+d0beM1XcRbL6ORPDfe^=kDYvt7s%6^1EMP^Icv{oy?B4 zJFWal2u#V$QWzPQufv1HdL26p=!;OQcz9xZ9j)67C=*!7>*eOgue38WB%ASMq~|D& zj1=?rnuSDdj-Uyvbok4`cRnni$^yOY*QejMasDT#)u2r1s^|6JRlPD#;6GX(7R_Of z%*gxqXm8&!Zz()}{CLfIcF!F%th=>UB%$B!_VNgvvLeIA)om&dBF#8Z7rte{!HDGP z;iBk26$8RY)DTHIxqjfjaA*KFU}c2~$yT=3(9i&mh?)Q!GYqulG&Q9WxSnqhM?_%Q z66W=9?CtN1`2YE}k??wXVFB2)4m_@Z1AMcKiwiL3fi57-1`ldTFrm%G#RUKiIe;~D za-vP^)OJffkpoI|5XD+$svfOA6C6TRN#Z)?=d)8`aWHem=?#qAvEelY`CqC&TTa`Bn! zj&^}-dh(XCFCGx>&ps)F;q^ERWG!vj%(v9Q`#Ty$#b&zo-F6&Wq(*|ZxIvC zGBQY^kKXY47qo>Ao$Ty(_s;|b>qR|Sdh}ovgUE>zglM zwtJ#-ZZCbjj_JZdl>L4TLdp5|#4$-^&+dXeF;son7IFEwDfZtV$ zXpK47Oe^n-nk9Gr1NMNnT2U|8P!^usr_N5NmCosez=qoD(W%+=?3|pqw<}#f=K$LU zt#uiSES9PbKdAxd@P9i39RBx!3f)FMuD43?mKrf$UDNGpce>0KS8F<%P zp%{bi++qL_W8lTg%5Wf#ORdBS{Uyc4gwf$_NN6kAzyM&V`T2RUXmH^uUWQiG^RU_D zVEXK=uFjRV-zAi~p`n37#CQUK`vLGY|PTMATyKUFLgYKy0WcX z1Mb+^*xv;6cv7kB@od$s_;ukCQmH(>)!J~WG!?)k>2YD$*%hnTQLJ7&O8ta?Pg9mJ zKCX35GF`622_DdNnbhM20t8sC5)?rSZ){o0jf{lf-!DI7Ta*2Qe}|w z;-ymWMiLV$4Ic8$v#q|0|VR% ziyRAyl+>)&Khbl+l0#Fa?f|M*Dj$ zfxlKoTNbbVt}bH=0^C#bvMn(3#VM&4TPB+9NM`K|nBtdO+}6Hfm|9uc`072E6;4BP zaC%idhuIu2k;xLlDqoeV*RZi-f1B#-E1~qSx%g$O&6Tce&<=8$C9jo$gZ-(s=xE?( zHPvuwV^@mX19>);ZJ{ukrPn%(Iz$nY;t|wj3HUg$_~UivA@51G87{TzHxn6 zIbjS3u!{_>%l+SL!4-dvIis@db)V%eR}U|*ptIyWcOeSkSD|4t7 z_5x|hMgU97QTl9t4M78*5M=JJ@Agzy{7yQ?#>N(!oMH<~pSw*>O zdsN1%4br3fOnEf6eiwm-@u3f#M8GczzNNjNo;J}=OIPF=9$M`5P8_gmoH$@hRHCa= zQ8__h%~qB#%cBjap(9QhUFp1gsK2_bb;-WY**WpqFG8$j+1Fj)GpH9VvmuilbZf<) zCB)H*Ho2fOo_b$lh9M7Gnui@c@uNH(IisWqhK?vd9-_v+;p*-VTC#U^;>qB3R<=r# zKlHZLe}yzh!r7wXGBN9R$+nlbb{;VC(Yw?Cip)Geknnpg(nDFD@fv zE8+DM;AH|dNV%tHW=Kd#%xh=MG)nv>@@5Vmqk}N{b?3aSd{88l7fg>W9AlFHad6>E zq0N#i0Fr#*#kU4iy~Q|?Jh4iqAB5vUZTIZiGr($wQp*&Mz2_4F(i2h9Sb?-tupkr& zYQP@?LC)dPQKc3FWcmPdyxT2IfWzTBhWYVy@=0`H-Ee1TCopI*4*bcJCzPU|Y{>&4 zie`Cwy4au{O~Bxm!86syg80JU^mIXt9cedB$gE!2X>>M_Sj< zO-+42JiJ?Ia}clj}I%(&ct zqgx%|1j#YJa1*u2~SKqn0Sl6d=-g2^} zty2TX-_w;5s->|T;4s?S+Camh>+PjO^-QdQey`~Hyxn)lqb@wVkMooJub+W%)Yc|S zfSrQPoCc+kv@w4L;Dt`V8GR!7d-VES`IMa}+(B5BP zzdGWgOMNA+uBrKPeYz17 z903lv+oVRl3`m8ChlUngJr014G{))bjPL)e6$Ag!^t%9kX5u>wUteDbhoha>4=py< zBxwRa84N9%?Y6hK$(j$WDl6Ddj$R!(SU6rQgv6=V#6}*8n!`BKvSvF6F(8L{6*$QA z{X}cIsh}a1j{gWCf0&oltZe0Kf>TLosHAi4> zj*fyE{mMc=O>;KTCNiBEBCxL)#1~Us?CiveEiIf;!N#6SLc)qbKpD&zmD03~wOICw zikSMx!mzk$5>0-x#yqRlp(Y@Z9kXy&6gx$~Yc$q)^;Ewob@Xe*XcG=hZBUS*oU|gi zN|kA7WMr_;ACmujsV&3rDhA|K{xAX#vV9IqUAU!ijxr-*G^n(lh1g?c>Q`bJgqZT9m-s($wE#}jzA!yp1hRCmQMmxcEI+wDnx5*YjJV$+qZB1 zC5&4PtQ_rpeCBvWKG|dz+kh`l83!epYs=!of++Afe0*R8zjv-6WpJzl`TGe!#meG2 zwHGGro<8*NwO_d@827znNQNtSck491CYk0MF2`#3IDq@?)_z};8F$eUIe%JAsfH15 zPvDBaN@Xe*OwjOEaq3&cWN3Mx5QoZMqwN&G#x1H~$kzJ$`nZ8@AuPd`o*H5jf9~NS z8yWdo6&nK0P&`}iSntEE?ed!;D*C8coR-GgLLrTP-X8psk@UBR7qWt8#%swVJ;Dwnik;UsnYsm22EiX<%nKrWy`qZ0PbVH6eW#%>HFcNVTSv-j*(j_C| ztCPzPw+_Y8*4%S{g${WdZiXEVIfz+DgM8?=rJP{<&A-jgt09N6c6zPZVy@e_izoTv zqvc|!N`j$*!6k{36XE7J?}}ygr+w;Nr28jV=%^6YfgN5})?W8{Deb2)cI*1<3y&6^ z&*9V`xchy8DQRmX3SBrxm*rV012ILZk=jf>Uof6DM-zXSKVjm%qSJN|L zMe4FJ_R;6iJ;@@T&o=jFiKQ&m-*G~B&wYBNf(hMvTCp2<&BcyVFD>A0%0)!q4$xTTWvd|Qw3hl zbJ1Hgc3!QENe9_NweycCQJ4Bh0})5LOEYNGTF}>8_I6^t8Hzj^hktqViQD_mN6*9{ zG6cBbTquJb!)2f-lIZWACQb608%GwKuxy2ilwUit43dtjoc;ac*V>TjXePP^EZD`x z1|tCmawY=l&>7YU>Ck>Oh;5Pjh*hfV+*&Rbq_o&3reLs6ox?5kYc%c2>AMh!lg8gE zwln@E*#%xhQw3VwBy?<>7i1^}YiPVTR%Lo#%Vrdz%&8Vqw zD2FaWQ=UBIQM3t0OT>CIC$Z+MaPf*1VluU_Qjgq!t-#eMHX79fW{9kfudccU1gO)| z-rR+bMq#Ys#NQ^VZv)*bNOU(gHpbp-5>Z|9TJjuJHZ7ms-gVtAbb;oC{yrEi)lyfD z2)YN5Kys&cwOe_Cq7H;U#g4vnaqJ5-|LhG^Y#)dWWJv`DqKXT#glh9u*7pAS zz-Ll?_@_cI07{gA`>jx1?!hDAg7E{O=wwE!Dp z+o(6Nl>&{J{*UJ6;5xUWHjE{hpx@xb%4nmG_TH&;4nf~tEyu+16fyp{7dqT++!;819DP=Few%4uRdbgOu64l1vWJQ z0Ux6-6v@^B1$OE;cVK14?Sy(6Y0#c=3;(O#3g5qk_paR%wU=i89Om16`Z_>7^L0l9+;N!L79wk z%{K+*Q%9pSeC%>RNJmSsZEnKaCRLiPjE=|I7N0Hj_7*+YXu$n4_@CUf@N}E6q-YTO z@KTn_6XGO7X}-8<_U|s))HPT(yeiS_D-F#rvHH?Ce8Rb@(NhRv^qGAU?iNDtSX;0C zZ-kCk8k6QDv)M)Rp2=!a&!snC=V_q^R?vM+_4 zSNBTta&vRRO0wu)vx1eA3-1)ymYPmwzPM7BqTf~JJZ~mJd9|=W{v_(|zOpMRBumf< z%shE1;*KqFTSneA-&=8Lvc}2qV{prrB^9*hFg*Iges#QrwBS)RY-w&te!gE`Z#_DF zlXJsanKM5AO|ngH#Dd4E^LiWH57T8;D$mCoS?}lcq=0<>xRT> zLo$a*8|GQt;xC7$)R3RCKbiWO1z5@h)uwEDE&H>}CFo<024>rIlD;u1+KZOqw|RsP z2ea4hfw+sRRY^{Acq=Fl1+IMbRXkc)$h<_6G&8-7#uQd7uKAG5p%j^^opWEt{3|;T z%4~7j*B>=3JaO%9FtUT_r7hDU*1gwM z!=?ew!yc#0AsL#Yt_z>T(elfj3i7iXhXJh3!2u*U1Cg*tO_pG+QI2w3>tNAcgR1t+ z*MW;-laoAO_4F(%*mzZc(slhTFn8o{tH$zQtoi$l_tL4^n)rg|*H&m^oAG2+<|CcWMq{)Q{R5;vtuis2-O{k-d3lk_!5Mj`uQ$*=}cwhe+ zi4#6Mf=?F@eD3uz!CjVdr6v{RwR;!apx+uDs87&rud|PKpTCvC!j^@LI7It0T|wP6haEV zodc70B!K+-ZbFz>S76zize|W@1dpBj&er0hp3ns7D*!zY{tlG4E zhWiTT)#*z8?fm}qyR&|N_*u^SHJ7w%y|=M=I0O^>#agrDhYo=W5(t=0R8cQ}K%V1eu7_O@-8&3uXd0(uxJJcbcIxoDE4ZlS6r0=}zXxFVHywtk)tf>*pP z6n=V{i3j<*-jnT6!rB%>Sip=s#uu+{I4(@JuOur)N`*x_r&x9Rl>M)TtdYj%U|4`O zX%tsq)){*z=EL=^^UC}h7|wwbi26q%)01LSOxh;=_?7$cDHqu*pkoH)_2xh_C{PQS ziq*@&`{}wr=(_*agRjCgc+ST5MgHS>-T)6PB?Scqokt!TI0~S40xG)g#}Eh?KR>wq z2Q~Yx|HAP5%(u+LJLgRR1@yl@1B4ks0e!Unbd<~-ejs~`rW$0l8(Z*xhQHA-eMfiJ zNAC1b)Nw(ld)PqIuW(Kp;c!|Bb&} zn7%QU`t=7a6g>Fl7DoVO)hB-Q=zKK=OnsuyA{L`u-dK}W!^M>C%Ih6G{7TV}Bdtg9 zbwdg@fomO&C-Gd9dxggYT{54gut;_S&Q3x5M}F1R4NCl(@7*5L*9k~0X_v;zxfWw! zSCF@N`qDG*XYN4tn3|euR{N*3fTDX=DB=mqUrcG?T zzrj$nH=l)oGXMUdNPR%;x6Zix#vEzm(de)rA6jxLi^kynIqi2A<6~xM^f(2LTlsv_ zwZ=h98I!r#%D4)f;i1mIoVjVCaIm+x7qe-wPFJjRj0J-GDFwNu7+I;)uaM*=YKVdD zA~xzL*53chKJYtY(A7snyL&oU2HU*d&_0GlR)yQp!S!WICo% z9$jXl;Y8yb)4@Ou0Rm+mw(V1IEp6?tzh_9m$W~TY*XL@iOfM!$W}v}Q%*R4^#Hv0*nuY)yJCp!7;@esclZ1}{LT^!zO=neId(6BlrcP`R z{ZY1d-EEatzv=Ah?A>qWgRW(r+j0YCW9Q4U@A<(gWBc_#;xE&gU(rBd6PQd&&(=45 z!0k{ zX~MSsIHFZfPUF!dgJHLVFrVd_DPl^pvq;c-r=-RwTSkOi)t;5n}${v(G)nB5ml?5X#B$tw#;6J>_ z7`}c!e!QVvmytb;onyS7BB8?ZgmDB#ngc~pX0?&BaCdV&i19KCek9{9WuQ61hD&Y< zMN_^FgrK-IftE9X%L~`kUYke^`lAWQMr$Z$Lr981M(sN(Ym7R`VXxblsa`^?_#JG| z@mX%}%&31IgoOb@0k8>8uiYq|JN0F-!BixTXIEym&7GYRLPDf*Zv!M&z-T1UFLzrpC|S#czho2@1*lhmZy4)dih*)gf#q44^2OQMlrY4mBr4Ag=EU< z2lsG?-I+G!_3fiLB-3-J`+Jc5386R zX*jC?CHT-=U~aC?B*Q#aK4n{`Ibem%_@Kvu)~_brV4GUXLXYm2 zy?PNNk!QFYnTqS%vsN`WrfN)ea%zu2kYeX2Af~GAU)sx#dO&UHvy|A`G0eFOY=HKd zs@!Kr>1HH9xodVxke|l8?di90CcVZ|EjQqUn0J`Q#$Wu|BrC=6cA5X%0U_uX3O!9G z%Y}J*vIwwRMG%bJ-C)y9*#h8j_*ccfDlCYEMu7MVti|l^2DhbKhm90({x1KZd(AO% zqxtyw7&L4jyy`V`@$m4lu&}VVA3C{8h>x$Ts6ao zK7dk&7On5Iq+L!}7+&lnsxzbJjWFM@R~}_nAE=Q;87OAOk>BciuG_n=TpFt|ByZ=- zVMHZIjo~h}SX;%6a~0`AIhk-F27K>BpQR{2`z8Z>-LG`k{s!l5#z$i5L%!+2@CyT{ zF-ADYlh0hZZC}bQX9M0It=Dxqk8T>C3CSTKk{T(C^LqYP3_Lv2e8c2VYc+*OY3@2C>qD5}mYjF_$S8gWt zQJN-*Z~x#J+=(eyU4+)-*HnLj%`PwR{%L+qM%-?6fGY}(F6Mr~`1OfO?A8g#1f9lw z=S0h$>jxvD9WQTUcXzk#)W(%p!Uq{f2HIDzQvExVM#=BUq<61ZdX~7IW`1~E{CdI6 zhlkBtBqQ9WIZ$Z}O(eWferT{ot zXwf$wEs*Jqy>~Y^?`a-|NgG|>`cw=0{xW%pewJ9vod{A!diigp2WxB_O_O1i^&*~! z=|1FNfBg8-)OB|>`ugGTco7g=S$TSTIy?XRwblbJWUY?9zrVk&Eeq)9PnOqMd(`hj z(GOJLiYh8#62lFcm;jQn3`I=TkiK;j4vx0Z86`PITT972lFurxTesHsh&@le7u9W~ z77SD4-`ukAen^LzUj!#mdYX;>;4p-VAC2mVaPwkhS?%-ZsyHYo&HliFny17&F5}p< zmg{7dJASa+>CAx$zIV~usOk0XnI+-7=Y6covQ=EF_1|v>Z#AVVR$lE7qRkEe-IA&V zZ$DT25*LVEpd(3(|1NHrC7rU7q(9YXPF#r!QG)Rzkrbo&;-~0pFlHjc_T}ZWvf1vi z%!1M>TMtAPA>9B~+!G3M5dcXg=F>pmSy@`14yOJdPvZFUA6we^o;pJzGcF@GK+$Fw z$UpS{9b@{eZW&f3jSXEx@IXz9cR3f>M4joPv@D4=-^COxLcX7>I_#b88Vh2JejwZ1j} z6&d+-yS!H>@XnUm?doRu%sB924b2)mk(nOSTDOnlPlQAHo9k5Y9~xe*fS8Xrgdg%) z(f?DH4eXp7Rcj}G24)99iPTi$4T&_Sy9h~>(x#?|@6iKkMoF|!)mdQZAv-?t8+7t! z%Y%Q|FV3g+oqWXpRdwf>Jxa$Bk4UVntN=6$WbHt|;^lSq{rmUmXN({gUL4FQwF0d) zkQMCy%m)|#8uY1yOfj?ghyik|4~XPqD`J3G69BC6w_n4-Y+Cki(L zB;&6Pw+t9Ms9gRW@D1grGZzQi)xc+3miFef_)5zjfHf`SCFX&b%wAsIAMMLDY;O63&_;itxxMY&Qzh)^;~D+x;GWJfA)u`Fxqq*-liEz0n5i!yWN z=DE9%Ft;E{mruQyE6?o0f;bP)d6XM1?IG7rNbohy1Y(| zR8#Q78D|F8>RvD}vK?j1mzFf!Is|7giJU_!sSLGM~QxVXHy z0PKBSLP8pH>*B)W9KSRSP_`^68`A$@3(yZ*8mhbQTWcYz)~>E~U0n}Yum5!a{rh)l z=mS#>Fb3d6`V*+If=#$cV|y)htF#cL=J6ZS`Kok;po?!PSw&)QX{oZ@mM6o&$jC@v z-!09{YwlTQF+!vUpom!Jmh$8xj~!y)@O`Ll;zqc(7+Bwy%boC7<*KIg9ytX)Y2(sh zkcOx{OA=HxvLnIcsh!CFg0uF6S;F>x{ahlQH#Z|R-?m7*k|R^FwE<2_gPi?~Vp5Sm z(RNpw56ScUtuH-!?a~ASxtv;-Dq;mgj7L=(fEek}N~1202kzt%bMH?8L^&ajx%LL@pZExPn4UBR@R(%**Sxwe{~<>1(p#swxhnmT_M0HA{`3 zl`mMK|AE$-GoKdK(&w?EGe|dshs0MUU8ixy2~42@>!*>pcDhREQ)O>EE1{>l_1)D=>YIDaQ5ka1JcxE|g0ErUzi6_Z}Yn zsZdLv7gp1lcq!1L#>PhdCdU9UeFtc8UC6at4sn#P;1}l18Y20?Tz1-%MvT~3tfK1Q zXD!Z$BXTB<@n?S>IAN)eGFzD852sWWeNyAKT&FII!ahaWWEw_;NWShDx9mE61lh!H z(J_9bij|VVIvDs-%PXKed1`QWyaIuk@8fxE4QY**HGlL{A!BQOTzHZUC9SyTmaZCU zGHk7Op&u-V2`wvTa;;5o_9KCCjXp}+JlQ*q>`C7VNW@N-2?y1Sc!*?8)66qG+bLUL zo4xxSQ9I+n7T=Axwl>j(-^dhDAh0Rhmh8BG?an`;X`hz|27sUXR1($O7*m#_2Vjlz z-HVvOphiuWV)ebPty`~SY{~={WP5+l^!-E;U|5)-jRqrZoc-2T-_XzwQNUj(oXlJ_ z0n{YXJE`_s4;`5cZaJkaYOpURvk01Mlc6aX8&USxfNhq5_rN`ZtVf!Q2Y1F+S z+h9xI)Xw9#Q=i~y*yhdNS))3*^KRH5_US9yIOn!sd8XD>LAkV&Hvh_Yy(tU+A{^69 zD?@P`sD(iC0jkxFW=U!;At9!i^}Ce{8uU2Ka}$)6JZ zRo}b2H>fh1d~jNBZ^>FHQe=38%`M<-UBk%xJeEFrAmR1>?7@YyiVB!c1)3Y>lOiJ{ z$M@VN@<`C72*Tg<%}-1emfH$s8S3d}W@WYcUhMz<>rb0ldRN%o+<Mj}c z|5p$6h;2VY&HR)JH#XLW(krR)Ad$6udmzo|d?)k!w#YgCBDnz2sS`x>jWr*Q^q?GU z6+m$oc%bF!kxG1(LCM?p#dGId#J9e_*$I^^DhUd}G)4B@zt_Z#N_Ev`PD5rW3Q!tn zW$0#QB*w~?+e{6}m)l@N+$gq%%&AzRWqM`b!P`7d&if#7_j`A5qF{#g#vj{Unds5L zCQDIBrN;N-D+5l3WW7cZqgpO5POb6daz%DeqEADOai5?<04}T!Wm03k_V#r+9U1OL zq*-lSJJM-sZ@ETKi^+BnMU~3da}-9^J^CX^UAdp23lK}71C&n!EFD8K&eIOZ(mzxxx+<`be=z9ZZR zumcY!$X&d=yqJhufgmW39IQPpiHZWeO3li@)kY9W0nma0lpH`K0bBsUqjYt2W@l%q z!zb?nO*bEW5z+DLQuf8CXn-4MM&SYc{blM5a3EMgV+LR1bdPp_WJ%{-1h)m|KUaq^))rl zppXQQ3@zZ{)v_|iX~ID$&}8udvitXZng5zBzNfNkYr-C5Qh7SU{ynm4?MBsXNI>R* z9Ul9D8aO(#Y*kWAv2Dy81+?*BAbAFY`^7~H1d6+1Dw5JHKz=5nNMvt_NAhKqLF$NO z`{)<^P6ZwDLc>1mx}&?9gEA~&-rM;By+NWpJb}lHrA(26qYm(l@qsiX5`idd2gjZ| zZDl2-wkexP@U69%gfP0%-FN=aV+a877WW20>G9n?_t~U>0WHaTJL7j8i6I|?ZLmv{ zE_v+!vcJxNnS>|9j6?f}MMGtYR(gR%Ogj;ZBu!%T^+aBk|0xC|w#-D*)v=|vHbVbk z`}YREnb`MpON8*bauKmMM^I~>I!h{m-&TSi?#w_N?DI4@ygX8t9ECb>bfv>jFcrGg z86ZlE7gO-#Tugxl29VUEBxN8{bmvIBH7YuDl6}g@-qtP_wDt|yO6bZ1jyg~SELTK%VZQ328MmRrG?w?N)`p2~VjKneQYurNR zs5DC(2RL9+PuXyJ!#R6rvZ0Br{5@tGGMXaI@)T%B)7(cDI<3w>-^5yR=w(KB zw)`cUzI?G?{sSqq^2y#2&s}PIff0O9vb&kgN0cv<9L>O*swnI>+WdwGjmkI-K@w+f z^$#t@Ul~@|`~8hEkMzretA<)UE^3zVTw{5uvEJi>v!Cvy*&i!J8MR=|gVlMy+1 zX9e?!*@%gj;Z8Jp75?#I)R}I`VR&@(;ME9IOcHqA|C(AVY&0CchY+Y&YU#$r>|Cod zZ7#F7x(jU!=D(~>7=*lBe`jJmEcky^%9BI$-q|l)zktH^eb0I%kg9cct+Y`7nm)Ey zj`gP8!0#;Vgrw(ALm*EGA%AYw&h=+Ro%J8)H_OSeVIG+oJZseDdNal48n{Sk&$F^#Up-ARtJGBHi5} zC`e1}0!uebN_Ps<64EIRyL5MmbV)4T-5@Fbetf>~kIR3IOI_~!o|$vz%$XFA-=UQ^ zwDT(&X8_^-mj9FX*7_op#S@KN_ph` zki5H-pk-LcK)z8Tm+;v~VCjbXsAFslC;v!D*OskqZ#Kn@nQVgxbrP;DN9i~@WXi+q zc>H>Y8ov7`>OyxK@i;`z5BqUrf31n3E~VuWrtmhOeztC7%xNNQ6SzG44tm~JkD^Ms><-h-`m zA_Z8?FT_4vqeb@$a(6q75~_KrjOi{UCk(cA-8hyK=8~qQrCGZ~=iLYa-Uz_ny`kK+ zWGOKHjG4{#p%<0<95MRhvqK*o03^oIMfbi5H_lf>@dqS*!d@?qXt$H_P&=}l_1*}e z0-}tP6X1UEAD&ffHe_`^WTxA)z|#?r13~fl@-S%57eeXzIzx*@xOVsehP7^f*POKC zsrNn54LAD9mbqPvV)q#p6x1*MvyTSL{g5?bFgGMk+i6$w{1TklFmCmDdMEL?9bowq z)Fd==zQ*%@*O8JdYlqGmPa;`PE$8i)M1R>`hC_%e~3X^Z*{@MqWd1F`Bt}=47s;@N_2$1kqa@U%}hDfFo1!rMY%56OVcuFCuj7sEM@C3;#87$G9s+k=`-k> zZd$Fep}`r~I`vXu^R)cd+cn_j=X~VD#o{ zb;$}kxE=2TJxjD-s^}HSyHy&rf*I_sAB+8z3~}%#;TxhKcw-*%A1zZAnQnKwTWkq6 zp@$p);MTPCNpoVq(bb^o7PFAB#qQ?uO%jy`5Yq4d^e| z7D^R=uf3EM21u0er}FS-jkD)`b!vAB(2+0Q!r#lj7n_a}T;{}m{=DMP&2fgFE;Qh< z`5R^8wliV3tcl=`k&KDQ>yWvo0`jba_0K02+A|Gr{49(O4MCs-Cx;}mo ztU!Iz7O`sdy*T92g0yMq&(JML%dufG363n{GRE^g(d1acz-j4Rr>zU>!U~N9Cy;&i zpF;Dh@WSdi@Jr2=!C6m6jlep@8JQMIvQ)H_2o`40i!Kz}9a+&3UL0Guj3Xi@sms`G zR|l>&-NCJ@H+IZe`z=SDMl--fV!pIin=e6%Ga^e)(eQ%0)&N{b_t17;KCDJ27lk7WrUX&k~__3lqV{}hdN(RLkr@Q1b zZ@USznOue+uo?UF)t*RCH#P9^R_Xr0qh{cgY+@ExG!V4N_x$#kR>1ukVc2`J&@dq_ zxD7wxq-af13_kDK1FuzRX}+h!eRuX|wuHp} zcF((2z3j#@__TW)dNv|;DqKZX`4d^LbImu|qiw+n?jCx_Al-O!-8c3sGseZwEq8+w zl|SpX3eHHux*-fDW=a!1n3#lB22~QbNw_u|Vou--?4SBX6U}tK3?26KHj`J zYlz)~Jf_4DhBZsvk}`yY`~m0mql1ON&mAa0zXWkXmbGv)XDS;vNHoEzPW;kO_d+hj z@uBLd%NtyQ$k>m0gf}S-q9e%$$#wacqD!#{mh5am0ygY!#T}j=&ZYeN#osY$p*d7+t<3mkXfvaKFw23KlFe%(u}UCc9x=L(?MZ3YDk+vY@NwT5k{E?> zo^rP%F%d9Cs#RTDxR4itH9#G#M4-=c77|eAS4lom4u8ru=ItM;Jal2TeoWK6`wghS z>s|Pf_Y~I&PMZYz;IwC9URw7SfkjqK3C0Er`u5*qjB}||s$;xAya06^{c;sVkcVm? z+5&gM6+a3vF`stQx%VEXu<7F*S3e7?Ft`rPsd*G|nU&Qt2y&eq_y+A9d&bH^_l6DH zIGTNZ)7CMP$`i?j$bd3as*4%kx&Z&Xi1dsoRR8UVE~m$nafxJE6wpfA@}v3P?Vqd1 zq^n`_)J3CvzDxn1aG+xF>u{)!>M7Bu&x;rbq7Uy}0X%o*8M=dDq)!{AHZvhq_#N|G z)@#={r40f4YOG`FhYaELOZeBzMH+{w5TmQbCej(PC^mV$UCN1+oWNlkB9LK#Eb1sL z(L2$cDBVRF-h<81ZY8u>wr6^m9JpC;fviSTR^w?32wBZ=UVD$m9(_+0kQ#_*(Nra)jp%CFb6-HhZYNO zzCC*n-=&;VD#HSC2fgRCqcOkWroG@TG8R;Mn@y{V9Cfh8Hkt*jL`b0QR-3PRq2zry z=W9n8r}BFRWmVR?W~Q0j^csipa6N}F{I`kF4^R0M!)?baG`k6I$<&F|k>kQb>YL4` z>_cr^p+ghlMRPCB4+3?U-P$ECZ!MT34zhgmMRKbRmYWpND+MnI*Cj-*KRNj<^F8p? zJWv8Z!*VUk@D5_n2xBRwLYev}LH%VvcJu{rD@Q*lhazb~cw+v0?W1c@v7C3;feiGJ z(cC3ACcE@)K=W?nlGea3Eih{Mw^+Ti^!wq-@87j9g=DCNDZ>(-&+-AsMH6)Yh@fOo z7aXJKN;h7OqH$UV?unDasr<5tbg?mZ9r*O9uK;8O0hj~st0F5ZxshmfS#x&#k(vfR zL=UnN1sVp;fBDWsc1jiOQT$Kqy6=j2$C%GvbX>g*{!r%nvKqb&KHT4H7fw^-Q#7d! z7y<&*sXXIGVdHD2Bw$akLokpvGCsQ?%a{~Kd%mdHhpPH)gl(v(@8xp_K;m`gn1Gz- zO+f4p;?!pT`tvEKr#q7HSGC_!pBAYe5y)~THvk=!YF&~Hs6z(FcfQcV&WFN8+CA4R z90X=`-^1|wFMO^b%lmlIgdmW9%8i@_8KS#5t7Y*%&S4{AWmj2ZvJ&0pVj22({TotBC-v_Ry7Yt8&YoCsKl6c`RyVA)Pa zzL_e3UryCm7HBjZ$+FG3XkM&ji7i@{eU!iG!EE1XceD{+<9_PmVP;YfSd9{OKcM}YzF67(DI^K(P0Y&xltfnxG(6CHcP9?pl7L-q6Lv?)N&czK#3{1mh+DY<-} zxxBpU*1#T3HT6n|%~dX)eJyo>NY9BsQCYv*c!r&=bQl>J_?1PCf_t72;S zo;7HM3qcq!uGgzG-Sz@ZKWASYIZ0a0-N-!iTF`xYEbra2n?49kxQo>&L$$>#lX`t0b(;HvYhMzV@6Ui%00MJnvg?zg+Js`$ z-X-e|hlJ#ZTNODG2956Ls{4ivR)MQn2>kgg zyf=wsaQ=p5Wo$5V?GuURfo@y!w$4A22JH+B!_W3BH9((6HzHoYJ8u8B z4>>OsT+obUEpGy0q3tPW?)4)P$5zF#1Cxkt4X#uiM zNt}^OYWqyi>+{RWH5AO<}ZBFB26KIrlG35aO4u0v_x0<;Xd0CeLD@dfWV@9{DYcymOxe&&c zJ6E?+A_p2!vuf?L-%Ed@`UGCbhH^nK)@~vg99lePGXk(qz3 zF5Sj!+SHuJ`nQ}zpj5Be`f-f57kuAd1mjLP0desKj7zdzdQB-7@= zW$6?tt058nuc|?{h^Y#vo~jmH&{}69o^x^;_ay?Jzd?$tVPAbFhwA=&l|u5_&bZrL zc<)x#8a>`=9N@S3il)%v;l=4~#g!5G2ihbTG(Y$8PzW>_0qLAKAVd8o{n}NJljpdj$b2w_vS{-m=Ee+ zn0=wD&{@$r#{3(dU#wjO7_l`+Yh5rr@-WGGdjUCkG&;9!8Fq%JD1|?Ft)XdQqlc4bc#%%KAnOuQ{Npy zeRD%(t4FL@!L9dbOKsvK+tVO_tGxL2CwL&kPLm}+miZA1eDJx?%QRk1i<+y{AA``zD!9lYnc&?M~f zi(90;>{Ir2MiUhEMe}qP5LA$q=y;K@Vn;RpF39j~pGoQ_)vf5lm8AwSxK>8fj~i1H zfrULep)qd4o_cAfq>6ib_rp-6J9X9E7 zF0lBfJdwQm1W#i8SzS{%Mvs}4mYiWo2waWrvp{5SAPA(Fmf+8%WGxA;Oa^DmK)J|W zf?uq7fci-Eso5FjS%N0(w0gKx)d+Uh)EMTM>4nmAx2kL}47P*dd%*N>%by-{V20XA z0dIaL9&QA@TY3}kl)6Nq7mMXR_y559UnypeB~l5B5jxnA;NAQv~WMd_w%NP6J5_T4YOY-fIK3_?6lCrqJVBHXp zylWQaDay}y{{0Zh%gwT!=U7r%KI61w(-SDTH@kugYZ2B?g`}^YaFMb@GEP%ym1o_uuR@oPvy^L1jW2I#n1MLv=*B@OT9#v%3sNSLoAkx@wU=^{-U-X-_&SL z)+FjV)26}+3^!Lavg=RGx@E&}j2sI;^!FELdRiqV4m=T=GvwTPQ4N=c9@6&M?H^yX zqWgf-%B<|{M$R>h4l8h#q996(?bIdObbq84C(4sB<=}gPG?9P2G1d#;kHvp?`!*%b zP+L3>(X2&+pGpcEFETVs{|SVA^k1p5qhWi60=o4E`a%2>_Djz}pxM55HU-V7@olV8 zrJ}hMcol03g>o-IQ=H0IWY`Cm4ixh@Xhb_Y{$Lferkaz79#EoMhCdn7zt!E@C6Y1% zo%9&X=c9svrdMJ8PmN8vU^Y~(h##B#yVbZLDmL|>I(up^qR_-QX13GzDA^as-h*wU zBPj#Mem5L-QGB%_zi-_1F*ED1StUdGpuTS}%DS>$ae+UVUJTQVfFJ={{ zU3Y#Izg5Zh{yF;8!dZ2q?FTS7+T-W_tB1iu43Pf|ZNk@XAYW~- z;=;dWZKE89v=Jv{vw*J?Wrg|&rOs8SWeVDxM@@WG>8@V2;oZ(~{b^pMC&|xFjPFLK zy4pVWeb>2-mF4tZlDDZ1P)K4&7RW8cNhZ}9J>sH(AY*U{Nw}vJ_^_nVS{RTDIXZHG z@2^>d{~G}ZR30cab1lEIZdpWrmHepAM*+{|XT-#GkGzNDU9VyGOEaq*g zF`W}ez+BpvcZT7SO4L2>ZP@D(RV~AG&xKAx7>Yn>r6EZk&HRti|C)hzis`jI7R^)z)xpZeb40yui%OkE zyvgsza#esL?Q3am{Hl?^aZ(#B$(@B-BKAr1cz32%Rr2Dy(OX+peu4oR;P~AvTwI=3 zl7JW!uzJsuw;P8CE2eZD@}7fgd*Hr6^PYm~HvS^ckRL+D#sU{nikvkr44|rcvQ&$2 z{Te{we%(v_-NcI+F~KTuy^;1%N`QR6-@R?Gr%$#J6!4K%f&G!(+~Qp63XK4b{IR?`>yY&)0zdT^&G*x+ z%OtL>de=-i@BWWDl13hX%}j85{6U>)7g$V~E&TBKZNmm_WT~uM`+`Qto$N{$~2kR2jT` z3=Rm!dE;pFGPyhcVHh5AL&93F%;W8bvrfYlHIvJkkMrNh<~M-mj@FSF~xD2CaM`pNSg zHosebp=%Re!2=--PFYgYBzj{?DliLz!ddKDd-UIHZG?BW5Usff37MCWlw1qT4qP-d zKa(AxI_xAMW{v}O|{~*lc;0kVCJt z+hPF03s76_NpCF&e6eSqk5rhmkH{z&Ro70}e++1$5(Ej@j(lex4iVVE@1rf`JN0)bc z@jRLiTX5BD|9oKh(*Ako>io~SK}GC~9@(eaL|I>t-kf)6j4e@#ywL_j0Yy@3Uij79M$6iuE0Brb*m^&_4! z@Vd|O%(X-*INZXwE)hB%--0Ojc(zuRH&U$83kA}o%>oPGT&svEfw;7OjtGvghFE#K z9Cp}H=0ea8bETi^m3r1`2-k<+1i;~_ zlUG!kh=0x#z-Be%%Y#u!;?sg+KuxJuxqGXUYhL8i#8>&Ai^hf7=*6D(-_Rso8Pxk1 z)e&W&4)O>Te;T>>>Ri2OXOL2xfh9Fp;dgFa*$P>|Z>Dgb39phK)inE{%UHBOa15JJ z4)}^r0`%pTeCgDi(t?S{hmh0Y`LV}c6I9k0RU-Ds3;a%wCvhjh}bFBl_OJ0rY4+xeGIg>}X z(_HEfFxHES8mT;PsP&&|VVQH=L&fH&#^Cgg%s}HBJc7COZ;Z)!7jCs}E2pGj1&v=% zu52oYxptr3riz8>I<&Tisxj--JB)c4mb4JF5NNqpROMx<;nNJS!j!NHn|{)Q7*T`G z=ZieuUtg=M2WM2a*!kfv<@Tp%Gy&7Au`GeIQWVi#^?t1h5rg76`ASLDwo?1c4xbRV zhB~lK4n1$U^Pl3x+Fcvs#99Q~aEUhLk(9XK=hMC0MUL$to1Vt*8_nzDTpfuT45Nin zhqB7KvEJt*agZOdW5Weiv1t_lMNBeT00EO%IKr5wlEU*jwc%{HH{~wik za$9H3UmAw%@zJWB++ zbXuSroo}V2=PQ-O0Q~Lm-jvsOG1xX|+s3k#)xVN`O{Zs%ZmnJu9^fOsI$6Auz!I^= zW?qGnfI=+va;?#+3N@bi1snvw>J=cGA{^kY+FZVkS|v_;A`D!#Aju9wtjeQoRRdX$+JQ$^Z+Xi-DCmns3&EDu-S`sAY4D?B>)+U4>BW|Xl zC)Cz$Y#%y7pD93K1il=cWJuEjU@n){Yms-42dz4vDYQM8uO%3GP+o>A;L~9Gzw$SX zebT=bGi*Nk>Ba0ss;#mX&t(l!OtaYP4yEk@yJjLUxo3sYYKlw9PcHp=mfOx#nU8pp zE+wY3iJmqkiC9Wr`CA`LX+tKc1e()w+)1nYws2@>SSv7M8o--Ex1T@tmpE}(S5;M& z3AUp@+tWaKQdPyR@^Jd-!;n{VV>WSj?fuX`<0^fjo0XofQN9^XDFT`5z7^`pJpK&w zXN%8K_KPj}^XDO^NTY~K9`cx7D+RU_m6%~rPA{_8DZ^^6E}VdkDKDu&kq!Kxy}fl^ zz|qZ3JGrvecvK(PiyT8P1eBb#8jW0fS$H;AcHw~^h{ESJgd(2h{Cz(Yr@`U)RyRSE zjBNF}rx5z@Hkdm4wuFmIDP*=H&LK{H8fTrvk(|WOs!v3P4dyEGHaR~pslN=a@4*s~ zTLu!`V;-AE|B;J$<^QfL^BW&ol)2Iv*|)f~5`27DR*EEA5+St~%uYbiYTg zIb(Q-`R5-RI>mMQ9x61|UXsc{TR-kb0Jd3y`^RwmQI}fBA_sOGzS58@bm`ZD))*BU zYDjCuSNMWEd%v3l44aP$_8yFf+#7ItF+lB!ytzBHiZZQEV7Tgux=vw|FQ5 z{I)+;{FtLr(FOgqg}R=qbgwKIbc%h~dBepbptb?mwI`z21i#D#bVF!^L4v;WKPgDG z9{(=;uGcNpNL3iUeN!9k`4ProK~BruvJkT|z| zbdL8UD@$Jenyb%IxfNXg?X(1$5_WEWLfXIwB7e4YJHscz`Lq_oZbAyA@(3;Qio^Nq zyHJ>U<=hoB=JT|zru_WEpdmDEsq~}c)RUlC2T_0MND(!c~cwU?mk51i8{r9z*bY=Kd;Ey+%b|4Yb}) zk2wL}v%Ig5^_zAk0Kx&iD1dp&AVAM?aOBplP*#2zQCO+JD)t+pFxi&>;Jd(uxQLgh zE$N|K3QY{v4Z9LF-53}JySN7zCSp2V*LukGdq5YPw0Utc@N*;qkx>ymcd>&dLx@t>U)awRiNi@Y_&74Mg3bNQIhHN zzAeE+#^D7Bb5ioy-Zfe+DBI_y-We+S`cIx&m1&X4`t2r9BkUh!uRO`3?uR0I4Np13tc;_;N~yxxPL2%(N^U_cHLuBp*jtUbgG9h2YOkHFS^+96k( zYx1`*VE<^P>5GNiC9c2yLh{bx(`|YhdAN;KBBnN-sZarCqLAppC5CU#z`G|Umm7y( zwp3p6^rFB4|M70x9~_AGiwxvE{CnLFyR_$wlQTvdU4>p6O#>?Wy~=_-@MaEH*}FqM@h0ce$^KzkSr--e&C!=aIZRWF~kS8sPkz|sa}llHK(_?R;{%( zB=TMW-+?ej;VKnH#RlrvoKPZh<+qk81wMbjT4!8s0O-9fjr{c|i96kY z7=ICu+Tm#F9as~%4m%RXlW8;+&wod0fJj7}1O3wAF}fq0=A?weCEdo5Z-}_RKTO;W zx3BUe6Mo=dg-Iy*MkuSjUO@mEk2Zgh#a%RufWRk#z#Tu_c(XR=T@B? zJiPZFd)RZx6@cO3{-D1N^rW&1{;Z$Js}MD^X9X%?4Q^q3ekQog6~DzBBIym#}~ZzsVZRT58ZR3DKYLhO4{C{GEjl>kDnOd9P%t z9A=@3C{23clSnM02<8y*YS(`gcqvFd5PFszp=Ib6>i}d6N3uLv~e6Rqf$kcL@!}BN{rKo)PQv&H?K5r z(^5DnR-&ne6ilsBU$UX_r4GQrFd~H_D}mgE21PG2tV6m<820s#*^z&KdLf?VpDGIacKc;D>qmCYBDOSrGl5eLP1Fo;IqescbbFwF^_V0kf#YCMsnG62C~5>kW5|Ft-Jc_4LIF_heI{9`A`5#&=eTNo-9MX zo(t6k%TS+XtXcDtMHK|YfNrxO(l4{_d{(WV#iG79ot!iuNd zpQ<^a-?+aXlZ8=lR|m18agg-jVTZ#n$K{irSiuMO@E3TX`5(Z1B;;NWX5B;PJZ#6= z`9}v5H)GK&%TDq%WKbZ<-P(o&qna)u&p(5=NxXE+JnmzmjI9&d=tkPoQYD3kpEVU<=r~nOc+?MUfH;k~2 zh{=%2)wcfls*KOhA{X`|RRh{h01vOc8U4QUFQFndemA=mk8+EY4xr7qRkVm2r`~@Z zlP#Wsh%mP93J)OFpdT19od*mke&uK#;YZ0-cpgA-q?i-b(8b0QndzjZ=h4yY-x6e` z3=QQgI9U%!i^L-O`{h<;?l0LZ*8$__;0 z&r<((uihIGYVifnE4!oW(Yui)zD(N2Lc3TK$PuReg{PwDxTd8nQGhTIvTf1QN){ZC z#w<<=#TRl-@$z#$ZfWzIwwq-BdHRl7zJ`I-G*H~HI21zRRvM2UInPRDT0F}_-ZK*& zK;)kuAKX3cwoQk(V`Au<7m|I9D`N-Zn~Wll$vo-&5&v^L5*@~2M{yld>9UlX(*u_Y zPu1s2dOuFWA;Gk1!vzz&fG9Cj*hT(0;w>p~l+Mnqu{%#bAI|jx9j+wkm+Y17{LU#8 zV0pNsquTx1VxC$t@EDt}6jd~z{xBUaZ~wa#NLCsiETE)ri}N?k7HwynLh|wF&sAs7 z{l(^SYlqK0H;sQvY_ElU zQ%~sr{rhrkjBDG7p65-Q)_Upgd%6J?Da@c60^`9mv%T1{FM6kPEQyv02Ba%OJ-DBJ zG2Cf0jz-M$UkOf@+;I478AJFae--~4_jSXj#PKv=@@>7X5Oxr%a_;4Mv4jD1_hx5d zwli9G9q^>e(#U;(@DpKd7AY%c)5OZyR9PmzRQa8=M#qT~2QnTQm|Fvh0X$>fZ<9`9 zqDMd?oZM75D9=l1CaETLx16WOk26zjO<*r_9pAgVKC>dE#qZX7GhLU;Y~;ybcKKch z?&tu2T=+6w=5yeEIGbvxL3>AWh(qjq7JKlHVJ(CGvh`VpmbGX~{uBQf8K+Lb3Fm5e@qVjeW`h6z z_%A|9w4uNIKP|x90J95SJh}dded`xjiOX~YAf|hZ!NJTyNlZ9%sd9!eQ5D^982dp* zuv$r!R(gT1Vy#1MI58L>2vL>o25nNVIbc*3JfDM^%G$c(57I0WY@2eDUM>QS(;K8R ztdvt?gCIYVq}#&yZ`bKmPmr1C@4LicB9l{)BM#ErIL1r|W|gn@-Yz76TSRr=AL=En z7lLN$?Zl|5XZ*`tM!I5v*ZUnv8@7}c%t;{*$0=m*^z00PkgIessRzY*pq%0%a}LvA zu6>ju&>X!m+$RHVIu-z=CCPB-& zJT>`nf0unvux9X@WkSbdBa4y;ur;1>^gRMeW0sr8P?I?fk9_^1mR&ywi9jH##&g`>gHg z$sRcFjCw%2_I1x1unZ-Au<>eMDZO2O*GGPo3-SuKN!pF!ukir~N4CP;?oIW`Zm3$D_ob6*c>SbPcy{x4`s;^Zf&-zRbU;23_Di0WAueqAHJI+U#>S#y+5>IG9w@y0{q1yy`4N6%cv!C^j_*#=&v&F z&lP=0ZgdR3d6E?6L~WNUYQl= zDEUe;H~P<5%YBSm2HrSOILH0cFDlc<*3f|--U?IClJd^O!uKRp*fkrsn>r@6D7Bla zZ`aCbN7%;Niw8n$Wy#QMNzPuJAin;YFJm)MfVluBg4x-$Odb{Hxg@CrOu|VayLzQz zGW0yT5L98^CTBS^?R9HEU>n)f2Ic@QfzQUqQj4D&CxrN*7YY^x;~yIvqEAH_efl|N z{E5mZIMXs85UpMkiutJ{U`+N`#9mazBjF=H9mFFcLdTnTn6x}WL*1V0Z;Ags^O>Jg zzUJned&q9LWj)`=`^~H6dizCq0OE854g<}6znWR*^&Q&Z2Lq3NEIy0}J1*<9>d_O} z36bx48W79Ps{ZA=1~>r5?UPX@6Kblu)gGoexPjx_znJAIAI${9C3*)CR>b`rrddCK z8)xq#SrHu~3uOD+wAucC7v;lJ>-W*e>dj4ZeNFbjjIVz(E?uu$uPqgomCX}2$B=yq zGK61q7P)8;Ie$znEk$U>PAya1J$Lw;FSq~xb^pxugZ$3`kma5U)ZFCrgz4Ekzp&D* z+6(#&7GYeJf{Fa@y=FBb-Tc8}*Ki?FSmdZ4m7Fkj{hyzzFrl zRiW?abM*1*=A|7;GnX;@)Pkai{nvTqI|L*7e>Zr0we*DJHSw-=hwY_^%{^YaRJP|z z^38os+J{@|u4&S0Dy{cn&3~^yuDw>y;A1xK{VvN#rldf)wU9R!pC<)F{se;ftD(Jsti4ngZle%sbL; znPU}B)^elr;g@$_r&auu8`{K*yPy{Uq@7m{4sz+rd?BIcxl6?vDS+xX4^Kq*Onl<0 zzXRh%5naAU#VY2tLzM#i#z#UhMZLMC6H%ksa9-Pds5IC08?1ak!0ruW&Uut}lMCSe;L zHx6M{M$lg6&Sa0aV|I|=;?sGa3AUsN%HMm=jrdnQjK#mJsM&k`&}^?s^#gQq@Oe+; z(e~o6-H%!Lqo}F^s(OJonjTWR_@gGK9f9Nb7|L|&4c(1WD3!}#bn@0`b~g$Pen`=` znp0NHmy0RKekTFTetBaJ+G1)}z1ndY+05_yEEA-KGjJKtZNZ|8>ilUqGd#$O1dAHx zi(V!}qqDC#X#zIMp65G-`%|>P5?^M+>GE?bn>OI)q-iDx3#V24BGAOffMfG!JcezF zgA@<);AEtyya0&|wO&Rz4p~pQ?X;lsreW(j!QqiPHa6RCAw?Z`8-x87@s<$)<6yuw z#QSo?{88OZ1BSfjDLMWi66;;2aKq?gE)U|?zMGDC3x(USI-^;8R<4nr70ZlXaAKIa z@J>DKj~h%2x?k!_%q@M}+~n-R0>?mn7gIR=XnL^+!(UoX;nF+TFh2>wZ6$c8kv#+y z8OQ32Kbr<7z$h5snVj;7ymP=uA;8D`ds=4;xJ`_ja{Im>!UwOd;>u^BN_J*=KlHNA z<;ri4j2vejdEtO=^t<}%zp*Zord^{AwfKl+6$YKFHiZFH$2Mu&c1xlIvjDK#aU*+5 ziU5q;t9g378`q)6I%$$+W19yLX(|t$B;)1;q-f!|tj=xwshEQ*GQ zcfA!}8(+Sy;>omK;DBcRZieb^g$!h2==nZ}hXRg`vyKHcsWB7={fHcS8qc!jTsHAP z@br-maqIuC@_X~;>Fd6cd@o4}o|_ikjxN@R@?{iBHz@Dm%p0?+NmQgCb0$}oqXO!o zPW{f!g{{}+%P4s~Y&IHDG7pampj6xy9HEl%MHNM1Vf?r(D*I$}ZPbJN z!jY?{f`zG6YE7F!P?*;g7k5P5eT8b$QbQ3~1~742Q4qK%5rQ$s9I#yoeR)%--y=`p z6zD9hH)W72k}=pyzYl-V8O0g%=AJEORgRU<52`^m%oJy%j4;S?F5LHLuUgp4Auk=s z$XHI&P3Ss~^0xMqJuXYJUo^4_tMu)vU=*92sw)uoK>7nTi>0_F#BGqb2Ep8q`i>!l zQ9U7RB3{m9O5Bpyh;je5b}nYu3X7;q%oUyHaj2<{h{^nYj}z>IGlJSLvfXvq;(I(j zEVjlf3b+z?#^Po^Bu=l`JN(!vQP>s|=>Zz6YUpA=A`2aBS^OzoK$MBeVUVEa({G1R zA3=#@UyL87Er>DYZz$c#9P|9o-?UUp{iwkrEF~!FmQEQN=}Hr@*2`xK!(0Kp2?4u( zwv>f1#h}E!KRLeevGBJ6|8X-dbBLt(F5oHB{Yj1twZZ3L*hO%5_NZQCAcwER-q@S5 zZC&mbV@Of9AO^zm$tgl1dNA>4_m)uZK98H8JC!8js`Y(1gsP zKl_KxRLvlIpX!117|!JR#N;Ul%q4f|N|lXjPnk}pw@(jofA3t%>O_Vx`dxNBIp^v z{mgFxK}LWmu*+QbAqZBr)`dp>SGz#uP=0j%45WC=_G(n6)?!zeCub}3lNFPsglH}h zOaIA;%XJ&$lvTt$>0~HW^S_n?f7glB>#;VA(XI@Ud$>ue+BEXv|(QRdpmU)Xkgg;J* z)RME&)s79v+8^1}RdxwB9&~ehkV%IE-K^RK{rzih5GLPnJaiWYd3tW+=`JAjw)mm?lWRTyl;)#7o=u*>}Kfk$X#32_p z@aUea?wzZ)P)b07`~?1~-jdfRYD>5;z#zMnuf*X0J_s)=p6|!4s#DVIa{HCZMm`)aYl7^1y`OAC5-$6&asnx>DW zL=p+>h^JOMhNBEdL4+ET##2@3RT(j#RAdj`ydNfeHwD)E-m~{RTXPKyj0vod*_?PQ z{ln=VE1^|*`_eVK~Eh2WdFFlAY9Z>Y(s({P(avQ7LQrL=9jDgS>w zeFZ~QUDx)|B}kVj0@B@`k^@K%-Q6H5-3SVjLrV7y-637l(w%|`(v8%2@P6KJe!=W> z_E~%Fs}?>nCP9v}+SCz%(KhRJXpJ+br*GisSk_#VJW>SSiOx;+ox4t^{ESUGg*CmO zf=x2L{zVWI)ZMv&8$O)`RXmvLTxvfl=MSDfF>#H&~6 znlx!#UzQm$0g=}cFh&<^aox_o?=!w5FmRLph=)t94pGH}Y1KHeR?RBhD ziR-4fquLv6tJaX#vY3Yt0npX>X6~W1S8dUAIN~ZLN7-T>G%KoS9NsaGPLzE3PEKMmL7+tWmW~5Z?rlBFI zP3EaFh34?n?^Tm7hffcG``^*-T7U@#IHlHO29^}JW&rFJ8wO}Eys2-Q+g;zst$l$1ay4exfXf z9O7DE`V%C7I5P8gJ##q?`|#D$N04k?`VH*v`}`$^c`VtB6X&gIuv@X)@UXGMn`IiB zBEeyu@a&r9aI6ozv~I7nhFe%bQhe{l*43zo)jP0 zk9i2S>%bg9XwYVF6#dG|p;ot?=V5QAa0SqEgG>-{YdTf*fcQWF6_EABjOhnXzOF9E z7=!zrsB2C7L>aP~``au2_=?lzF6tv~07>!H5o>EUgt}>Zd>CpL*7oRW$V57P(QvT5 zF=*J9-s&^6So_h_1E6gAsU4t?%R8=VBi+JB-&OdDgas%!?=TB%Pr2dJE)X2EbXqIJ zv7Y+=F28`L*BT<;(t|yn%_03U92!!JQFt>*cG@!nnv+Eq*qbD}Gn$bFC=f*fYEd@X zCAJvpkVKlVacjgJLE>vjqx0hW!;_$M5TnXau z_zB1f-A3M2_v{W%WA{}E3Oi@&7ln1(AIXFzzW1qLfth2q1OfbLcYCF^uq#<<(1vO2 zhKfeOYKFY`73}owDY)8YcapX=0SIvBQ|uh7wS@3x#QcKc&YOz9)}(D3pMR{ap$6o+ zU${LBa?~hXwJTT0c6J0B`JCS|bTo$vJIoYJ?!DdtAsRroo9He6Fdn?IFdZ!klkAaC zvl0$HsMQwBJ^#{`ot#cvrrVubnqcEmI8pX8Oj}QGmwE@(+X2mYOp&z|&d(-=A8Dql zLSI-@>d;KWEJlj)_y5c-B(u)f$OKU1>%PW#_VJ4@@3knZS~R2Mjeqj?YKl>VBWXl& z^(THkT7kfayAx?M`x6ra!zDXA*$K|~{~>+{Y)S8mfnUa=7aw5q8U?;FV3az0R248q zk+)B7v6kO&YefMt6Lk8lU=l-A1khYEs&&VnlSll343NFBawups^f}pcSl?fur~iw^}+f%eS*Haatg-4?Kb0 zh5}3s(h3D?28+4Aa&7D+GF5E@wu!%`BKg3(?OMOalG9#1$SHw+#9kVsa%XYrxOMh< zD>p^eb9 zUrHr(f_7BUbzMby=O!j<>%y!`kO?ER{?LBr93XAg@q1k^TQ{_^Iz4UF=%%A1!L@J= z@FjYi{uD`=NH6DpM7N(=2VOdVf2*v>eQ9u2#u2kzgDExv%l6GDIITMnJlb*HAr%If z=ED<`get(9*d@$1=+e2y*Hw_v+R(GZR7}u}f}6tO_St;|rwOV4GxPW}>GuNP7Iyic zK`^(-euj(w!J`FzDXXFhx4znT1QE+6xPh|A7XoWXN{>RuSE}MfAORaqHUoAQrPww< zK~-#DhO-i|v?_znxt$11c=h_wNK!hqfZIhE?E(IBgin2C17RZ`z*pK8f6F0zvz31oZ39ShZPWwhSdK z-?s2f(SoVku$2X#h}$@=bpWY4m`qZ{QiL;I7F8e6M6IAYur zzqEmxTy}+)uC9*0;A=vAakr?YVeS_jlocL4NOztIFvX8^T)Rv>rsEzn5Xf}Rp8LBP zt^3KeJh!YDUg947qMaP(plJn()Y<@DQ|90_C7_kE3UzOA#RQ3$D!FLN_cu6>X(U5m z7krG1zVp+VRQOJ8S?pRX@x3_0FCG_*=+bI0+ML>qC?K4#6VWSH6H0*)L=owtvuPUQ zhN+5!R3(7+17-5TkD2JviZ3))9{;+{I^xml>Xuj~(z5GOju)qu6`qL;Lgv6gFhOED zch1_mvn;%B$vqY@4YN{c4q_iHv2CB9MK!541?7aflQiso@D&bnxDlVCs)$g=`69#0 z`1$^WR#)~}B-v>-8B7(l4* zY@1Ui(BfTh`0j_Q)V`S!;}N6uKkrHB)vZLZQ!weV>jnCR?{7N`6;rlyF|YsO+8>q| z$GI+}9EIxKvi{`A6i*}eOUz)g5D9RXIMc3B5mQ=?hBsu zR2X0{T`di-+Pyag;~e-8`anLzN7Re`;?1d}0)fKZPTq=$-K3YOO0*xI7oUi)O4jD7ClPrPkbcGbL*Jf)=olv9 zpbiAQDC_QT-MK)Y!?aG~4Hg|w`)DRV+mGOzn-=pvxNF$q;k$%j#a5N%pSsvCr)iW{ z;dRz-difc7OM(&@0pp*FUU<}vw8RQ$@>-yHMYjZqJ51nyt`9vU!*|x(z1^QVs5y&J zbwX&7SAw;FU(Kfi>G!WY0rMjwBdtOksGBVv6ge-r(vi1*;HrdPbrd~4S2tm(-k!2C zy4o%|L82oW5+A4l=uY-vnrgJ1{W|pP3)ygJz_(>7Iw4!WX2L8-6X6<;(xm)FLbe0q+jOq`TC)w#~II7TR2d9@Z zg(vhzRAK1e=W*b4Zo)g1jzy;^0L8Wh)??<{Q9eeL+6QCwP6Sk!$42#hTS%|qpPRQ= zNS4wu%_vK3VIL$vY;tAM;ku+_sccbhdVl5=IrNhBmm~g69}`0sZ_jC4*zaey-+V}S z*)4%P+2dW&_EJ$%qu;*qR;%)Rfb+dL=-B6KW8;OfN1$SUu9Nq;*@$WXyYwQ+Hh>Q@ zVi-K0+ZM$|*mv6ND;pk*u43GcMBbX#szS`6!{tdWPM;G0PrQRolo8!#N%T#qOwlrk zRtAz>O@fYhG*x1$pjXgc+v=jS!Hi5$O1SDrAmL=kPSl5pkI~OgDM3Q61vT03 z?EUX>Lb4#f0s2cvA0zW*K3$Vz*#~)#sky!@vLym9vdt7XF*4SI+fA@H#WZ}s)+;tw znJk5yZ9pJPGhCD4n46rMtUsbjuwABLhG)^tR|JL!f5U0UY1Xb z%C`au;Gnv0ZpHL@jieQFc;;1sgTrUTx4`X~hh~(tN@^w=LdT8tY&akCYk#2@_#%JG z+sr@^N-VNZ_NxxRXx-G8x^j2l&;c1H+Z5shI$HzoXP3{nf|Kjv+m8;gGPB%aZJSOp%iV zXWxDK{*};x=am7&hy#qb0D|pP(Hg~X<dWYy7Tv|)0)80y+dmcg&b6>amihGJ!~D`FJz3L?dQZ^kuQn~3DJqGApp{Y zyFT^+qgUlzS($yn9JX0>=b_%-FcIW}DO+y_3OPnm8`8(UdKBB`D6IgaeA@rh0$7sW z9^hJU{){GTz@FOYk4C1NobIZ8VL!@|sF2%e)~JoG4l1b`uldUm!~c_*1_3J%!1v=! z-!MQgsjV?vzkByLta#n{FgP|g8}6x}vlV*%%)%FlsTLAE+JYN58LKLQ={n=13a^M6 zvxxXUTl-q6Fl#G@Tr~`UjqliSKxava-$|UCSt6I{g`68o6x?w?i-Wg_i5I$IB{6tA z?+UkHv1WTDA#xaYG)u}??(k+je;I_Z6-2Rvr*|VS*O#WHZPsm2{Y@1N4 z`8&P=+Ubez;t;~X+qODv?mqA{5|z+~`T=BO+owLGC`5@~Kw&Ao$J%u~RSHVkT3Dri zT~gSBY!mRxetwc_Q|KFs(b@99jvP@5O33UjU@y2SkayDlP|qXx>P@N zu87W|VZR-j?CVK!d=a6BWPWjy{jl5Oe_PP?%L6A}Cyt%uUUgLdEi?-{e12X$HI@BJ z=p0O~X4_K=Z2RPocHzd>)k5v;z`Ts=CMG$}sE-}D>C4_HK$m>w*36LyKCW>@O0`td zbjA?E&|Md);OaCvUD!_qrWqV(mcOB%hl`o8n?qPZ=Whz+7wyvT!?iyR{-)k>i+;&! zv}Kf;IP*Cn53}>$uO0T1c^RF1+lKL^{uTuy#ig-PKTQBu`=O7++-W|i|4rwEXM{RP zC6gX=+K|asFO^)Wx5q`zFAnZmT4XCk9jQqr%3Lh>s)QP;ufr|q#et{4rs#{oD`M0o zfh#}BZ^$ao>}2~JxEl@_%fGI<%=3H%PFhA)SBmF-4~!J>03nnt9l zzKdwfDRLQ@9>c?+1#6G+$wsLHJzm*iW!@e(@dDkaDI+BzagD+A@*vTDoi;8kwa9qaV znDM?ZX?deaa&OzG0UMs&oCFUl%)he3qQBP%-3~a!?az#--~tei7tb7!djJ=b*A3jHNgM z?Q4@`KkPJamTTB5HmxA8!Dcb=5}!#$J~!}^gH!Yaw~q%;HWHN`)is`oqV}*Eh)r`4 zGzUC7XCJk5t4@Mp=sgU}PinU#s@G|LXrtxTgAfmp5lmrCFb>{phDV0L%BDv#;|2)G2^p;x*bCkuQE( zr-)-p26kVucH^Dv&o^_+nET!`9o&RbcJlD=VReR+2KFhI2lXs!NE@%N>I{$5bs{VP zjEja4^_R7kk+!@E8=H68=q>UD`{)4^ zqk^+z@B#ae$9`(PH}__h_VdKSu)s?uPm!gXzZ=sap~(KNNs|>u-FuSPFp(5>VrHZ< zVkrgx=$?A6oZEN%h*aI8qO_;<)Z}AE54|~gYd1-fGF>a)+i#1Xz{{Ba#K{KcI9JCx zmkkuWGOf1?@PrXAy8A5ui0ZiUk9CGn+;R?%t1YyiKM_Y|%zA_Gj)!Zl%TSGoRe|cf zJU8n(UYzE@8x8$r-I_rxKWLLjW!#CDKQuNw?~z9a4-fa=`J+TfgORW23XC}ar-A0> zi-N(2tZD(VLUu`rHreYSn+iK)s=E5`%`~sY;8)GM)IjfaJA#|v=4xFDVkw#`88H&A zI*8TMdNuEPOg+SuHC41A)P|R(uE3$Ab3M-a{&NM%xZ8s*8~=cy)VYld;vNRrH(0Fy zrOY;+9{~e~b@qF`*v|ngDhx!~*>b2v_kA8e>7S@}n>~4`LyE?Tz-GFlJAz>t3r|$t z(7a~|?v-daGSz*A+HB<;j|t3JhG)+xYljS*Kqkj0l!$?IoLcuc!kt}#F1P%~Sr2P= zKfchg6=eM}yFU+#SslH3-@kgcmTA^iyE0mBK49nV2)D%@Y8neui7W2cD*zj`UY-Ep zTTL?7voBgR^PAq6h46(Vm(5-bZ}cbnNu=O)eQCmRw3Y%*Kp7hfI_OxFskU#}l;<_1 zMw{W>r}Bppbee~0tR~tCoQ&{SftD8+=P?a@y{5I#iuLt&h7Xm+_;+fl7`RVL@6g{t z(0b|ANe59urg<)gfQm8rx7MKzqYd{HuuHByjJM*s?FtH5squV)ig{D!k<>jiBZlC> zJF2_nS)|09ML)jSpou>(XRF%+lalH$JLMi1CV4LQ(9QsRto8!tr;Rc5u`?tD7c{ zYqjxa$&yNzjly}rzO44ioL)-1S&qW>Cmw+`BK1WXg8h>>->yZ&(_HHanNnw>8iCN1 z0oi6qQW&4cKPtwC`dGi2!nJva+r{#9w#S>lDoVXW*zNGkuRUyeYuPspUPg7D&8?_X zRWm$CjLJzcxx;Q0J|R1t=O1@F4smD^eg|CkWNlx8Mi8gM01%na&ZWIyKy*%~1Lyr8 zZGdGl)_W~$PWwJdJ=YRwA7ydf9e*jjte3}5&3bV6`8x$rj*PZtA^8xGuBkU#tvfzp z$qbCNCUx0*N5RL1f`;PZac%X}BU5jpi9U+Q=3q@cRO z*tNA6cF_GiL@|EAj%W};Ir-NgcAReRU`+Lk<{Km=u4Xo?g5q|T^>(&As9Qn}gLFh$ z%F`tv?o1`US0^g#Pb&++=oP#IhdS>8z;jR>x?)PiK<%3<%eqjyH`eCxb3<{0NMNOIJm9vX|0~6|7j#Rf!c=NY3|1Kkp;Twqx2A<;n zLQ<+2y@zAbf6JYY2HA#(G)n0&9X2%V8aM^euK&^_lh<$>C%ZQ9FChB~IM0$(@VY(w zB8^RRTJcq-(i!+NtML#u+V1NSFzdu)P8Lwg6aRtVU zMkg%=8gA23J!#dN*WBB3f9GrJ!Il}aN(7C*&GJYG;JLTRm zAMn$*@E^O> zCKXPW;Ld@<*`tWxExE=tnoAi$&9&B7!1h$e6u9a8Y<+vSPV1@))(nr=Sm>^}jy$`K zMv!mR)yfzUEB$u_$!f5J!OS3}B0&=%k=EDK5=8>i25miSH0kBB=W|YqGt)W*cMec# zIsPqBh=w-Vw0x_fzL)vOk_3^7bb5cg2-0VOw!mftVsdSHsP~vurWSnQiazA<2mn|T zsdcVa{C#rreg*=V9R?xLvIh;BC%IEPTs8iFo2sX>?Lj6tn0_&wjKWrwuTuV7ReOH zEbXx5&n!DX?tOTMw4;15UR*Q^3M zxoxhvfVMwgJ~Hsgammwqswiwq`wvvR7Yp%JcP#R4Son<)#x8TxgZF9bnOrn02cI&d z-&PWb#+T%f*tDmf3#di5LV!{lFiY*RT7!Xb3ShfVDz#he9KonDkrX#?UW_4XGpqpA z7k>u)W29D8#$Q0bmlc?jlW~TLq@~-B$VQ4{r%IPG+V2Y-sXAMVe{1B6r|cL@Z%yqv zUivh5_DlNPn@N?y+5vFTm7o^VdrKC3cf+^lJ;J-aQwHA<8VUVCvf z`-rie>D{`x(~N$}ls)=awEk@4EpP@`+a`)2cZz4v1YUClU8rPx8n&W#23(dEA0yrl z5`Y|hS~%8~t4j0`vH$^Ib%t3s%YMtE(vz+Y(Ef)ev6ctTx6J^S0(AuwmyzPj5iUOJ zSZ{7DC4!oi>Y0mp@@J-~nOL;-q}(5d2VPVyu5%lvfD!vh-UBoZdD&cKVdOi>U%p=U*P2@qG87jarTK-!dMG8Mza0K{|4OO&huZ`u}FO;<* zCXSINl@y+0e!r#R6o-yWbTLi4#yX&?hux{w8*k9cg2TjAX6E=K3P|S#KVs)t=4Ni| zs*4BUMSZXyPx$T3bk<_L`a`d6vpDk=@^^Xx9yn zBz(>R&nz&BBJ-42KD;-8)5co;?^C2@)Ye0Y9M%UoC80}$%C8w=`|IB(qM?MqVdZoa zl=bHXwd@Yy&%Rj;lPlZP7|*ACwl;Tm6ncSBKSV+_{684lKQ{pZ6q+_%0#fMcdvJp4>rky z!>p)n3f*yfvUGbxY>@S*Vto3%sLvl15$WmZ3Mgkfsw66n>c_G?7VqW5@F0k{ResmC zV>(?EOf!&!T9*1XPd!0o#getWsEAsQwcv(^_*ik&xDV&wy*-nw8$Oe$>Db5OU?Xt& z_-2y)s9~o^YxmjA!Z%UguA*(18k~t%N}MAjX&lzcj1y}b8L)P z@e!iV2Rc4rh`e~FS39wY_i69_aqYO6oA~s9g`<>Y0$Aqp(=u0->((|BWx2GnfU~$+ zbS{>=;V+xEtOTf=;DACei_{&8qr=OU#lq6*j9GOdUaaWDJ; z80CGNTXYe}ew3ekC?sSu^ZLV3FFI|o6Cld}A-3}qHl3)!@u~u*NtRPb`1;!r$a&{1 zs}V~R@sLQGE@d#uL6&WT8?eL#R|fvzWD!RI3DmgDy@FwMS%C|U(^^?v*_vS-7DsDn z$Jd7|3*DNsKCxxy1E9#+BlCs*hH#s8WR z5LBKy>1X-S!JVO8_f=1u)UHu~O_-+d;1LKBka&0uBcacqPLNluS+kgsB&aTF14L^p zrJdgM8%%NXtald5C}lvbnW%3ZKO#&?I_+o-=%%i_Uz()3&Ug!2kli|FzfGmY13-2~ zgzn;JKaNZ=B}A|J(9O96kGsA%ZmF#U4hlf8!4%scV^KuykQdPNTch1x%e&*vFH)rA zR8Dd3ZH2>qUC{kgSDZKrPeM#}Ys+zV!3~<2a&!CHe+w!q?qeJkRF7iQwBt2a#4l@6 zb!dGvgJRfI@?SraD`kt4(&*FEaIg0oC=o@6%{V3vCS?_>dL-r$E!SM83^wU=BH0vM{L5&LST#dGw&rUo#nCA}z5NJd1i z8m|!<1{KDG$muojhC&0sy|^Ce>xYq7z+AbvqdvmT9J($76s%wgqhdCsNXgJQ7U}AZ zg|1D4yhNti6qJ-+;z?ZnlcHbi-M&ooM*mmPL`n_x5U#UKOZ;t7vNAhfAv)a9j1Q&v)N{2SKIZLMCMoo5jS$9st4T z!EW6&{`UhI^=GCe%JNf@7$A!vVPFl_0&VB4Gc>KSLrug;VVJ4--h1B)Y-xY;qWb#{ zcfXjCZt1d;0=ing4JmhL^xYN{!db2fIDi4s1ndv`U!8mLl3kYqy>-#c(f23V-!n|8|R=;)wTtQ^uB8E_bb#Rh9Bo<2kVJ`8) z6m5s$+#vc_v7K$va%AUpjw$dJ>^*!HcsixC=xe`^5KKDC2{xi5H_xSIgYX&3wiYX-&RrnshV4d$)Odq<|f+Rt4|6iXD1}( z(%a5SM*e$Y5Q|$SG%yc8)$tBfFtJHb5%Bo0Gy#@n(YcgLmZhG{$6#^6^O;Ad_1kfF zyy91)>Hfzc!0i4(242RUY+MIKVR*~J3-F-2{jyutKEShadVN<8bzRCH23I-ow2{mHHc9zckHj>o z%kQG0i#M&sYQ7aIeaccevp;m8M1WXW|J8%&9Qs$`f$>7skdMBF901EiyNzrm;+Ag;8 zmVb>@6ifMP{yB(hPiP&0VcSLL3SDEq`>DS*hdBK^-b8&XZZC$Pj}wE{ekHYo8*=ge z2^LmzlG-tfF19lL;&q??EF{uqFT7aA9gMi(T(vyscIh(lerJ02Po=*{2D*;F`!?7> zUBUwb2s|&`!%HlKV)}8$J_?A-F%ohU4d1XovrJ=zx~5n@3yst;e6z(+*p-L*9{GNj z<$WpJ%iV;?oEFr-Xp5KxlGRp)uM-CajIn^qw(|U97xJ{bW0ZJo0b2QU5hE+f?}eLI zJf8|->Gntel(@ENON`PzsbD;yURH0*H4&X{o?&Ga6-GBjWdfD(PEck?x0Mw9%RuU=lL-Ly9?YEW-Ui6fJ0$1gEA zd($6&gG|(phySGz(FM>JI!dV#xlmdyI3+bFg)wC?4P?@**UH!%SV7+iY_hH3eu8h5 zEXB_}gY?g!D%{MViedq6zI~d_B-oIx>b*~e{=gTqtD`A1c5{c-eSgt>6UWv4fF|T+ zMARVKs}d3|MlXWSL&cP6X|rF)8|dO@sPlT?{%WCdw0JoeX=HuBkdIZIz-|g;S!!^! zouZpND^#ObOiz|=*OC(H2Y(E@>gC4)+J2ii_*b6@)Gbc{=jqNT73S<# z*KKwjO3zr$cSm<3L(`CS;{IoD7K|yoySBD$3`}ER)1)QHt2i0SBsCQZ)t`(2a`y76 z!$IeBlO2KASKDggjbeVxP_RO7^Y?;|m!@+xB z?|N-j$iLNl*jr#_A^#;IZctJ2VrP@O8APOli9E_aHBe0$+ys%Cz_a^7Tr*^YMJ7zk z-bHQ9Ce!5bzGPv?3w8eHcw@G;-RqPOiQT#uNTX`aP5oTlss8>IJusxp+ET{9us>#g z5$aH=WWD3ZwYz!>0-lr3;P|vn2&cVgo^qkON1DQPeEQ21nz)th`|^%6{nL`?rQ%=C zVl+?|0LK??4D!0S6MRcHSVHI&m1blbmW-(St5HtYhB1jtqn_%L-wdLO;xyQC`ibHx zo&vZol?a`u0wUS7R&>uX^d4G?_(H;x}xk27} z7MAW*aR5&cFWsy_o7z; zQ=@;2RbDvuvz3VG(U$ZlYqJlLXSXPRbuCr4sUx>BtdC&O*39)wA&j;@*hu!ZbdSdO zLR}uAPn`Jj4fw|m#Ia?8e>LxzM>I#jWT-Pzl8-BumN+BlWg&*rGyIqdOs|)wt)-l1 zf5>@ir<7@>ETv-n%Y#XtvO-cIFLThUjRqOeq#jbq4^wYAR?Jq^xAk#3d z%zF9rHO$H$k#W;(S=N0ooyUFMqvfyHn8PL^iWy(7>gvi>t zv0@cDv3tUxZ%zimC}UIk`OjNhs%k=@L^r!!QGU$%EYdybj@abM;nsPU2DZ~E*bo41 zp?-dI3`{ByYy_uW=98}1`Geij>Nt^? zP$kDN4chMUI9i`zKRSYg47Uoa%NIpO$w5j1;w%5B1;E0>YVsVtz&HL{IC9@)L;7)X zahb+n!s`8mDB?O!;Soy33G0U`o@~NO5<%~iyxUy*rw>(2efF@FcA^EA774@>ovm2| zVRJ#ok18EmWTPfIHpjqI*?aW5*G;<5_VEcW?GV2R?HO7Oc_g4*)5WJ) zp$y&)C0NGtZwiCeIp^6Qp3aLD@!!1rS^y8U9+2X4_D1LDcq_VWD$ z1Axl(xxXpK>pFbQpP{&V7|?Uc^u1jANYL`M(cPRmEUrd z2dK%Oha-NMX}+a}U&h5=pxz}#FRdqiUi<2o`@!~gV)e*rjc)<|Gk{apX1G|vr2_0V zBRs&3s5ygwdnfO-vtfty52Kcv+|trG(c?i+G*wtd%lQ15nITaGz)QW92Mom*VFec) zQbqh{f{8L(rmrNn&)pr zDS0#1SVj@qYpw=^w#Daf7)IyE**#G!jWUgN@oG=VbM!Ju(@=^q7W!{ks7~E-$vBn6 zvfv--GshJX;IF`dMqu$2O`t>Pfjuy3(k*&0zfVa;Me!mC$iAz*#3?NmwE{9A_ulvB zev9`i0xk`JPyie{DnqJfxy)H6URCtyF66;d*upeJEAvx%3i?yG-CQ|ZyVSkz-F2B2yWR1#IwIIRv}}6 z9C}7Z1b$|WFmngUG<=NX*jQz}|LCLM3~_soWs6rD&G8o9QUC%VfhN{?9ac0TT44IZ z0z*Wc!-MKuN#0`^qCo7~UG@h*zK6rddoOytakBTtrdvjdG3_3*o=+0$%TvP8h>cQt zCh_Nj!H|po$RFyFc10rIEYEo;vz(;|mw3Gx4(#o3^@Bg&^pim1hwpn2egMJYE55jI zVE?+~i89`>fb`VVph+P;S|~VE#G4D4%gmL=yIqc0FhgEGtES+(9=g9Hdh4_dG^J>A+sW$A{?}Rt9gpvNngH(KoACO=c;C;$HIiHP zwfYaj4MGK7k&4&c^`5H3pdC`?8(EQ>vXvq-T$r7O8bl#(sMN<3$9+k*k*H1T9}W>y z^tv3Rq@+~hulXhc2-`~oP@{t1zc+Ww3E>3Ny6j&fj2#MC-qE0K1q7$JM)@J!a$b|5 z8=|es*=8$Hx;0GkP%hH4ahe5_y1-M7RHe+W&1uC@jMn{-o8EFXZcrlp_C9CdB4OOm zCuTUTqNv_{gd*E!2}>`n0R9YbTH`vgNvHk_ltT;gjs2Yv_hj}orT%g_=-c(?^#CRR zC)3FAh;LFb#?#_9avs-CJBR(gv9ZGsG7v+Pj;`ePZPV~&9cz~Q2R1LgS?s41eJ@r+ z-ptIb`;1VBcp=c@@zCCtHpipir&llth<|w51Bx5oMnzAfl~$L5QA-lRD(?ewIEBD- zm1uFTE|LLGF&nz5qz17IPNas8j-d~Em@$h*Os;X5D2g-aX#D>nQKR8Y`r#P*2)L_u zK0b@0S5+*p1Rm|o-qAeIdPFfhbX9<}TqAX(3F@NZn26^7iMjNQ6K~wMkNdSvyk9OU`Nn;d(bSl~|T@V4@5NMCaNYzx!d$ zJ9F^H)Nij6pU5ylVaK9?d`4WD<d=+yh92G2yaP%3hSlP=_)e>fihOi4RV zCj}|UBw(BQCXK8N;tX*T{gq?tt~V>S9+QMh2#LQf65bAg`sw`l@z@}56Jr#qmjZ@| z^2}dafxVWt9F?8258nn>xfeal7G-J#3&g|M6t}Z#x6_gYFthNAzP3 zIouyub8&iL>+4b1kI{Lq}0ggk2dkpZvC$Wd?yNUeDCb>>0N$+3Ua@zUNAdb{E(9@6(_o z9%8}|gE!CY?~k+|J#?H-v3}Io8x2u;-;k!-SiMKn&ru&y>hWFFNV*U?RRzS>yWwIiEPbSwNDtF5IW&K;|V|JU@^DjSJjzl|(eSLz+@H;^{ z=t1miAX_l5Jb1RACZdjIV9beByN`(KuJ**kafUVJ&moQPk<)<_ zWOJ1Dm(z-YFq^n%bAzAdFQ*ad2Kgz>w*(0$;3RZ0$&lAk{2ZWP6V{Ic+@i(fyNA2p zS3w;rxvHWa0ZQhmpao;Uj*?|K0bYYgN4IUfoq` z`nEv@o*rKW^c6dwzYo{fv>u<8!*I(V6p0^MX|fPram)@kqnvYck77MOI)vHq z4j+i_l~Ikn`8X3Vu3W1n_&dH+)TtSa9!a&(AD#EM;u!(K5u>++Sz@kHBwx~0u?qi` zN&QV2jAOThLyE|+t{~;1IE5~!AsXSsLH!&MidFb*c$4uXBSBL+1gAy%G=Ps;38G!I zAUQ>71*bQ!rbm$X&}NOVuvoFf{S6qqUKTC0H5fAb>dR6A6V86Z9x0XbUTfZzYIene zWq<|YN>8KX;qwGf21b4Sc!l%)NYv-N@6VjGlT+=C@v+jEpFblHO!`I4^#vM0_ak4S zlio47<$7be7mU`;gR@MM3u71kL>0`@F)x>u4w;smu9=D7YpUf;@N}8bx(43gBkg?x zN9KI@IJduE>hyhtDnAZ>uv6HKAtfhQU(ILIlu;2J(U3c<(*joHyy_*MO;VFYI^?0v z0M;I28#P_(lt?&R>bPH;9Z_;v;`8umRlAH4Se%$}Bz;cW`sd79Wq2wO0@ozGqCpRN zjZVF(Nr;ckA@a>@>Lc>nMzfLC^7^F)hcpzz&OK{VymFY;AEk9aVk7M})0){j9shi^ zQ47O86gt^#WV_)*+CRV!ETrHsOj)UR8wR|Lj>|>+(;0InsL=aOX+tOT>YIH{969Wt zQ-OB(2ilW+m>?od$nj)?824FPqp`O>%bz1WCT$`Q!Tn)tf;DYfqgf_AB+ZB}FQgxtG`A5n-?MlkHQ<(C_QcTybHxyp?~Rc-JuX~b-Ng&B za>cc?5$ldxw7Rv z)7aAGnBN2Nw*xO0cr7729sAGNHM@%c?k)EUVig**{q@z1hm{PQ8jEF^(6dO~dr38F zd4u0<^wH541JN!m?lX}iCiGRAXSDsAj~VDweLufjL}Sh*&Td}GMxGl7mBPZMh)Om8 zeMKS-0*`8sZEL>3@W|HUVx<^ZnZ6_4#2%W+71{{y%nHBBTF||H-WlAUaWpwTg2?}D`kwRfSL2D_>=^SZWtyHe za~dIcaQc_^fvgPUJ7qt8wK9uxSokaxnkatLK$TT9t9u(L6!LPx;sO#Y$QlPB@FhsVV=rm)bF53egdzOz=|b-VyZeLY?M$f-Tx7~R zMJBbvYO94=d>32>y}}%n&@Bgd9|eR=NCwg*MCazSM;vN-}diDT&>{&4!FQF1TV>sV|ni6q=k?pW9Q(|LxL z3dygB9Ue}f*9kcg%`$6w&RoFhJLsJQM=Kam(b-uCh3s$I_I=m`7REe8QPE8vNrVs> zq#~TkC+lJQ%?3dirFJ42i+#1sXG;aAKh?e^ z+2h`ws$w5_bBN^Ie}9oBF+eeW{7Yp2^K#EnRZ~+=UAcz;OpzoJdU`~07n2TVd|FmJ z#(HTnPSZd}+F0O1^Imk;OJlDz*3gsb1Vk3Stjs?HUtVH;h;{#0UO*MLutcZw z1WH7mnuEP>@1WFKGR=b~jiw?Py;fF-A}7c}%^&V^ZE{^{jMACvm?U}1A!Duy)tS|# zL9sOpJRIdHAbo00$(DO%-EuoqQv^`>!&40n`QZ0`C-7 zLUWmeJm&hN*Gf*<5-T#y;;5-)$AtA$SXrn@RZEcw@@_`0^P0kEdLAvyo@*#9!+-1| z_TYS+MjeCcA;40VW=BkY{#to?!8!sZ4Atlp2CLd+M!T+COdr}AV|eohuNSfu@0vUMqlY}9e7s{ONjA6F0JVcMDZSXphLz5ieVZfD{79YJc(u2i%uBD(Ac~-m5bwrsODb?&3 z8x5*S%-I6!vaAb6*^6%<$w1_;e(V?yUH8(pMoR``&J3Alvzu0Q zyiAR^E=@1Sw^vpDff@kCNLM&OWd>XpNTY|jdZG#YLd@coyJ*zI(^zZ zl3t3?1pi$s7&gsrbrhUs5@avZfy;iYgZ=6S4O7=Kfu4uw+x^jcT6!yY+M6G3P4n3M zx(3KDt;J{$X_Dc~BT78xL9J$-awUj>>9Y0cdI@$;Ig|#IFQoqW+DpDLNrl)Xx-z%9 zwUP8kEX0pDGij-Y+SGTRW!(tB|5{+qW%i>bb*~e(3Yx~bo?Ae+OP)y0(Ixl)nEL9l zsJid_A(axO6_Ah|8tDc>N+f6K?vxr*Lg^4BhHj*0Xr!g2q#L9W>F$#FU47s8^Zh*! z&%=Lk?>*=2z1G@m?_)-&tKK}K*PK2C8~z4M$>8Gn_6zrRWC!^fE<=$A#!xPB4`c{y-Ba7>sTU0p`*8U10xNO5o?4hO9i-^%}IX-F76bnWFmI^_dnWBofM(i}U(n zA@|_njX$B1`^k;b##91?ePiS5Y$>9lY@{iLyKUe}=E2GhXd|K>L27AbMG_t{J0;68{iJ05 zCr`T7`l$W#37&XfP>nR@G1j*K2_Sci;cul8bQWmV9}^nnFdp;)R%w zRjDH9vDgx0<+4p_9L3by3K)3lVu);yF3e{shU~YPW}N@7@RuZ$-z)f&B(kH5=9pQ% zmZgQ6+dBI5uwR$~1_F+3ZtmjsFxLA~Ijwo0nuxzFq!G_7>G#L)pz(AZ03Jw_pejQW z?*1a(57x{zLFkVe78DQk4}vQlyA!>j9F^)oKOn;srM8Eg9~E668N*M65t@%y<{3|B zh|O@e`=(sGh6<8d#&4;akO4s6!3diM1Cl{2TU%Qvr;74&m1piA z9`{w>+9q~)Z_TS%Q%VXhW@CbbXW;M(iA&C}htgJsI~<-8_gBMfp=YbIKRU` zs`oNiI1AMJ6>YfNa45EObiWH++#2~jD41jc8Pkf7q#1m1krFSydjCGZFf(K;XQ=N%YZgz`ZDP$*)k>6@Nh+fm>-*LcigsYbME6{Dn^Hxcr4^+241lVm ze9h;^Yj52-E(A(hzv7P|fU5ERb@{!wt*xTLW0MuCBbh3v4U`WfI!fghFVr6IU;#m} zwwo*aR;`|~%;5LtN>?OMf6dA=+T1(4v@4T-`xa3raMr8h=Q39d3~h5?YCX7>*tRtN za9~kZ_4!$MOUI?*kneLaC?Isc#nS4RWQ>o;gUHIgfn763G(EHjPFWjT?H3KQWq5}o zUx)nBp7E7Dvs|pLzA!#my)n71g2Cv~#LeqlsC<$e2KFF_#7<3~L)2E5(v9)U!k3(0 zhEGs08}98qmjiZmYpSbHR=Q5cu50Pz!&iJ}Uu!mJGi<)0HmOh#v1ssyy>sW6m-@l0 zU9P?Ea3)Y-wW;!F-->CLasj#_b9`kb_b?N@6yo9xH!F?s!*#M*HY$29z)Ix<5Z7wG zT73%2cRmM;FYN4+UZm(X%$Mr#_iFC~KUbbNo^;M%^2{cxFwrO;>~s}bh*8JjgoA-p zTLAG*9=>l)84#$Nf$~A9gj`l@rVVjM5T{Gze~AEr%u6BH^^Y&C7B5dE?oR;T30%2U zjBF+tgfgl4DV&gRZaaQGuY?XKru*Iwk1m z_T*6wpO$JFX=78~l?Fa&%0qLK<@ZdvitlQDFqk&q*nuiE2B|Y)9-FjAvyTZZ z@Dh#vWOO60KtrTE$?4J{VQBOgu8OhzJ@z>O=uX&>y4u=;9{ZFwkbgc33hykX|M~#M z()E-;uw#DNNp4}GUVcji@wHTCjvNOyv`6xt^1KV1PuLW$tF{An3s54$5&6pV;yksM4u| z$0+|;H2@jIuHfGtpyV_FrG>FNGqpqiaNFD10&ObGN@Uam)dfA_D8^S zIR!p)3O9+g^ZhcyCvH-4t$lmuzl)G27%v3$nH zWSj%eH2hOpG}FX1KW?-t1DPhurhqaNW_|b7u>J2w2c!NCy)|Smh~|$ZL?9zV7mAJ? zDV>0QTzw!~D2FQ19#w~%N7sd&YQ3iLYvp}J4R#x9#nVYqngCXJXgGSr&>6=NRUrIz zn=%MZTi;EG)!Uoyw>N=F@%ryc}~%Wz0QyJ8Fq>Sf{mc@`oMJ9a5= zrf|Zu0ygEna-n}m^`Pf(ni2S@a2lSCsE->QYJ%tG z_XX3dmTL4>F240eu^w_jslcVW)$U4kehTbWO7lS% zZoDxdvD9>2CX8`j_OaflTBD_a)dX@K#>KN3cYAB7<5~}5`-w$-xuqa zfmkBHfd6|1dqyyiUWU*~x9f28;k+wn5$n@HqYdGJPc=Kj)uR4`L*U#=Vg0^QqL3>+ z*!GvPQpg7kW2GSAQ8RY@Fj+MXt@*f*GKJ}8)4~3X6hV#vv;n%%EC}PSr^@7r02+I( zHNh_e;_C)cb^3g^gG}k{T-=A!*g-_PL3NyWhgoc`b4gx5lDwE1eY6%AS}tE+K<`#h zAa)SYO=p3z%(aStG1av)QJW@5()znGt{^BwP!}T+C5T>wuzj(PqCXv+QuXI@TMOxG&ayt^V?*PhsI( zaEJWp(Q7&HnkcYUM(LJE?l%Fy4T^2~?x^Bo9srg zEWP}CYsozQl5z}x3+{54h=suBhP)Nuv|s8V(Yr*AyNbIDoactH8wO1}D=d$90HaO~ zpfZqCh%jqG)qEjML~a&ygxhu%(gtsd$#p(V76C%gRKG66NPGwrXNIWD>UaL~uXSdn z>g!6i22g(+p@nqhQe@7|7pe!km0O0~X1@hNoVKa;SsUq|(7*=G^?a;Q`-O@{_BO|(pg{pS)-pHNVYMrDsa3NOo=vQU@tIMMoi$1o=4X~S%+*OjYX?z|Mo|ZS`iuQn zoV&5G5Uc@HuTW(-gb}3%(^%0Du)&0-AAlneMpo8Q=z44MY#W0!jo^>;`6}h2iD46y zwKa0?)9Y!cyte&)=KgVp(;-;<+w}X7jM_+0ROc_>z`#C)Sgn|KY9kcJn$)zU5C4qq zK51NvP(w=BuOOtxMKk3$Im-tCpm5V2;#t#`h##@AZS9R)u}cN&)%>eHqaP(Z-Q92| zgomMnJ1`%QG(1|CgC}USA7<~Q3P(WOr+_IP`Z2&LiJb>JCH-PEI!yVwr8~&5>vu#G zR13y@{QL#4!MPj)*ik&*8`poRa?kw*^}%H%)p5luH@nGRB_=sPUes(43ybMT)2>~v zLZIiV$z!D4Z6-rnh}%3x$AYPYFH(Ed@@pinWB$jgKcO5RmJWk6YOCDTT<%)ejj6>D zHINg`0&@4=vdThY;^ki{R?40fkc!zkg#BgNM+W4x9V-Ykc1#-@XJHbSUUzR@wv5d* zE38Snbs2!X^^8C~V@GAOgNR?erI(ZWnSdq>EgcZ#r5dWv+{`sQCy~E^4Z{>4F|^YU zpcR)mxoAq8b&~osD%N}WhcEZ#e&@aI2co_XKHC#p8vCUPrr+MsI;hYo8>a^Y;W2$? z|3}@#eL?`URp67a+)yK~kBR`9EL+8Alv4V|P}bRD29?zS7%MVif&Jp~lif8bfuP1d&@VbyIT(}zSP9w=s!^gGr1G!a zC2=ty>z+_)FEVyu>{_(q{Z#=75fcWt4ezc>jqcCxwKE(^qwoCX_BiK2cah`v%RLIq zLpM{U+pqWl<{+!xecA%eyOfIH{StZpgsg3$@ zo|-F9D}pk7=qz#`^Dxom9X2ykd(g!vMi?g-dldZjZvrQhCrO*m>m?CMGqtRnkcAuD z6MIr%#82{DijMIFnj|NC9&C=P6l>&)VKtsQumh9Q{YGz#jXYp77E7N&j3$;pYm zcSV;xZ%12x6cC+t`+A{Bx2oLg#7Fb7`E{0Z3?&81NY0g8jCX@Jn#J?bwj`+s3=d8nkYL-K|_x2xoWqquRWt2+4#sa7JZi<_UC0K zVJ2F1qXL4-$(j4SxCX9A#2R$+uqgx(((bzPV7fwz&XBlDgUaN(topDlRSe^aswriS zQA8>!8hvR*n7D~~71!L~gQ!MDM5IL=NRmo{B|2a~V~nxvp|ks-%MwYQvQ9>E9=iA` zmqc0*iH_6OGoiCekg-$Mj@`x;Wi#Pc%p>miejbvB2~iDubbX6rS6)tNKQ#-xI%^Q( zMK|8RyX`pJd^kZdg%U>b2z>B3z(B-Z^jAJaD7=>Wc?o11Fo$fb>o7P)AcItEUZ^5< ztM>X+qOzcT)~Q(ifH1wTjg1aP5o#r?lxlH@+bRV*DG;*k|fmw5#i*_FruTcuQ$WTGLfOuhN z7ks0u6B2Tc$lG)VK+4rmd!8%SZqR4kUz0AhRaKt4$j%S-p})#RJklWs;hm(VFId~| zi1-lI(BM%-N$zbaTeK?N`1Q@o)MM$%tB-ii#eKBJHV~XzW!-OQkEV#I9>|S>4@x z4T{A)+?D)3ycO=>oR_(p4M(Z+CzhKEz7qf4F7u(0=4m`3bx5H3m&2wDF#qzTX-@aPo5o zMn$(hS6B?yfD_$&NH!UATI-edqcx7pXE=21T2jbY2rXZ@vG?`*M+&XU;#VFXVp(4v zGb>1f0H*t?gqNkGsLPnaETe|f4!(TX?9*>&XWC$8gVmO5@kEwdzo`=hvxCR7EmgfO z9EXh}{v~inp3**PV_p7cAM6n3juatf5I!bM`F}SDx*8RG3_2LVEv>Aws38p0gICm5Jg4?s3b$AYnJO+QKsmdZq3p7ALip61a3}$)3n(%0!AKcSuMvO_Vxj)r;w^FVYxm;3upB$|Xki+P z67Zh>#Rwt-ZwK4;;vkZoCg9AIG9X2s{N>9%LbQoeh)Gd%mF+|oagL$_s`$W02Mz?3 z_+%%t=fY;poX9lbGvx6+b4d-JWPTe*}0^ z2Z@+M$XpL=6m4_1h}fn3Ckzg)pZq)%&w+S7-Td!7c$Pf8-53hXl|uz`RT?Q4+gyWR z%{QFTsVZ!@x(OqONR4AFVB)T9X5L6GM^V0O22fo>!KgU~X8C^{3E2LSDdIrjCxHE$ zzE8`sj=+Frgb%gHn54>8>@$$W`MX2#e%W-$mz5pAX4w_1@eu&o$@yq=u+~5=fEp21 zu<=}2C(z zjr!5~>pzQM&)jWKf`9E`J_uykMv}iA%-G=ppuT&;;_pTe>B&f-)4*aZTO;F*Cq~x!J+5 zCN%mwX$4-yw>rPfz#PkZ)5;~}b+|qV%CYUOrCvSJXh?TuZM$-EfsY_Sp0*IY8fff) zL6Y|a@YwzCWl4i*uO2u%|9EW`Ynm39*7n4a_CZ_RX$?okHZBzKr4;AY z=C+pwo@bw$B`W6U>NG8;UxVAf41Yuo1yav*JOij5DsX>7U*~WXX^X4a{fFy#lZ+bR zTgl;>{ora0C{0IOMk3ug>e3alN)-u?M3+^ACj%jx&^@2S<>lW89$vj+kLp|+PADi4 zv&4^pZO~HqzmwviX!rcRg~)WELgn_Ioe@g+z6osg2g0Rkwn|?dAkCk1~|s#EN;zhDlCF;=c3yc>wXHF8x3zyfluNt z&Ra<$0Y#~Opd(aZ0bBRj*v+2>*HwHl*|8Kmo32zb8R5RrkXQDp9^Rj!qt_HS7_Ez- zAup)kt~CK!`{9220{&Z8d6=8?g`bdozM*WM+9@$qQFbEZQv{q@|1D*eU_RT<%g2~* zyPDEP;9@OY{8%G1L_Jh?%7%&`rL}wuakFQa0$gLW3n2 zjw0_4j=>`r?8wb&@vdsR%K`23`ODbwJ-kORm%j}-U3Jv^TKHQLE0b=<@SpmrJO zdz6K~)qViX3ae}MRUk?kfZOvIV)2ghY6D3Y`w1GcG{h;ZkpMCD)_y(-z0>gGyiPh& zIkWHie=27uV|H+C+w#zv;tuk9N9zek#eu$@br+%qcr3Fjyn|O@225s6utZKDKehn+ zDlTi(F!vd}JlC~(VF&pTxWQ6AgU=8bkpR?1H@zgUOcqkyrvVyekPnN^0WMrhN!S~X z!-INnG#1thbGpCi?PR3 z2*&>}IHvXj7Ow^4Ng!TJZd^~cN%#olG+_s1yg>`2_S7}VQ7iujlMNc{Vu9&|sg`_J z-)a(}7=G$ys9EA@BW*(VBRgrXfUc+o(aiNGOT3g78p~c8XY&QaezwqEOn5WZU`E$_ z#u(0nJ7Y|;s0*9mI#03eyT$Pys@<@skUXCkS}?ZQ`;qfnS4qbXK03!LF|g3WE-~?> zrsP+6XS`#chM$A7pWx)2kEMe$83KfB8yD}%jpo^w?D;&w>(~F6cLq1~maYqgZB6O9 zvRxO7%TsL>PdNiF%UesLd2PA1oiXS3g47dOZmSD36qnSD)>mXLlEaoIkwLk#>q+-63JW{l5liWh+xrud^uJ+8)f zsMhMlOD+u10oN3^odkMq^e&rzvRq&YD6CVziZJd6l)6&EXT_&sL_ zY;vkAnW!5#e6eB=klI;f5nyNcZ;vQoQ`3xuoKnqhTv#jusUh>85Ziqfx(G)Dy^zfEXj_5wW@Z12T)#vBLHTUx?3OL0P1M+9O;!nF%sC*^-yShJR$K1p zKTLi5d&mH^xHo@R=gWEPu%v_%0WWO(+^_OXn#7olf$1RdyGSEGkJ*o}ml5tyDG#}{ zg-ixM0S8!5!@Cgnn=n_?bn@mJ917H+5&a)gcOp5c6O>Vf-@R<4SP&n-Ih#Idtmz{v zWGRl}p3%iHUMvOeU?Mk(%e2f(k0%h{9zv9AZxZq}(+ zN)2kp{l&sqo6A){ceVU60QrwH-2Cm)MHTRAF|1yIW?VN`L&IMG^v<6G!-&gNZUH^V z&+OMIpd(;&g4xTi!%e=kylMa7ARvvD9_=nF>iA#2QC|PU&^`lpCn3y#TmVeTqqCyf z^+MUN?Ty68wrWl0zdB6N2gD$z1!cziJ06d{uerBPJpTz9-z{nZbtTfmO^(c zt0QoBm3(4QnX2%pAD_fBt|L=7PCOw)b-t9lSOk+&=Cvrk`WGlln3Dg9zmZ)P8L&e( z&mhMy>H3PMd;My5lux)Z2*h`5w?^XwAm1NI3|gYxOj;Ruln1JGG!mhqj~HlbQxbjB z*I&!tK+$uo02G3%jSY)Zu=(|Y3!|%_*>g#I?7)r4tr4;qpKj3bgMA3!wa3%{V!aG9 zIk`SJIv}2@^>g&o0IQAb7a?n_C>C*s9R)e8P?U$UMPG^f4xOZfXVrurx>Ct39=WsO zD^w~Hb9w{9BXLKv$zMY0Fk1UYG6^7wrl?N9wXe*~&{9Ns1aaex@FTCxl(OvGP<5dl>F&t#TjmChh^ z_{<|B)3W3mPrP~l;gB`Qsl2$g3yKXdggw8ulX2(^7LwrSg!eXq+$?yp>2!Y|#}7L) z6G_;?Z=A|aBqLBTvnfglQ}qgMg6g0s-C5!bBkia3E^nZZ{hiJ_l0qX(bqtyHe7*N<_lw93j`byZ-!8M8*-lN&#Fi<7I z45XFJHKme0wF1VT^;RF4f`s_r(*J?sz_MzkI!aT7A=EAZ8FM-za3j zDAHDpQno2^JFR?s$~le zaT>@KeLGpPDV@C!egk6ZaH0o`VTK`Q`_4p-;{kV52?R(Myx9d{dV{0-Kj>=$N9BP9 z$&%$iTLOJl@KoMdMdjk?SC&@DN69UHBTP)Zv&P~X;yq32{J12cz#5<7vL>T=e_*^6<*mwjlN;(60N-=9a!?+d+VD?vzLst~iabbP-y()8Hp6Br6LI@0yG? zwu2WH1ET7rp+CL>=+%0z7bd;gzo544d_wKO1djVnh@vsVIdkU)`h zqT(O>xRgvhu*26v@t^FV$NxqU(w5cOwa5A$FwE9Qk-4ar9gy}0oK97eQujR?W8nT=AFkoLYS ztHES75V!l;%S*IS1__SN)V_M(<9^TqmkhDgQ_;*L#A1ALkFBp`-i4 zMR>``xxnCrK`CjZ@w7w}C5$A2W#&yj8%~t@nD;uy(5LCs=LTl#NqkHRbP`v4%=rD3 zpD$@!UJZ?`r8iPs!N~w`d{(k5r+oP4FP~BljpBAi0hCEH196|%s_)FN)6_{-?BHh+ z7`+waJwM)bc#f5R*6-gKo;&yRcV;377(w>8v$@}XH{MHDYrP)A7dK5ztt*$Mbaa|n zs6!}i**1)TJF!~_=~ikBFqMlJ|3+^a8EXgNQu8}Q%qmGHZT}8pR*5If9tXl!&)mUs zMTE#sdT}meDo?yDU|8y*xU*E`pS4Ez;Jz8kCnm zrLeQj;!(qp((31FlwP%}5O!K_TVBoO3fCUO#a%sb&Zd?T zs#?t1zt~N`3PCvwOgJ--fZMgL*iA|a-*F~U7~9(&k?mA>Az*TJ#kuu;w71O%Eb)yLB{zWclWBU%OT3c! zC>5Nd)~`E_*ry;v3jz>8%0HDl0vU802)(M~T_($;oymqFouawznUK%wSPgQd2>L>J zbvgy*rl6{7iQ8kuYLE+K`>>&CuP(m&4G5bq$z4n{cY6pHnwhDY0C3KrBqYJC@#NA{ zmOTB_j0Y2=!{+fhNGy{4FF+9oP*J^l&v2F}wO`Me{@?;|X^exGmj2qZTD{@hK=_cA z3;vzwn%r|c2{kQwUiMoiB2|5$SfFA%g$U^eG}y^+-%xds|I+nZ<99c4jup0V{_K@S z=DQ7pE&X!hq^i7Pp`j|#fpU(QYQ@QVl`crFC)qyM*(YWkG4N0#MIX9hD^B@0KOe1Z zbP)Dq=zMHV#*`9&5CVAWIAfrL>5^u$E0- zIBbfiW&axUhgGU;db!g^5*lc}#sL&6NR3NS*O5b3*7MXRl1O?|sekFUg#`LYhF6i} zC|!;s!6$`3EmPL_-}p3-w7_M*%3ecNS>i^FR0Pvh^%Fk|b zT}dBalq8q2YETUioh{2}zc$}NrusQNRr}Twi)uiB%&X1!J|apsEiNK100nR7Q8{U# zOWm%z-2!Y*+&&dl>sm&pHK?E$BE_ly;M2P^h=n?tc}`zU!KCKa=4{r9X|yi1&SY~6 zd}ZQ0dLSqyB&0C)pVrg-r*7Ey8L0D*-ZbmpNW5dx*4ngl(5X>N6bnr+W@KcZ0uR2) zFVb>X3*Dw94|AYCpGd~WxwBgNt}^uE`dO!)-1Pp+L)>_%p*@Qs>0YWrSGDT`C!ruv zi~?9sWQBzEhbm0gjmA1GueKgUi=sfQCjAdDUF2$LdAI5Bh*n(6K=>gfANN<0$?lPQ z0fN9Aa5&}LFhEZF=5_v@g{#?{`=@N0>@(*nH8rGDnp?A3p4@WmI|_rklbht(chxWd z6Y)pg|3uM8!|bj}lT7XUv2Bi={VHC3avJYMGgMO^Oha(sUrUO$bh!G_L66+_{Dsdu zD^A!@hB-DaJ8iyOuoy${LVK==oxg9(Yg5@}KZZOwkm{1hduDHcwbWB*$7boWNCS{`1={6qlpWJ&M zmW$aT&P)6R1@8^yw$${Qfa}{c*1~QQpl@%GACd@lM?J{?MeZ`8P+1@&|K_)s z_maGnLxo`UC=JGvP#PwL2DSXMG3_hMC&7XL&^CIdM!UjXvVEPbR2dgjk{)=uD{nlM zvMF*+_1P(|>m;_$gET!U3{7k$>bAJ(PlU~_J!96W)W;}C>X=lxL?F>MjYuAU(*{-q zv@Up`PaiAV|6?@zk&PH=K#M^OMSHx(-x8$4Qkc;!8>!!s<#c{jRQHP`m+~s)4MQRnC8PgNJ zA1G+W%uInv9JH%XP3^DG8#MU-`Yu?ewSWq+%HX7>85!jxE%&1DNVYgzsDW;h#u~+T z4dk^UhsR=VhWEi9&tV4W5Wr)-@Bo-9$N-|y$;XVumg zDE3s>EB5N<9&t-Hmu5Yk`Uif5DYyM!tx@ysdYe`I8cxic?rU5PX1+{QWvO!K^>#)^ zWhIxy@e4;0k>gzXpj<@;#&ozQcusYa)lP{Ac4)Ej{n^pWd#ejdaFdT?9*$G+IEUlR zuNK`&5@xAOATc@sb&cGpp5J64KpWzHZ`Mt?C@_)e_V%{gQKT10@O}#Va=^`O(U6@! z8#3G2o88-O6`*S%4od1oA9t|ka-U(dPpk_!0m<_uu2W8uY6*Q_@+tqVkrl_pUAiZd zEH(a4{FzoEDBz88I5$YCRxG6-!j9zo$S~*rXAu#j+>#5rvj4@3N-T2fR$gA-B0+?= zcVm{%{vV=zT(SS!*(Zi8nE2jksV9nem$&|TyX2O)~#NuN{%p%cw z7M=IkuU};J=Y*_)rOxLY=Gy}!WGtve3dkyVaQ}GR3Iq}6!h-&tS8ES(AQ7>MIj+v6 z@h{{wUt7w*HJ$&Hvmer}qyy%|-gu+!t*yjRz+Cdfy219*4aaWt0H_V+(J7Z%LKm3{ zwUt6!DK*I?Wm4{{K9L~LCv6T6$;ED+%*;2PwTT6@COE`d%`c*1I%O_03^e1FOx1#D z!&X?@Q<+D}TR*w&Vke3c>gS8|Q)y;-IU|~FsIk_2`|+dy(rGF}mw>Z)zM`!4@mcWyod=cp z=kKE~%Jcm7!>t(H${BckyBF$Hsfa5HLBR|jgBl{1z|2`|~I5U%sn zu6Q^1@V8sh7r2|lD|IEJc}tf0d%i8gpcAU|Dx31|OWUaO)O0jMFL9%9Ze=^Kzy_T( zbkYoOTV9a^4TC2Ez?7f}8QALg#|GWDST%N5kVs$e4q;w9_!rDW8%5#HD|3#E1juaV zFxQlQ(>b_kx50JfH~<9`3B=`gFi8O5VfSW41MNdE!M5`b#i)rjr{_*YJ zIxdCM3)AJ>-4&X)uMpf|`82UA?0uBV{x23uZj~$1)H+@pG($JzR8uV$N^BHt=bE#; zY(H|!#g|r}Fc8*fb%~?sMWX{I`0rklfU?DguvB~O9SG;r?v42K(rHaCie%m|b&Ub* zUM3(66@1=HU#fFRYw`<+O(@{%rlr5GUmIF&4~$IJXK+j@#3e~jMVP>pKW_;r9~~r` zmVzBdK}9wHxH3O@zCMgXkN)_PU$YFg1JRDMi1Qp}FVN@N6{%0sZ9F+5x(uk=-QC^h%7y0-4P{0QxFQ~HDx9AIp_@k>%pw@t`~@r#{yFjl zXohiZ>2BCHq6+WYrqS{uDZ>ebkVumRh#Tj>87gP2Ko;o%{r9Z`xrTr*D5&J$)`7Il z)O%!$7qG5CE5Cybz0)&yPFyah5K+%WSCE%efHRH5A$rus0L+VQ=9Q_ zPQ>&}>2#OcqZ>*U*cttbWN$rvB1YUph_J4Wl7eg;Lv(Lh>VU? zWO%J1@^V1!GET_{1q%(CFSj?>4Cl*)Er-GU#I{?tAzWQok>QZY@;7yTwccSz!%t#9ddP%hP_0>aw%jf$( z8$RS_Mk_&iLeo*veJT74U+3<9Y!>&PQFm2qlm%y3RZ__=r`e2%<=q=Lf2PDN9vo^9 zQ!mE=isb-yadN>x2V!&@E1k^pVIwld6xCF0>aLT=_!(>Op1q2Sw5W`1VcT5#?It(u zG-H({(LYBVts`2}^4_jzMOS`qXy6jT^WiOEXz;IY+LVGR&@>sbn?q0} z$xBwfX2grR%!f1j6|j1I@t;w?yT6?n${1q=|FtI{?RrzMyvw1QhbRCv-!$E<6#KA# z^6_mNQ0x3heCsTb0~}p{{I=d|pLDSqp!u{`m*jQzD0)R|xV0#A0fX4oUT9w2+@Azu z1x(T^l!@J)S;dE>6kpauz;Z#yx}+}2u88BRs^7JRnftHtnlk0BA$`^T{UJ&>$BW%| zo(!2}_$X{?WvnB{cWq&SyRex{e5C;d5Uh>Nx%9-O+JZ+e5T2B;{`W0Bnz+!wz`)~< z>)c4ew6T7&g8IIf$hfCdtPv=vKg{Mplu7Yi+TmpkQdD@*+pW|7B#ymC*9QS>&$X~} z6a^r?1I2;Xv@*Y2Rw%fw=AvuB%O8u#{&blznwS357D)5#0btZMX!X;05+R?>Q-X$@ zPCHnSVcuTd)mqr|4-+|#u%jaOSajeTC5Z1ReqN-oW($3B@e>IAveY9+1h zQNaD5(R`z}o;SMfwHs=BLyGqaWsvC~T+wjpDoR`UngaWV% zaA|G={$nZN=rRyu-R5d>Yx6yo?VCXds-~Hh_RjFdibuV=5H(zaHrgQ+Tt)1p!gj^Q zY~gE8eNPjYW566CLi8e*YyPgDOL~%PV?4GF3R`I2=>(w+@Nol8@&AQ5DN#mVTEfes z%}tgfevp+mh6k1;u8)J=gBMhMiVxLmx1a^Q3w-yV=vMeZ1P?vS%pju&@84GMmfz@-*v%A2pye2lfS7 z3nBc}SpKR9)b9@8`+V#-p4=48j^?=dLI(M&k1~bOGOJWH3z!pnuxvhs?s|2T`Wy4Z zb3Pf=2g(`~nlQi9*eXSSZLcZKn&-fR^0NT#{FAk6L%*P$fNdlJ{U1*~%`5la{pH{IlUv%Y$9L|-f$ zS_3^TNEVKuf79TRG>MEhcd=gTKh}s09*brkTpR8?FSE$IBz_~2G%^&ShZ^R}Rj#S> zaZBQl5Jgkd2YCeGNF=iC+nwdpl7HP`WBceAB@gtFqBRKP@XtxE#F0qKvGmphj*r{? zQGij#CCl5-Sxtu(7Yc+apcg8W4kPf8GUo*lCJ-Uz?ZsnsB<`e+J&-wwLsT|+%lz7W4K0X;QFu#0`RH9L6%b6zQKaSR4boqN%LwQD z*4&OZuRQfr&|lc<^blcPeLp{S1Kb9)=>5eL59DIDhu7rv=uxt~FID|KKe{HI)KB6p z=+;zJNdCuXm7_$6rHBQALgkeSAoh>uaZdFc!^qUhRaFyUP`rIM9Gms65(fHbav$R` zSXB5Fji#uDBgn1PyWp;j-_Rg#(j-%jfG#~VgNeICv9%>aE!ybcJ0t1%+2yomtlFno z3j?k=XD|~&rULm{Y>1-zy>UoS+_nEi(_T%LXv0+TB*x7`uVR&OPlug>(B zf{T_^CssfqkI~Q%h2}z<>J`@$8DYV@`ea)Y!+O}32a6;)z$^L;i@MsFo108?Trlnp zwmiUhU#!o;?f0JF4t6XB>jl61FX0dZ9pn4N=41*Kv&Qc}I_D^a*ND{~g}34Q5pUW-53IJKX7hGC(KDG{Qxv-*R<5Pn3s>%iIBm+D=4vtazZOWLV*?HR7+Yj1Dw?Z761MSX*Y zArcX|&rD)W2~rbxXy4?W_K+R(X-z`-!oVg-52IY``t7?L)JZK_%C~zo^u4(y%LMin zw${&7%iV34t`QM#Vg|^nA>Hn2JWUET^opJy;oZ{=725|#JNlfgnpi*~@~xAf!*6#l z>%AYe5~q3i+Tpd(nuGShq1Uf6%>%N6qJ@F60;OYb*A)H}hMRvdKQ(7lX!N$8nI_bc z%X_>%Fs{?@u2)1XrKpy-dXuehVL`^go`cuR&oQJ3hKrK*{47~cB*cmKu4&0^kvMCg z_$Z*2RQ`Lm_$HWXh+YK#!r2{5^m~VSCK=~}sif9310l?1+6@8Emi+=SAd6{z3%3@M z!j{$%J@G}sWF6kyk(I0&XOtxSg%0SHlU*Pb$`$EvA#tMFGGa(0_fVGOkVu#2hkN zrgvqBCd=>WM5yb66P{0`YcBq5}^3d`JoUB^uyFNGi$L7G_Apn1A)mE z&wz$LI|L-j+}cU9!=XDl8QVR0!*&mMJ|a3V~5_SULkmaoZVkJ)pp*G{f;_d05k9KAV)j{d}-^yF67Y zkTgE6Bo`mE#VJj)t0{}}X6BV4^WLWar$CDJyU8CTsqOD6^p25?!`uPyF$|2Ly_fZM zEJ0xpC;K6dXy2s-v~xC(t$|ZkNVS7>3s%x3p7TqS}b z*}0k%Zz-g8y{(YQ_J|izB|07M#jXbLfFbIG_9P?rHC5gVz+uBrYVQLH7;m(RRJ6pl z_#6bL)d36W_Go46xH8w9Av!RQs86l9Gi5UihlvKMH8k)0DIQi8~6I#Jds(x$_<491M)3$K9wBZYNwjBEPfO%yt)IsX|wA^0gO)2|k)VEf zXmTG70#|;mjmt#T^9lvz1)h_%eMFTp>mF>xKO-7wCzpH z{MwfXI>RlQlR%4~u4w=Ya~I@MbUS$P>gfiEFp7aMrJM7%FmFPuOTBpc8bLc$Zl^+q z@rs?bwVpXKV+Aq8t_RY0;kV`Z4@i5ytDtZXR!LxpH`9+?K5KL8%+7Kg9D>b8yQ5_b znC%Xy1mh)#(vTR}f=ht_X}`*;xsY*kfOLm+ z362=^=)U0`!(YkI8)tqQovh+=t9%?E)c;C(@>jqU~C@6t=GatFbDJJ9pJ z(Cojv@5L+SO@?e$=^vo{01Kx{Emnl;LNJGSsQ&BC`ci9ejJ_Pm#;bzkynag&y8UMo z*JoU-MB_ySeM8Q-7VIMo=+Yy>oE%N={H96$9o`pIG>6X8d`CwIa4!^a_suqyai^wrXBpS3l zk$`rOSKb>T=4L-2$ykv?q}}(+qDvdRg9iDwZf~D0^hs}-mKUutZT!#0PXbov)HH%% zxhu^3%um#*=5Y8VM=VZkscI^eKp$#KY%edP2k%6UsX;a9t01{KeJ2Ij6)GQm3|FpF z6%Fom2aQd0<1avdvZ$@>x7fwp%CTo=BEc7q;(^vpHa=P@8{0WH;c{JiaUf~1XSJ?Y zH|zm?2zc*mxy|4&>3WDf!+rJnC- zoIa2aDd3VHNpr0(E;IICAUKcC4O>=1wHQ}TriMgVWfy!h4I?FP6?6*bgXCSG&Rj74 ze%mS6Yr{SB-eYYw0iRn3E-931&sMPlvZu$HKIcSw)s+NB-CC3?`SZzLzo z75C*1mN@u1RU@!BjrS_@@}2?b%f*XE-+h1lB4u?wMSgrO1<3!TTCm}=Am}G zzP1c$zm}K!Upo-do$S}VWY}}K)}00ok96bMs;Q6>AFqW5X;~{Z)$s1x8X6=UBu*X~Ey4 zG=s9N+44Xq1(e`j>}{tkO<{p7S_DI$adD|RILWOnH&Zy-Ht79xF$IEmPuj5{fa4e( zk;?z|d3-jj+vlMAjkj7e?P)zjzw?0QYPCekuOa!B-1G)c|cxk1cG-TwRM+X zH{Qp|XVIgPZh5A4oVOfzrl)%>m472Tb6la^_Bk=JNze6)tRrw=NIB~2e40iQ-8~^& z*oEK9HOmSI2L}FnfV;^mmcym&japdvd^*)scH}4<-X0vZj8HJi@YT637~sOA=ANSX zX+LJsEEl0jVDG7#haS?^1{-56pI***cC}2*@13V8(v~ExE}}0%9uNpE&?~2~99^ye zw3Ua4ldzCi|6hW1@3Z+W*ZDyj1$QamX6Ir_xpw!=_UTGn1MAZMO55tv-&j0vw3hFI z%jWSno*TuEsS=V}%Dqp@vL3D8lGtk2I*^QCzc`!**58Sz;8joF5o{`g%lZ+H>$W26 z;OACOmwT=Fb5j02)bF&@8MKie9%>lyivdz~!xZ-ER?YWr0A2AXqE-9moaViOyrnE~ z?lCf?4UPfMHqE5yray!T(AU;=?PI(P;RhQ^JZyd~2QEQH8Ytt09VYRR|H^vS9%x#( zCm>%@Jkj+p=Wi5unD(9ICkMiWUs+C{P9d1e*f+HIt-^|MHdTAKnXQWzUjK2YGAJuj z^70wS9IF3?M&TcqP@=SJ9<3~OE^GEgo%MUK>&blyimc{^#WWJ)cxu01y!l&0HJ}AKssQt))SaNuV=xGo1E1bGhqV$$6ew zw<*aCVqNkWgR7(yN}-!?X+GBE5@V#h3pyTPB*k-ncx&3A)TEn2FEN`EbL0+KaOXBh zZ7w)p6G+&|M-YAFd_@8j5CNh-3}OvvS;LxH)g3{^eX;Eiu6y_Yg--lz*X%EpbfBwe z<8(*L4A-i#GJ__N&tvT(swUB&+yJPrJ*9kh9A9KGh|`HRP1p zfb8>5ZhjX?%M!kpSmgE5PWQY*idX>(dbs*;aOYYp*eTcCb7%wk@LNjM?ZXi4nXctB z6{Y8|>gK^ZmTo@*8%vFKL9vrjjts*j|6pa5{T2t`Ys$SCT(s~OhzvuhT|N# ztw5IF5vOkkBdWSMaG(3Vw_=-B?yJ51#K~-QVpGwon2TfTXO~I6C1rX_Q(GK0_&88s zt3o;_;uWzSMQ-?R(&b4(V@XD(X`W;aeJ_+V%npGPl9;=8vlyL2w0uUW4>e zh`@Fw+K+CLv?|`L*@O0jFV^v?m6~&X57e2FnC@frxi6g60$f#!1{%qM59|#o@8_9% z|EDe9Gm13KH;`z94>En{4eAs1&g*sVwKpGdEK_$OiA2Zc3P#t}3ZAR2{|U-@d#TEK z06sEb2t0gdC5@8ojJw`KE!Eu}@hS&yP^Y=>E3@u=xT2AY5B-I0i`6@gl|G8L9d!1d z7?@L3b5N1GJ5V`8YOPcI)hi+UZQkHf)Gq(HfxzF4ggT5)I_I8v8`Eyd-{x}QlpT@0 zpF+_7V8jB*tu(hgO&F?S#_?(t5pAtArKsvI8sj}PD*}9&e^4CzKb%cDvu7bN=bJA? zFR*LwRYv{kvni#`?Go%SHoZ7jD|D)@2)5$l66hMAcKOIqE^c`l?ytf0X7(&qcLljm zcIUZK>oXX`hdM#j*5}*7Jd9wb$$3c45-M^`a4IZ`mK5#QiceSnX z8JJV~MY?W^YhNvn^|2#b#FdC9DR=LYFDnbRMDD9MIqkgrU|%Kvf=4|UW#}k zWrRhrg2RVpnjuO_$X}IQo(cS_GtE}6+2HsG23VhQNUL{>`wn2(Sin!Jv~cfdj4qfV z_Tv`FhUW)k@%OO3t$04A+@Um=L{3||e1T@8SLn5a$F8a0zy18$$9^T+jw6Gdk=S3YbGiux$i&rSy?m=WZZfY{pwc! zra!crh9zY>oi-%TLG$iH>YMzb8CCM zhypHG|3gktP;jEY{klo6p1$^Q5>I2(g3w+gg89|c%Z+`jcG#*}lVRxxl(4O-_n@VP zID4tHKm#js7=>JRovHlAO4E4yl<62zA|S=PacNV%Cv@+|uFpGZeCcJO!?+r2Yc@x} zla6=oGUKl;CB?v^FO=SH`z6_ZgThN(%j3MZb$w>zP=a>#p)-T) zX_d_)d7pN}7fBF`?MNGWd4`m4DQlv zeVqgS9rEt`*=q?RZ&jl2GXdo)8OVvJ48bFVdo)4^J+Lw};gi~9`HQw8XYbY;n%7NY zQM*?1*~9@NrVx_wD6cOuA$3J$wWq=gGOo%3^+G)=Ie8V~=Jjn>GR!R8R3}_VI$+yGbv6kSMSuT`qC~Mij(Q=>lM4L5mKcO& zxr1ds4!;+{|5Q}meiEq;d|6ElEG}}CMSlg2Ntune-9L`(4@D~|)R82?%4!W~3i12u zdlW@{Y_G9*pOq7P(G*nqTw>sCkVCW6ry_m%KI4qe9UlpI+b>%cZMq#p0zww0onJrw zeQl(mXg;`8w@#yzQ=X0jut3p19&$i~J67c<%Ji!yxPh#&t z+zA`Oe}{?nvLL-6_B?}^wXEU;BQy%l^(W?o zUNDd>BLqq-T;H9Zjl&N9^b#|pB{kR*aZBI)L^06Rdq7m=QZY$!=tx_oSM;Be(b3VG zcmA91D^HnyCWeT$CvW!zNmQl7k6+=dwy#8G?GTO~nY#;N0; z#xX9JFnAkZ!7W~a$F6X$$1Nei&E@*&cu5?M(R`@c7Ra@|Ma;;o1g$)qNC_WlG}NQ= z&Tm)ADTD{NK8uW0|0(KmLVC$Hdp(*ge{~!qDS~Mpvd~pLhk-NmqQ?ePdi6L&t$ab( zU;bgCK}$`tU7d!2Y2NH|>;~PV(_?xvJH?0MT1B568v153)T(x$l#e|w03frx&;bfv zM*%AQ?jrIqm1n^mHCmT!oCJIu_CPu$e*av$@JOm27OT3z)Z4&Qo{5xxv!?jGDy8dM$b3 z)~H#9ZV6@?>`DxQ3$)w-hWT#}@vLrYeUoxidt|GNZFRicls(fC)EZ#*4d=4N$^7ClRI4W-DOq1z+kL=rpg_Z-1INQUwu*mswrqtRQ7XxaoN1W z1TVFiiB+{Mb5CX~)~hi=Oy2VOt)^$|RrpjD%q#+@y4{bFn?FPp_r} zNhkGh&{78E)PpZItPXMcH@_nbr(`FhVKU}8{FZ7oybWDykNyS;@74GmT9 z$+!xvWwdEfpv_fC#}HnUEFwS4c56W|_t82|c8_K|$wsENanvoi@)G9|yG_!YO?UL2 zb-KrByf-?hidU0j-zF1iDrHDAU^u4VUp$f37;rdIXz_qqnf0#G-|YQ{d*|5<*L)xB z-DRFyzOUhUVFlWffoBE`%SM2_S+``HMDvVaY?1XmKKd45F3vHl6i4qQJJ!~Q@w@MJ z%ixK~W1jY?&Zko37P&;-x@5wg)Mw~tJmC*hnidTB>jbn=5QE=6npw`K>9pP+m& z{q}A!521bK8NZ9@^^C*eMf)lWL~GRD>@raf?!;*VNg*30DsA2{wF^9%kIx2tOe8NR zrcaT}Z|X>%mM+W5$N*Q>zUMuA;M&v2HC59YJXefej?8NIMQ!B6Dz(LjDbJr?k$y_C zbqvJYFc#EKhpjc_d>oAEqf=2`ABs~?{0!Vv_-sk(M{GuIU0z+d_kMeF?75v!gd6(H zIg~pzKQ8AgAx3QXBR}Z7MxlVz&>U#1>bshV_XYC}#)br^F({QVG6Z#g>*c#_?FYm_r_o7HUBN<;urN;jH!SGrH>Sz)vY*6~{{+6t< z1D(Pqf1pjqYS6%X;_esq^TyVZzPkP>TZQI93toOAgS5TWQ>lO<6*98y*x1cu7pB;c z^I2SNkizYsIxWyFHUYEgUUPVLEl8X~_eg#f+L7!nRlCdryM(b^WkT|)g4RdEpqM#V z0w%kkdDz+~h>{s7IKuovBe=S{y5{!HoPA;`i|rV*K=gHHv$Tm8740V{Li`_W4sKsn zi%x6oT)i&}isH_&xuYiYTjS@+iow@ADS9R%2F@#Q4Lv7EO24=ioPrqkS?VlJO~1v2 ztgNm=>T4{`N))d93*`-ebeY=2+lIWQ_LLhoBPFl6__#`3T%T3hL5&CPBY(-g9mPWF zCuxqF*Gi6FZEBN#L9%b}{TmnTjX>b{>&bHV=XVX$nFfft9CY*nOn|5Le9sp1p&+;{etV zhiO#S;bwtYyS}prH-agiF31e;Z^peT!^?6<_r}Cc>c|9b!yaxq1odDSvVg-)cu>d` z&&raS*_A!!C;zeUwgmP8p8#!A0N;#w;T_8dM6J-gm*YCOqsZw@|g6DL8hDAl>5oRzxnM>{=R%vx-m zge_o21>Nl!GR_5aW&?Zfek!(PJ zbIE#n+qnNEBR&Vtr$uPN_G!BO8tdDqGhlMNyGMtGTCmy5r88PQv8HLA*Wv5tD6={T zWzWf00V$M)UNRF0!By7Vlj)zwm@2t*-wbAQlUEVwa@#_WkA|PXn9(8XC#e8h)2cw+ zr)^~Z1;qw8Qod0XT*~Hrr#E|r+xA-P-m_qvKetnWzzwrCHC6W30SHe*!bdABu6KK2 zfajFY__(j`eK@k&8NmWSPYGf#9tpXM5Vdlw?Nz)iyqAY&M7xylsS8_AAdB>IHu=L= zobBPKF}MClx&fC*f8U(jxy;LT)M!NZBVd>^{j671za7GX2ShEST2OGP zWGO1WbgyL&OvF(o4seUw!&&%FT~Pb`0yZTI01h!_ zD2P63gSe00EAGFj&JfmiUP=AvY^UNqxuFmD;P^G>zRu6exbH;Ioy+PPHo8GYxrj{q zF5CJJBznS#D4{GKnOD5?*PXkup;GsETU5w>3LJ&16;k_jUF$9(@P}I~rw#G@8G)*t zAHYoZVrR-HUyl%+owp+#RRsK5gtB?HVAJ0X64v?ZE!`QGHXA~Hq)z9wZGY?G1S zy>W&47Zr3lS~(m%0?^i@*JQ6YYPVkm!Ja+Py?HUW#_*q`ftjnJERK3S{bL!<)qN1L za6{ji#1QGoBZr2d0NqCggZthZ5J>3GUSI|88yPMiq?F9E<9MGyLzDwihmSoRQCirj zNcXcW0ipmvhT`{tS`aDVX(OGWY?mubJx0z#hX2w$g3IOD%kc554|M5YpMjtcKC6x_ zZ*B<;4S?WsI2zh@VVH5->FH3#pon`r_(z{n866&r3=)6WR{i#67c_9Jg;t-PhcNf{@6k&r-DH{ zxH-5TMkR;|bGPZm{mFq~HfoMB6uQ}I1*tN% zN;tmRuRfl&jXjwJQvlE50+OKjwZd5ov<@Xf0Y1la@iHZ9NOuwK^a1HZ>Nbtw9^B9* zwsYT+M)0E)y=f1Ucpr@C9B!U;tW67N@qWyrJPSCbXcdvE`>M*m$D;k+U_kSY;x z0sO}J10lDSpk6vTD#7{MeR|_2O#3ETKWDz%uudU4E!Fq-y94I~7OXtIMMaLe;{HEV zQx}y^HJjfuD2pW1(jHU2|Vt5IZ*{n znsSRuI&t3q0&)E5>TJ0_%U|aZkPuik6ioI|Rr$Q6Q^Ohc3s}3@=jHOu&eSI-$<52# z+1g_pouVxuZT6iqDa6gfm)v#s2V{ez&OHf((K*ojBb{fqT)j3G_%8>zW0fwBX^~1DY&1@ z6YAN+i?bP&lFxl9R>)t&I1E?@=$iLi^}(;B6ORxs##;CD)bj649Th=d|A%E%xM3Yj zy4=4%0@o({qSw+A-=<&S6{4L>6r8WGUO9YS>VmW77)4SYJ}bl09d<71Qh5aVg2Wip z>ZT7u?`K)o9VklzK)y{!k~?8FmWUru&{)Wi7;G+`UEIZ}EVJqzaZ4+Z5JAmxBO>qv~&cD+#B2#Y$ju#Zfh51u) zUz~2~ZB{J~fI@X}G#14|BS<|sy>THgOwGvp>j06lhEbE$18nR`SU|>6q0plx_b+T> zJs40Sk3A+Jm&vVeX8hGkc5qNTy>=%rIE~Lj1Je|96&yBO@9yT-fgT|`CU%q0{2|Hb ziY~#pAlD0C+FxRh*dTcYCRxD$!se2I6pEG%t1v)G1`i-+PxtID0PZvg4pY)r#y!fe zt>f(L^N*0f`YvG{K7a*^K|Ye8%Y4$y zXZhz(6#1PVQ_Kh_;h^~{x?=Mh!7@=AQHexbAO_2=Z8X^kpvDaJ!RmlmU6q-@t%q}w zhAOJZrFvilMZL_YxLI*t{hMxapXeUTM%~lzDs1W7MXXDI3h>y{bS~nq=NAXhfhUK* zY4cMsrJNJ*NM5dI7LVs#;i%iYgJEV%!6Y5~)J{P>P4a{v3+pk)TImu^V_`;d4 ziZas=W$OH0l8)GEQk}2G^&$ULGQ3*vcXL9(zpQOz}OOi8|V~v&{pw>Y&0T$W!RrI-lkSzjo>F zh%`S1A$^#zMTA;W=6Z2bl9;%tH#pkqu2LZDkaf0F+@*aMr~L9eb2igcz6YY4zXQoo zeMP0jk!dn&*^xm{ylU=FxE=l|^12V+iAos;3FxCN^72_?q7UJ~`ZXzDM`Wfl)4m-g zs|J1f4?=t!5D%bw-M_YO8R)dTkdq`n>T2?u zm$Gqz!XyF;qDNwV21bl2EPmspTpQM6>~>XSYISaqvZB@J`50{=aw2=O;Wfu}O>2>_{KjIPaaFN%!YV&bI(6N04 z4Kp3FBmol=utTo~GnJ^bb709eMV;GaV%7~$oq0r4fLV%E5e$x>cx9H6k>S>v4R8m` z{Gb3%72P_ylaQUmW{Y{dhKwKcs4$PhpW;s6AmYzMd)BzT9OP9QH}FlbOc>hfJcK%5L&L{y+`#xuh*9*psZe5v87*>LQ^x0oyo z&jgOgco3^^Dy5EQCL*&AFHz%dtT)R&BvCv?K1ENTu7U>7waChV%Gmp!oe& zjxK$!S|K*F*sKqcs&;%gM`I_yC{((93X`i-BO@bo-)^swUXr6DNZx~NK%488teyZ{ zwaoM+_~=NkhB1ImK`US!4buH-WhXH}Co#)=HsGRCq0WvjmRE+Sw}NiKQZbV6Gq zc{Z2&YJG31lWZgL-Ns2!f8mYJU>~l|mtby>)cY}A<9_LseEzwP!M5DD?`tPnAZU$_rG3%HAmeY=lFcJ?1HYrN}u|C_x_;cxXxh(641|lqy)#R7VxH+`#2d=_nQ)&U3gpVkE#-g3E_5cOl$EB+ zySON&E<{G12_rmV@~%)NmjC)0aAAYi4YkHHXyG>{xLbH{2fL}G2$jc>a?xa=UsS?f zzcg)59=ml}$xDX{Lnp_#uZ;t&04ACj&+DQiHkeaUu$}Nkq+pac=7iwfN;?Xk3CO$Q zadQw(ifU)v8$2-{AE}3YkxcPP=#>a$cvw2y}>G_`A zh>S|NJqDzhdlL)rJq6(RL(wgUjx;lkB_T+k)}0Nxe81w$2IES z$MG%Qx6kG4(Evgno|NhH&=<^sb~HC}CdO|wrc|V8I@f#z3J3cJ07);)lCkW?a1eiP zxOqI5SUP{*_=SD$$aeOovSFwVM zhf@6@A8jr}$}}5uw}Vsm3;lh~Cbvjh_sU13*Al-H6ONSieWSe1l%)j zS<^8&Yhzc_g_Hr_18);@cec0m@k7RRe=9cT6v~F(yV|JKdp&J5dif|BD= zQ2n}Q!lDEuJZOAcsTspKDk|(jaqg=(UPJLNH9fa)hdyC)ih<#|^WfBTf9bqyWmK-z zmUhFd+mM@O;X9WpTGJOX<=}{Q@_Fzy!y;b+rG4q~OGJY^DdEDVFhK9bwgePDhr@hH zR;@?Wa{c^D^5RJ!5}WKR4XZUSWW1i@U3x1-Z-(dWqTVqdB4FcEni5z1{l6K+;@UJN z)T@_L%KDV~n66l~HShd|_UpePOEbOi6m+*)tFS)E@0$B0p4g4F#`63^kc%Xj>rqDG z)%slWA+eq-I9lb=hbH=p(H0(5&Zf)6-NTOJ>gvjgfuCUEnD?_4lz92>+$U+oc_LA1 z5$&}go(gntqUgUGmH}eRiuIoT(bwOV5jGVtF>ESuugZkcW|eCym~Q>R_GM3e_^#-Z znDu#UDW!WSI9U3;a;p0@f^R|MSI->ieDoG#B3=b3`igS_{KwKBe0j<=g)e%oXzWk* zFE_$^^_%C}<2I~6zlzz>8)>;=deEQHeUB1Q%reOi@&qz24OKaNzcBsTuO@P~X}(@$ z$~%a~>u&ptMRRfz8xOGuj761rZ@%Z`B=^MFP(h$d}M#=$AWK^ z*R!HS${G)LvFkFR=nJ_k({q31+@|x)mW&|WXA-Qv=}}o!T36_?x_wT6wSZ|Z4Rck9 z7iE&DUb@3m*ERlCJ(+j5I=Np=ujefbbqJTJ2nzU*uVXc5y>ADJUAvgCAZw^u+hn-Qt?dqY0<1pLiZ9EY?c`0+uk_Lpcy2AxUjDkw_*OWg( zy!9u8JEe6q7+^pHK^stA=;?vqA0fBdMxifN6b1V1rhN(XC?e{>7?elH+eZK$G)p(off&S#cNzm0F|&w1I`$acPaHF)%P;;?B@U@v?fh zx`#&{ts<=ckOg+lf`sa$;xtBRk$xyY|HB^;y?qZP?bBxBR&B0D#Y=Mym%!d1p>v4p zGs&r-o;5Z|d9`a!l3n80f#?4Imd2>dCUz1(X66#t%78l%T8|5b|H&y?r6Fd8SR&ME zag6Ig-E(ORyPX4%u9qOSvvm9iA0?MX;ReNUV&hRLiWuf_*$mZ%xZ<9_tueCL7>0U* zCFzmnhbM}#eY>kASJ+iGx)}(DF!c3QEhsICY#_3#T>M^H{c*$Mrzhf~dtf7g015Ky z*($1!VrlL97#@G=Oub!bZ`gaPOu6<2Ih>cA*$7^CJnM{PF;~5TBLbvn^8glpk+{6! zka}bUOir8XiBNqH+4y5F=hU)1%>{7&G*T_QMX~JYpfF?1=F8vtN}s)mh_g7N_gU*0t|#BH9b zr22i5X z*0vHg2Za)KUD!6ei1+%Qpx6=d%i9|dNCx(oO*DYBcABG+6Zg-gS7>4nuG`Q2$|swS zW&rf5W*;?A6(bmVu&VWZA7wyXITw{|)r#Gp+01iHkdD4x>0(<@-w;@4IHxkf!?p_7 z?PPb3av-bj46W(~m#tC0DaB$*<^PQ4LJ=&guTK7^X$j*qFcfNq=7rFF5K0LRJ-Sah z6^MHaB5VP1pGZf`B#&|$1+I@yCj{<=0rvUOkgWVrufW=5!MwC3-U)phD z>FMI+qD8hQFEG)x0J=ymB_4}gXp>*%afVf+3dXykijh`f(4%8=hQ6Ajpl)2W!q7`8LzF}tb{cfGK)nCAL}^4aCON|wC%Vpr>3vVQ!> zw*8xOGA@lS3XGY<=5qc3*vUo8oU)?b{x#=HiDncFTz+A5@h|bRACI4ZRIz&eLr;Kz zWtGwm&&znDCf6lf;-d4YK@g!~n_mzFv{kzl{_;`i7Inq@>El_gbLByjy3zRneU-!t9jyP=5&)5XvoLh(in#`gP>k0Jtk-$5z51a01USa$u z^lcQPp`zwho)*6*u7mb@bKPs2Mk4RG+8qoQA}8&Ng2sU6j$Fv{!b~zN3qKjn!(TBZ zH?wGNOo%d!0ZhI2E3yB-~c@t6URZ>o} zmu$(&60T&VV|i?Ujy{fGFo$3LR?x#4?(qDkdD7n^Q^B2?FPuS~r{+$p3-4Zb!@GIW zH{CLdmRFCYu=cW!KDA_3e@@RO3-2j80=BV4!4IynGbuCtvs=guv4;w+srj`0f#!cL z`azizE+oocF`kJFNq-pGpDrc8UGM1}A7K7z&E+Edun}h@i(%5rcT2lx<32W+BjSQM z4;0g5*LI`x6+G!)IgNwc^NjEtzswJL@yUc9pIgzl}+Qvqfe)h%6TM z3V1FoJS673*{{c$TG@?Yk4A#LLB;?g#z=Y*fC?D>IjenB@!p_@3JTP<|D+4<#N^&R zZ~Z5e8Ysj#M6Jd6RFcY$y}1NutAlbDHor^8dvoqwRJ#qsd5{$atz|>MyUE^WgoA+< zO@UF-S^c0aW9KQU2akKRPCs&j#`xcuJ{PUqTZ}WOmrX0}l+IP%{PF7@A$K1%9lq^R zWdaZF&L9`A+Rg_JOWbH#!aQmb0H#H9ur1@P!Zexq$9Kp*$IIqT@)gzOuc>Yx*YKyg zq%#oL!;yYKu!rf}klP!$ilmR8LWQ1z^&j(gdz zYXkrI<5zc%6?IjQL*c7EKA99&zKLIlEcDT;ZDUM1C&wG2;e7{oGQedG|4`39LwDr> zpIcWsOoI*QZQ`Gu5MMyJ*mRVNS4bahpu`e&=ObmFE{RH1#3`Laj5*{ZY(xCiCe^Yp zEEs|q2^7t+4R3&Ey9#$~#*2X~X+%x~pzWosX})05`u!Vousk>d7pnYYGY-3aPGvvS zyZj=n(fD9BOf+Mi+hO}n*OHxvHw@_=gvDwBVyCb4IDv~IBWv(+crCXO@JY5D9rX^%sxo8?-FxoB)`sU= zK3h`y0kXp)B+Es`WMq}ugD(7}&r-5o-Xp+FdXgIsZzTiJaMSbz_Jokk*J|G$ab8vj z1aRsHJ&+ILeI_q+nC)-1ijaGuwAK9TDD-@MGk=im`3I!prjs+Np4jw^R}=EM;6;9w zjLO%mUw)32VnVB4W%vL2Wa25);Bobk{|L$;RJ&SX$-1I*h2r=1Ovu;SkgugYNKN)L zf`RmGKWMsIm=mAOp;2iL&>d=+CTsk&uA7pGh?U~~ED>$}-k#rqJOgi86^K?uW2=W{ zY49VQS{EgdH{%@p@f$ekb>!^xn-|_ra7&+F_XzmWJ{P`)bSuHJG-)TYSY-ZtY6HlwC3Chz7x!(!@+>?zqEx2ln3Q{Btk@k zf23SJfSJZzQv|FNq!87D;5Fr$Fsitp_7qSs_YB?}nfTfejhmQFHMFx$^~0L9 z#fG#6+q5mJi9{qR&r&7@?OAQPb<%IJ-^5qFT&zlyYB2pd}n`a z@tRVlIEZ#tXRE}P%$|*raI5gnq$D%qo95}>`qv)k@0)cz*&@F z^s&d2oty->7lf!^{6ZgO#mi^^7%n~Ks=@!RcL$&CsHD+aZqHjX|o4_`Ho=i1O&%(xT&sIs}`vcPVm2h@m^01Yp?z1z1^ zw|!Rl#ukF`>3b;%-2%#(y8^#mfM!&8yo-gcM$do%KCSPsGQ_}BMO|MJ!eo?c}(1EYvUJi81D-Q8pHJAmr4yj3rLYW5csR4awP9M0oOk!`M^V{FN_?I2lvjV z;kj?-Ko6C3>KUPaZT*cin?v8mI;cvu>lLKt<$^=`Syi5Ir;t_ zef)2tuCuF5DV^Vb`-A0`9{|s86w#3R=;GR4@?lvd7$|+agw^>z2p6P22e#*;%*Cl{ zJ)pInXP7kCf%RHrRap^$n#UrwtcreH=LZmw5OW6oo`{Kd?r+pN4yvv7m@$x#uWIjG7lE=HuI zQ|?t2y2tlu5!R67FL#`OvzW0O9&|jH;b*Ia@lTFvt};NiH07Zk~N0<}F`(o%jyzhg?1obZkhKOl>oZ*5J=ORidSePz%(E6L~vE5By zdPtcd@i{J)ZML_a**!1j1c~_$R{EyaGSyK)?!w;E(}IyY;0#E3uVDNl4E5LNmqM<7 zucW@+rtf8s70hj^-qmefKmvVclCg_Fn*8l(ka3c%qgf0H_JoVO5$D{KN~asB%BJ0 zg1@#$Nj(hSHVe8LIu=2&cjr=wpupfX!LI>Z$cv5?(z`{v$^MShiPby6tpSUgUg%%H z^P?8zFJCcuJPxks^Xw|;VH*-?C>@W5j_bgzY+r0n6r3XREH)?_!TvLLcT5K#>EEnV z-+9K|H+L~QlVLsEv0!W|v#3e%uqOpv_=mv56TIHs*-^{GEl_ePJhYfq~`|qMOZi%a)5XQp<~c3=+EU6e|bxUG^$+ z3(q9g;&e>2BYek@@VMMm8wmyw)9DjOA zHR=p2P_Y&0AR?xj@I_T=^8DY<46V|FtsU)7tupo zKLgW-a&`wVur20!N%Z}PtI|dsfdS0OnIv{Bz_x29lK7W;lPc`nLAUB9g(oG@1z9*6 z)wQ=Ffg{p`l5Gr}-?h9EDCQJX)Goq@*E1@bTs7;po-F+MG_?6aq(j#7lqr&A+e(!q+^{9v$Zt&G>%z^Ds6tQ3jO3nn`r7ty`=~uxarJ zeWoGG@|JEAij!6+gbfCoQnH#U=REAeg=@RgufUbo5oiC1!5n9{bQGS4N@y!2k?za4 zHes5}9oua61t!H>30OfMb^J@rZMGE$_FhGi9%{Q_pqn1XMY1tmQZ!UJn2%jXLwL4p z4pE&&;**t@+%?6_-sUG)&UEi2sD5P6CWe7QZ@k@bH-9t!aVf5}g;(*}y!OTynyuvP zw4=FiHJ5r<1imk+E*DQs9U{Sh>lZ;ur(PQ$j~lhQWxvqV30{5Jc!J{XhQbxt&UJ=J}FETGl$5?`?qink_9Oq;*DWN4xXA?9c{>@sZ+p3gB45)YxgWS z8VRpzd}A#StM3lUSJreZaz9C(&2xMJZFMVbT%`aS5y1Fucge_2TzvmLES+u%s2z874gqU-KoN{g9dx=A3h)?{X`@+Oc*QC&t2W;x8- zGBU*xozGEvl~arW%!*xaYLyee0NYdC_O~ z3q3TdMcg9+q%t5l4U{;jhdQqjUE1jV!xA?{?H-7W*2=C1!C%*j#3^E-O&l(1!TjVE z$t*6j%Um$zqu4@79EpUQB#+5$-~nweN+beotuD1)vxeDP>k_R)7Cb+`@~{DYRx)L5Y&Nk3L;p-lAwQt;%){bP}7z&B5RaW4=G2H`)oSN+1gBFackv+d` z#^~Ek|7*;AU$l8rKi(90F4F{ek@;99LE-NJ*}ToMci-z%{nIi{cH*Fx>N}p8T?vzi zegTf>&Xw*T$>>So3!RZ>hdoAr(0u+qeUJCw?K`p_>NCETIXc>=ai1~V1OE=h160^J zoD>~XZ2cQMxHt3kJU_+gswLbrM=}Xl`(ywo(X6h!N2Kv$nYGo%#@rI6Uwue>?PmBe zcLu6gSCf-$U6kYq9A_O-xfh_=6MZ$`uG;Kctd-y5RIAr)HtQL_Ysz}~{Hcn!hDLz7 zhOOj1|B{4#sPmeQmXkMGfgUne|6W!RQ66=GWo~(>^35Rb)vafgkP(^_cU$FeCMOW0 z&WgrsBfE@I7Y_xU9t4&9o$*sSe;CN)E&XVl{T_iabvW1@FUBYU{S1doFL{8TvL)k6 z?|$0M_kE-uvJV^HQ{}$?*GIp+1H8;m&%iy`ad(yjDnKWmT1D6cxxa12uR!1 z{#%K#l--mHuVq$;RL7?BX>+{1JD)nLtcR>|9mA+7Y-9$Zep7v$t|&nQDq+pP>H}?7 zcJ_09YJQ5p4Tv&_9!POy2c93ku}LqeY;U4;nT`&7Pgq&b}UY)-_3ciVmxOhX& z`z^@AdU0*=@%Np5smH!s&v_B9A|El(N8NM_yLeJuIn%eX$hZ|X!P^TMl3wc{Hrl*DLW(Yc3 zYWq!z@p2p>JOZE*!ahuR43?}mXLQs^oq3u+Wg8MU)WeYp zP##&Kl6B^BMILxVzca3V&#^Pd{hI@Y%JU?QyadyKiBa$(tUn@e|dSqIrCf{`%_+o%*R6t z#X`?L)#E+}4a!)!@mc}*<-28Hf%oL;;Z-$_wZv~mZrQb6jL(dWnm>gIEu+A`8?lzR z-kffI(L@ghqbS2dSYukLE7^St>N=?rXY9(?V_;O%B9JNbtd|?KuCRUmCD$6;y+X|< z)~ScNy~({zy~XQGf(T=pkd$>-gV0?nlZ{)yWAimQt2~E5iTd-4pG1V)(h(6Z!b341 zFnmJgRnl6A2aH7BVg;7dYbEgm1@v4BD3UEGnoHlpU&t7C^YM*w=>BEy!Ym3`Z3y`Y zDzxF7w(L})?8F{b3YdBtXT?fsjLRl^l-ziJo@ViqN-pQLAvl@0q&(};YVZ3fzbjPD z$iR3HT&Mw5!rKuqLHl=O4-G;d>*lWbtrz2b(6|*b->0DDXP<&xP4;KqyO&Zb%p}}w zSk!SB3z%HVL&yi-#lWBXrr|w+ia8iJPJy#uJ%nlF%T+X*)4pN-ke3Vu93D2lH&0W0 zU2J2h_5&`|h(9YE`;_!1+&cHRniKyuQ(A0+5zCkCz6vB(pVo;-GR?*N{+*%<+_Qod z&*%d&FETEJxA_`R2~V=s$Ba0$KJtv80_Esmk2BLXYB5(ItE2#Rmro6@Q>?b|YmB)~ zNe$vGAST5WYJjAgA)@Hi8DrM_=$(#v0tVw0 zBI(>K{d3V~kC)eZr3*7@j2iQ@dut)1oGB^94?4ZM1+yyt^$*F~EQUO?R{%YV$}N=y z#frv8+{g7c{oa=2Ew2@M@SZ?$n+yHW5|E@QT(K;Zm3HHi^D;MAEpVu4$`G?C`eIjq zHcyAUWOE7X^d)i_GaVniUS-W&tmk6)Uf~AzDqLgvz~g@*45YvJu=R~xB2Pr$DExo5UPS(uo)k=Gky|gFJ4nY2fM}ILeg7jRu#a!$%Qa6%W z+gmoV%=4kkg_qFMX1#NB3*TKA&_lQ^-NrPn0c@(QIhB&X^rf4lEJAOVXwXa~;^8Wp z5+)NcA|;@7frv24B~3`Qf)z+E2z%lJR!`}-;L%ZxVBXlZpZ;1GWa3JG0*M+WlzjI z7kcGF0EE8vZHA9JAH{gwS(7ue-LeaR@_Gpn*2q`_G8Fi=LaC9t)*Vn(fT01G4sU69 zySBem&7bizuCST5)A;0k?dsM_`O9c`ks28Lzxuh5;AjImst+KeOi2FR5=$fFAtU&U z+KoFO9ZEm+O!Yl{wK@(b}v>(NPi!?|c>zxUQBq=`m*Gt2C&b>BHES)LZANalk zxn}^h6g(l_5lc)R{V~41>gSQ8&Hcv;9Zf=%(&W-JuUWKRIl)HG*UXMND0o&6;E1 zO;I>2h-IuYAmvKV_w7yQ4QAlJ9rXb>nsV6s0DBoeg1I@Q?2PB_l{Z^0D^o8hhmulh zd5)v+@!W0c;zBs66m#!$`#pXCA@00wmX}ZLw1sLqSWJ&AKe#t_>g*dk#65;{{gtX- z&=FBak2yIB-~HzBqMHRn^#wkoFUscwUjIQ?jo$L>f`!$4^l8CDX%V&U~*=V23%&;1E9rQZ$-xCDwmIFvBBI?UX z^$|nkWqat4tGU<2Q`*3Wm^d&NoTipwjnFJrjl)=X$kSW-Iuo^}c9AcL z00+}^GE@un^>~j9J!y}P@6bw*E>yKmV95c9uIRZG?fIAEm>;^T#o&K&%jYqTuCpXO zLz{b*X&U_}G)(S(-l7w0kn&Yvas z?<(e-=(Vromrw5l=R#*+LO&8=Y3wQ0^|jn)l>Hqw1|GJllFfW_jg#X+{N#iaV#2+; zo5X#*!R3>qbBtL|^JfNQ{8!6Pg1258*uC}^?-JRT*^%jH7_laG-KfnvjW1fh-?A1Zr;%QXL>j075*zhi(aNff6DgY?^AoIqpe`b~YZ^7t_?T}7SEy|Zgs z0xDTwKcmq2Y;X>6C@mg6*F7Mpy4}~W0Hs)*YCDgqrRphxZwh_uFsSl7YqdJbr{TBP z2k7;?mC(L2J#j}P2P>-(u(tz_mbx;@M`6+`U^9p{-;Nk9z-G7`hx8qAo(!w;%P}S) zsvaA-azJ<71*`1)0?XrQYjn&`p;~zc$it+yXpRJo|JYbGGzBcNuV~r#w^?-RtK;kU z{T@TZRN1ID7g*q+-a*<}wSxOuW2gnp#OIv}LDa|)I)CrN6M76XpMA~+7((9w_ZY(x z02Az+5Lj5a;KJ0Z#`!fFVr4a3wqVd*#Q$_(3pY>#?f7Fm)6HhN0iPIf3B;xZkk=lr zDXSN218zCmZu!9bvJLDg#eDIk>cxGC?UWZ+u6ydn+#Gr0e{LzP^2U|p{6?8lZ|^Ri z9^*Mf32p*khU)sO32%dZoOd)N*ptaOhFfWM#hH38IqEE0_=;yX)wXM;u{Pe&w_W0r z!q*Y^aLGo5iQ}Y2<9K)?b2M#C>p$Ku1HqA2(y=?2g*Lw3AVyX5Rd*%UT)0`C8A_nLOncD=mI)i@&S6wb{BUc3qD<@WKOnd} z8?lo~XZKgj9!H1{C{T_fJ;rQ{m2w~<%zY$fS>=x41{ehJujQ9eRP(J44ebL@u|7cp zn0Xu%67HKC{P^Iu1uU`g(KU;;tOvii84w+Laub=82(xL-bpfTnh`44wuslQ0(kTn7 z3IA77<<^Zn^!=g^PKuwO1-OFA&d&;fHS~&90ZOEmaC@r!<@Enfd+B-kDZTc-#j6tH zc(zpQ_v!XWSsR@df5Cu@mfU$c)ok%sxvOhxJg~gU7FzfNfuq7eI&XU$zL>Wo3hFwk zUsf9_4de3!5+98V-z=B%wNHTEN`S23Dfqv9X5Yqdi2+hj{B=MAlDGO(00DTcODc?V z*26qwWl87M2G{M1#=F#^fA5eZA$WAekr%u3<54G4U53J`t=>~;;zcpf5T0syP|*Hz zi;;?hUjM15Hc&+J5v$60(c&>%#z1z|t#`$XjsE4&AyY%oFdxJgrREnO^d}gnQtn%D z!?&c8{Z-u2rcz-hGjduB2u0DHfe#9SWh_BwuwmHA(u>RCeW5yK6eediBHNmR4`6CN z7Z(6)>BErF>oEjFGCsGxWap+PtfO<>4~g}DEl)%!$H6+>pm7r}F7blp5Jx{ym8gRv zwXMAN+WzRea8J~izk)62V^8LS1-*VV??L?_a4EvN3O^A?Mb`Hs;LZkZnKf3F-SOAy z2XhJB8N4?I*8R>a8aL7BM1})97qB|{PVS}8z!?ky&hS7YXOlf<8zM+>U>mP03c4V+ z^ov$)KyA&re%e2@{wF6jT^+4U=1ubBwr48^9LNd+(JRD<1qt@+M;vt@??GlOD2q2x z<$a>dPDu$7XCwD+nPqY-ej>aWeM9$edY!>f{O~j*EnN2NzgAV+QQ*SJ{+P9X&~z37 zO6EcP*J8J6WwciE31oisFVz&7aiYtBF9ji;-yx=s^w(sw*njT%?a0%(M+<2Z>}bwx z9UGfZU%oyhRpHnN;P*oet?G+;UqEfUW~qnhOVA&J5->zK7Yi3gM;}22Rs?G0)t5h& z0sE$Sk{V1$YsF_R_&TB)Khz8HxY_=8KYrjAZ)sIn0Iu{=ECPajl1(77*-;GdW&ENjdC>CHdl2w*@r@h7Nu?vC2(qhV?{h0(M= zkZ366H!cVBStqtR7G*3H`u8T>m>)Z&K!VNjYd9XYz@c^yq`Gl@uC*IP*RHpl?!x$2 zQ0meB{L&TgCs?2F;Qe82+>|@Y0p2cuR7B%P7BX*61wE)T@EnEG%Cv!L&;EV|6Byja zc?5T{UdQ5vJw2p@gON2Z0EW(~E@PWRL~5DzyA>oH{|d-9qRr5I?t5`3>hWP!y8C1{ zRjaZm4vdzT*32XjCIW}*v;0Tqz20%OdC+g&=0>hc3y(3;yUVeWzxj>nr3R3+P_aj& z&q7&p_t+L*{gXnZG4JK`^vk;lJZh@H{?=f*`5&c;)~YCKkpPrrwb_X>44qO~CX#Tlvs2?Yf6TwYa?~q9SiIJ)(6Pe|+NA5r2x%U-1C}Flv4J zf_r_Y?qs?bWQ_HcNBa0Wrj!8hbDcC2XzxC)m9ILs2>(wcq8|JMD$m#B+ljGLYg=(R zjsGU(WCQ#o3s6I%*~xx&7ZUaNcPld18=1Up1&v1H3PVmPUE45(?Ug|_J2gm18(k-#=GbviNA&AIHxGn|8##ytZw%9NCK;G zWwq)Dw}BUE-vKwBoJW>O{uH`ZIRATvs`?OLJVN>qpQ_ZNDokX|Wg~;!Z%4yBPA3Bs^_tZQE{(tRzUHw%T=;_c6SC=9~Aj-{bR!S7YBx^Iu!v?hMlI2C#I(f!_? z7YQkU82*w^ft!+&lNT9iH*|LkZx&coZFRpxNk5T|h>fid&%-o}!79}5T^aur*6?nh z-|%i5#U0?ZE35I8&>}RT=;_1c$%n9V4dC>c+1?@TKX+DI>v6E!_@~Ts^vq8S6CqYl zW^#Z2?+Zl^bmy{ggr7s4KnB2O05!V7d*G{fp<8+Qn-Hqt`4K#|fVd1XgJ&zlJ6RUE zyMfB(ng?3mU@O{BzQia2OjP%W95W>cgGAE_?|Y5%3TA6Yu~%JlnY{5K_`RTGx0mPxz%{p-|~WzpqNh zx@h>FH~2+@2?^IT98_=8YF0Gcg_+ZHb1Mvg6RcOy2)mB2%O{K0=M0`1Eac)7#m{DATWlnu52)!i9Bb*{;rOPv{I!-| zfS0$EMNi3PGuq#0H9RG5`C1xk_2VUQ^+m3q1$yxd)Bwn_)jnAa>ODgP8_1kp&my=Q@4N!(wl1o7szR>lLSC1iEGYu0U!j3 z+W7j>zh@2ymg%l!wNXVtQC}?)tnq?ir-CM;zpUGfA>{+s>7_KtJ6yVcv!#?6F{b@y zm_9$#L_58iY#5*Txqr~VJ8+Zw)~);nTY1mMg`%5^LiSj`*|zM++R%ftG5=gPQ(*Mc=Sz&E0$kp-Y?Fi-i$WUykYxZnc-3?(Fh)#mBadEASP_%D@0| z<%1@CZZrKi*?G#`B|l;yF#82e-sObv@$^`(8}L1Z3<|VC*14#gO>E%cfluRV)a#5l z9GCri-E2kye-Wa2ii{OyWky?2p(=+$pYLE9@rt61PTGv4tC42XC|2AP`F30}f+&2+ zh#-+l^@Qo7AM7+W^TT$FSHFf#nghYd9yq(=wKp^G2a*sb-?)*=mPoxLmO#Fye_^Jb zT;q~O2yt1?RuS{uvu~QvmSc?B1#Yp!A$w6t%AKUR*?uLW?e)m}FL&>G5(Dji38iol zY(-Rj=|XrY?k5Dq$HtmSyd~E3!$7cFYa_DaU4Jz`7ScjVKnv-Hm;6jKgq~Cj5)<>{ zT*dXKHM{h(W%&g`>%lB>Q(gtyH0guN&dU?D!;kguwdAljokJqnX zl{}=!%cZ3D&EY2-3c+yFD`(F=5L@&-GThGgiyWh-m<7X$ry9y4a(L^pNwx0{#RZ8d zl{|(8Jy%FOIO1df${tZ)yRoH8+ah0Q3{nR^bID|1I^|hz7LU|V#SocyvnunG+;{fX z5Wd3l?Ifif@0Qy_v^FJ;`HbR^$%3W(hClrHJ*KDlg#xgeIk|$j%{Te>+fsD-tD#U(PWjDsNimZS({6rpS`x1UvOE7P+b&Gu zi!VmPE1ZTNP@DK;x15-Z?TJ^@4K=_?$V3*>&~@kfDyO}fPJFTR%&Ou3gGT8l$FR&| z(Rv|+Y0C)WsIT!k7V`-n^TJgr??lUsE@Za&9=plt=_0&K9)>I1Pp_=3EG`;be>wsq zJB-*kfF1E|7Ada@MrEY%Du$VKftNOACzBk@36&XQdW_2^oOD4QwzXgQid^0+3)5L# z7=S?ZJDZi|V(gx(>Wa(;)-u6C0`W(>+0SU(@^Y1Wr%Krg&nA6``c#FcHe~Rp&fo1k z&-T_6TG$EM-h@W{{&S^;?0L|ubJqH2f!pTTK0L*M4@#a{5DGnKPv}j`LY<+d1W( z?MW4n$FfvX^70s~Ryb!0PI8}}Dk%JD*qoR;qPO54gB;O&P0h^k+=@FY3T_T3IuEYh zcwjf*e6`=pQKJziCqZ%Q=1^~|1a3P3{fXFwU0kP{1^>L)eaXVa&T6UEMhkmdPZTwF zSXh%f9JA7mRXiT|(%?<#SPXuZ>2y?+j}h0n65nw+R45ti(_#c2tx-1?GXw3O^lOmh zvv;$6^ZJBxOe0Coc~wr=hi4f#iCJ(|3g5~fwIZ+bUE!7VXbU}%&RFajig=&tXZipxy6lT8(^@s1Q$}*vF zJ11HPSZ2hRRieF3M&{MYP~6sM4Z3M}v&OBbx|=n}qx*jh4ws6#kmr$QIM?V z_rcU&4%<_y>7qfAzEXfFGvmX}|I&pKh0iN&L9VBAkf#ZH~>Pp+4-SUSf|t z#U5=Sw)A77GUFl;+AfU{gxHDOTF@GL-nKB3t4icc!C67b7rta6TdLoe>@H$iD89SqU*?{Noa;D2c$4V?`G1(dxy z$l0Of{fk}Mt*`fM^+0-gs>)hAcYVRJMe>{BtqreqpMPiK`I=!jg~9MCp8XfWXj37o zj5N64ez1pO02>E~0TBN$C~kCxKiO_KzT)#YYJJVy00Ysl)&JVEGZG&i@!5``Yq*#? zv2NVx0epFVV}mij0+KTZZYaEpr!f+cW;EX;v}mE|Na5S~1z_ z?#-8RV>(cfXi+=_9^{TIE9$%w{_*gYr`e2^L(8F6Ybf-NG_Bx*Gcp|{QIex3SHZ(u zv<3A&+rDyD2bzZuk3I+PA%@UoQFnv)CbbCV@iu#d|;RmRM5ZeFD+LfX}$jr&n#i)25b|B8q2VPkZB-`%+I_ z2YPQ>e`0n@?48!L-2R8UO244!0xq#QUNVP~*MYAX73jsXrSCs25)6V%t?!$def$(rBJexA{dO1M%n-M2`K`6*<~X_$2>NniiH)M4NZ|4KCXaO^k5Tk$JRN%67p`8VA74D{vfC@w#~4deMw7vUZE$00N=f7^tI4$Q%zto`CTzi3?_cK5?M zyJPx>23VNShEj|3Y>}<_eq;GA6Z>XA)^#ZWN$}=++FzEtZY!L8xnM^rGEebG_+-LY zF>Nu#?nhZjbN22vOkjU(tT8Bv-D;)z{oIxyIV_nyDqehXII#T*oU>V|8=WaZ*riaL z1>D=VFdm_4<23aE=hF}LNsv(53(`3z}iNWG+k{| zW~CJ5-ax}{eVgSgov}S~x{qxZzvXVtjYLCv#j5twZ;z9KimC;Z>@OC7FMmAIzb2uh z9?Y%q{f*0dv60Tg`CLZ!JwC~nmc2Y29{h7_D>W!btspb8SIC4a$t<&hq6S&EiMQYP&eq*w6E^bZhEJHzLUpMG?sM8G^t=c;jA6 z-&;&;Cg?^-Z_6Ut94EB>ZN%0(-sXvL!hkrB0(qvsE99Qn7)C|#$Do`Mg|>DFff*4V z3Oqdn7l~c4N~)j(xdUynyFPc4cKPmVFcjVSIS#A%Kz@<^*&uBS7E#9l;CvkIoA&)efk0jUb@NQXt3 z_>g$!Gif2@@*ZGp7ck5dp>bMy?ioBpYt5OQVao-q$P~X{-9k@cknCte(07n2%+RlM zszSh9(|P$_y)GA&y(n5X|Ft`hdtAO2+B2 ztVgSywtWq#;35BlI{Yjnj_^Tz#W*1So$bwm;H?W!2i}nd|wSOp02T{5y5{zC>v??|5iVmwzifwTk&Gd@a6Pg{HHEaY~i`6zvK!HzVmE` z(MN1BD-t%C(^hE^$fS%ZJdJ=S5mS+IKfBCTNYG{-hv{wldU<-iCq?#$b2;Pm1Nj7m(Y8PE^k| z9nkn*HU3X~9MVFE=gfhO46x` zx1YN#*XqnXWZbuyt)RyHWa>s#+Jm(%@^A;gw$d4Pw5I-T-Q3yqSlYLnI=|89qFS}i zbvqe#69Q)wU!P>KD>)FE=5m?CzCydrDI?g zf4<8Y>)w$ZgHyfk3j$kihLqn0n1?cQd#hkB7t44LjyW)$Eq7ne8 zm}8B6_wfPv9c~t?y(^@aD+boT{_-mF6GdsNg=i2o*=sDYw$O*Dw7`XWP=v4gb9wWI zVr1ULU?G1^&rGK}H}Hyop1iY)E{V=+G7R$&EZG{2=*{>lE5LT4c;~+MD!NJ8X-6Lh zo|zAcvPDldd>E_pdwdZJkor@5E4M|DS-NIMGUo2cnKXQ0pIZtnxS?Azmb;LX| zW$Xy%NOf=nUy#+L9D%n5$&md8cUwGlD5dTIx1}E)_JvUjV39v~TomBZ8mwi2Xs&sX zZ4VpAh{I%?6<GK@Rd{@Y%m=Pa|EulNo@7d35d0E;q!#G#x? zeBCA>={S&i&j(KLCOOfp-=!upcxiWStokvO`_5V7iNn(#M$rI|`oEeaH8)l+O#CC7 zO3Tz_Jn-U0h%7zjPI(o}U@B&6A|Mp6P)>aorW9aK9JB9GgYkDYauZ1|_BRr=)FpZF zMKbEmkD?t8&01=_FJ`}h=(7L|`g5mnXmGg(xg-58UyC5{4RkBuYAQ$TMAWkas=9Fv z?y8_+Zte&wu1G3Ii_#G3?4Ca#i?XRFsIyWO%Z?<=#qG2AY#shqyIkK|#~0u!+Lq91 z+gz~*->b}{j_{!!?h8^ePxLwsZ#0pzpMliowg_CIS^(BPYpxKrcUfhq4W5TT_Hu zbWs#t=N``Z+k(;IVZnn5a&3Km>WOofc9AO$x@@26bM#GU?KgVhMb5NT>X{_UMAPm_ z!2r?CD2G#bVBcA=k0|qEU>BIhb25&3xiODi)x0`+hm_SCbaTALFy0d?Tk52ivX`z`MWyq?ZHn!icmxfk zb8%0xod31A^7BWL-F+MGR`WWe@7I0t%D*w)|7(jJmtmN?>8UCXr*!JB_o}dTK`-m} z8-cBllGTVnxk``?qwq=6YDSA8wLlg!;PF>}=@W5@{prp{A@XG&#Po|-!=kl`=`X;Y zI($-;6`VO$gAv;xTBfVU*B;BSPg+m3ntdg6=alZ;zx9QED1?o+CaKekv(QnmC66$B zLWgWiLa6vgUTRui)Maz*H^g;~c(L%q24knd1YAs|Oexs(W?p(2#aSqkq`a!0>*YCr z0x=3Y_Z^xGx2m#=AFQhJ6#dEfiO(G$srnB!>WxzvC{<@@oOR<+EKGL$PN6G8yXp;F zP|$N``vl@LkO)zvl*y3ns7RG{m3EaT+o+XUu@rL|TQG>|w}VLBuf*?Jok`a<_r5Xx zqi<3Wq%#!A!6s5a;bNaQCzRP&ND&KUc5>IPDyu8g&?Z*sARVHOh@EwsWL1zOjmAkb z$yH!w#eW=LZYC$d7SGVk(aZtUah-K4sN@rF_^M2^YH5wIa`9@=F1UMUMNb{sVLY_9 z$IYvl!;s?Ff$WOYlrRtD!xa?~MAZE-b1S}+$PpAk@RM*)N`z2mjKw<6bGh#a#gZG9 zjoI>t-2_`5HiZCe#i(Ae0 zUxR`KXzO)-oloo>P1;ZOV%RAfzpwQR6(DUPrxNxjmkJ&SirvgjN5fy+7fWT_7|&^| zgV?Q%)$~YbWMpp9KOhvGADJX%jP<$9}WTKGV0TLf(pUhjNE(&SAHCyXh># z>%{hCXBq(i2VsQ7d^k-tb%J;Xb#j%vE*IL4N~yC8Oqs4a(Bu!nq-CHVY7-kQ+C+ri zgi&dvh5l;7b>OehEZAv{wHE7_waJ(#%)b#l5`Q$PP2)M>c^)i zpUviLtyX2ZldQJav0fI%%X>6H??a6pm9)zXpXOTmQi|BvQWqld>KuQpbV(QM#>dOT zr+i$B{Wulq+0-}^tciyVKRK2GxC2F57#`l$iqj(51Nz(EO#)}$2z7&jl@^xKe*g6K z*N69xj_n|QgH7(ZUMpqUE zC=^XSJUzde2)+lvJyD_HIN_~rfr3YFBagpcRYX4B#c~#5T{BgujSq_6-guVw2EEv= z9x9agLOXO!SPM*`M^#i?&4}6DXKrzi$4tog;7G>k=40#}DSe6Eh8L4Pt=BEiCe5))vQ>hlFln_hgZsO z5x{_X$~P>DjP)cyA=3Q;`iYL1ZjN8jH-X_wXQ{*hSEcqUSAb)p7|w{oK_~G-556qD zdO)IhX33sD{wyAQXL#izTHdVBByEeVpb9&Jk&HAed6scxEg#>hB))|{;Phe zSHV-rG9;RCJ#?+#XOwt+wI|TxuD{`B!rb&kyXu(DgBHe?(-87OtsrbuKD&%53tJLu zZil!OND{deG}-$;5&(ycYhzL0r&0Vn%%9C~sPC9Y_?VyW{;;1+gitr#>95d5-fR@&Gp{mL9kQ>KM4)Q&iT<30NXDlej**R zI8;3B>ssm3wgha#-RHFvCm?URkHnKUW2bswlGETH+skAkcS3?}6|$enZ_ls}o-j}< zrwYE0y<~l?#LgBwHYP%-(m`6LqgG{j|4k@88EIEjRiU1vHzT@2==@FFr`?dB_^Zt< zv`)Vp<~46BfS7Am!1nnVa8=_A6qCrFrksLGk1LiD>Jr><1 z7D_P25wd6HsFlRl^bUUoi9C}pU$^1kL$I_lGJ*nXN z`+oD6&9auZ@Tj!kQaT+|;o~Avqx9xrlRrDlG}}4q?7jjg2z%Y@p#@@S-4J=c={3>` zCcbz=tK!D7lvrJ%U7arGoNjmjM~n(G-EomP7(^Gfwq=8#&KK8{^D+q@ z9`2c|#+ndFwZ|R&k;y4XznGApW=74i$hoiZPP=^3{oUj3X^s{kj6?1pPF~-l3tn#yH>F3>(fUM4KEBGu};b}L>1w^a-xk@8;vBgjk za{VN@Ek8Zwa}hT3|2d^+_EO?01b6yH5u9g?+^}Tz^`VIdp0SsWUy#3-mWW-KF!a-{ z&u-CJg7m3{a)9fm@1kYydT03c-$ygN(}^u_K;_&5Mqw-bAZXVFhTp^CQ?mIcCke(X z&9hcETn$Ugx!1_Xh%$eL)jBQ?k57TQHOI}m5 ztxwSP+18;IpGeWfWq?}MymCY0Q-7n(@n3({5PS-@mrP#NpS29c>i{@L6`zm*SEJEw zaD}rSjp{5BSJ6WZE{->>Y0E25uW+MyqyB7IugJw%dw85JCjf~u5Zm


!plsER_WS1P?J41NfhQ@d&Zw_i!X@H(Ij_91ie`J|qU&2p0H zu5`|KznvFIuJ)tYQ`nD3Nhv`erXXfi}no25IVMqO~@vW~b5a2vA}@$dmp2 z6LpBbOG69SsL$ekg+=_JpKg-jT8MAjG3U9l-VY_pe+!_hu-QQjtPNb8sTGyBNh8sQtxeL`x752CZ2GqA=WB zMMRUvcSN`gyhf=AT3AJKzTi*3tPonPiu(`ApFPOyjD~BXZkq`!GfpM^W%=sgMXOzE zQ@a;Cg-FOh=+^-@Dfl^@tFO6wtEJDEi#*Wx!@3y+2Pwp#EE(w^iE^g9zu&q+%Hb(3 z?b&6B)?@$3x}p>UfGFowSmS-M&^>G-%E)@&B@-=yjNB!}0vO|BJ zsWi>t+XuRSacoy_)_!WXzuUV?lgw~PQo*JK6{2gB^;T>BAk3|C z$7dROMfMkHkJ!+^W()utw6Rjd=C(ZWx;{*0Mr7-xfi_IlZC($6XAJ$vvULL$gLHQ) zwIoY`wf?}3sa%Hg8l1Ru5yLM<*?+#`B#F0KNkRo6ZynQj3g;9~A7TJa-3C2qVL(!H z@2%f1hm;t34nAD$>Db4}Prx1k(!~RfpSvFo*Z{-Y1jHri))SY7d$979&)mzdyM ztB02*Fl%)??f9V7$?$w2yR{I;c_^kNUB>i}TjU&9Jcp`QYEPm2*ZQG|jcH!EI2-WV7tkg4tL*-*WEejsyZkMQC@!6Qu`o{-HknX3s zHNL)KPd!tG0>$ZYoC_wtd==!{qg|-(vKlSkS;KQg(7TK5H%Y=dS%I8a?$`-6uTX{O zTzu8`#U?FRZneyHI8uK&+pMZVLN~-W`6iAe_rq$j+sAF+#RpNc_7z&_?THYcSvED# zze6fHC%k-8u!2WPeamGvx|YUgS_Ihst~*KpMN~~d{v#O&Aez^C-ovPThSqqzEbi+Db z7GzrODz56$E3#gj>^G4a3J}_56R4}m4DU+0eEE~BvaZs-_8sn**>oexZ%)s+UIivp z<)$e>+$d-)tpsO-3=kVvc)O+sdM&<7W5s3_A#=}Q$%;DK3Dd_sww2)X?%Jcdjf$K7 z6DWDM?NAcX800GZ9(vV%5vksuJE6$O4MR;oc zMN*5$-Yly*6;ezNiPwxEiXp9HF?HH~*Tb(&=;t4RJc-N6ex$F!csw{b=qHf43r+BI zzHSFJPrChK1IoW2s>8=p*k4mcDxdjX+ib5d>9wl_(Pq8XmXg^^&gZFMGFEuRZlr8Z zL+wgbFYf)JQS zouOGM$S+a0WhHc^)-s3+@^F9jNXk62)XL{;5dDX=|J4F4>S&m%$V@$NmQAH}B>B9q zfM_tsLi5*ulGG3hz?V4;hG!L@kE`~&qEE--{tnES<#1*y!!Z6heYc-|8M^jtk>zk4 z$dp8piMca*&LNdHG!DOS_@}HklPy5Q0rnDu-ip|1$mov}=0~LuF*aN0k?=c=#EvBA zJO78?blk4BoQ`-aP!o<>lQPqrtLAoDwvelp2g%E)FyX%bvXU3}J%jM5S+=B|F;fAU zX9EDY=84YQ<~l-daj7!w^@Q{ON?zsKTkY^aJ1mM=i!2W%osO#POPU#JGe*wSg@&&f zkgIKIe8gZQSu$H+<$bV{0RK zYl*Yq*KG)&7Q)-YT7OchsE=A0_W?8i63#`9^owYT&V(w>b^RJUSfG5AJ8XR_qMUf( zk0wNW`;AMqrEfgksXy&ephu+x9Ag=8B!PUBoR`5BilO&x6!{Opp*?s8y8{Brd(zu| zM#|K%uu;7VPSo{^B@RgQG5>!~^wynnR<8hyg62rVNr|+j$i5RT%xvcnI~0-7{cL7t z(mKU^zMROW(Z~aW-f5uS4MOQZTC2Ne862;w4XArC$GQUDf}Yl=Ho{BXKQ%}xdc5XE zgHjy9p5Aln&XKnYjkaI`e6Zapeo(jrjB4?rB$qthn_ba{--!%i;{OJB-}r432_R31 z($jxQBD65vf4}n&{BwYhDhImTLvIn8LzPUk|J9+9BraH3X>1`@Jp_P;a~l?^aDo} z;f)sf#;NNa^J)CB$xE8LO0FP1jT$@l6ox}!8zA2WVy6F|ELEe**kPe$Oo0Qa3lF&> zmk1PYk&yYHxPD;l!HN8p|E&NTr{urCkw+vk>BgP-H~&&Am0L$69;xZ$a~B*LYN@z(uV)g;*e6-Xx+Bn(?T&Y^1lep5EQ7$#B2NXV4M@Uu z0m}2Bh23YpC`|Ku%diXmYs;MA)Cttr;J^W=Yq>Ma09$Rm)UG_oUc?dqxuQ%gK^Ta)>5!h~a7+aV=k1Gbl7Ln+@x3!H95B$NC3BVC zNE`%^!vKu!)yo24?&&vwH_cs4Kf+OF(eRPz|D)=?!{Pp(_u(Z$A`&f1NRZWAi0D0n zgy`(*y;~)Etg;eGbRv51ZP$`uiJs^sh~9!A+UmWo{VmD+^L?K4hl}fSo!2RIX70IX z=A4DyEv;DGNc_EV2DF+TYzm+8$5~&+tD7-!+;c%4v1pnlb)d8;c5bZ6_2fD56D4_! z;SRUem5w0W`9Z8WiZtvIaS50x$&m>`@H2h?HG3674_|tEIR`+kRz&JU(-hWt%HY3B z5pd}x{8extmS%Z_e^5j@n2XYX$7SN{%SDs@)5BkOv^zvzCW*F!z6IVTCitgICdqUU zbfq&zUSj4_2-0-qz9250PT6QDiI#hY*V=FWJ1}Z~UYjD|;e1M1!*_oc25MSC%_w z?`6l6mw-t!hs*y1@NC^7q-zErSX7g~s?|L+qO!8%qft*zN&z$CQ|90)ue;ocp&by<%gR*|W zMt%IBS3^{hj!yk>4G<{Zxu}NInfR_$pUY_WGhFR1yI84drF`@Qk5YyTgZht@2LL|H zTyDi>9zkyQQ@+b{75HYM)T`q&wXkmBDkA7>R-I>fLLA<|MKzNRDCtcjkd?S}{XXbl z_8Z7>sip*rKXtA%86*UHU9L;%%3m@jMrU@91771tZ^?7MO8HO1_|>|f_}Xw;5&)Z& zp8e*XkZeQbXm_IK;9w(41I&*G2EXa#QPoSbnQ?)2N^TbF+VvRt@wm~r<|B|)3K8Gmze#+F*;cvGAa!tA58@RTJh`?FH+}s|2^>SNw$U- z=kwx}QD5-krGow@c(a^~d?3H#)YjI!$0g#m#rvDjjNU)n7v|~?(KA>c&VVVsU^pfT zBA+_@bop^JenoVt7fze=VU_phwy+5ozY6yUb1r(CPIrm&v8%A-?OBKz%?k58{N`OP zuF_##?r&wj!Uo}es`v6*1|ppwE_+cygdN`#%i}fEJKwG7jmCbT9nFM&mx(7QKbbE( zo**)9tT>gyHW@aJNt%ajzE`y7V#C=V*8OJLT;lz%Yq;x^FiyxI)7!`vWow?b-z8l3 z`q%p4iW9ZVPT|9qk01^C2cxaGbuO3lTee5B7=}IkmN>aD)K2)3Y5nexp$=IYT$#bm znO%%ff2vFJB=_lsAomZ zlawdKjAs($b$D1CsmV37JC>AWaUyJP%02T?L|1hGotHasx$;8f`F+B5rB`0B$}aIc zfJD)A>!8=jTAmL?yrwK4{$hOR7Arz0CSI;f(*8x5>z;#7<{%oAYiw^3hjRi*?x%!5 zfXazv+TBC?mLzKjUaKQ- zojMFmlBQM_GFoww%pSfb$E(Y>&8%>!L1D&@4Gi23#zxorLDpiLHq)@x25OS!i4pfY z{nNx81>G7Q!#hvf9~PQl3TueMlyk3hTxai#yv47@)lbzEaXFSt~5bfEo>uL=4WJ5$Pe971$iHY!)8;Qujbwl<5i@82HeGFE$AYG=xYF`9cKn? zsMwzw2|dhFMg{ObW51K99KaVGur~qolff)LSF1-I7o!(yOfM86iyCVUzMze@Qj;6e ze~vE+y1+M`iwVv+=Ot*zd+gcMp`Y1=cS(wynktOf?(vewg>;h3xVRo}L#jJ&?&bX0 zW@_Au^)v6OshtaXF@oO8BmeOJD|{=g%|cviMaU7-h{Yv;+jzcEz6?1`Y^8w6L%XY& zE|f04nX3ZFp+CFIojebWWhj9D#t6ful(_2LV973k4ckPCdf> zoJ%*A{Rim)A4+iP@ltVLv@1TXZVyDRP(C20 z4NkQqFCVamS%Dfhfn3_;p467ATT?sDswtE&FZH#j*-0{ZcUNg83|AU*yiap7E#u0s z99>jaI1_(Nc_dk8^k^z3gpxQkWW)Ep?@_F6-*`ekikcNTZ)aRq7xSW3OIf~qQJIZ8 z9E7mV)wJ%7=bqbz))BVdf(|B*bYd zYGZgEZLk=V>o|7wwucSb_GLYoUfqTQXDvE)FT7Ad1L3joFLpl$!IE^|Jhs9aMjuZG z4`ZLNaaUO?wYar*7uiYDO*_VQUyN2^6mB5FEP1%str1bi@PD>XLI;#Yyri4`%DMh6-{yxLm_$Wwq8#bD?nvW#OixYeLjB>z;l_$1nXOxM9 z4g)e@Kp&gjgnG?&q%`-vK?0`z%WvD2$3jV*{=_l+_;vo*UC~`TArDwTV{vTak7oYG zzZ8e)CB-p)LfUkZ|Ci$^f)zuL+PuqX+hRTmURmx}S~QYteiIZi?-2KSffSnxwjjBD z_bwy7w2w4Za)(RM$Dbnj^3@dN$jNU8x8!di(Xm3-t8m>tlr4A1fpOW~bD+85lrrbb z;`WOEVS1|P6XqKt@c8bCLTbJjs=`}~3&{~--ROw)ki4oE*PBZKg^VBh@~tDz<1_Z& zZm2rG~2Ye9@G3pAFk znM`X&A-zT$BocDth$pgzd|0Lii@vHIIx+L$Lo-C-bk`$>4e;>OBoEHW5Ey5;msUxn9y zbMQdr;oe~j%vgJ%7BqeKizwOsOqwz1DX_FTu>N>6oSwI!d%Y@@L6{))t5|{IbF8Lkp7wFwhOQFi zcY;}Ylv|Ia#=KE08y`YK?8sTG%7Y#~p506T$c#e`ELL^zELi`tqjFpEZg>t%GXgJFSSigIdEfUm zISjhYzN+FdH~f~k*sRVcx1gJf6PZXuO=Ck@F<~_d_UgQ&@QJ*`OOnc`5=C)c$spXW z!57waCr(Sku=p)jLWNg|TRF7TE1xd>x##wE;FMO(WMAaA~f1)zS#wKnuS?K7P|>B2n#*k@()w$@oM#!i4Dc|_{Q3ni%;tZ6c(VvV4R($6QFRA9tc;`fQ)f zj1i}!R7xtYba)A4AbQtHK3_C3btrmq=nDkfRmOv%Xz2DoqBLTwGt++{n}&gqzkpW%j3%9w7_H`3c#4!CXin} z`9X6I%FcM);6xN_q5vw<5Qr0nHED6Mif}nE8ZDi}pnDR9B~Ot3Mo~#eO06t7ADpa> zl2j)5Z#*^&E8O}+f9aPqWsYg;nZ)ANwh@+SKWp zs;Jm;vvhY^sf?x8SJvlxofStsSqz0e@X(V;nCUHJNmi+?O^e90aDK6`#tt^;#twA* zrpDjq7BtihMcIA%+_>tq2|Gk!PiQPeey~r)hcKKg`PyF*+7MiTx8S4xw-+3j)zgz# zZ=oi!DU6kPtm4?VhEy7pM|Xv(%Xn~AZgU#S=SfuM!WkuH@nF=U=SXJH4@lkP*rb^0 zlg4YQ`Qo;qx+VoqT_wHNcqYq9cP;wqNxZC7_N|kGr`b<@MrzFa6 zc=1S$_|f_)=MVS2!=>hrJtC+2ahrhxN)R_GC6shFHE>!Fb{FM8z73?v4Aosrjf5_o z|EhWSpn{iud}~uklHA8A;M{et#W&yAWLO&Y%Gn>Wo1EW&(VjosC%We=BgS_7-$7>H z&{fBtZuy@ap`DHUyIa`XoTxmV&gR-1>fTEj#BD*ylfw(rHF(4*RaxeN<*Cn;gM5@Z zS-FyKRr0)yBgQXgK>sRdeY%UHx6mK$Ze z?t`!87Xzp4o>QvrPZGicpgSitOVTcqM{?-9gZqs&MYn8Gm}ckHVCxf=BJ_;l#oUR$Wem8WcI^>)<>`%<#90)@(` z{d7DLKrK&*h5Z0l#`oxuS;=cT7;`4U4io^ocy4W`JhT*uHUo{t76-ocm~cXb5Bs+QT?{f&PS2vI7xfs1O%y-%T?vz@SByTWkKO&!ouM z0?`P}aYNQv9h0Sjsp+h5)se^6PYhkHh>t(i`nG7-w z)s09~44w3G#ip!>F8}2%LYJ*pT1H~e>Rb5vL9Z#+x9Ko5v#-JzvL)FY6>zbh8+6i0 zoTiO;_eQgZ&K9Y+5$HjtG+lJZ9v7}Mil(z$1wh-??PKsm;ZHM1cNwv%he0MEuT40p zV#ylnRb`$R!}WdHr)8{98V7e%zzf>Q3b-D8GCY_wU&Ko)h3(E=dHEk`Ne z-Tixqrwb2OGK~$^6{=|$xc&|>hkp6x&J^sdx5<*cZQwQA(5m03CHF#fE+gnR^o!;+ z8tHUfMB4vY6RffoSyh`00F(<{`>3mLkhcdUcqJ?YJ&;dWs~1UZ81G{Z&MMl4+5kUS zRUQ86T43*&4*0w`diY9PJ|jPv_?@N>)#AeHGeAF^dL>6k?!|Wx8QAg8w?ntYkrtC& z48~s#Q11|d2_6`|9^zS-9c-#6Ja&n*_7O5Ye`$dD$7XyC!y4d|~E3Vb@g zIBkfHZD?pw7Zw(#=_s&wV16Q&0d86X(y7%f-QZxWC;O?jJ!yg`J&y=bMVJcQ zb@T$fzy8MEfV!=|(+ETj5@t|%M2^7Qrkm%gC9G#<|GO~Ibi!D7hM>c-ru~hDebFb2 zU5;9cV7w;$I9hr|Db4rjhJh-)!)O^0$Wk7FyB=cZxo~+W-mN%9yeiEeNDW?FJ{mvk zcQHUy9K9c|hesAdoMk{{ix{h_`Eufj)z4U_ybl;(caimk1zczP{DxfH>K=gn<_}rI zP;yIiZX`AH&ve&57=^rtlsIIYk{s6tXoiYb2<2c$-(_C(?C)F*$#o0x9UW$bg}oW) z4}*T$@`rt;>e$)Y-&tL?zpIct(8;bUT+Z$DvpIPX#}8JPc=-s)%QMX{;Fg#C@pk_` z9Ud*@oZSsGfn-@L0hu&g_Nm;B4J%6GqOce%QIckU#F9@2BLN{{`*a9bnv4IM#5CKf zpL6Rh_kb$D%wApU-(8A7i}6Y{h(^&<5Pl(ca%>dMEWxdaQhGp(msx0rt|0SZkR7k0iyWEC9e6Du_8_vuoHnE2EYSJ3 zFzCQ6;JOg}5&B?vLjLW~6zS{jw4$;f*TWkNcNf-9%sduxuJYezj3|-o_oAN~_3(Eo zr-|?#swBHDZyxk*@@GGMDr~I!6K()$1^qf8&;m=7m6V3iW6yhHFiq+>za4J z7iwD=l=Y{9y3mjTG&{+o^i`j^9(DY?^}kW?%*WMFD^?vJH?vHabvycgtzo!>G0<(# z5{!pmV`|qkf7th+waztX@*VE$R|kdgbvbt5LtGPtzym;#re(@H1gH5s{*WI7tL%WV z9FA}cNjgK?H>S7I3ZCxy{T|yd?Vsx=Ue}|irw4(kt!r*{++okG<(j&;#qv}=3rO+q z&5#&?+*JF+Q!oFM_T1;Bb*lSt<5^Sof2%DurrYeT!l)Qj-;MXqwFDhV{8NPRs6?nE zRvnMyqir&N?swV!6Z0Wuo#E*dXd1m4t5OL(wkywA<1_5E*!`qoAPP(cAc(4_c&wNW zE&)hMGi*DXR3CHrEKP;6` zY2|4~xTLD%Rw?jhHe8aOc-KDn4T)lQ|kP}rYv$;usd1$`|Tuk5Hi}Av(FCy(4c9xl( zeA-VbuE4X z8d9J!Z-(8b$vmHb=@QUID7-QeJ48wTc(i+_f2JNQ^j<>gC>$OrHzL)vAMQ-w4*I*H z@?#E!)o6Z%Xjah>^|3F}{|w5R5_3}NKlA8VTExZdaUN>@AD+NyuxBn>!>_@bamcM&_B z-qJK6vGzu4*_*M!vez$1VO+2vua z4+h3)O^f_?_iAzl>JPG`M%~aU&>O@yG0Vg$#b8XCpJM?lgJD*jXKpF}Z9e z@9R6IFaE?vig-&;Vp&!QTq3+-yL&RyqW%%kX2vZ3c9p`RhKX3@!ofnUCDrl7tEzIo zySmdwXB};AA+zAD3jw-l(&##ECQTwEg91uO375RQSyqkv43eu1C(1noZVLKS6F#LCZ2qSABwg)HNhYM3 ziKK;T-+hHGR>`}SCL`QC0q_Y=Dr7cbZmfqB7XoA&B^18lNJc`4;V0SUxs|K&@_=t4 zLK8BqmLd5e2*CvcjjW}Syci1{`A@(^6s(}G!-&e2_XG4(brtI@o4mUBstYnMs1*h# z57o-X3>j`(#h$Y^7x(*p+e>?5<_06$wnAo=~P@Ri6ja|F> z+lYW54bE|WD{eQq-&b;;YGQH{Ej+N?f`*Tod3#q+{S$1{*K6Oa05?1=zY3|fH*kn& zY)(*To>@)QbL?he{CG_jJk>NjKHM--cs$&rUjmpFs{?%QEH4?M0Vw9iz`={%VLFXz z-LPwb8(BF&L^kh&|FdW25J<(8hqW3Xhk&w*g<1MgGu0Htuw&?&v1%MOUZgu6yK7+r z`mH7;bK~ioF>6=V+_|5;^l0@@EM1bRM{h-Ml(?f4S9T+KsT|G+L4iUx)6=b_FZhC8 zsWhFIj&Iz&IvLRPh!=Mi&1rQ?*E>Rm;Q8W3vVK|%kfLrl9SI?Xel5LadC#XXzt6?l zO2f1G^lb|V@mr?NqhG(os#O+nC2Q}28X!j9nl*p6-#a@4lLkl2>SbjA2Q24S{)mc) z7PhVP?F^+Kqz83T3Q~bAt_R8r&yI5-93)NF?yuea$=M0D7e9-h{*y{^@z@5ygn}#Vkk7IKNM91p2_M_R0STZLB80S`=BL z1^`WYS$@Jf$~WEj?-Iu;JWf~La7*{pXVV$s4uMy`E`y%VI^c%a?~TikPf;thl?hZY z3(IL$wtCNmzSVjoBFP5NyHgym)kl6+%Kf4RrxYV9J{e`%b`^u#wIWjdq7_-qM3YWaUewmQ608OU+7^V@^;{`Bolwu}6^|kS30RIe7Pn?{+36L+7#P zE?bL{tB401xTFBbYouhX356U*}Mt}w81(SUcRDmV2LNu zBiSIZ;fnD(^W13WATCM2&k*n1(U{_pv=k5CkjDSwre-}#H8DH8B|O00hI=ROsx^j0 zMfaC2)({4#Kfe$J~D=;I+ z;{~-dgj?7BcDZnlutQSPivgMAGNZXWw!w93*nPf>YXI_{flOIP$?JC{ItF=hGb`=y z!put1`TLSs6~f-JHw{gz{&Y(NdoWixb*2J!TS#24Z58HtPE8|mFyDm_KXB(D|x zEb=R`c3-06<$Y~7GLeVSgX>9!dn~I`X%EEv);0s(KFZL-z z1MmS;VcJhWxZ4n#Y`(o2-M`#FBtH3I!NvbF-T1Yws|^HjV{6@wMrrEUB#2(`Y^(G$eb@jmlC zHghQPzrHX0VbN;-W!NKuR5iY2kazOSV1n(#;OO)A{-&zB+GYIZ+j@U|aBs|wx(hu| zZFVLZ+jN>GefzEY#OD(v7iDcL3+nZ;%`*&pi5!ZT5JBu-ex4DA)NkKfx+i>4{a1zP zI{4e*Npc@i^Y)EU>5+~F&++*$q*u=b<-p-zleyVHJ}IMFkZAmtEukJY2j_T1*Yz3T& z*scmzDMk5A=ce8+z{skj$d7 z6|ggzi`~95zmpypddrJ-KCIQ&cGv92(Fb;<17988+<;U2S9Es+_Tp^zZ04vISvI-v zex3*$$=HV#{|6FyuTcTC)4$ou<1-(AUwQ;!ZV!1QSF)F3fZ61AA)rj9w3-aGjWgNn@nGGs^aP2UP2J ze?Ocpw(GFZtNNfMyaiWI($^M_Ii&qA2q3FuXrSqIn~J6qY*Ph+PN?zj7FAwUTI=I; z=*pbezrf2=kXqXYw$tLh{dJJB+2GCZQ!6F?Yt>tV;QQp{=*~_+b-MGzc96&7W`97~ zG13{bKt$9u``1PTYrPM=7XZ*cY}O{HLZw2Cd?z)H(C>3UIakt{yM2?VO5lAOo@;nF^CE-cD73#tyZsy`)T zQNqvS>aj2(32tedGYLF(;?qkO)&qmgHVo>kL@hrmT7w*qyt~=vQWA^R%UfvyE)Ud1 zx|Jy%rNp4M6UYsU-#w-m-D_b8FYnpo-$BmI4T6{Rm^s}(lll64E>K4F7*j2M9#DPI zuD5XMeQ%O2wcnTbz*q zf&KiBcV;RYyc>7>7P04pcM8wr8q|7q48b;qg@uob3RZ{TAz`0MV-kvQ*2Vk`Pfg^M zyPqF?a7K~DeCLyB1Ob2kgFC_8L;$7xh4vNi&KrZ#UV&TkZ)Vq1NwgQes z>X7?rqajlk>7H%g^an^r<=P%D8a~ zBqA!@oS_SBTupph!!UNB9X?--6KjN6U+PL?{6qx?^Vvl^llpxTwf@LjtWrY$y}%Aq z#+liAn4r{pa{SGpTR_4V-t-T>puc;!a_i6c z?6y>ZMr{tyEl=t|q3@bz@H0bt^^D%<{*+3N3%)I93wFHgWq$<1{kr+yHhzqs;FHF* zy>b`j)0XGp3jofoQLzq~LysMI*N2{yVn-)uQ|_za*w#odqQ}6G{3InPYtVr_JO_S@ zMBcAPKVCi7YLVko%TANKkK$cH5Ax}Nc;h}w4+H&o(ISc+Qpx)Zxw*NGLK@@CQdC^3 z+Bg5a4v^#Jd{*(bZnun7xOp~lf~vStygpF~raff~8xwGJRLsdX2Br~Fkq zCnqP*)D?F#BTri=Jzw`&_ba;s6pya8HpgiaF5f8EH!jZ~Exg!oIf*Z5tQd_ilBk(64PE zOi#ld+RNr#PwZ*5_=Gc9SqDJNtYDJ#4PamcIwNy2`N8-=>NLDV#=lJ;M7WWj8D$)# zFC>-0h)4FuG+S9dEa!$JAS=Zd-dEE-vM*%9)nM@B!B)t^t!B@^!>$eG%0e+fOH{u< zU7JzE-7?(orYAd>w$>&ELc%FlcxzSF*q#v*( zfZv+P7&N|*{Iod5iWj)*k-+je<(spXYFOoK%Z1+V8aTW}h$D|9tel4-YJso#QGmsc z;FJDTHl=EU|GcnM;N+}~o*})rp=mWw|DcESHALS@3NY9qp?CBHq|^g3|j@BMwj=a19-1QM@4?_R>v#ivobi>ufLY} zE+NeA%aEZL0lFCa_4f}XIc{)@f2TuoSJvs1B`%IlwnYWzhArB zmQV+O*qC<(&F` zK>f;UUWqdqwRCO!Px-_mveuD z@tfLFg#XWZXJ^g(BVpg@kaUO__Q*gUc^c&`A6OfW+$4GkZ8Li@jylJyw!T?kIrH^iu5HbHWpV6h!grT z^Rw(W5xlIDFs>pN9a$A7E-kx9?s3-f%lg8Zj0M34tNlj-;F@kwKt5vet_2;~TaG7KLqJGArwSKc$o12#TN@bGU23(@qgZ@g4F2is>DN=-$Mcsq( z`P{d36F~YPkbb;1C>|7V52lXa)83~GcgqVH6v5xA`9vCbeha_T23(p(vb`F6yakjF zqYyN$XR|Vh%$`iqhN{92QhOIiU}$ie7((W8mSQ@BOBd$a7aFo9l$wF95nOt;DNQ`Oj@Ry!|xOW8TP4}$L?uJLCWT;=caTKg&Bx=pA#}i z^0<+f8%%@se&I6l(JAr(#}X$&DH>yiboV}mBj2Oh>3cG?(TpS;or)0i)1@M@bU5HG z+)eZD7>#`OJzMF&wvZf0uuDdgBgDyXaWF~8cJKZuM!+e+p!6W_@WC1z0kewk*ZO}x z76jPqw+=%Kxo_p3>DZmjL@zcGXT2pEH!w~&)@9(kVQK(!8JW|mYXYF__~wP|sr8N) zj)z8kSyZ(x!48mft8Yv<3MNRtNv7+9d_4S0Cd|$+OvWIt%$vX0$qg7EwT_f-N8cfj|TNS5)vnOf1*bv!JqFS#eH>8vbx2HWbxjZ zy380L401ZdyFvOHiPp(#wuLTDoIqkKDynbxoE4+}LC%lcLEhJG>HiWs(|FoXj8m6z zSF=2ZqaoSNMLe4D5vD3(euHdr&Nk%-r^k{-Y8m{gYGWd!c!CdywYXn6v?-+jw$nVV zwA+r{s79nB{kbi9)s|ZXuvJnX%Rk7Ja`LJl;Atofs{7H|M0^=_c6M}f#GQ1~TBY zlgxe`MJt}EUP#$VmXfHTnP3e9^@+)R6es!?>h4z6Tog}!Gw)^`dQ=U*XuBbl4Wi^j z7N`t5iL<|xOLyly=eSU>_UNIMeK^QTXqfi=`ZqhL8)lNUcx<WO{B( zu6U^yNpMixji3S9{y)z>8??2LDobGa;9V|&=j;9Z%Zu75sIGP_E1)$IWSpR9+!@V0 zpBZ4soLaETM7x+`3#wenhl5K_RG4AXIMU%9tvkDM2^IYQL%{_fWqVrWh)%g(u*%ll z5S6R zdQg0+z?-mjQ|hdw6;`4ErK=SXOG!$HbbR6N8O@UijpTGkin$Q@);furM*P)?D+gzh zH3T2K9Y5$N|7n@ySY^K;VEW1Q*$XO=nx>ZK?y}LyJIJEZ3tU^VQN$OE1)+*yLcdLE zihV`OyxQ|7qkcSMn8!~{yBm1ySw+_II500W4m3i)&&9cCVZi4@0Fq^T^X}<492gAz zAKX|wQUlFqOBmj^uD3gS8XJjofHf&jgy4R@w?(z_SwC)4tcJgGAlLA;D0sy9{$!&f zT|AWP{O7XaK1h-;4L>2Xg~%;XQ0AQ=&Y@3#@)>-MlIUQ0-;@eh;^g@pm#t!uBGPo! zfR~84%6_P=V~~RW!bK;{9aP-NhTV$Q}Cni5nRK%Z@h*Z!SFTKhX!dm$un(Gebf;?L_eb1oGYG5h~XK zZRNS}uo!P^pOY~c@1sbZX6KoS#AP`Q(8!HQGNs|H&WG3=drHK^b5Z>{&HNFHb2B?b z-D2E$fpf2hdyDBja|QF2kjCL0=wBMP6R*9nHMRyQXhid}<)r)z+YY0Fnn8tBz^i=x zkXSuX?B`6-J*MD`dm)1)q#<>EZKJEiuFC&{*#oG$<5|su?;Zll)Yc}1`Et>0&)t87 z*QX`wQ?!CW3Jqkk_uD(9qbV}43w?>~_j~lB{C8gQO{@QM0W8yR9dh;EiYLw@vg&yv z84Mp?7;ETfJe>C`ySN`1LNZ3E+RO$5DFFzKH1Wwo`2GldM4_7pR=mtT|HG2EDW1Dp zoMzv?c3bY$wLQ9U#1#d&U;aNPv>{-vLfo$_|EDtY ziC%%KL+ttZn;*{WJd%7NwFvPw?AX7ySfT|2sP|dX5UT9={0A4Owb6cIhmAuJH6J ze#INtKDo}H(v{rS@ zuENMhNI&DAWy;6rc%s@TBKFCLjwEK-iAI2dXjAR+{BLIl4>mjpb%0|qc)9jf$Dp#_ zB9T#j%FPciFSIZUo?azJ#c)PBfUYROoUaH@yjcEHKTej?o%61^pWAkPb<^ou(?zP% zp#HlH<@=0#ng+V8E5bji#%E_uO-;9|{#s`8^uiZCaxXI{Xe|Nq!YM#1JpAOe43eOM zrO^U>iMpc#nbcF_61B?VuHwoE6rN{~UP#CfPQc)?Wy})%BievLY+_Fo_gyj$9VVJ6 zKL%KDqYm-U0uzT5&Fg@3OR|yv3rGiTwoQ0jJjs`V(D_SSoH zO0Z@VUA*v-r=kfiT9$C*89<35{PBERNJ*T)2<2i*kPe=m#BHquDplKC>1gUq5T59a z+c@sNtItd_tZ{eSE;FS|hDkCN)c5+~fO=V~AfE@?dA2i0}m?eFQ%*T!T$LBTu3c?Y1 zpYdo%rYp2R_0u+Ocb2slpkiJyY55nxZeMvzKa~Yo{kWmF@jGem$OFYaRfVaF?duwNI<~Me)qs3^1Givo=melyrufW@ z60yhOR~Aosvg8#4rW9l~00xHiaL<0R^$p!%R3ly96U#EcuTLX7b}AO8X9@2VG-E1Y=sNr6MlQT06Bv2fVx=->!2D2JHck2ddLpBBb^ffgBN>x4SQVIhOwHze|14^V_DvqEshkN zP=~n;Pa#h3214a>gb_8>Ub3i}1xom)l&*Vd?>)>jybcI6o_v-pQ+BK}DBT_2SFAP* zM+l-Hc60UbA(0y{ehaB}buKJQlK1aaIBvo;Jin5+EW;32xAT+7BQVOhLuVhK6gJD8XCIZS7)QN{L#S(J152BlICf! z^OKX^Y@d^CvMVB)sLK4X9M zsHq2a>I}N#WF5|FXMKK!AC=ZgE)! z{OlU>&6dK-+$qI5D_VZWRi;7nseFk#f9`3q81o|SQ)Kj38?*3 z{C=6*DKbJyUa_~VgZ>lXO7jm)?=c&zE!=Qo;le#hUpkQxH#WKe|4k?Gbcfn7AeWL&=r;F}G{r^eJ--RnrbnXe zE&?qw*T9xMO%LC09;-Tx(pgQIlRKV>MTC3F0&qx{9I(oBkUiok?sO>9W)sXEPe!Z* zT2wz;V8n*H)O)*l^V3Q}_lu@uokiP0`)K1&jCijNttds$tiHML<-XSy9owS#^5RS; zbo+M_W@ruT{ zhyXv-m&c2VLKntEM0fJFx3%#T2Yw2a8zA4|i$5I!4t~05ikoNHMIM>}Y>t-)vASXI z7Cb!t)oCsqcGmxosPB%a`hEXDwnRo&R5oQMd#h|AJ-oj%{+>+#^xU&q~f-S>4rpV#wwU6*Cqf~rXwUsJLT9c6?dGBVym z+HWT@w4C>uP@0yVR8ICc5m$aAmNB`3lu!`o{X0UgO(37M1Io^FOtOXPVc09*paUcI z53MPKaY61^O*uGE+Nbc8W&{Z9s%?7Tri*Ah0thknM%0%t!@{dYf=w>Y>5)5 zTqoOZYuHVW!1*w|8W(pQb;&#ZNH)t&_Ph4sEN;QR@L=sD(m-iphWGE^$LZfpO4eP$ zIG2D48}ce&e+e~eFNGmWOVW zKQ&L~V6`k4tZlCox*Inz5c$$C;B1GeS*=05E@Dp3)5Ivtnc8<7zm{X#Bu1kNNE)=T z8DUW`O3bKOAbP=`s=Ji3=0OMf9ed+fQbA?249i427ger-Cs>zrr?DVT=Ii%_f-`?A z2~FyZxN)^fCmy);TltB^DQ4H+iuV1azxK!h_Lpe5v(85&f(hTG2zK(gbL_W++aT4B z92=wapuSjC%Nd~8_4A=51*K#0b)JZr}e{ni-(%W)@!|L98FWLVP>iqM0>JSI5 z;3xf3SHOJXhRT9r=9sLFnhr%I)Yd+rJkTSG(hKMz;LYc_(lF*@t-bq7qMBRb zB1M1IFYaog6)c~tsi?QiegqkSf7@@B2;bqOShH>hB}bGX{Fmng0h^dlAwcs_P*v@~ zpbdl9ZZwea=vwX_)vFZ#*=ui)CmmM2e0#R}$<3jBx&rv?7gCJiedCHSem z%EpxmireGq?VwV}L`S~y3NIKq>(i(0nz=>K*BvUWde86nffCr$M#gjLgzu$yGlMs9 zqCuGmcFmX@{25{jOVgRsHqn z=ajD54%g}i!V&F_WI(O7N|qdTcR6yEuxbHBUKyA-0o?ueg^I%x#TcfCC1`8yiVrF& zStEZU!TGXASu$CX$@+;?A3w4ZZ4$%zXiWTqx_AATUiIDL!~N0@V8Ny9}V>lhHY5`rYvm&Ix8B$r)b zN9J5eqgx!cR9vvU!ros`b2v^@{n*n`mzR>^U%ms^^xFP zluV++Ph3EtFoZr|lCIcY(o8R+c2NN4d1kB?0zUe>r}0FSUMA*=fD7YNF%m_7D<~(9 z;IC%LYE1cSU-;hPyRE~a^L|hX*Djx4djLuL!EHfXXzOo09wU5J!?%j+Jk1H_Tksjf zy9+MmVkSckz2b*RcYLcDLCf?a)Lr$0^+tE7@s#3e)$$=_$m1$dLE=GP!b7$#>t|1$ zVw)cxe>oVVH-Ll#W;4K~Cyxb1W?<%eFgX_&9Uc8fG)$SQ3Z5x?tL0Ye3JRW~r2G1> z*uI)pBB(U))KirxrE5j`K4f)}Bzi{|!9pvocy$7Yn&~x`nJm8e3I}0Kf16 z!%k=?p}GadTMK$Z3yQOyON}AX^q(=ibhZI+8;EOrc=@|{k5Av;l-H)QF=B86r)zyL zFa~9F3|bG+=K~o7;lyq7NEfDsxW#*=9-n98o_<{@8;!q*hSz z>^~uedRQD_o0CMXxPS=m^ zyP7xAO7;3%0YwQ>%0P32EAk7y;y)6D2!1D)&++CzqVA-rm?OeS)xZCv2!>_pW|4|e z#z#Jinqu!^W?)v3+k6%RQcYdU_@HHi7pP=1jS`PT05@YZeMm zqJN_074pP0hsJozm~O7!z{D+@0j<9jCSygWXbeVy%o)u4S5v{(0>y%&P7u>XL@ye|QT*DSg`wRb)O*X;vH_MM~63;6zNE3Y~Tj%MO8h6@tr!8JxC zGvKb>F*Qz3PPi&>p9H5W1mdT^?RWonvp|uA`Nr+npj4W}W#WyOz^g3|Vv8JRY(B-O zx&aJHy9Quz`5S^iWm>KoMXrH9d*&%Bl)=b}2?F zP(nclQ=wuyZK+n)7^}vYp5U+utt`v+NEJCuQyivsOI)tdnBvDbVrU|)w)~N(|4V8+y}~6jJt36>gL{|y zLrCmD!5mO|ooe`X{yh{U@g*nRQ{&~DLP!-)Mz=7;}QY(Sx)s~g?@fk+%4ZYB?=c))R zqh^IOgmqmI2&B4j|EIpLM`Lk0{xVvGJK-m?Iz@iGSpQu$qE2N4M^shgeMJ_%`_euy z^H-KMi0ZJfNdp=_R@v^EXBcuD-AD+aZJfS*j_w*$oK4xgk-kXVdBm%ySiq~!bxYi? zqz@?$Q;NNkh-BU*FBcgOL`D}gz8j3A!z-QNDLglFIw+y?hun)?n5)ch`$%zks90f`@VNjhak8RaP?|58sGR=; z*c_~T!hzc%o04QE;OJd28}T1NS$`9FkSB^D`zr=|df#Qr@yu|!RmyF^y9hseWBYR# zOp=+Isc%yVXMGjcB8Q&W^hziZP~yJ{rJ2V=KFV|RPq!;q(_Fc4NUjlhLin7eCZW(;TS({`z^bZ6Hh!q zqBkBGzF1;3pW3mx&N_I*S2X-2Jd}8u;d$Jk%(5>Q)sIoPK)Lei!-_HRv%5~RLm>QW zpVtr6To!;@Zm@6B8&#$^|-{DlUF7DFLcv1 ztJ!6XUVqz*gyT)fXTlFafW_{k%Kn7h{La4mK6Mc62$ig9)qgMjCxq*k?mJy%=F zklR#U;da7fvWpZ{6lEeMLO$C5Jb!ZR?VXujN_vLt_owyE$dEeQ5yZ(~Y=?>Vngwen zm_Aw)oy_wK+=avSm`Olw;%oR~L+{{u-_$@P;9?^YvD)mn{ks=mwb)xPWbG&&_;5?T zz9#*4$n0BVc_Q`_@xUEXf^8m?-r{dWoz}DFk;u~>yTFJJlg~0=S8za%ar>}jp`Q1yrWRn#7Ss{`wKbumVvO5Tk zuOyl}NkYB|*stg|KhX|c$*Q_I;gZYNByW*fKl;zqbtit1Cz5~Bzc6jI5i?sQOepD= zf=woR<>L?@YP+){muRpA)D`WtpS%2@jpfK~CQvPy;_wY~iW*LYxT5{?qZ_q}q-6xU zu#dWDWHeUJ_CL7raIu`3dpGpXo&1;G-{|WcG1wlJ7lBzp1!y!UQaduW!9=zJlsqR-^kPc;8-Io*I+pA?=-&r3azAihi(0!*#liqp!?}RD`Q{TzI zysw4x`t$G0N*ShCpHy8h-spqA-^3{9nmtOCG!M)u9o(wxC92v+j+m4oDy99@? zfQ;@fEj)~wQZ-MWRZ&!&I=VbEDPHiz+13?te4lTjZr%6W&!5}BPqFmt7CX~I9zw^& zz<94=8L<!rchg@x^EPY-+&?GjcvU90VZHEgD_AF8&}frtt?3ihS%4)$j=CGM zvyJ!kuW`oOq&mB{>xVC1(ewPpicWQ9h-Zt94@e;Oj3PsgX5_}Jt>&(&AAt5_U{Rkb zd14%=a}Wa=bXGdxPfBk)E;~`Ntjma7{R_692KApR0+MX*OzJPApnOiM8Y$=pxd0i{QvlujZCJJA{^8(_ z!aDZhSe~OgNHxKeuifYiTD0J2~@PJs(zNHuw zuJN*pXNJ-Nx41y!Tv4#awTr6d7Z?4l5eQw@*^&D+dnbBHJ~v0I67Hm-sy^JzGkxa| zy3j$Ax8HJo5fIuajVg#tRmpcEBRmAA72_N6|9f>8W2vwH-Zrd=hM?-n+nz?z`jj?M zU*?cGzR4awqH1qt`H%KlTep%&!Hv>aQKrGT6JgrWjh43q5fSS~pR=qJo^vv;nwWqa z1Z``w6B?=h4~?1hIeGZ`(SB1ZK?z1|P2CjJ{pjYMN{isJQZT+2!ak z8+13yQHhUbrm{3Wd|nEAu-7^Wk1@{o;z|n$xLS^rJ3R@lnipc-fI7CPHbQm5Nyix* z52^;c!GzSaOzoi?q^*xuCOG%?+Fe?IX zdtNF{B^b>LLRI#uh19~89v~7l_(JGezr!R|y?-yQH}zxtyW`*2amUWLEX*Bg;e-*A zfk>a*4=d*{?a>RM`7eTJw%>dC2W^{z&ZinHuH}?bS`uHA;Q??)B6rA_m|I@tLMdsJ zUMxuw#0BSV&c7FkAocg3un#?spzbH`)VBuD4~IZ!ap~ibklnqT#|!FwviOG(S}x7Z z+jc$Eo?<YPts4{EJ*JVD}`*UAMyYt$qO3M_{ z`ab2pefRBK`if;`5*qocEb}FY~=zBsE4{k}f;))7_&f0K^9Nyo$*`zT(kv2>3 zD#SoTH!hT71bSqP#T;McM))~S>c?@YK2F=@M}8mIU$X3MS*HBAQS(~9Fqoj5hsc;= zB^fWKJ{=9aW;Y;6pGP13`14X=aR+#ZXei^)dion3@xl_T2+^9?MGol*2irm8&Q{8$$U@arKD&i8%S=T?Q4<#+#K0T~<7m>#tSn z$zwfm;Rf~v9EnC$z!3vucX9C&fA_n4Ayl7_3s=Jh8CF4tc4b9oEiYQzQ{m17+wb`I zY5})vJndk2Z!0|ZHfVYxcae^A9*vYOrZOUcfxe6B@J-=GsSsbH7dB^R))y8otJQYi zxzUUgR;5?k{9)?`0fRPy$3^MG+D4-j3&tp`p{{OO2()pNK(R;Fm^v&dZ(Uqt+|$<} z+g5o$Ut7|c+H8>9*->t2_KH^C_l$!({y;h5Vt%l@sIs!u*=U9XJeb_X+xz%|!+E`38kgWuhF%Xj5Ro?W$!IOU`>Ivik5Qwf} zVuTBaqR}ujQ{_~8ZP-&BBc~S3Ei17EN5Po6BEpbkoG8nR7PTBYJ{ku>6>rbWd2wvT z5Cf=Z-Sv*V(jwD>8w`U`Y8SL!U}*8W;_0DJ?1AA`+pF&avF8)olr+^toaq{#+}(Lb z{HbL=Om|okg#EZnfJ2=Zq0Od%xbbTqGTc1)bHal!Bk8RBcNco}U6Xn_z_ZM_2geSd zt(qnm<`EiJ?3lDqw@)wYhI%J3MO#2cCw0rpwF+VgUXio--1946+^#6q$bh=g^_)Y=^*%%C;@P_F>!3 zZA3PIUZpw~A6s*4qaLt;&)f7CcJv?62A#`YS5wZu_|U?$IP13|g#X*D9T2Q)4$~Q_QyXVIuc;oR4xw0WAn7baXs( z_w&8arq>@=IixA{+yc{hi>173%n6NBP1&ap#}9F&wt6})kY%zx(?kmJ95O9GGIWrYAwr+goR-oDI>jTi6N4W$j2dV{ z@(f`r5B1~B<7%m2$n$G}tKiKI?+0<3rv6B&9ng4d>`Gm43f#E+ka18EokZ|Dhf01! zoW%^sM6ZZdU0u)#)xJXq;U5ui!n+@Sh1;&Wz5{n|Uc}B^jdWxDnWGzmNT_}JyF8oD zlS0(t?xm@#y?a0FWB+?){S_C3zCl-UOjqa}*`Pm6;ojG(^Ju!^N%VSJqP0vqJj0RZ z7cU=4B>S5nE}4Fu&bDq9vpa!{z#k~k;s}hIFHVpZkqX|Y4FtQw9pAOwX>7kom%kbZ zH*Q@lEJ|PXZ8vMS{Rf)A&t8>s_}!E{Z;-<#cJJVJ{`B5ezq&kz=U|b`SJ2~KCbE$h z3D@fT>3{dm8XOyBb0tk4&E`;#!%QLHFjAnvKjLL9YH~P>XW7jBUGiqG^FY&P4MU*0 z5-8VP_q6vBhd)zP{nvSdl&=F0)hDQLbGwj}YhEZ&;*iPi*$0U!HtK*LiFRaQhv0Ln$v< z>u%Rf!t;9n#I`<=z74dB@HQ;0`0^RU&j?8u^$z8?17~%7l{@Wny;`pJ^MI?jIA8pR zo;|)sX$H!|g76~~9JNKmkIm9zjDb1=YEV!;6tKfqBV?Y|A> zxk{%$Yom1CRBb|L;foI~PQ(sqeWlM1EgXI}a_CJLcQ9^t)KQd=VjtCmgS+S0BwID&7YjR4ej&N?FCoj?{x7gOUioXLY`h$-8y zy^xUWaVb6DpPhvqM&5gOcD*cvB_mlkG$0bY;HMghZk^!7nzpzm-(H>Bn(|vu%&fg+u zlBG{x;F4g}pY*LqrdBgl^MDi-ur~#CbX0MC7Au%GZ5$>ms{Oghs%y*_&&MiEoYRY3 z*>nj$h#Oev$L=R%@1!t@v>){nFtd;n-5#d}!c1|dDXiK(tlj$p`;WUsm_2`7;s`OA zHa(mqHxGV&*!yPxG+-+m`Z$%MNA5p1ozKDZP=D%j;0pRu#T9s2|j$p#=nqz&6MvGab| z$R7q5EutRxU-~KSrI_+`oQ(aF$v4fhk!EiyTQE9{G|*T&EM;*^C)rK0%|s^b&mFKF zBlXp4&SkMl61Z(CmTJJR!%nSVp#0;74D|_ z#me@w90SlB>F)yqvFS9ySZ3g5Dn0Ed#zFeS?>KTR#g1s_Nak}7zAI!9hX|_{*$Fw7 zD{pcQRAou44=FJ;RY7NMjgBzjP=lZQBXZ|QO;;}s3%&Qh$So=C^aCG{4vblh+MTOz zj{6${?7M%?y=;}7FpblCe_S(rkHL!KDKQR({5j2=vT?eH?~ghRpv@UOTkpN&-e*I# zL&5R14OK!-3|sfXbmQgLG~hPR0FPwIptX;mTq+#})ZXlD|6fZ8$`88T{ucxzo5iRdI^N%e|V-O;74(WbSma22jf!ev5w4Q15&b*55<^8 z`i54b<7tBH`%|nyu`GnVopE^L__@d-QWcK)%#%Lt<(9;)2ekzG>@<}$z{iC}l5dwP z=xI|E7$1bMnUo>CW#&EHJaoXbq8hqY(c~@l1DzD939rw`z+iRYX=9Rm_>PVlPcRnOVU~8Su>}ug zsL|&_Z(1?$JnMyhG~f78(?*v;=yNKH-YUN=ZFi8cOfec|Gte6{`~OSjpu10|KWn-= z!_0DG6Gm%US(|xC>PpIcbq0eS%!>@iPpRd9BUn~;6db#xip{DPZ~idt5PEt1fn61} z`JNNICyzo|$}7eoGWp4WTxx0IM5qKmh645F3RNE?%|d!X$Sqi8!X6^i}ST3D^plsU=L*L8t}N3F_GH6B^N1)5!7f- zpTU=>I(@a%eW;d$_6!6g3`yzFX*@K>rHjqi8DJ8|$7Rj~Ps*nJ3R@te`)C8u;}*l< zl5`uRbdE%4W#+Zz^6fwuYn{Q~Q26MdC?BV0i`Q#qv7sl|_aot!rWh4%f9}4ahzJOW z`Vq48yp}(OB{om1%=)m5aiB6}qJ4Obv~C4x6~k{}Ox{75w0a-tf$#pR(QMtdY*HgO zpk~iCUZr%+y58T+%yXymiljs{>n()>fh9AsV0KnkvW)}Zvp8t)&UNC9aumur9_`RX z`pQTL#ovY@|E_4Hlj>HswO9YWr*anl%6Gj?j4b1q&dQ3#c=RnXbdH%;vMmS$mz9-0 zs*sbBlJfJy&&_Ix%aL}lI^Vn?eu3jWv0s-Lk0;+tPnj0Zb#)Rq!q3k?CVWSBr(t?_ zmMM9S47dc)-%XA2f#O==@eIwZVWnC|6Z2R_slM(DB%KgrzJXus@0xcLQ!@ zJu9*p_u!f8_9xG+%*YprGZ9`0Z-frO=Ty1ar2I^SjebeQM0|k*9w>WoK0RJ1`}RUx z_x}DvIy@JFpw%_P%*CtaKJrW8`Zk%LMV7w3{=)|Kx~?zbwToocgXJVmD)DEhdKB{b z8g1$Bs4%0n!3r1*BCyf)(ecWujTR-D0lxc+?tG%TkV!_Miaeci$(zF)aHA&MDSg~{zWs|JQU+`f5D+kmmfb|D;7+^QOug<23 zR_D0$w`N@9|Gxc&QJ{Ub3%LhfLLXOLaPOtN_cSC&7&^{JUOu3PKyt@_p*^*5JJ>9B zeKspRY=q~X8uX!=cd)j0p8nNkdm9#!R4MRH0z~W>t5Mq%_T3h0Mr{v{xqJV9_P1eb zZn%wj`;GZ64x>A+iaVkO;qV4ckl^0v zWoY7QO+zJFyMvQm)_B2Lb!H4#H&>v{M*R4o*^>W@bE@gvB7#aznLQ6!S*h3+VwZPM z%3EK6BfpMMAoQ8%%S0?=;DVeQb))u~tNFE=x3V)`2b04zO>fU2b{-2XT4gMF=zoiYD%GDBnvdlBhn*M zJ%L@YOAkiY$$~QwTj=GAcwg{t8*b|Ayz-cf&>`K2Z8>YVH9am0yN}rnJ;$1+AK_T|~yT5(}C%R7o@i66-bNQIbZcowk7R&B4BcZ!v}ukZSr*?q&n z=dTDpDw;ud6R(-a8ABo^OTXyhkWf%6*hmIVV0TEjad6Fy^Csu?HM0h4SbdZ29MX+f zdx$|(6%{7lElp_{okndzM@uKbWWWG89_qXtV<>ru)-B4dd`%l|7>l8Qo>)!fMx1rg zY2iPbY=kD-%={^JU^G43S33yG)C{sS^n=n>sbRIu0=^{DEuv008g92kzkL$SsRT3R z2BC!h8B^tq(xVeygO)RxHiQ3oYhBU8k<*RPI^HvBn30l64Dxfc1 z{$>p;K_E+rj_+%3L>D=m?8JUu73GH?2{j!Vh!Ni`$RGLch&Y5Kg3tq?PNtGYvFuC)ToNbzO)hx}8n~V74sS2j| z_oWBpfBxv|YM06EGy3pC#3p-n*vJV&s*MM-=4X=KVH~^c@Sfh=Av0R-DHY*VrNXf! zRZZ|&lyqVX;DI{s3G=m)k580xlQIWJC*iW z$n?5-BhljjgcPOYIh zS=@S7_&?grWqwM1ZY*~^jr>jLv0oz?y$klu228dQ!ZoyCA25xSr8Pu89deg$VrEuA zt$X^(%!A|Z2krvE5d)-;evFyp4bk|loSbJBG-KGyisn+B5et8WqS()zoVO<9gj z@Ojk~kJ!eEjy||`L?q$w3KRrV*d3hElTFZayr)z4)Uh#MUQcI+sI>w&Or~s&I71pl z2gi5^%WIap`}=Q%2oF`;bWh@R&fpuqb8mb65lLTG6ec!m%P+T3*C_-VmS96h&D@DY z^$DvFZ5g^MxJE5DI_<5E<^u_iRC6^Gmn2|8>YD9~*jm(xi;4cBo!~9?sU@IHb+Y<; zJrjbj_ysl5KVnrZZv!W|F%mWTXUW(r#M`!&RLvsp8m?^cjW)`NVR=UOj3zT`T5Qy|liljtdX=s8!&;+H2Rz z_+|_9nMGEl9GMh2oXy3X_?mqLrx_YBWW9@?v*WD8#raMEW-WTKR|KyRguH=a@5^4C z?2m*i`UL`6OhJIV-A!IQ@->$my_SeTAiJ4CRz^^wGwYLp`7>m=0qWjp$+8h!#-KOS`)zq)XL>cQ?bGf9?w^ zN%#Bso&~qF52@^0SAWh5#J~u_gjGcV$t0s-D7lzM5}?%8#q-&d$3Q6}A9bViS6)g= zNO)b{zQwxImT-6UXGFzlUbYx?{n?$s<@}w#RQB{=4nKb=d=THrJVdtiG`j#5x-K=; zF3r_0p%}~*4@w@Pt@1n}T_J>i`RjYp?G~!RDus@LD!Ji0=Y?;Gg&I_rQ^t*V^s>Ge z`0%dtT^~E`A}EkBct30NKZ!2`LV6RA0VcgLGoL}N=vE#4xv42-#fWY=B59(aqH({n zMa^1Z)?DUAgH!$9Cynu;l67wOgj0&AG4Rp$aHD4s<aaH+f;xjlN%q+P(dL02m zG#b4OwhJ~lY0)EFG74=R2@t!1&D5sp9rBXf&b-iu=Z1 zEMJu>QE3!Z6^#nm_qrt?(&*6AE2_QZDN6QJLTGRi@`nXEEgY+)F@zF(h4Z!cIf$|b znLAjlpk^L*ppFA<{-dAoJg@9x)Dw9}fDU};Uq{y%{>&-~AD9J2U0cf9l5}NikT)Jx z*~!*x<5A0=P_V|>`o3$Z(eM&1cXaTsz1eAOfO2gKUX1Rgw~BdD;z-BT_Wdlge2Os@ zC46YF$J=!AZ1FJxC_M2Q2r`)DvF($l8W}+!J4){qBRKh-Gx3ri&HW#-ST?{yi>KTU z<-T11uNU-}H~#hntd-tx9EyIu4M?f~0k0^n_LH|D+@y6+66O&z ztFitJcC|?~y;a1gL+FG>-1NH?*%6+hRctEUhS%HOO^2P$sR96xDbHpacQ; zOOB{oUTE_Nazr=&V@yZT#<=TblZKmPVh=|o3^~KD72WS6Ht0^N9V_c2h|9)msc;5< z1N5WN*L!JJ&-bIV>`UpO0%Du{PIqi@e>9PEAWgOpz1DYWHf9{Zp4%@N5x-qx0?_(1*LOGS?d{K zJrf7-frrWZjN9@h^&&l3@ROBtnGsdKTKH~p_N!HoEayZO~mK}0o`dg+w513i=Lg4gw;`;iyia~qqIpIxdO!@men1d!z?rY1MYW`E- zFs5x=f6n-61#cQFYOoo>o1InSmRkUcysD;z<7aE61bkZ<@H$?Me#I&eUbqLSkmS4HJ;iaJi>r<)s2)!qT*u2ar{2T_X!hT5k7G}nrW#cY zEq$(oRz1!8bgo)@BMwX2Dfcob1n(faC@e1>WjI_+mD(%e2oufeZgs0l9KLEfEO&gi zZy}9svb~Zc-!R}(*X3O(ro0hYl?;M^&wF57H*+>+(VbTgxHtorE1hbZn&fy#Gki2Z zJn?>qhh*)TY=|7&I1O%Hq&YP}ep{%3UdxJWu)A%@AEvjTi(&gCCN!24@Bzs1_D5UQ z20Fqmp&;K=e*}k^dEQYxmub6z_$Ml7ZK(A@KZ3OwrMgmfZ9sN~#S1b03XLEqC62tsNvfoi`arM)B_)G&rnH*<0@1RDa;*tYjkQJ)ch!&5BSbV1 zllli0@(pl!ZCV*-=G50Y|8wun=K7B+V1S<}EegXRBr)VcK2%V=|5)W-@n}vj4>Y6| zZP#LRD@1F7W$Q1>XGIt<_=Ce(fy+Q6hVq3Ibfb-2Ry6_6Z8hO0$WOPW0tUmj47ovn zj?FLTfnDXlY9wgWHaU&T){=cXQ_lIUS4jgQ`Q(eoSP82@a(EW&J$=!LU%qAqY_S%u z-a7|t6PZac5DB z?JCy!V02tQ`p%Yk#(j;PQaELPREco|%2SR>F6-DlBA28D_YM8>@bItAP5YBp&lX_8 zod2hR9~uYDrt-K{oMD>LVNutIM_ulr+5Dwd`IEIoMoNeDA^}{I=U!YkV6_kS`YA!s zS$%LAH5i<rDLbCu`wYxujoA$>CMYq5B5U%_PLL z$kaP8Rdr=g_nair{$ARRv1uYnuB?_ZqXX+=T5$Sh`>3pO$HUa1?{u$X=fR#0fCiQ7 zf4mJ?FnDafUAHV;Q&ME4oT8mk6-$Iq6&eV_MFL0Z6VbvJBXnOnxU6$6 zO_WaZoDXzf+yMgVcHLvUD(mtEc`@aXtM51mJa$Sy%Rh^Ee7+%BFL)zX`?fHBO|S25 z3NB;3K!w8jgTtajqep}q5b~T|M8MfPFo5Tx&LYW-{C_5%GmNC96f3sfi1Y%iMn_}y6d zhPbrG4i0`W4NvCmYXsn2E=@^nT+h!gpt{_x*0jG<@#)yleMmn(<^j$v$twqh5kOKn96RvRPZ}7xKa!)3xJMx zbIQ{?i`eT}?Gk?brN`%SuD;OS-(rf?*6DOv}@TBF2&TEUs!uhaxS;A>Z3Uw zrX6y696!>~?N7pQ*g=UunJ|{1p`;~IKCiUH+&*!$JSs!0{eQJQ8ffU+=93P6%e!vq zJ!iI+v7Ckb9Z`8KD;@C%EJ9w9GuLt)x9=fR(?F)6lMx;7AI>CPGT!<~>2fD$aAA8v z0J|qpA-6iamRC_`{^!`y4@anuMHr3=G;xB)sIvR&%id%uaU^Exd6~Dna6Z}8SOG^z z^pxa}-t2DRIRIoc^Q*I}TV)50z&;b9%Y8wp@2o++>G(y0^D}vp$|l%QT-; z`0A;MlyuN)4ddE&P@pdromLD9km>X3DeWRcf)770Sd~Z`f9T z0R}UCCb#u^A>lfln-?MYMVUOeoCnCRlM43GXL|ghr?Cq2gW~Afh-7Pdp5=iYWG-sTp7<|+kX zGF|4LFn#c7vPJ}@e2T$Cil=(9xRjK{c{i36f9u$lTQzZ?br*{RD_iO1PyLS(GQf699 z(|vIGtn^|9McaM7E_nxaoglRC!X+;lt=xZUK*A|9J)pDi=s!hhXEc%tp3w)6D>$R*H-;g^_I7RD$0mIHG!JZ#$2gCBk8yoglo7^6%+Il!}q}lCGe+xD{=fc=6_?tJOd;|TYrQqnt za8_KBIIqkYs~E5em#Q%eHZQC(E9>@0@E!eAV!?Mm0>>LQW}o)JGT6;pfR+dMlh+ym zdAZVeAk6vtYcg5!q&gNb8`aR68-$PbmayQjCN9s62I-2yboFgs@I?Wbqnn6G(2>!E z!1Ou1c5Z$?OTUgHl>C##kc}jOS=o=<=@^QI8 za0>5xEg)$@3e<2o3$o)Xr2}Y&A5Zc01G8DrCpetqDXF&ATSwg~WGa3BafO20WWyF& ztFE8&e{sVf$^6zL$z|9MxF@o90_+U0FEGEF=x8IT zSDi!%0**s32-3+A0VmFsml~H8iIxo(p+F*_JjaR4XA|`Kjh_hW4+`U;O@mC#xbk3y z0l)iCooDsm0u{#1vT9TpNyh}o3smJz@KR;YA2iK8K zh0xBwz1iEjPe#NP6zbdB#V=Vk5=846p6Nl;iyRo)kWI2m8g-NYOqS0di@E;R7V(}r z-E{V@r(14ygfGuTO4P-QE_+J5vk9`Yy7BA4BfgEOQ9dlBr59AfH_CqcBHWmn0)z{q z`N1q?Es6(v0ucq}66b;L>V$bE(cXU~!T?5aCFVqp$V@t<&C zL;z6TvgdBr{Vou0eo^L7oiKFPD`ER=>DQ}Ov&KZu{2sk7aW*Brv)n=d#l~3p688LJ zf219|B}cEn4h1BTe;8;>EzP9kwnz^JPKl#L)t>gP_(lhWS`1FbO%}MLOH|r$(8WQ{ zQFI^=Et~`#TW2fjYF9d>lOg{hbz-I<+8bf5Vo4o;TE9sJZ|^NtuVAph^-xfG#sIPD zFuzoCKHsNL^8#vB2A36u+glyKp#+O4g*k4bOLHMQD4EbGV$GaPne1SRJ3E`dTOQ?6 z+6Uf7H$q3s_Q&fIyUEEn;78DnP-Lwddj%Q}O+S^!9TV1oq+p%$wz`12=X3e99KnP1 zY>4{7btInf=l&Yr@cKu<{iwPZ;XiPEc8bSK)lJ8R+kvF9jZCoL(ZOX`Xk|``<^T{& zkBJ>CZpRlndzM31wJTt^87M&>l*H^ck(94h9LL(T)IeLa@H6sT)$(NW1huWN_U1p7 zg7pZPW^GO;7E!A)N2z882d zR@v_4WM$oP3YhP)r@;V3XMa9%(tl=to@a32{BmU!a18vf4rX>JP@>GXp_E3j{~j(s zx-OiE{Ed@I(x`H8-`=i+hjHUR#d+zA5blF=X~sf;x~t(cha9Ny>9LGuv7=82LHMx~ zAZFV;JTQED*6JuYd6lRn+pp7Ds!(fqTt%|?VJsLven3~T|;#Ct-gFIUZE z`4wKqs6s`Xm~MEukIeyd_zfignCTw%(sZ~jynCP zQre7MMP74Tg{BD)?;Flu14K-+C$*Ph@FN0PM*^4+=XP z#6REngoSLsw^`s=qbjTHfX5X|mZ~$FKl@%kRJUKe;8XGx0c3CHI}Q3=0VMP1+3))%k&B{vtK#}H)?>9{f!|_$s4lls>V%+t!Xl8GL;#UUoEE= z)VFZw^PZ4(8MpWnQ8NhWd4PLOSHsso9p6V1D+E$xh$qU6yc1{8u>6JWG>HT>7`-xg zvL7ghwAF*9Yda34cx-rQXHgEGU8K0z5We`;^k@jX_{}S-ZZAMD#)~U4=i-3tT#Ber zpl^BCQyQgaNeqmh0t@aCs@ymeWv49ZN!+9F1o)$rOF}cRMxAOS&l_#YqXkAQ);BZ; zr(=>E9Gy@v%}?ep=&c^qUM`+R7l`wWkcc^Ayo}B3q30{(0-?KhD|d1Ql?Ymo2TRoR zaqUxtMjLqWl#Y&$zAZ&LpE|4#1-N=QIb^UtEU&qLIm6zUPbGM^7D`AEbedmvwJ&!C zh~w<-!FG1V{{H9P+-)>S@YE_`lnlO-y!5euG%(I#L@}EiYD%Vlfk$(yA7mw5*b4#zU++m?|n~YRmQ6EpurNjk?F*g~l zIKAetg~vK&ZogzGs(Yl!7RTRC!F=+9oh^b|HC`dbF5l6tdE$NgJwXZ)99bpBi2(y` zONhbb=aMteqtE_m2anMzGCgn!rM6;9I!*}O*|gGeDdF&$d<^B{iLe%3gKXd9hFDI} zBg-+~3LpvbK-ivITTmYi!NB45lkYmSaGFNSu4Jz@Jj&5nf1O~rV9(&W=e9rdNLK=n znZuL!saQ2;e=E9FY$fChtF9XJ=&^ycw~A8op`piS;85~t7H!s$r)|g4BEhxK>oix& zt3aS{Uti|=)HYs@s4UhH2qJm4wxW#EkK(qCTdTjqCofI17nQYd&X2NAW7N4>LzGG) zBUN9+4{WY{3A%{bXqEI}VvBgM+}(d=I=MKz%KP~PwJP5ZJ&mv7^631Jy5BRW<8im{ zn`Y)@ebbUHk)`Kil7F7gP6w-?^i9T#AVKjn7J7sfzU$>1Vumz0uP;l5Q=~VLhtnrc<=l9o&U}`yK}y~ zvu9^!cV|Xurf}uKQ>NGLpI|~*m1^`AG$7Yf#fld?<-snzb%PiV4nB5pjn#eF zgZfa`+Q|0hF>Lkq#Q&0Jjpr)9(#;N*3|ad#!_w0r(I$zpfwTcAju8XZ#^5W>y-qdm zjwJ6~ozQ;`4v?WP4FjIyQyqkhpQwg?AFk$X>2(ws)tEBhtu=ePs+TD2Y}r1?Hy%gTq&BRA1(GJj9hDkIEhP!M_Ov zLf^(_|NoJk`5aeiBQXp3{^ic)&hONghk9+)IbZhi`OyXgzF4#t6xgu=tlMzKskSmL-un&9~wW(%s zAr8(IE)1%z656HPX>@gYmGA^#%X*iN9>5QYRm*&?RHhvF$Vc82+wb|~p!WYqo%6;X zogX^=CcxFuP%jPsz|6@+*R<mOkb&^m^@1vH(^DVVTQY~OB>aLH1GL7F>y4hHy7 zI^=Kx2#kt)X`WbcnDl0)l=l)plnARp0k7Gidk;4{R{-Q?7SYNPR%atB0qj zfxB|p#I_U@%(#_V;Azbe|)Ew=qjR$9?6M@nD{6O z^K+rbg7ex}mv(K?kJZ!UjoE>HCrUm}2D??Uz$ikNMwQyNPfpHpx}SQ|)8pa`zhiP% znIp*}B);XcG1xLivd8$s>6$>t#VnH865efC8&=|e>ji>KHi_)(^(p=MMp{c{9~0#=2m!Eg7G>Q_Wq#9a#8r( zy&*dt%-&0cX)#FvYSNnwd-r|xCpz`%=-l_E8N2I=r9*;7ng6^Cz~&Q_nFvdKh5zX z9#gU2xC!XI%QGIJL^mF-Qe_ipKLfXydvE+AEkn~j1+QRGovm3YFs{#BtZ#>iV<|2u zlt@7pm~~3WL)7uoHQc7$N@|Q(KdmdbaPIop!`bL8p59BmdqHyVSf63}WVfLX3wTtr zLU-yF@A68wHgy02aokwrDv>yxFd$S@`_aCjTPg3Hev3OS2XA_v(lS&==T`&c5S;~J z;0FyQeNgs-^jO~kS4BTkIak3jr_H8g>+o1w4fXUZCRqK&&28bA`xasxe!P6&8Ewb{ zluXm##P3118BLPdvNA}SUX6!Iw`?xH zrZv8mfLl;yN5_(d0+I zr~-fDM<&xYeW@xHDmO7Q`OnNW$`lQgji3GSDV@Dxh(M2cZ5fl#VE%$VfqlYY!SdPW zb1Dk9u+3-pQ^wTtD=Nk(U#_52kMfwK^M9mE-iZu1y`_|Il5a0$Yn)mugce4pI0OQK#$kGzi&2(_{;r6ew=)A%0+@+7MoJ!m|Zy}N?8w}ohu@;HbMdfC?_ zx61K;SC#8{Njyg zrxZbRQwxh>gaFv?u6kz()Vn5tyC>s_DP|8!`x=!$TaBgeOx82b_Sy2C;>wm`O=WM> z$Fc9h#8`gzQhDLX1#+ET(sQxXah(}m1{mKqJ1 zKb(jv2`isppg9NX98hRGp1Oc7n|&17Ep}Z6uJ1>q%gEQsU8oBsWH)=*SrBaOmW+%W zEl{g`YEX6|s+0*`sGZsXkUD9*%D*#8wYF%`n#+efR-y`AtZjD>vUupGLRHd9qlvSB z6D;e<$jllM5s<4ZDk(QUU?N*)TBbiQ@{@@zTwM8n7I(3pP3&#&cX6H=m{82{M?b$j z{yQIV^aK1-l)b%GgujOPaM{H(pjP;{#JBKzvzAP6<+_#0gB3yII*;?EcC?#c;iDvy zq{lz#WU>iO+JdPIS?s!|K)7K#`e$snDn!QmdlbL8F@VQ&bkX}a?iLST1E;w`}FQyo3!Qce)HfAY;eWV+0g!l6eCrW!U}zlvr3C#gC3d zkkRA{c470de&?~v<5FMULZvjmb#__F01YpEHYIvfOM%FX$gdM>%Nn zmfRB0o_jpj%~7A4G^F%NG&-LYJNRV$X%T=MctV-{)I?b>bS z-UtS(=Ly+f*5W!GIIc3kkS|FO6t~ZOx8DYh_Jm}*(oS(#de#W4z>E!{6o)mW_93;y zO2QXfek3GWPnT6Tl>ytAqTU;mLOW}{(*$I=^p)beEn?Bc549U-bt`>n8N3tWC}=Js z8tkz&udQ&PhJguhz5bFME0MDcW&#>ZdhY%aw9dF`nDy*U(1o*xcuZcO`8u>Q@|w$k zb=EJtvYbkfHVHn(YsgBIQ(C@OxJv!75=*0du6C`JOpKmy`ll*8>XT zWlJJ2e@-5?aiB4H#rvOQo<6>2185rzZ)g+!gF69F`%6);>wNq!9IoVz>44rBS5E#ZJV@OideXi?)oh(nU@z3&U1)1sJBKfDhgNMl z_j{#uUgTH5ug=~5x;Wo>D1;f~-Y>-?096DcAgBihz{=pjLWu!(KkC`9u0Hm+=tO&j z{gQl(O=SKQ$$Ww!c_+pu1q|_TPM+LIdhF71y??tq%lfV>3pVGv88X|nB zrW4f@8F?Z%g&;34XAWnUOJPC;H8%~;*!X3TRDi~9wLCvrX`aj?1RRI{I@!1KI+Ari zsmLpNmfuJwr)aN=ST+|3XB9fJBFS3gn{o&>?uW6Fcoy{E|c&9e)^$rROR3zbqgmYXCP|g`mPCj3Fgq zl+g)tm?ea;zc$-qu|HkivLtYdUw*(sGfVF7fsJKY8m-BV)GlwwZ6oLAj*KBfhIF&J z^&n70gDc#7D9ysdx=QCDTz%Vav8$fJWJR2e55E(i@FG#>GSb$jSoGR5SH(4WBE%_O z7=?_rz*fUF9p%_2LFd}q5yA%YX*T7&o;mVxMc zQn80YaoxtlzkCUF*d?bOrHQ75xOAKJnb1+aX))O^-|Xv`iWKc_9D){0E_A!DE@S$` z+597HDry^RYnp1n3#+;9GW7ZJ-6#&26*Wk&25-~$s1_o?3dx2Gg4%7wZ}W7gY`>BZ zgfA-cEr&E#52b{Zj{uR1E{tQd+-i45nstnVDi1utE5}>arzg!{12j3lv3)asVs`l) zR?S%4BX>T|)0G);#wK%!-HCgH9!FeafnI^?2j48-@k`0>GObQ9P4ZhpIsI1VpaJ@z4$iZk}oMr6|Gavz(<=z=wGhqY%F`g8XqeW z&KbprH=J;D_bREzHp-5XL@hEn4QEXI7VrjYk0+uZy$H4QODXyy&?K|j8v7uy{B%F^ zBj-`!VaY1{BAFi1P|M?qFPRx!+77x(_l^>fi*kiM+dlY;(%^$k=x>T>)XZ+?v) z|9k!sPlLQ}#c>YgCrneyex;n`0BMGMl^8Cyp@{0HC2iI}0#8pX$<3 z%+_$jVTYvA8=EX_EzOLGEBesf7BtxcZ#ppbfgOLpC0O&znW)H zY6Fg^S{HXPx3cAS+H0^sTYj9hDtt0I{t^5f8eQ;gsKsGr&*^KtYlAQzW<>op zY2{U`a@ZLY)2aLd>P|De_pEm*9^M?rR^6Ls!K^9cDzJarmOPyx*_ zx?)+}eRlO#%HuMIJ~&tEd7GE(3yk4c=nf(jzpk?bbwTl9HM(Sq;Zm7hV_5v{1SRxk zqn!ycn7;0q*%lqOC7UG{BSWrrq^#5rrP8Y#$7>A?q90pyLdk>maP7Kx(`!9D%2t;r zDrBP$lQv_5n%9opyUn(nt&l#u2OXmB58Z?MaXe*@-xwQUCr~gK%JjqmXYz z`Qu??X+sH7HT(2rh`2s}G9s!#TrTJK^(^0Qh=S0U#jpCxk`qlSTDA8Ouj zP@H{jVX`F*RZxT&sxi+VppUy@DZj4#qlwcobM=={Gs2T12bn!mj_~y84`0Yar2Z z@!BEcdn=GhYQ=TVXB`<%S zTA2-~MoGd(TObIhKlBxgiNvwDsYyerKoU`hc6BpLQ+kW|A~5~EI`HA%DdaSe?^kw# zJ{{8fw=(XX(^E4aT5$wftq7&^Yk}#k1vtHu%;Cm_O~2nGenc$pa1!fByq_i@D%2#s z+6x9B>iLbH93wf2Zox-{sae-_;rK_X4zKe4CGXtWJqYYj?GudoA1b z4FkD~>bellv;LKPyFHCR(1HA(pLB=(R`h`Pyi8v9%ol4hvpkqag8#fFH-DX!<`_}; zIaZssB~NYFwVA9M|HMrgg z>)3()R=-NH_}2L8pE<@%sGTTnpe{(aRH;*1Cevf#aWRY0*X4v6$&5;Su+cG>8bhzY zT868ylyB<}48EJxZJGryhoL6_G>3X{t@+*iYj6QJ-cRIo2EW&dj!K`-Y0nu{BJK0- z5PDDMa!z~~+66^NQ;+rbk;Gs7e~2xo?zB0R;OT(X3aTI;=DTNH1WeVu)Ffo4yWd!~ zuLB>?k61QsD6)P|jEQRUpNk0H!MFTKP`L5AYWaY2&=mJpMbYnk00X46ubs4-1o1e9 zfDJAG5E&6qhb)Zh`Se0V)+4G6oqUG_W>;E&2Dyo?RcPIHxm4J?cXEUIOqZW(%Y-`o zo7T4-iV_gqM@0#^E+N4{1QPH0RhXCegQ%!kkgbQ$pG^>1l@nkBT zkzfv_RFVEXM%KcZbQ;3Jl)50$L$zb@^PEoT8jJC<+h$Af;kTC4eD~woel&__qlr7(}n~QD}zo*<&*XI|kqpWu#Lmn&=n2 zRZiUZ0v7K-kb;2^66#JT`aXxLJYeU1x0y?DJqwMsPfF@zS&x@1b+ivY*B7&sg(@#{ zu;|5pR!r&Pq7VfDvMcPpge_a|-7S;ReE)tq{rn-ogY&-vm$q_Q#)A}9^54hrZc+?c zN2C+((%A#YXvR&S?n_u!9OJ!)g3 zA)%DuI$B&5fS_ULCv#@OPoW0V%;iEmL?f|naNG-pRzyfDl z`$WpiB z;Sn%@01;kjb182|h)$PKn0{6eFm?TmiFJn&E2xG8C&JE^v0{dgPE6p`FkPIWPWpnEO{*({BK~;^(oRQQ(P-Wd2h^Z$9 z9n3ldGo=hFn>dD#Eq($M3YXfn_Ab&p4JU|)U6g_!C5v~459KF|h0TA|CHSxC~Wer9XBK(|mu6C08{Jt%4F)aJSpxrlxymAz!xqP5N4oK5Tsl#Wk}l`gekebGT2DW5jv_l#zD$|}y!mU9&qc`K=t`8BmVU_)J}o;vpMh`@iGm295nQuk gW)b~OVb#CHi`RlHybQT+p7(~Dk`|;)(dza81N!exKmY&$ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png new file mode 100644 index 0000000000000000000000000000000000000000..920d913d98c17b5ce0535e30c6c98e8c88499cc2 GIT binary patch literal 23635 zcmYiO1yt1E_XP|OAc%B#cXy|vba#gcNFzwMbVxTyGa?K_m$cF)(hW*Vmz30V`TqXz z`#iIjBCPSwx%cj~&pz=XT0>196O9ZF0)b#ED!kHyKoChF5QG&}MDP>6&dvAW%d>Y1 zhTtn9-s2yHvoK;p2!sZr`09m@x7q%(k3YFruJrxvN9Vz0M)7pc{1ejcc-Nfb!=w^c z&Yv=@so{8Ys_CYcj0euFsa&hb9n$IFYoB5+LjC7eErcl+2^y6@2x(;3+f6Vz?Jh;G z_e3YmrDG4a2qxPE27Q#EO0Y6+v^Gv&9h0YO<((KSz-a{{8!RNC+atH@D+UfkI${U)oI>wlpKRVio6|F_#;$AG>cF@s>(=VZ>sf zud$Ee*Hf90$+v2&e>w{}D68t5-A8u?hbEqwRb39$&_gQpTIKK`OtCTC6I!3y&i}L& z${`Go*1EQU9L{?t)UqJ-yWYLLgS3dXN|+@W{COwR(}~^P-QC`Pb_q**N6STl!LIxa z@*K`V^8|u}6`^aNrUchA%jA{|)ie|s@|}snW=G$oFvWss;fb_RY_Z!wR*b6Xs2cye z7{2$8JFg(@+A1h!u)Gc5jG5iL8;&>bA?HHzg|uz7LVi_7?q?{gL=Q? zXg}!+DM5uOB`InoCO&he{gIfli^OG$f`Y=v#tw-($AkDf-9C3#ejwU8X@>?4A4oUf zHH>vIr2~W0s9_kAB)b73_dUGkyo(+7?*k?o)sw(U-*5bM8eUZRlID=E#>JMjY6-HObR=~uK zN=9HO)o@z)d#4_L!~!4Fy4h{QCokA$?dv(ojpN&VdbTg&W;I5|(;wSyK8R3YomhB# zd*7z{d=D3~#!V`up~a7pD>8{PPDH7+6E*NZ{x#db`=p(){o?6C?cVW>Z@VnP-L)^UBc;*RVPot+E{5-G-X64C=npJDKG-G7XC zEd?Yp4ct?RR}1Lot!}GnI%`%3+71XJ)bD=0-J5^4u&^j$Ha0N?g)}RmJ|9mmD*R2G zzxwpo$TdGFxskik@)a>BN#|G!=_`Kq{%{#L`dG5IUuL+v(-@i&rlundUSw=ETsCgrEkm|bj$L-JM z9zy19Hb1Sx#=|#Jt|wj2O_%4FaHE=`j-Hj-)kqB6dA!92nQt0K_r5B`(1BC~YXsVL z>o?GjrlQ&FU~NM*0Sf!(yQfXV+OI0r@imATZPAx-@U8K}DZ`EbHL)n;dpoqReV8k* z`z4X*4NH3Q_6rQY*SzBT_ewKmuw<6e&ghf6R;wP3$T>I5LG8)W!)-Cyvn&|_yg1o6 zXNIiLkY8#&Rb--xk-D4FRaJEkYXzl$){RlT}By~ z#(KrPdNY1Pyq(kQm=qDpUNtJIltiF8Nu;RwlURpnG;7E6OJ2u8{jJXaQ2HMHkL1Na z-dSPOm{S4YgSx6gZHBbZaFstaisjpK>aLnKMsO4jeQn~{-c+vymp@VMt{xm3>MySSR5lSB zUUIolj$ZQ6z^Cu=GG&~57AM~pU0ZL<13Onvg6Vhk?*m3}eo|21!`jk+9fmZJP*$aV z2?}_azBErOm5p(MCH`~lAz(acQ)I)zpzys*tR-mnyjy74o9$Uo$K+hE94#&?x{5(L zTdkC3<>Mq^V9-4igej^L zmAjrB^+XE(P%ZySYQloU34O_yCmqqdr{loyM~3ODJLRIk%0Jxb;uvOPU!D?a*O(r{B zuz*5Oeu`x>>R{p`C*f`g4b8j6xMh3vrDl>pKKGLFO9_LA+=&{3EJN8>bZYE_24x)e zX+;xjTGrzwCEWOBI$D$AWDPdKAz>d>hq#d)8HiZB77m#JaCJ8b%C)J z*}To?GX2PZYbZd!XHtHDu@X5~>#5(LZ$I1B1GVibkd6~v4i>KOE>%i@hOWuwvS3`QRYrw05c#YT_d6a@5_f1)JLF@L1%2M}917{k7*h_{O~z97d(4ITKXnV6WB8HsB$(FK1e;`l?^ILO6FLGYs)3yjRQ*6=cV8rSFb zXH|zWfwP%P**K%R7cXRNY*)ydIc#EUZM9-Pmqfh8T>GG-o#nQ0E#Z>Ttg%%$ZELf2 zfUi|N!|}Ly&K^qT;NWFrvbNQ8OXb;bYoUP8miol8>fU(8lpgJw1SC_+UH9l>8uIDx zl^ zYmMbE`SEVc-)bJ{!IIyRw@b1*?(G9@C*8a*JZ2p!$;9$=@B_8UW_KFm2${Fm(y^!pgVrck* zM?TS>;a>XUnqa1j{~h_Ma?tF}Pv(xB6_zVM%iqU%m7MRo2W-hdLV+9*BvD>i#A%OEVVJhN&<^y&P|=f^m;r`jNNuk>ao`x*)R#2Rsd=>trgn5B zbqCVxXqEZ2T+0|pGZh&KK1M$(68Q3AihLN|wfsTvdW&iZw8N|oBVH3Q7O|qgy{4_h znpRK{DQcz(yP^zt#lb|0eS|UVa%1Zw-ySGe#IA5Y5fTx?zWboB(^Z2;B zO}^h&Ku=e<{r=xxlESO1*{1sXrDoUSl9E@j>5hv92Z=FaBBDx@ueHU+FN?<==c<4I z882>Ht=wlDehtFQ=$8AFj3ox+w6{a8H~Zr$x!Ks*SXq7c z;7t&duWpP4Xw%cviqvHV1zqbWujp_gg&I-YKDlb!?qW}$KK02XM(_2kwiWRG`$x0p z-AMrr?M}uDO69d-SUHzHSHgxJ@(h(=N7M0}Sq!A*Z{O&0H^-Eko)i`0P$M4$7+-$k zW;f3Y8Tm96So{!C%fkQBTb^z_YTgP9C6suP3$dDbe$Qb~Jy&v*!hOs5w93;&7dCa? zaL%lrkMaI>#OoQj+1t@3H;U59ofa2&^A`VTYeSTeG^qXR6vR&o3o8p@b$kCB_At7q zIN&DjzSmhP{W=&l@3`-`GAfu7tmmK8bgZbelvH5socqR;JK&$)-1+$UXu*hsYis#j z;g&COp1epLB7O$cD>Gl=2lg6vzoOrzIiXmtD1)s?)@mNVlwWqXjR&n~L4$@~UfC{o zE~hlLjT_il)vvzqxQz-R4^~|3X&;i*k(|#wE%{0m>3yD$t+xVB*oSX5+kWaU30KZcp@UWe;1W)F)!;UrlpvC}fqT=q{WPI-qm^bxhAhq+ayV$rWitpe0H`PEqFS#PB+;zHWS=x8h>M7^=b!oQDYz@3@oNT>0y7mh9@PJpRnE> zJO-b(uq}8ikY>q&4kxQI(1B(j`;bJx!icEhmO}}prNBb6Ah9{$orV}08xt#b`fB0d zN77rRKkC}g75F8y8~B2K>GDe$5*UzN(_AmHBZ4X-PXePcBPfB7SHXVy4E+zqTanhS z)^=`5%hikIqwfGotKjIBIyb7sgJ{#1&NbQ{!eJghdkoT&y@C|7qN1j6(naD!gTEEN zfN%_xVaoX=_FR$RbfVF4b8}N2|yyfv?!1x-blB=HEgp>F$$S9%Uu zRR|W64jxr*>@${0#>X`fQg#9?gm-?+(D;ehmpo%<(`nPd&$p?`wTYu&egFM#bRv7D z!wjxxY;GKM@qNCgDG^uR{`~wL047&D$PD&+<-F3X!CVX<^$HR--*fh*vZB1A0#AIg z*I6{;H3mxPydzd5NSC{73@Qo>fA__aL!nT!Dq*77`2$bb^uoddo5%XKzf_tM8W?#<+Z65))Wwh2%qmJ9l;k%z6DB+Nohz ze%E)=J&a`F2sXnl-$u8Esh|^Y{qW3#S60{UI zovT$}-ikc^^aG*Pn*;TG!w-j3SfR$Bk+1w~yklqZQlrrOno*XUe~&Ln*vl7Oh;Xz> z>^n0Y8XmE@nW@D^cISbCv)l1vd8odkcV4IWNm1Lz1XTG{J8AJi&HwB0CZ0B%J_ti! z1zjeUYSq>XYTdK)5hk--igqH!+Fz6kgGD1g$iZJTACf5&=WVO!Q_Y%XzuCI&1QeXB zM<;y!QM%VtD?&R0?TsuPP84j(4=c$NxgB5ac>iL_JfO5?v#dNrtD+!Lg=cfr(>Sorb8HQU-Ju5ZJdP{#GUwjoZ#tnAAC+i*1Jc6i(aC3Rjuyb*ezgU|vL=tPAyl zDROXJ^|RAcj6U~!^}Hu{);VuM+IVKgMb`Yel`&dGLceDIMy%r(gZPs6%6sx7k&%m) zKJh>TNz`8{<>?O}DX&Y)k%PUD^K0nWl%>k-uhn+mp9&kkyI{OfU~nsRdd(!zQ&h9g z98XM4C|ueLDR z+XXVT4$Mo(R{0aXXtSGr2Yipd5ep-~4#rhm0Te`px_Ohjdb!?m=fBH;_Kx_svxbL< zNFxkeeGkg`@r71hDTrg`?wp&T1vCU$!f-n=j|+mav)+rfiR1|q>b?D4_k?EJp6ncF zDZl%rQ|sZB#{Dx1>S#H4qg)+2wOuL_vM*(ouMN|;uU9%&aL1zB2e_7tr)`m?23w(& z(1F`x8rrkBQu6NvDeN=-tqBH?;v^wLPbnb_(`Ip9_d)SDk(M1~#qFH$ipLEanX23v z$V7Pjl}y}~m#PC^Ed6Q4MGJS-Gd5LS&U*j$2`Y%bMsba>Qdm{zSb?y~S5Mg*;*_xM z>%=i)Qc~O^&BlV~!?nz6xf`T~Hg<7(Fv*~uwisPbn7QZXu4t2=MzN-#(3EMLdrOBi zbS=R5lO*yrGE&C}4HlhLbF1OH*X{v+dE4E;s|RgQ|FuQ4uQ)UqA-tzznEKK{1EAT4 zN8UWdo;r<)T>OoN$^c$=Xpza1Mvz3o_ZM-F!rk3g@+EJ6(zw~NN9=SGUhYACm3Es` z@+R5#3lV}XpN^u6HKT1o*R5q}qw=WgsHvpsT56L5gC$>fDmN13l_-~l#K>`5_G<`+ zmj{X|*NQDmHK9qfI|x|sO`6viuCsSr__t9=3fBM4TiEs-y+?Y(`9Ts%GVq&u7twRf zKfE|3QN5PRr~N{-TXdh~@Q(;IHOh3@Je|oKzi2uXf(qod%@nyZ<$8L0@|c`jM#JoE zwthBmpi;4!v}}D8rimomWzL`Ll9ub#`2aL$Q-g=q^7ny#2?ChR-TO20ykv1uMriNF zRoC16RpzSjf!0>Wyd>OQx$aX5^y;-;t#K0cSBNj-ypY+-5gjwp(I^2$CB=(IzVbM|Izot5%Gt)~zZ4##Z1gZh&SGvJ0>~GeSab~J z9ZFQ=BDOMkS(+MV*{B^42_{x#sP+7d*@9XAMpfTDR`t?ZyLz(Nc{<Z!UCjDl?$_3JVr3f|Za7hana;JQxOqA>Rr}7__`Uwo^qNCy}fTe&hLQR+XW* zp$jC$Qi8g${glyjke7Ev-x#SEeffg=Tvs>E+xPC@xod{}yrYnHlFGMe#5(H;{5B`$ zbe%6A4S8#5vDm@l1NtOv1efn9m=D}j-Ny~%*XxZAUTHJIT4Bojj1Uh(8*x`N&G-H^Xx?Rv%MR}xIcig2yaaQ{iHXQAFlVX2Jvai5FI-NM!l z(w!V_|9VS)=z3QO4<`OD^^ho6Y^Y_GAV((#*Mn09yp+X3fP|P-|J1M*Amg-&9kj9} z>9ZA3GNt7h-pV?&9MA0EGi>lr6Ce;d0LXa_0s%6QPrAFiyN{Hp0FxjoKDV&&SXe1i6DlM#RUS9i|NDgW7C9o(c$i4q+ zGE`Kr^syexU83f1N4x`N5)>v@>9J&9{evEZx>G2H2kF<>*6SRTvzfAh&OHdEN5Mt(Nv+^CiV(;^jWRNH*xUiioOe6F11Qy77x)^Hx(E?$a@ zQ4vKyB4Ss$j!LbwPjIYU@ATBPtSnZnENR%wjzSh{LUCn-JUBvkpA?2@0L^L^IdX8Tq8=( zO52Eujdo7p{9PZu^3lyq192*MCUStosnD0NpYvK=6=8b)N2FwK*qDqDwE)SMy6d+; zeKs5B4LbwdNs4Bx%=PQ-nHpcl*pOCQU4W~=;%i{eSLThrL7#zF>*$ak%p$2l{3;(# zm>f)lvAOv(mbL2JrVN7XQ4||<_DE?JH7%?vQnNXp4LYfFw7Y~u5xZgom?0F@j(&kx zRwPL-rhbLXt6q}7+HgraIxUugmG};vb*0Pv)}z6R6`=alZ2Y+iRT!~aYoycrX)@X^kE8L>|!@)^r6G&e{8XDi-Rj}Owp)n zGGr=9{r48oS1Y2&9Q^~YHvaW_q!-GVc8purOcCq;F84-e=OA2dx%dt~|Ix5E1vy-! zLMH2eKH9G_Az>V769bhsv}S7-nmBG|V zpCL5rch(mEs4_|hh4ys?4ee-UbJg^ZK4I|;KH=`%5kTE@2{hB~i?Y&l*4Lo!@+3Lxnv#Ih~ z?)B*3O-O6!Ym|g{{>WeXJ7M3Ts;X+=;Om%VY5}rHj$yOTz-5~{xOwOO)yaB|!H9E{ zzOJqz2a(<4t2ntjyUEY-@$nx%d>9%Uy1l)fELB%_N!GMEhB2duhlC|wEuAx`uXv@D zuLZjvzg$^p#Lo+fiboEibuP2$dokUtG9RyyeT<_Z08u0a?jfY0N8;G$mbK-Rarcex8rrzj26j%D;SRe)n4jM6|B6 zwcN+pSn%s-;Y&zFWMph??Ah5_WMm}xTRl(0=jNa(wh5tn-ceFga?R{DMZch+pkfAU z7VoYja~6xMc$`mlhUjAXuAj92eBL%|)Ssd6a#TNe1lm77ln;5WOrA#$Z0_#b$M$}& ztx$q4)Z3*P!Lgno0(&qqF(t*j^b&ZT-qx*Hlx_1>ZDCOAGCq@00X23y>g4LRL_#2vGb?vyDfqzKM*b2nJ z!bUJaDR4%)g>i61qTj4$i?9*}n^TA{ygmCD!us=pO>!F({bEx_nL;I~SkS#ha9^KX z>7>v3t}XYJz|o{+ z`iMOgTdf>S@BiN{0EFo7@P1gId(V4$cNzxlo|v3OvUqpgm(J;h5{kru9*=I)@)v7t zPlooup{kweA(f)^S>$vu+E1jKcbRc=P&Hi0?{@~JIhJ0&AY<3p_c~Y*+(ef7oDdSW zkxlAlO@4a%QLb37xDz$#jn&ep7scbYe1?##yTF=~FJBa(T8iuLATSt79-5~pL0hi3 zau8mv#J|Hjj95nrCLt!T$I#;;)Ih?JL!|#nLxEw;L6kD6V{D9mjM0r0B8T)S1E=h9 zu_ArUdX?ClBD?K-yjTfx2y{Y%$8ESE7~RLUldk~A%F4=GTa9;NV-)CGq>Od1UdSkX z>b0M?#~jjno>Gc^jfnD+3Make>P%u4luwtJCGS^USG?Eb6d1lwyB_4*J}toBMV8~i zB83uJe;|ZBk0YTL_c`4d7*G({6(spNH>aUx`LwGR5t4?Mq=2D;@Jm$fR(=>lf|<1$^UG0`$uky*c;R=#$9^auQoQu0S0L3f@GM(eVs=0Uqt ztgSN>dUO6B`;H7It3xbK<@4d6UMj zZ`Fj<6^>5q+_J+|I$1_Kah!4WmfBwrfBZRSKq*ztc-1=z93;AC|LfDwsyUz^B|`B| zLs@Lq#a@w_7|OEm#eOJw9Cw~5I6e}5^x zmUty392<;UTU!I9@`2Q>v%v&r>s6Ui#`gZmlLS!f=TR{=&HXD1sG@9gN62yR-SMv% zWr>M)iuYp?i5!;p!lNB^%SIYJnlTU!yD7Qin!5Kr+vGPd05&S%Z_Vbi}qA74Km>!0Gy+YIt~;MN^0$3Y4fR&OWW`W_|IzZ>%H7p$tI zd~(NI%JcX4!H5X^yvSAQKbJQ}nh>$h)rX5k7bFYa@}tpM6zY^?aU z`xYbkmX8zx8bXv@F)_Cp#a%T7C;HXG;vymCzQowm&=+M#k%^?4$L3hH^R~&N2PwnD zW3#q@A!PJSpF* zVf7mqPuY{iRVXpu*I$jHJb9t;G4dUl&xj-pCyR^NYD$?00TyCWW3cb(r>>r`Hkj!t zlmq|r%ALpL5xvmGv@?-WT>&CRQ9%L8bNvis zxSD639&E<`+5iJ0zIO=x@^r>{t;jNLzqX;K4J$!LRy>^CaR-(6Zx%l-crY+Ac`;J*^Q&g}KqMI6T=VGw z>{mJ&jkyP@H*yLLlp3xL>|EVGdyIC!-_2R@0ESFcg6hFYBS2J^%2$VK8N&4%j3}`p zdr6m#;2^Vl7ShG@aq*yW@qnJ59&j*N`~2U`%naPP3Gqu+mHAgUs1g+KNnv$04rI9Y za>ehcD)1b3bJ(g*W^Jr1C^q*Dl9->*O_izg=1iif<%|1m$A`=56&?26&r!%{HQ%ze z<+edx#g_^)C8NXG%XZj?3TU5@-OhpMt1X0AuhkjCr*|Ly|!2LxvTt0 zF;GrAU((=c2=J1|y$S7i6j}rn)?fr*J(Bi5F7QX8qeYJmVYnp4hyZ0o1CFh;YY_M| zIE~Zu^H*nQ^|iFL%*`J_`Lc#%nCE01iW2&I^0TVt;&`p~Fqc`|A9pc!HZ~nLa5TGr z{_v2+AtNJ;DOd?Qz^Sv)>BGxJ#w){D@t}E!gu8LU*LRBzcb>#X%&-Fftem0O#c%?QCi@9gVdz8 zVYZo`&n4RVgbd`vK7|90LhMQ7A0n6 zcx?x2_IIXMX`bwx!*8l0bd=WoaIrgz-K!^1JUA(?LB39OVHRForZs)IP)Tiqx8ymlp- zqT^i6y7VNf*-ajyFhu3GCPc{nqQA9ub61T?a{*aS5w8wqe%!dW6jxYZpl`O0p58zI z4t+Bp~670Ma4Z-_bS>laB67hJ8-rKkAI8%5@h8rinnhPV?>%6MNv9hVhQ>_NtA zhjp<`XjPOMs+0NQJqWVmUTP9TBp9);6VsZfcn8r47-B=(pe#73Z9r&Dl&vK(pvpKn zz~&Zd@%UffV~zhY$baSKbqU1O*F^K)R(CR&+kSj69Uy=QKZqvb8bMRiKOq)b&!?P8NV6@gpzFw8$3c@WooShSI zvw(BmO+j#S(+Wfx&uIY1dJS_nfmUocIG8t08^R!vt-1|!f*t~DWVf}obq1GdvbiqK zY>vINGZo3Z1@xTeYGyJd?&lCoi6Y)V9~&24I!#Ted8DN~>+5y)5$zlu37-50wR-(Z z6T=qwG9{={t0#QgUef=H2Xd0XEU$V73l(1)ZPGTmF+}RQJI{b9?ny9DQnNt0ZlzN!pYxZ5Qx}lZ%VA z$8PE=87+Douuhf^*C(Zg1{F|d%=ByEJMI{V|n zR8d4bp<7SbQqqp#w6uFt0#gQ9I)Mon(AF9Qz3t5}tp0m%#T z@ceT7`gn4(JF?Mxwz#z#pu&+2rJ|*iC43sJ6Rnseko87M@h!b&y$PksX>~OzV&I$I z1u~Y&kaMzDJ-Jik+e@=a-;niE_88~>gP|hL)1SV(-RgstDxs@K;Pn&$y?l=mNrke#=iDB!!Og?ob6)#cKgC-{wxv5xZxo`qg{`3Jw1G$ zMYQkoQ8Bv?l@>T1LoswBkDj`4k@}GPv_~JEs+Hb>b76kD>~=+Q3#f{$;q?;=k$2Ax zvkNYh%yzD1{>Y4dV8|t%Y-rr-hFq8jsF{ge{~d|$Iixfu=mNEZ3=aHg_6_FRdB?A~ zVf@v$50P&L(ePxn1nd4GY*Q~b;H2>m?NEK(rTMH#0E zCg?go9b@b}&zZgTtoQSCIE~@H@%0jRd|C~2%0HEoiNXN;cWotaY-$njnY%LU?l(52 zlqMBnOMgS;x>i-(prR08{FyU(+2&_jZfYi-U#@&Aaj>b=jc3CF{(2Zra+Ey-L+RDt z?UfYIf??5eiWa}VWlXh(Cs;5Adpb9{$UJOu5PDUHI!FX;ZruU3IWf=Oa`#^9CClH% zCvL{2n89Vs1k%*`0{GLi8y8{;`_)Y8Lnwah7%GI zXE7yql0mYNv2fAro3l6*7k5XZJB$d6c`+v)O4_fHAz?URiic|PAN4vH5~Sl}K1(br zEf{(k@Xvn17?C(4FNi182g>}A4!65|W?0@+$$!rj5kMKygll#R`{eJ1jdINibO=nJ z5^$!noUx{vOAb;HFodbtAe_CyJsjkPPrE8Sf?!_tq@c-Tf#S$@K$+)c&O}sp6uc!g zvEt(hvL8YnH1 zXUogfW)_{%BSF11NNKac*cgt?Km}-VaHP+z=hg>_7c&If$kbATTYk@S78;j05BgAH zIDG72KR7Zr;SmqX9O)OlnrjTnVs)Vi^zo3qQITIG)H-rtuq!dqgnx7DBzl1VjnFl( zXi%;>uS-&*qr9pyLoD=h2xB90i}|p+iKPlx1_C?|(IT>)(Jn>-V8gF^jmUaO$3}F* z3zrMZ#c9t2UiWB&wo~=8e6u5YOfRvqet)Z3o<#uFS_Oj^&17HQH<9huRcBGPsfn^6 z6}PG(WY_=OF$c5#rM2II1u;f|B=n7yw3qi(;|h!~CrPVN2|+HrD4qVzO;GzXn;?m# zL4%$RDn6o&@Q~YGQmkFR@oy9{c1KuyFrQ=N@93-XFa7V#H2IJ=t5S_Scx2UYzE>J5 z4q#|dg9>uW6fG+4S?K?r-y{+3dTOT@mPN)^x@YW^@4$f)0Jw+< z8MpEKzlb6y>l0UF8vRJ{lCF0Vb;GQYE|3k>l&4-BMGf& z1gJF7_+YnLzW2C3Wxx_CSzpFnJfZr{zv3-x6~D$jMWEC&FHUP12h4eHf(FGL6WD+9 zbNA5Jx1H>H?)>=S!SZyYOVQQ0D>luEtE8s@Acuqoyq-^KML&S039iE~NO6dj=3l#r z?sPQvU$>mP@oCQnntjs!5C7dk&omeIBx--O=on^WO_cb`xIF^^2}?8tv+P#R!0QHm zz$V^%xVy8&4y--z{P##bwK{Ie_A9vR4J_kQ z_`9Ij6L-$Mv1FlFGQ2K*?a^&6ax*pD9$T?V{OkG33XOnwNQc(5E^t^O3z7>PH_K{m zvn>P?ewg|5xc+i0Zi00fiDpo5QKtkEM%RtYk-&2+1YpY&FI;v38tB66or!YMf3;NE z7%;(b!Q|ipYkgC7hMJ6=z;gb}RksDri|F&ps+yl$q9f=AD154aMUS*ad8u3WDwRZn zuBAMuAavre;g9#v`^iEb;N_6AIqCZw;0*DpCmnU=<0Y|H8eMrgDvZ z`}FdQv}B)kH`T@q#=++T_OVu9NF`JyR@FOhuNe4Oj6L+5jr-$%s*3$}s5%?i54B28 zc)`<(;Ai#N8Qf=DZLTVUF;8xU7WRugZHVVVOC%eqV|tU>Qk*QiORr-OYVEkz#VzGJesCKl#I&H z=wyPX6ms8p3jbWo+7kagQxF2fs-iL6KRrR8&tsAgU6v7dEb8MdG*V)8U5^C6NXs0_R%x* z`n@_0U&G&%)Y=#+h|K>FJ$%ZVnn|^`RKTH|x>x8b!D9eI2tLHV$-ZN;Isvp_6Ves_ zzp?25ja^Jff7Gm7%-L*vy=6Yff}bbj5_x_?&cXz4UHD%!=Zv!}rjH~~ zOiy$w;-k*+dpQ)X(R*20_15SZGQdbPhrMNt3IQR&+c;BemxVpGiEb86}gnO77QHMLePlBQYFG;A%5i*(joGcwGq62>+w65?U_6F588DGp9TSe5E-;z zZwI-K!sKNFM^r3P2h~5EP%^N(pW`RG1sd5? z*fHPsF#sZhb(MA&`0c&AJt0~)ET=%^gtw@mX5k4sCG{#N(Yaavc0_R<^3jS8(&=0)>#m;f z^*TxuBBSAn7_V{<7}#0Umz{#@O*@dIEb-Z*{Ug2>MElaM3*}8T?G~oHeRym|J`vi*GCplHI{{MJ>S*$4sm8qTj_%m%@?3wmDzCn zk78~ZhK{}obOQyY?Ff}shzIO9AGtWlDn$3`c#vyV-n5o5aiPM>F}IQVq^&6N>-TKB zp(wnU4yRmyFXYpXq&e%AX$I*4+HbB$IT!-QxOJJ_p$f^LbwWyX8UF`;UylbJ zW@*(Wc~gOLowJhb7pRIr{SNxZP(}3wOvz3-@1kLe^fYMoc#!vo-kHh=c^|#lgtL}T zeeAYd`86K~G&mL2m|I{-$wfyLo z(YLIwh4A`J|5P4YQScm(Rg*xah79^09v}bz|9y$gqV@}P4BOx-jpP^Quqmt1o@12ZwX zJf9Sw9qjg}ydBIEyrM?SlmMR5n_)Pj00iO$0nCG~T8)TZLbp!0f5)#Lf-tswk$lJk z(8pAh<&qWqtf8&|U8I1)t%QwBIejcfbaw3oYy{#^4LaY zxkgRZ_2L%uB*9yaCeTJ-*>WKdYJoeC{mNzN1gflhHxZa(e(V~zZo zApui4>3%P{k?nXFkF#Fz@iBHFN>@ngch()J7%6fYA|!A@q>r6KLjmr`ESctK&r2B_ zAo;C|K72s19;YY{@FY(EOKEu@bpGFv2hs5Hw}!HKStf>IKr#QLrDWA)tW>4gj|XKtk0_@Jl=L!8HFDp?~B!3%R5-BNoCi1Mr)-sB`-siyDBLCSpm0~AsL8gY`rBq zZpHCe=ruUWi(tyHX!7s?x`0A!_Xw-$k|CEs%_GLCct*T{?0Zuk{QohC;!2o-zo`+OGC$^-;FV5&ewLdXuYPmz1lt-EJUYT za>!ZAAX{sk9WUIkqI-;{R*80!svz(&!=I|`@Yb`(Zgq{Iq~QWLzv3PwTT+X+e->s% z113Ej)6%PM6JVp$KRvU)ZsW$aYas)I=tO=GJhyqme4is|z$ zt%dU3#CZT|!;d{15K!D%wLXdiWttvN#gbEGS~$*2g-1t^{c#v^06<_l8%08^CHyQ7 zg~_S~T=iOQ_ew3O2(@{cuE^6hI%}rm{P(ye`{;7p34n&(PN4d1&yDPN%Nmwgg^R}= z#Huo%iB(S!Py*|UBI=`hCmmQnVTr|acR6Tmw|yxy{ff*zr(Wi#6z*?p0nzNpSUC@##xY&kRcf3SliSXfh&p0IQU4$3q@ZBaG7tji&k+gq z!?Z|+mf=Bq`iSv&tibOIAU}Bgy#UwbC(j^P%@5RlX`Szdq?-@d*JD0!gswLoS3HDw z{uv%po=hD=NeZ*V0yiZ%rB8id@cDQ>Zd=HC&fs3@da|RGx}BoRD+(Ry!C}4=@d}pL zne1t&x?JvqLGZXcO@ zN?T3ti*~R7Tk*P%-SEOqz5(Pmb5#_$4kdxK`RuD^LhvsLj~2ha-%e4NGIV4^fe1qk zIxKwt4VHptG3bblqeJfQ?#!=;^qX^+I*c!M&Coo#_$jI+Ry=+9vwt|Vcl9_2fQmoA}&UMZ` zeA%&V%-Sh0mY1%SVQTnlfbNlx`$|D%^M5M?CIb_1C1RzS&4o58PxozrNj; ze)v17Ue$$ml6TL1(|MX!1xZxO>%w1qVYTP{%V1ji)`~gs^fV*?g23*tbZ1-Vo~`vX zCAZ6U7xlw$1Rvw9IRyHSGzHh}xoWuqx<`J?xiSd)w^NFbjxXDIh*IEVo#EYbAfErU z8aT$R&yyeYxbL4e9t&Mp*k3@Yd|c0Xn?OMK)-ZLI*+2R+{NJqesoA zxYg`4TJ1;1l?C>g-mni%oM4P~2zxIUPY&UgiMh3%iUhlum|kzy2yZ*9D$4NTJO&nm zIHMFEihE|~^U$FQ0v+GJzJSpYlPXZ7q5!^YXlJDSrZ@da!Eq`(YWKU@xkW39MA@IC zBVz0x)|fC38Q>|}I{Kxri4#kjr?JVf9#U%EE$j9HAIAWDF0E6B3}heR7UIE?M9*L-j&!nF+JpaO4QZ#GGR*NbrCd&CW-yj&=JB^Bb( zf@#9QIdKJJJ_DL@qqfA9exmUJD3Bggcn=4t{seXY#-DI16MmN~;wob(fL{L6P2&OP^@^ZxVZ&t$W^Gds_- z^O>EQGuUcJLm!`N-{aaWpQ?Bu^$!@UAmaWr>lxKFKsQOWZ2)EDsKeK%@Oeb=;gIM+DutlaYCrGYyE;Jz!k zWW`;241ib(JZyOO8r-GtbTtH5grWi!o(o-|!5Y6inBSYR1KAd>ed9t4XXuR=+?<{* zug3D8b~2HE8ShdIoHqetM=4JMI@kwdD^`iGnFw*7bzF{XHH*!a;0jXJY+dof;%Xfc zTUS0kL~Mtj=UW=(bs)i3OVE5xy_QYWe`jlI0 zIv=*f*N)_jbBa35rc%!*AAP^`VgiXScP2vBX>rGJ23c4d9n%q#PyS?VcKm2_H<)addIdxCZu^ycKam3T z>lsU+cg=z!1#nOFRfj1=$q7xB%=(`j{ER&*KZ>}`-$CzI6cn{Qf11y*ao#!aS`?nF zMis&1!Cn)TfaU|SKBG(19UbX!oM=}L(gRF@_e3Jf9%z=40&~l`*~2c))|Rg5%dgfi zS>>m&sXGlGi7PJnm=p-AXcakawFDp4A5R0pK+gGUF~4SlrNz-j@a|v$Y#$xZZZcH} z-WLt0biX{|g&sJ*8nA_?WUysezCqfT1*z3+gft4_SUktjha4V1aI0abN?UJ{rZM>A zTr!4zj-aLE|2M{S6RUtdDdSNEUEVj!)(3mq>raSn&I0gQGTd9TUVEu6zX=X1u5(GOhkM+|U(C?&HSM_bf0~;e_&`!z__JUubqpOKT=c2>fhM1M;6q$glRWu7sIQs1Jtzcs>@H;Nx}=}%MoHlYwhZ*b@blC;*`3bB3H9Td&e$bUKgJ5-Y8Ui)mC z*skp9jUw7EMj$Gj`TmpBu7nDOGjH5i$QrTR`HBj=l*Jq|&DB{$t7{H}{!NDQuE;9+N3-?<2wKg%IzlC1$oyl(?-A4GT&TlwO^UN_KN~RCvn~I2U z8|iz5<1pRJn{G zkRjYHn8FC8W6K*z8nSw$2-hD{U+_)y>S0Bd-Xx2m&#A`@ahe}Uh_ao*l#=a%ID})e z@uw^6rPoWKYf?PtT#3!5m4m=T?)eNS@hZGgrN}EgS$<*m2d|>+&pJ2Y4p)rlVXSn) zT&%t;*u&TF-_bSvOov{Ewr$feCKR(Gv<5RduJC89&x9h7mU5Tqfr0+lTGY0%Nu%PB zpU)#uFID)c(~J%vg->a2u?|CArDvszV+$&Cc!Ad%Q^FJ2ATXp8e| zU!%0%2DDvGjy?|=B{yu1hZK$kXr{rbU8v>>udYmgR6Qb8zGM?sOVP7Kz4p<+-qW-q#)6N_$`8z$4E*)2Jn=ih{RO)-pP<_?+Z3J zP8F8w$2UoLK$LvPCN(bcjq{6-jzmochF&VW>FLv0^SZtmr^+9kVfA&WKwJ;XO`6gI z67hQge&-;~P~=ck_^NGG_iXa7k%?pf1OJ_|Rao8Z=co2sjWxV3y+3rzvhM z>7Zj-O}zP~U#$=)Ww=wgUwk!FD|HODJ}<~)!=SGnil1umF?oPP`=AHdd*p6#hb({To%<*~cVnUN`kK=X*`RCx`$3;F;=qZOWDkko*5`XGRz&|gn zCn&#$9~dA5f^YeTCqbgrAE|IP@ptxrDBI``6jgK|PK&f_>brNNzn-bpyTgyt+a>yD zr33dorxC4x$8!CfsLwe+lP0!|^ltNjZKS>AGR{UsMMVlzr%DS5g6hLS z$01K#IXI)4;7Pci^%P%-!xLr+BE{baeR>5@TH@uZNXXhJg7rQmA8*Zk*Ff?DyaIhA zAUby7)-|P#i70T&yG9+sF=H5!&%kfZQ2LhtX=~8=xbM=$0qS8s4a$SAP?(8ZWp$vY zmR3apamrLx`(q#b5QD0jpw9;aD%tviCF&t00nxQHfJD$Pgt~U47Cx9;2zne+X^9WG z>7Vg|T(=v(x6=y|PkD!Rq^`21Zy`Zny_sZbDI_nXZ}%&QiOZ##`#dJZxH+|G~jx0m6WTg ze?ZR>>Irg!W|(V0XXetS2oxqBx?dYAE*L>IH0XLljC@4d>3=*BMwsk^>9V93DA+$?R5YfMIkBj|~XI_)Oj?3}SANB}tzx$qodME`(#No*u0o;zq{XCVD zK@`_?dbe7?Z{R`7tGl-ZIaJ}-48JTgLcwWP;A z@x8>Y{7V_;9NHSNJF0I{HUCh+mm@Vb)u9*y!8b0M6?`l*H8O0s>)PC0^QBmc;@9{R z3pqAp<4EHjSuE+Fqs{!h!xMzPb(4cp-h>wnTbnm+XDE2OZM~CP`zvl`jmF$E2en9Qyb-G8m$^J4U|g|D+HUSJ>51Bpb-E32V+v0Jof%#B z#EEk~NkHeSacGvF-!vEMXazex?E@Ws*7Bai5k`d2V@(mw5`sB9Y#bKYZ!E`-Q0&oH z{r!W-SR;Ky^Ui%d?FiizHehw?7h&MFUT<~kDjrx zD#B`$X505Gv8gyQHFUvpZ1QfN5`Py&YdYJ(u^q?-eF~=wyr4lT8+_QNcfdzniI2&f z90{FCMy$6KD)(MwP9AhU;23{l4XHSdn8!-4EVPomkYa+ zo_eE@&J5G*SEU_#Ry&>Sh+#0P(qt%j;CLWk&LpJ>ikCn4`4Ul>7&g1#X z+R2py6=`Xy<4U$6UCX=n^;(R`~E}iDaQ2$F<-+UE_xgZN#w*2}^PwwSpM`Xia#@b(Uwt=e zMc(|STe+SmyOW2t!-qX!ZNyLDVR{MR>t`L}of;Y%o;yxBZPCv)StUk^JOo8juXNF- zJMk0?a|GOsU07Oryt#OD$-ifFEjrircY~H`*m~m)t)-us zh&)BL)-s?|%`J!TY^XSXjV#>`&87u7fwiFMhuw`9uYy?8-A?+ZZvmWCQu%G=7TD@g z%Ykk8X{i8Fv4OrY@(z`9B{Z|URK_(OBUNTj_kmN(T|o6{Vl8EsMM%hq>z4PluS(5z zo3`Ap`a1_l%040U7W_*+*Rug~Uky=+)3KeXRqa7CP8L(xXeVJ{{iP~mR0C*PtTs%& z7Cz8|SN=lTT7KTRCa|;T7+Y+x<^x%XcegAp>#&?P;d?qg_XfxKPC{@F?1RBo5Wj8= z*prW4_Z#m#eOd%-C}pgTCws5Ic?dES1i)2rB49oRcf%>eGGIT?9+pEh(L0M7q$;FW zBHIAN$?Ot-n`a|YMcG;VX&9bZ8b9#JvETD}oC{5Ctr1g}U2jgJg%2MX>f34=uZOf0 z5^sHZDZKp2ud3TayguRe>z>kqL}RTa{#vWmNl4=Awu$4`HjC0L8EAvRufyVq{SpQ^ zbU8)L?#F)I<)ardA1_YqD_l%|zkj3$b;`|j8aR9)zvJflAbVHa*luYGy}Q@@+u{)S zT+EDtcYh7%X9ijLzR>z2iXxF;XGZNQSI_PzwRI+uZ+(_3;?F8d5K@CeXvI2|3x3zFpK5mVR!8 z{o3>OTR*4y;qYw^{MoL}BVoZ|lhHkwA0_>gGgpBNpcrUjGH1fc#mU+G{K4`M%=7&v z)Y4vN&Ydg@&-w-R5RlLV>uGfM-6tUh-6|}Y=09u!K-96gdd+6B)k(?p!`VMv#Xj=$ z=P#(mK`khO0$|QB<>kn)h1JzQz0=GMPB9Qm`k6~AZrZxyGBSQ?(xr7N_~>2~BO$yc6@>4F;>OV))8c{O@GU595c_;c@&F9Ujw-e*5XbfTyYFc9KqWZY?ommaaskTL_%dc}fj*VWrccOb|Qc(fXX0MLiDoGcDGMN?C>ytC0kn z@4CFzg7R{5ZCV(W*YT#Ndq|HH4PUz;9L_@Q^~Yob9>KRFf9gyxpxCdU<&Sdm+pdZ+ zZ}N{$L=w5-oAoNc;M~r!49;8;>+|FN!?aQRG4Di}nS*Ac&%P7E*!}S+0`(Qi>vBS_ zle$_bUSSNL%*>y?*zVzyJWP zOwo@J@=MazU7vDS%SXm^G3ITb5>|(WZZHe$I12T0DO+o8rIl9Q;Cywfihdw?J<%3EzFL%Sju-IK`^dlIg?*%g%m7IMo0b}^6@@SdF!PH)dSK7cG}IL;c`aNqdQd>VLXL$HdPx2;r0 z{g0VeQwK7rveaw+&L0hEj@9`fkOEV&gfw_^sd#@-aj`trU2Hn4%1OmOiAPfSD{I%=C zx*5^q&q|ub2BQ70?50ZDqE<69cdZ=%XqPM87a-ajbJYqrOjLvg+cVo|Z%8OO)Y$oG z8)+8CLO3%nQhLsgvH|b_G-GI|X}4fPUOoE|kZO!}pe;E&5^=IXK>)~z zGuT-6C0i|z?hx(OOER+0(*CT#{{m>eps2?#G5Kgo`c)k7NKR3lU75m-6e!p_=qSLD ziki+!w1^TEF6TlI$_Ir0qZYX>T|K=VkwB_+HP!zojRxia5b(dhl50hbPrJKIG~ZV9 zlK2POkr%(_E#$Tr1>E?T5z9T<-r30!slT8R8P|!Vn{oLU1^jO&KguXAExlt23gFiP zfplqEK;bO^%&Kv2Rv^OBd&Thyg(N?|=OjHr)7u znc1>5g@<|)h&7?|j2B?kf6?~WK>odoMAQ?#{}co0cUVo$F8E(N0anpc`cI))dr{S6 zLqoG}Agjp#e|!IT^MALIBzd`R!Q3hs2^iwP7sa&wW#1Wt|JG54&6K!8ZEdZRUbx-` kVGKl2JNe9i3U&lufz@BQ)`kX(fI*`=6-QAZ)y1Tnu3F+?cll9DcIf&cJ+>%VI$uEV)I zX3sqHOl+f6m1W)_6Cwiu@J3EnQXK%G@c{s89T6IQqTRde3jRQHlGOu$;$Xi1fw~IA z!vO$tKu%Ij)9b_Wny;Ior9aQZM$eDDN7>@XpB=ihBkAVjEyq9We~V($aJ8#J$IX4C z2om>R&ETdyD#af0UgAH|=PYEMhTok|PL~#iL11f=L+O8KoWtvEI$ZD9Y92?eKswqn zWyRUrZD}+~meADPER&JMNjPB@kUvQ2nEuc8 zR`aMGbkN1cMOT*~z($}H?j8QHKX`HD%WBm5#WBuxa}vg*)BoGa4pQ$jCgc*%|0Kf0e2o&CJ3K z69bTd%(luHEu4JHfBgtoL&I@0306c@&CTdYwg&7=lE%=$&GE`WLu?VmM!<6O?Xif{ z!C2|GBWZ^Davy=khel~b7QA+RGO~PsI;q7SONvnA!~*ZAch23<|8{)4%>?DO+4bU-fs6BCVB9kYb2>!@8Eyl{PND<#!qocX4Gw^ z*GcRXw5Xce%;xmwO~;86nO)VYI)XJ@gVa!SQPLlqK;Iuo8fI$v)K(Zr%^JT6iRYWA zlSWFP9v33P-Sc$cKg!zIv`BSpE48g@(JB8i;7}!Jq8Y2laF0-m z1y|~Se|5ww##z)wCgMZ&kxW4q8AMWvIGG&83!+uv#niT3(ZM;8OJo|o^|_Lk9zsFc zcuo;fqkiYI%MJuBi6a`CVk)yZK!7tvQ*s;g~C;J&R0iDAmw0}EvT0lxlO8=Z=N-$GH z6g3_I{9~SiwdJnP#oYVFCu_Vvob3l)EBPWCxZNY2ZZ4(frqfO%XNoWVQleSE^5vmS zvtO*{J9waBiBK#N?;Ful7t*&c+AQjT#cPqEF!^x~j+7IFR@*ZR%9!N_$0=c;0CHIS zuV??DQ#Ph=PX>-k(@!oIg;^wS!%s7Akkxo; z^zUlhgYfVif$Ybp=H95={clOEj$07R&- z7OoVcB_=$}O0%B(&zBKv?SU_!Pj~4#`1mRv_0QCoNkB1}50E11$1gk&GN*m~eYkg1 zg+&Ju1A=DB{5DpWP=J<6BEZ-|1i=CYu)FWSb$xl}3moS#s}s<-WRpsN<4bMDHv%kG z<@w>nNsbyaPF;Bz%hL*9VuiG!q4yBm>^ zHcir0D`cay(rwVqO)6A$k_v9T0C$rze4}0?*-eeY-TjS|DkD9c?6ka82!_8#1Xgv` z@7CBv`;!hAgWCRncRe{_U*l+MIPlCXV@WqD-MW!mIt?CGN%lhQYLXj1Y!zrXfPhIY z8%Z`&iu>lrt0kqa+}jMNIWEZ6;!l8*ZacXw&(o&;zlY}AO-KobZTIAau>tSaUg zn>Fk_qqO`R;shB1)`q8Jy|o{FQHdaeaf`b-7x_p2t=}uZv4B-fqW<#2$x`xRYswssS_q~H#Jss?{Y+>X$(I^p&3+o0 z;wC?jNskb4iIrKKX)5R=`7Q^iIO+H!LXfI=IJXq&G}$v)s?nCJ?{ayLfVVa@Bsa3E zv(&8)(LT6?RaN}XA&POYXSWcAb^qav5l#5+&*|Dz{u2{Ul;RwpzzGb zzC*E`?0JN5lXm!da}qazdlHX>li47z4v0h(f?}RZ__r03nG1r@%n%ZcwH&9VY=r?Y=niNpU<-hJn3sAjEKO%-ll5f~~>r{&5E{Req zT1(~mgJ)>Y&;PxU(p(X>3w&*HqeS{{Q3&N?pSG5^`>oqP-&Ga2R`@rH#!=!-RId&p z?HKn)Usqnt7CrkDyw$U=?aBVa{-SS1u6UF6sGaQ=uAIa)Fxrm2?&_HLp=iQ_UXM2s zai!%d`SeUoO!V~LXWh3zL3K4FVO$4SXUyg0C3LVT6D~}U6(_@Z!;BR%DJdxl3C*_7 zj8$q81VER%n6K1W=BSVY4{k@{6u`qR)TgoT>^C=cp`;x;*7l{wY!BGx2e5H)7c`d) z+x$$t+<1qR=GNvW*zJ_uC+=hRy@SgkHabtWzdjp^p~p%Wd-ko)EQ`%?!hsW5u8R~y z#w>344E$St9BiEST!f1ndU6u zBFQj}F#rJMt1i=F6F2Y`KE0?S`FC>VF!oRToBE4)QfkuDmckp4j<+eEjoCHYF$*Ui zyuZYCxe&{^rJ`nPwG~l9t$E z8FjTrNCUdkT%jxkGplN6ae1Ng2}0K$r^+iy8u6`AmJ_-$Lz$j!fsdTVFQmVK9C524 zpQG=m?28+N9OoNilw@l5A6@y8^}0Xo^6m#m?6_0>8?dDomX=^deSLk?e^gIdulMqX zX+s1FS_GD^Dl{>Ne=Y8M#NlAVLSf^R5WxZ2Wy}^a+_Kbq(3u@50C!GY!X+`!?T^ps zI9_>Z@S)q=+x<~n#GO&wWx@{-09h0Yeefr=7$zd@D?PNpAF|>E%?kKg|1pvrajEuw z&h_zeC=uoi!&t$$KF}ZB8wHy0F8AIOy=3Im2&_IC1%PCUJd>GsBadB87#Vn$dx2kq zuU@d>&at(%xw^V+o{AbY6`azsuVT;n!59B|C0l=y%@Z{-O+Pd=)S-3NqHz}o`^>&; z%4VFVQu5g-y|Amx^lZI*hsL9G&7oBT+nhV+#6w`%8C-cXwLQoPEE=_RbX1g;<&!lv zHB)nPRyQ_O@>D*2YhY@J2XZE)31ebnh=_<5SgoJ39_vU8OGZ+mYLQxfzci(48kd;X z=gMrHM~KtrbZ^h)FJFe9$q;%VC@4^1f{x?2qc=RAg1W?J__%)t<2a*rHYp(iAt5O= zAeTH+(pm(;V==0LRR2_Oq#2W8{m>3U3>h_}q>z-nufWF|y^%;5)=*bh*U`a?8Dx1c zxKBi6YK0gnQ3O%IoQ_Q@BVgB;n&Tv>!IY|R`tMU$H+6KKC*PSXJB;fzR z3Gn7l>N2(XKYCoN_<>gYMcelMdlDdQU<(8ysJ?@_avC}PjiWZunH}nHeR=$xgOnUo zg1G!!SX;lN|L9Gg4}!;OK}gDO`379juin5(zyJKVhrBuyHuC!(?&`M_=OgFmBW&&3 z*t-@RN+)YpoIVF*G%n2JE|1|ivQ}j(g1oOEM8J=e@_W$7&7G*?XlP_}PNzk1l_@X; z=6b^Jhp7(?X-wlwmKn##fBsAhQ~wJH{5S3|yuq+Qs)WVc6t2Bgg$u9E+$kB!A~n+T z{pb5QvojMgcq_pZ*S1dz{RI_7+>_HX(uSPv_*gh&*0PTcWm~Q*U^&TQ;HvB49$1=g ze*b$g=3&ttHWapoU-(=3$*2w=DH;+QmlV9b!khB--~*Rl{lnms6<2vxAN?lw;u*8O zSPP$Lq#J5=Y;%7!dypV#>e`flf8{gU!=F2)-CPWe$lY6I%VB|7kOsxLJI>_tC?t=C zs^cnSq#EK=LvYkN`kFOCMb9$UVFfk~#rnU{L4n*96$kf_u*Sc;1IA~+>G)l1DLX!@ zK+DNbtzLydDjHs@R>!Fx&}ZRWSeQteh?#(_8pf6!&7M1Fx#8b(1C88(W6SlMP}ovg z!naN!Ure6uJ%k&LxLct(tUm!gpeoTqL;pcRMF9jiCb!q^12`tN8voTZLGMPd%6#5NkFT3eLXN!eio?I}atyn?E=;&6z|WJL z+-m{PvtLR!VIauO#+CB%@d+Gx9vT%>Ac|8Hlak=07tQp2mmG+PS9dFEt7tQk8Hhg- zaB+2k0NKgyD&tn znnah7g6=KXjc9Xr4}s5LXn31XM-^Qpi8P;j|+i zh4IkB&CTh8jk8{#r>YkC)O4ot8Dlm<&XO>3PC#Z(hxK!YdAp598po1%^LADF zxQ3qE!B^)7YW*fuIhc4GiXPF*WTXVct(vyKa;tAvEwC}an@E0W?Beo zX@~3@Gp4ec_ikL-Iy1ZYf2PU%rGhK5`?x&OlVi63emE{(=#8(#^#-NEx@kTBJ#hjZ zGPH=W@+iB48o(A%&HDRl6xTJ6<4k{;D{mhz_^jQ#xoXz`U&fx7P}D9Bs<;-G^EF(F?DZd?5wp)fy4kJv=l)r(prdcc1G=b}!FX z16Oxf9tKb-IwdySzO`iZpQ4|(x0ZAo+-lQ*tk>mEwS%xQ(4vJF7PR28?;C3xn|`xm zn{H5qnJ(!_h0Fl;PT!5$GF!=?@pdh%2H#--Az~+;~QHc0}xdRvK2gK5+V{N zm!QQ5H1w2@n2IzAQfjm*ay28>5^D2bM1+@}RBc~l5KXFmeb$1nU(o>uhB8_TAK!ga zNf-Xyhq7hj_%QBbP_xWJs5g#i+8Y-3%YSHxZ&!3Y)O^Rw~%k;K$z@{05&U)SXO7!e9dygDy`QXt$Fq^he z+9wwos&5-Zc|C|O&zP2$=K0GR0f2=L=2_3wbIx%CpB!HAs`%S*jE4-m)E0ePT;Q7i zsq1%2ynQ9*ak8>7<7_n55Qstqb56N-h*Wq5BnG(@ zUpKTwHo6G5DA<_yk4xK+&w8JbuvM}8qjZ^u*kb3lV1WpekqpjLvT{gO$yc+<&vTft zCRTQz42L~8_lVDs;Uu2?pB}VR#eY(XSx@Ze=;JlXH?2_}Z9LnH1fBo>GNaG^|n z->;8oV@fMZe${$s2Xlpm2*->ntFaN_vk@`F!xP76iA;XadXRaPP`9#CRfJaUlQ%fA z5CFcSqRf4C<0zkH5T*S&YP?rOFJ9r_R-r~l-7$!#0k`iTU{574go+tvvGu_}&8X9% zgV649B+r4`X(qToJSs#K1_E#nsJbeR!yp#PR#i5JhqFXd6?6*W5@VSsDW*@ezyDy! z60r}7t&j*|er9ruF0#r_r?*eI@H*vwCO||alKEbdcX)5e!Gs*!iEH*wQ(YO zi6sFsY!GoM6cAzC`p1zf%wnLBIqdJ4i)(TIqhaB)pvxcCJdQxaKr#wW6nG?Yjj&l^=;(N( z!7+Sj;qQ?%WMpn2sInCgkpAE!=T9sCsgGQ2+2L~8av`l}s9FbwpFgM!s?V4cx^HLC zX4aw0hf7}#3i$RhVWJD40*pt|k*3&B&V#{WJqnUX!kGH81UF- z@{z?BRYXTeM?^$qXA_<*Yg;sW-=40m`1DB^J0C69bb6drRa9i28GZ;$2N_vub5atR zNKvmWZ5j!0tUv^GEgpWx9!%*qE|+P$7#6riPgpQAGv}TGX=Yozr;`F_KgP#7axCKq zs_N=I`E$FwyBnC!R$CLy!=qnwbMwH!z}ngx@LEP$dhhA(;qmbF+|bZ4GouDTn3;wAAKa)h zp@7i-uhw&Apg6P3Rs~j`)I{(BEBs3|cMnfO^N;@i{yI83fq^1GZ2a3_o*Pd|BZx|& zq`k-7RfsHLsMk+QGpu`CDv7yJv z0jR)8h-iS-C_8YeTtxmgJ53)qW*4-&bw-`q*tocZGm0iAUYQUOF^4if ztejUHL8($pedx4(3FKP8?@k~i{CT{GZ_&^-zp^&qBY1cP=EJxhe#zGI#jm!zmixq@ zOR2rr($dr8YaCY1dkY1qf(#MaZ(BHH91cJo$ey_Q{Q38RrDCCV^p`GmHy!{8LJQ}O zr&1|^jG5LeDk}cT2iXa>)X8e=*|%_%4(yp)d}*u7udgc#TG;x!>WZw=BS9Jf+jl?$ z05Upgfb2WxidCXT!QS%n@}?%Ym*=No(SnMKit1_wS1e$2rP&rVn&I>Fugi9Oyr;RI z>n3{X(8y+h^@9$t3rXnY zBzY2&i>=@un>q29bOlCzNZ9aWK$Cp*FN3-#?!`ZV38FDfJB3UmqC4S zxjXLAno|U6U9Abo1rLXZFwS$`d;em4ctQFR7E{RK$-MQ_3=>`*f<_9ayS2;X7W9(t##f7S>*ie1=$l;TDLMR|t z`1R+Hv3VAJ0TebMhb^oJeGJ_fvJO1BH093K#@CU#tM{*dcK5k$U@`=a|n525CyhWlytH5 zGGvhY9c{!t8_E|rrk#JTa>*d90V55;`(o%pMUrBPaKYw!%IW4VctBA!bbaQ?l}51| z6ACWM1lvWRp`YNn;M7%DEf_IEO3p&3!Sp;i07MR`X==`IY}7rPDe{-k>FMhJTwbmW za9Or%DJr6rQiDf8z`L8Hk7i(DX<0o9AxA|;rS^mgqY@F}@wCC)@8mjaNY7pF5f0tfjZdLL0{-BrIDR*+zg_oL*@#yC1|kd4 z2O5!#j11lfjt+5bsn^0GHa2gra>B4g2sJCK<7$ijhq{cS3eaG$!1OBg{TsgyZcP&t zimWmZUSduqnPN2%3BfcE=mbw#XBe5vw?@V}ra566pRfH(iQI|}w5yd|1KkPYXn}%? z@brN%g5v1%$f(KJU^RZlu0@vGlsjj5Xh`-6HDwfg5Dg;!|GfY)gMPyKOyl9<;nKxP zs9#_}M+qhbIF%yB3ys+j0p;?PeecF)V&riA2+$;oAZpm5{p15|V2I2#ekrKp;pY0e z-?W|~T3ju4K(#o_M^E>0nrLXyxJJy7%h=KUGy#Xn}VFbv+M<$NQ8`7HqN&Arlt9 zk0-5ENr+jAD`DE4IE{ZiwLN6hV5-6HG#pO&XGaOiJ|5%<7qZC7 z%tVBRrlFzPa{6h;{=Ua=*@|;-e_sO|4v5jd)1|@E((>cAdjn5LOIyNhAl>Q^_sLX_ za2|u6l@&}XgX9AS=-t@(`LiMrUfdQTl$sGSM07|!R+?(q`F10)*Js?K(fYOw2OB$a zCBz2hzSPUbMcp1La=?sx@W5?vZ!g(1g(kR+f@gTLzE36u`;!IL`Hb9RdU+4qg!_i4 z(QXu0Y7x*EuaH6O>*Mki03_;in>F(N3wT0N|1$=jL#-jjl0_pQ5w6~~A|8h50UEdj zE1BqTTj!l;J=MbV{?zo*v+L{176QVwa=^KoUOWW(yXl)`SU^or8+OZC4m#*9P`9+Y zyi6}C5qr!*7zDk1>LhO(TNqp>iZK9O!ABKALdYwMc{r6)YNw7ZOJ$de6C8LwVoMMK zFVAC$qa)o?EQA3LZsXzCe$QQ;Jh*ODpLB$yXxekk0p(kb0Cj4q9~DbeWg^vOk9hYI8yqxHCW2N7j9S3sNX8&EU4P>hR`}pDQ05NBetCV9BbC^7Yuav^3D==J>HN z5!4&Axpr5;seH+oi-X732HK#56 z{<+h&fg@DkS-zi(hNb29{gqJuo#fV^KTo|+_GiN)r+@EHMO1BMzCApum-?=6!{ec-E# zGVWV6G`pXwGpn7Q-MMZW5UF?4#Rj$Sw{_FYtU0Dut+LgzEqM+1Zec{1mm7OKZr8C8 z(6n!E;E!(#lQF+8$A$pF#^ZN7(!eKo88+U$90mA^2X6Z!5UWkB2m##)HH100XlZE& zJUj)|0ohq6lPw}N!ShP87v1jalfMl_~q6P1mVF(nb4BN z8*V6?;OMD|s*TK{3X=h-yu>u2q3_~jG8MU&>QW5&F$cOX5CXrR94{}+ej8PT{#zQ zoVd7zl#5d3&RliuP--OjP`z}b$A@)BhG>^x2wfilUTrlK%gk;tbaU$J@+;ox$5txz8WA}bWpaw?i{-HZz#_5_BsviZI8YYD?Tcw5)42!{uv_d zaba3Mcb~U90me~m>9RXX3K=2r14$1)aH1x9`pMW*%l;34n>#wb&dFH|50eF+G=KJ% z|5p|YmHzbOSRw}NZy}ohr!OhOes^D=N#%9GJou>OJ9xkj8bdsD!Xjp{=slmduI?WQ z(=iF@dZW3*eMA;anYP>#4BDN!_f-AIl_62RW!d-duZbM3hhKVZpMDkpvahS^4qj*n!BvnH6NRyP)DyH~=;#+;Z795)Gzr zXQ>Bwa+LmgL}rrKchX{y{B}8@^Wo~=+E%U?s(=%$txsdiD8ztC(BQy3gaT{eQ)(K0 zO$|l{3J{G(5~B5ojQZ&fhCUWPHR8l3n2Pkh*4moOkLTvhbX;>0y!w&-&&Nv41y(ZuB4|Z#6mbQ3gD!f zUO@)p({T|*H^cFWrv!`b=Y6YpP+6iVJ?c=0lf2ve#pMVq8w0 z1`_KYq|$e<`8nvCnhOo817j;Q$&IGOHO7z&**?+}lRp2yW|0k1= z49Xw;-f6zi4ZQoh5`wM|_LqwL#FyuDbMb7)B8nq@#tvIBQen!!aM5IZdoN;eE$9|N3w@9X*V_j%cBhKEWuU0qog>4v&XXXycQu>)Hr zVWqG=3vf-E8dzQzQlP7zHgvjY71tPXkZdSlJG|h{3-IX){e>Z}4-O6WV}0&zBTrK~ zuW}V5qs;jxR;rql6-uF0k+{J-I0|gEP*{qfdyTL@m{p9|RgZayySh>$#OVr=9;cFX zf^tap;MUPP$kEnlDx^qi&<6t&H(jh)RYLH*msyfd5jQKf5huW5%sXKp36SE0C{n}0 zSWVtaN;||mR2BEX*Di4Mcss(UKfj(p`}{(wqrQ1e?TG%JgNq4{f2uS1ID19oeT}0& z7pPZjBWWJ|l2#6&k~4M9z!us?(5Qo1C8wsQ?`Mv57^XIk!`Nb0P#{+MU;q6J)}H4y z&1>+CV5N}S*A^q-HGDfOyZvj*q~)Wd9~{=_TP-57!4&6fGu$*2cqH(EhU=C7ZlsM; z)t@@%^0`V!@ho6p7Cjq=!Q=*|kXUFebI?AxU*W5E8TF|W387efr!rv@{ zu?<@|xH*k0FHm_FpNO61icnNsDpivg@}B~ZdAOE+Iz?sF@bw)-2FiQx-ig1ix8c2C z^!M$R6->cKFz+1ZN^O;k*oBYSF0r$6SYLHg=8@tv(fy-xNkM9oNsrS7eeAVSP>7uV zH{)$m?eik`dk6yHKDmBC?!uz8h?@!7hYlj9r4Ew{}>`T)05K; z-xb<^%8`|Xrmq6Yb@qau+|OVBB-3u5d#6V~2+dptPgLu$f-PMN6hWX{M5`XIx8T-c$(~q-Tut@qDUnP;nt646PFvHj}K(J$dCpE)ko;8mrB5ehlhw6|9-sbN< z3~}4nq$Kvtsh7-uJGOFX_U)w>&jO!PbSJLXIEsU&mGM#(oAHH9&FqWV2maJ%fxnTrCD&LhYhYu4gAIL$ zIjRx5-_RJuk8tEL{24(zJmkJIi!O6NzF$7-Q;JHiO8@J-#(;f)A|$FHh{WSO7h_s7;3c=#!s z`5-+7~C``x5P`o^ZH?Uah(mBEgQM(vElC zy45`$E528IUwjcu|9cyf4X?M@N*j85x0*#%v!RpmlDtWQ64Kny;qfO>SBRriZvI$L z&Vszj0X**?Eti#c4U`JLvI6a@p>)$Lhdvc>oFpX8b1AY3!>c=5br`P-GtFOrOn}%x z$+$Ajw%_tys+F;7@Av}t18QOnj<%B+Bo|aXPAw$`17s=Y%}nEH^3(}XH!Ku>GljD# zvw^uMbP#(Q6Qk+JSA9Qe7k&Mzx)H_>n=UJ6T~%E!v%%T>H$OPj(G@A0hn>C1QTzaG zfhp8WHpq8gjv1SOLxWf<0?MHulXbF;t8Q7<{y^- zJuAVQynH%SCpNw~m`i{)XDw_efY@ve_81zhHh89gnLRWMn|%X1BjfS)QyEaD6!#|& z47L;buO76+ra29p!)H;H<_aJWi-TT0f1FA6|9oA&pVT*M6A%aAi4w#rJOYZ_N;GA&yASLg6Mk}`#IYIQdS9;7KKIzgHr z*;__MwRxm4QU?YY@(LjIuMRr$X`=9oo6?7 zdc;D$_lJkGJQS%nAQccttU&~EM8>zO`dTT=PA*&veT)}e0G0KvJ+(7~!2i5y3<&sE z5nSF_YghJNGFDHo{uU6ma=^{bk>KL;QWg+b2pPZX)pI-MZZY#dyQG>QnH5^`&5VtQ=y z&^7foh6Ub6!T`|0dgalDv0yE+AyvP^8A^_?#(x*b5MACCTxKJ)FTA+HZpNpn*gKzi zu*eNQ+di0tmQxKuN=gO0l8oPYr;35x+nn2|ed<;!{}kfB;P-@6Jxu75ABt!BW;pU! z^uiperzB41q%{$`xDPl$9Aa{bWA^xo(T1`UgKtmy{g^)xc*3~E_0n8N{9C#B0h1Hz zUs^4Oab7AV2W1-(hB*$nJMX3ow*B&ZzxyOZ*Jt{RIEAWBOf~FRF8^vp+||Q}UOtP~ zhv=RK9r6NpIG~DwK-*hVOZ~Rp0O&i+T3Hr0s-qNUKp%4f*AQcM+vhrsYh}OtVUIV{ z!EWuu${H#&ng)S)&ycdqNCW9|FAhnr@cA3L}e0fxQH&@rTvb-8_zm20D76yVN(3aA;lF?#CAU zk76m|J!rkgJpsQ14)$_NWvsftf$axn)EAnJ3!ke~Fu;2lvZ{oIn7px)tyje54NC<1 zXn0-bd4qut81mgjF={vVC>tz2CiUB_r{SVZ22MX@im3k5^c z&>Axa107f?D+g^xTRwe##gmg(qd@2H+S{pj1GwS*%zr+y_ zz^R#qKopA;pJT7WMu4{A{pz!s6kYdr}-`liDTs_K#5=XFp#|rg*<6-toI%{&E zAfUq;ha`Kth#STZ4ITpZL146fcAz(64g4$U%O|8|uPBY{4&%7A>I#`L{+?f^=(()p zee4lFl0%WFX8Yn-{Lf#Y`mj+<8xw1mc=ANh( zz%kL>-ZZ6lOE)V=Rb2{Lma>K|zET}I%w?5$ba^nQ{O=1O zs@zZt$O3(<^O`=#x=n>9!PyY{0_{&?kjB@ggKKoPw>QI*J8;uuZkQ3$a}J5jE_iK= zZI$gqh}+4XU2a4N8k>6VDgvqEgT0HIa9a{yG=LcC->_wmq^f7T;S}S;&U1si4j`W z`n;ApR6Pmbnw#TD_)Bah!7=Gp)ygjYW?+owd1#GO&Z2veHWkiw9?HD)qR?l-3s7VD zAS>%ZqDX}YYr3IdT?RMkG6?AVx61gO?d@kG zBJNv=YfYjh&jm44vtAFE%HEt=ygRSaZH%4CcUwrD00EqW)&6tl%IZ=TRfuXC`2FSh zW9jc;EVt|w4{KhM##AeXNP`Dbo@!Hq$Rwt(k?@6X5gTowr_!;LL}W$+f5Qs~aiD>d zhb`s}Y)$hN{s;zX3!&UDHPrGiQhO`Jg?Ul+1REL1YRTz7ZXs+I7DTV@+etw1;v#t0 z2H3Q+uJ`bGWyqA9_br{Q3-a9SmW`t11+O6>c+2Mq^eXOGl!pUcOi3ZC5n$*_5cS!n z^l8wjvr%%@Xoh(pP9+J1mA6v@`ubsedt6hPOjHT%V1JZ6-nUr=T$=#^B!sJg2zLsILVC*_Zy_nR?v$hTcBtbvb+)oEwt3w6- z%ZlV^GvIol)tz)}RbAw3*@p6G6h9&XU&rrp$v@HwB>s7;@%}M^H2@Y6uHOc2SJS9> z;V!MgbHx2Qq4)3a8zL2)_2|GUFOi8d-H0{*rF;6!M_Icm%(7T{Gu%d&-Ok zEC0_`sf2n{DD+&58=CQz8Cmom3k2i?LdT@g_D~5s+*RY5TE`lz$~S4>cD5Dw3i2O_M@uEpU4otF5mnUqn5yZ zd>{y>4@wld=%0px!Iw&$Y<>4!)EYiV>(KqTOUx4_sTE^m^8Q$35YXkN;0tnWt3_$R zkY9d3+Edt=U8gKhMvwT&oJ9Abyp@|{>FYGExI)m!2FMA%PWg@fm&!Df>+g}Ud{JSW zEF`#xXx0ua4wDYZ`lR`2)i7q%pqk*AD%F?)%#QrH9ndjs^D1N+OdiT{xy>ahNI=-cFm|Mla|4zf>D$*F#+T=>IR=9rs*Z;5tw zN^5=eDrJU|V zLjD8+0DkxD{|msXKSin1MJn<-xPZPzQMj!w6~a+6lbRz<8{yske!dQh{gyChYA&c) zdl%f^3Pwx|Efvi*O(|Gr-F3AB;tY>fXkhSlC;{@L>0e*`q4nO_eR$>3;M%FYbGjNy ztA{s~^Zj!IFL-`2dp7kz^}w>(avrbFtX<)1?SO%~wC81F`{GasA-Is9zG&8Ffe_V2 z5Y4iJeY56B6MG;>7mvfj7jddv^YA=Rd~G)8eK1buhc*wA>k@@VwxRnR>O0IHOj4{gySi)nx`AFn(cw^{?{x2cduX+P$vk!__TEDaEwlRV*+-7j8$M%n zU3)&@QKhbfLXrOc%10OYz$8(0Wk}foV9dLyj_S@46G6Y?`GV4L-Lbpq`7vFj)U5aG zMLtxY&NEKX;1%uHv+{V3Kw=-WMGpVn9#56tYI}+@U+%_FX$bA(b>9y~CUPGwjg_`u zjxx6nRccIZ3rUcGmy91R zgu|^b$U$0mG6M-Omd|J(Z1?WpzjQsK7*)UoObMIhx{C zlXAuq(=awvYyu8O;u~S^~I|ZL9sJM z(0F^hY6Nn;5h{7a;C^HPoBnCsNpvQaIHzM=wokw8gDeEu$z%JTOy>3(t>p~%liJPR zS!Ur?SxRv+Pb<(jIs*+OaP0y_<^3rguFZ)LTyQ$=G+mI0n0zVwRty-oU4C>Pm$6*O zCBGcGMO_M1e(Y$D`_H#FDa#t<;Qe0}R~`>#^z|Q%GASCOkZq7Hp&=wYQI-)QOURyG z%93Rm``9B%)<{{R$)2@j8QGWY8L~|FeV>{4(XaRY{NDeb`ONb<=icu*_uO-ybHBH6 zO*pzK4b0y2STWx&DgGQZOH|XnkbMaNzm=t-NETx3;29L@CNrYc7S1iIB0?Z=QQBOH z8OC%52vpFsw8}SE)|8v(4`exLHVO^zxo4HULXz};zIgtEkc7NtEtHGoEng(Q4F)9l&0~9P+e@ zDZ7XWCV+>DHN8f5=Q1^r>f~~Ny)xaXsMc53YCg5VL+18z#*X@)hkc_6lawk);NxA! z_X7EK>%Ym5t2bD^4>=Vx4Q!oW##t*l?11@VXSV5b5n?LGKxlP28heNoPVegLzkbk2 zGPn^N@_p;J`q9&R^MuxeSZ^7VhHQ5)?4pv&f~bAHdB`8RlGOCEv8JTAUt2L(`KX%W zTdUfi%C$2f)-yLc6*Ty2DQ3{Y({Os!tJ;04<~hzs7OGA*U@Hb}7wJ^ymRmoVDV?R& zj@8O-yLoAC9E3~_N>TYrl6dF|reCP1uHy9;tbs%o!}vCz-37fp_2vk3{TQ#xC7Ry> zrs7>#%&Y7G4wpa4du^NKY@b5c-}b&m$$ng$BW+4&f7A@kOOdY23*{Y~$dukNw2vAh zia(zIMW*vH2MN@n*H3{F%4ck+fmV#2jM>e}eK$vo&i3D{okBg(&aR2b0fK6t^*>qS zt(os83#XHZALu)Qo5gmkg+C$Q;-~!9R7{Q?sdnDTV&KN2So1}fsqq}AvyWJOld&hc zY~{hvqbujS0Liv^sEo$Fv9a`W#JFHMh7+P9z}UILi0(~`yh=3MR6SK;s4Siuk|o3A z>T8Cg0)S2hKj}@10AeYa*}RC;yoW<_EO-Up1`o7dX##8Hg1nDiP&!8udZrzb!}>2o-;i$4+G4GH-Cz$?nNVg)jVwkd-=W`0=u=s#JpJqlD!2VLJLum)<=EpqKOpBX|+WdolSna}NkQ1%k|Ua-#J*6U*stonI6= z&*;ILBjyt1}vV%6X1i*QUh=3`mj}!Vvlw_=av!wcmApY4sEgiY?kl1$ZvS*CZrnyeqEv zX81{>s6CJ;HuDXv3hIi&Ep*}ljr4!A0YTWcgiaTZ@tT3zqba2Ya+2qa z4B%Nj<4d)(09fwVm|i`iZ^kkMYNK1eE%R1Af&3{09mHMHX~wd`Jg&d#x*hm=muvKg z1CzH=7qa2<^Go@aACk$m2lnK8V10c=XOkc`%ek&bA4Hw+^_l$68t-x2`Bf_UD2zXg zsO7HZSY@JSstN*&uRDkA=G%N<-{^1@cj{1=0aP zsggQE3t34|?b&n-3gqV^owDk9HATRVZrVwajARo6n!XlC0E)Y>7o-Nv-p~SOc=$>= z*YTDV*|r(QR2HIeBNVCIe;xq4Q{3LsLj#2kX0-+K@}V5#n1<#4sS@o*M)|g@vYAJ0K=u`@T zMeNyL9wS1c@Zfe^eVWu6d)k0Qc8>ungqsrL+o}S6z~aYsbyVSlGk3;?y&JD@g^m(7 z*tXl5p1(ChSzr4h5E!GIc0$)dJ2^$W{<;VTn5kdH)9M~s-j`8cNbj4IIaCy%d3o|M zcfUgTsV}fDOSf7sfA$-8DfGs0f;I_6`4K8{!XPMUNkuKl%6nvGfPo99~k$^+Gv zjOmJxWfe7-uXwSuja$l6vKW6BqoH^awi>ZIyc^H>el8luFEYF9cN7>)uJ-eKhUg@0 zZ>;Xs_H2oMm9wBDF2(){%Q|fP={K09iay$n(#ZFEyp8B-9~CiZmEV*am5KglYDAqC zAok@^)js9Q%F01*MRP?BvtZD$yA!P|tjnfz%Uf5$8ydjcVa|ljl#K9G<=q~I@HBoN+MnTezVV+Qg*Pm}@s3+<=}AiZSQ6L5oT;Q7892OEV<^EbRP z$<#LUMlHuha5z4`Q&Ft*O9Bxv{_N{V1)62D$6`nAU={-mR%GQ>Stv7EE%a$Eq9Lg< z+GRvU{+Zv12-EwQXYkY$W9U~8MnA8vG>|ORIrg7Wl zt^S^Br~c`o6KTyIthmI@1(MSa@YfS|dmBGWA~|7L5G)YH){(t3}sIvXR`dR5iVKI@z;B5q$j)%L`{&AcoQN*lz@Wlqy40ubnS z(u1^w$}*u2XJHs@;FWWIsnxs`KXeMB&8Xu*A-&{6l>=4(I2? zMsf(m$jHe4{QdyO-ezFl9hqNvu)OH|u+h?Oogneb^vas?A8H;R9!F>zmj?bC6Lsyv=a6EC>2qlB+8{jXM^IeWat?v3_S;&0w`H`yyTJ#pg zojy_dE3JN78HI~Q42f@M^E1@F3)=uuZjI~+gb@@DHwZA8Uj3AAk6hn>@C;$iVvM-= z@?7S9om9yiOTEDrB*pF58T6}~I0E9u-LN=LV)lJ0`a0JiYYaPn zzYuDwHXj~2m=0HtO^^B8T0YHpSEF3x*1(^^6`W1W*!rG6@isCb?YVhi@pJ!`;DagB z0)||T{45B&Q^|+GB2D$!GXvIFwkww4^!u^c6qbTvvLYRah1~k4r1sjXyw`Pyxc$Yw z!Dx+gnY1sD5tdxcNXM5Z@udd`D(a+1r6aVntA2jMtbUZJkNP*S5D}4=rcmn zXsZF!IQi-qD_h@yx*6>s=gFos^!0qSUBi`Kqz41>_F<=waYg<)u`t}bbG1TJ zzaIW1uGRE(zQ5mXG*<*haBwy4!ts)szxdD$_O>eVQ)WMp6mWAWNw1yZm=Vi;ey7gq z%xl&gFR}HvOStPIBk$WFrDE6#Q3fo3QpFGBh>Vnt0n*Rr?63G<#g>(MTH+~12*LfW zOwhaOC^9pdB(mEv^IO4%MrT_cchLUly*aC#*rtwKi>&C#5~(EXs5a2GR3O=xS9azl zRc^)`o1~Qs+21qv$Ynu#&t|?uD|q2>klN@7RivO{s7B|kl=u1mq^Kz%*Ye(ZC58|SQf1kPFM7}oT(qb)rX*v7rG_%}~$~V6Qt||#lxyyT>yQ_}r zvd=q{!_?Up+B=Los=tH;Bi@#pTruGfOrM4ROb;Hm*yfAtk!ki@IXQ!cN0@dsVC+ zD~r^G5OKRp7ndv8DeBNGjlEhv>#|Yr==nJs+)E&P)Io#3FvyRh{|HgRsN5CIX>Dwzy9wkXvD~gGGIKM>%-s;i?*VPms%!4<@o*&UzYi{07aEFZk}W+c}P>!ADTw ziajcFmKxRXWph)g`f_kM4Fmpd4T|J8$bhGSK;8RpZSNXfpH#c3XaO2Y!_?H2w6l31 z|7OT-gpRq;hGRKG3dY;iviL!&J4SJGVt@OHThP4 zmX5BF&jHOvarw{k^8LRNxT&R_$GjjVNKZYXiD_mTMP06z0K^FhuXOSRgP<#JJp2?b zkGDHM{KnL&cc97YQ>!MT9rm)T@SUEKK}#yj%FA|;Ypr_~)Z7jp_$TdPjoX~nfl@9F zK;6;NakDg*6jsSI0JG$PN_-DhB`nOY@XvWwq$Xtr9UX1enE-X+T)}~u1m=aRnP%Zk zKT^%aQX0$JT`SfkFN%5(Ct3md%(l><)$riJw8rtvBbRlH)cX7SxEYIhgD!fgQA&S) zJaFZxRpexEZW8?WP#x{HrEwu%qOmwdHxD2DCxnx=ghrxdyNeX&fooNUwwF2ux>eUI~hPjQX48OZyb%ExLu=& z8BRhWTxw&9)~I(+v_MYNi_`qEEE=r}hgCo(35P4xKs7{(Qu@his|Y`VM9U7^M-8ze z$)M;2+S6m=U^&APx_$}`5s+v1R-p2|HA*La9qY7IoY52%0ftY&J(PGQ?8oO+u33MwZD6&njy8D+v;;%*b5czjTT9`qjfH~>V;Vc?%n>z`H z_UC}WV+hnN&#J$`FflgKa=c!B?XdVco2re$`xGQ;5DR$4e*4lpXh_DUdl{ z0SP$I+k3~-Gh2tlps0m;lkEWBSv$lap_-7rub1*J1t5fQQB1r=uQv8F z{bHw^<2!~=oq+IY+-Dti8t=}rs! zY5s|_PQ)aNLVJVl?0=i`-+0_%l_I`|;C*x^X!(C)g5E}{!X2Tkp!>ng8>yeFCIGHV zamt{&zhiB=XwLyXfn4CTfXi%-%s*Hz7?&Kmr9_D5i2OI){~uv@T2R@~_V!25XBX28d^W8I{BOI|G!26y^dQ$*GABdp65>HAMT!2dqOl91qLT}K&R|? j%s_SW_g|bqWJ#QYV-D8ZD#c*`3jpq@>8O?{TcZC5g_%M@ literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png new file mode 100644 index 0000000000000000000000000000000000000000..3bc4465d74b0d454f377dd080dece7c24a88a283 GIT binary patch literal 28315 zcmaG|byOQqw5GIFplFfeZbgeb1%kV~ySKQfXmNKh?h>qcvEuH~AjKs(!Qm~xciz8m zPtGCPWM^k*?%eO*?|ws=l7b{EG66CI0s^YE6i5XD0Z|J9;l=V>MBq&7fU^Q-qG6ZRmh?{T;5}5{g#^S%BdeLH+c2NYZIkK z<>SMMR3ov6lIa)o=mWhlu;{;I3-#6Cw&j)~2SW1N0X&^j+6D`@TXsj}tVF(n2(5+H<63NSAmy2ui%-Kp(LS>z(_t z#%g7F47-{G7AtsrtF39Cu7C&n&PEq|3xmOy5bZoIzuerNeR%7qqjcS)sf?{5*x_-S z_b8-AnlnDXvNHBaf&9eu^=9nl!Yby|Rl-9||Fv)%A}~x!;|o97Fb5%eYhw7#zZ72g z#2^`vVbI0e&;9^zAm3}m932xgJ~EQJ&b~CVU}bl81my)MY>%{M0vFeKR;ER4Y-|J> z|FaRwaRk0gwB0PG8)~qfALva>`2dVFS>TQd{1cuAKeWE57co$n>#WrcrUQGlc%CBO z8l@2h(2`sai0gV7O}K2a%TNKBkMErC-@o6i$buM~=+l^ty{!lY&Ieo>w%wXu4)bo# zkS>u$Poq(U6UXcwPZ-6#KsYzbV7Em7(BI#GK#6v~We9!$=!8XADg3I2#xrjh=kM$$ z!M8p1Gzn`IBFf)8sZP25L0vL&rTawV_ zUxuSuQi>L$_6lJ&Jjgg%)EMTcV(ce!Va&k~PPzPRg2zb;yTevPd&{B2Mi?blTs-^_G`Gd^DFYe!;tg0|In^%~N zelRQ?02xt86+qW zlxExUl(62BlStg!9N~dhyPs^6wJL{As#_N~F9r$+u4Wu@Yb$;t45}GSiVdJ1;Ki;A z7O%5GTSGnO#RD$g;|;S*!(0YnR?O@ zT^WHfJ_nd?^OP4-i-b0M#d=Gfzc>}0U87ii%nK~#o)jsXW;+L0cDxvFGiI_-;FpA- z43b}qyscT}{gLS+1&&Q-&;J@~Q!G5=`>C}H;w)HN>gy0aKk3(0KK{`qpJG0gp??}R zf;gsfr|!||!fD(Co#|@k;=dzN5G`up2ni|>#VSGe_5~R?C4R1NWFT9Uwi{%|OuBS* z;F4-O-GybWlMybzNT;10`;zwM0sd{xNJd)Py6yQe$&X;$B=gAMh{q}i&+9{kQM4Yv zlwtQoZA16@IS_lhi@x(muESE z)w^j_bDpQS`EJp z*#RFal@ZtSeFiobrwS*Fk9xB5M13bbcBBJNOB}@i0bxv;8|fxTj4uQaMqWa?A9uzaX#WO`*SvMAd}$>kAbZ@;pnaf#iFT` z+ksx2M_e_8j+Mhq{xkbg8s07vR9^`Zm^d@LF>TKdo7lM}OD+D;O=!WPtN{%ZM(l0c zfF6_&biv$yK;$&_hC!CmMXaai2YOw{1b#Ys4}Y-e3&4dgPv@VC(H;+;KN5TP$z$r7;P+kD# z&Y^i6FD+$H`+EDomH8%%TT$Le1MznH%^6}$nRc|F{gf>(I`Iu8=lg%lRUm>o4O{LCrv-;(?B(iDxGUoE)LO?VIL-}Nk40H5m zJ9O9LV!Ql}!K}a_HkI_5SG)h0@1ZukIj8_mTx2H8RmS)IoNqOCII^I^DxHwjO)|}< z_q2&kFi)eUz?^*d$rN{L|6z(PC6b37faRKUOFT?io<7K|n~{nF4p?)u23GAavI-ql zZPyhf1ScB;15WGtg@wNh3vKoFyO&3Af8fD^D-|JrY!*IWkK}s$68d7kl#@9* zBW8SOxf3khTB%Pn?obmlRY{Q}z(N0*p{&k{6_yImk^ct3LWX}&x@qX#!otYo{Fc*? z9+Y|kES;yD$J_i8x4w8mlj|vOm`H*%UzS3#D*tzbC*ce> zQ4G;VqnPX#W8YaBrrSUwQZfjOZ3&_TXkVzIzO*YICnMM=&1jur*PzX#mSL$-xMfnW zs)6vkycUl*24X5+4rR$%>fl>_B9&5{nole**Ru4e6;TPAES(gWwU&be@c@tF65O`a z-t=?|LlU}b*isT#9?Rlyy7g;EpG9vlJo0kuzQau>VQ;D8u#HviS6aZDQeLaFb^w7uFZcz1!ZNc z$K0s_vxf49@Y1gCM!`HT{oqiPH!KrfNvvbF5)|VFYv~RWju1|qo5uaBppK3=YOeHH z?=Y2l+TfmwLS|8k|IGEq>8te~o5^iC+&C2bs&Bdc=n&C(mdxcA*bB zy}{(<;20fSQA*_X`}@A^-Y~PQtgf!E*DdcRM-!I-f<~|t>%6xx6$!Qov9JSM=vun? zmiR4juJkqS7i~4*CT+WL@nuDUsD_D|Q>Gp8{+-fc*3SLw)_CyaLJRn+`g=QP3xe+# zwOo-#p#S33!^v8jnj#xq)&c^>Nrj@K%#CzL-O6h?yBYEEGU?&fOS*U`Sa8j+$bdE< zaE@=QX-f3X2bgu0_vppc^-bsp7GY?uP?6#D{)((mBr$(X7*r=2pSZa0>j8IR6zXu& zk8JYV)G=SpSvsbyOg4=AVUp3#ajLXVwMEt6L{odSr^;$zsM2oeWU5e>Iz@LrrjK0N zSs**IKi}E;JWh&=NMj@+Ac*WQRm}};BIEPygeggdNqnfQ;~wa(O^M>})o{>cwExCZ zL@)$B`T*^L_T1)g4R`;Cpr2PlbVliW>{|Z$PcI(2a1A@XQD(`}`+Kry_G&$(bOM}= zaDW#hX<9pTc&JAO`4|SWrMq$Yx}!*N^oHt6KGZid7r4;Mff zW#iRG>BVSTJ+h+|nH{cO*Z{wyk){y+bWt24!9`P?sq*Pt3oj>Up)TU?>9rPkV%GQA zCdN`#fxen(sKDshxg7{Qp-D%jf3*RK{H>$Hz+wI|EU4Z&=+wi+m|U6czTU&t_a$X) z7oR9XiCBxv`cOx--_BU87V?mjWCo|RNLOb4DweE>n=T)@=eV~fi6pR&c9sLGOHZZ( z0O-x;b++*F$xPP7*KkRg(i%}hF58b^6?S^Ky;D^+CCmm!G^j;+tI>m%9oF!g!3Jo$ ze&eTw?TY!@jY{lbTClC#?MIe-z;nczlVbwjH}Nw{gbsg6nXLbBCR~4u0bw+e63y!i zWP}mNBdcw(#=Ixq1C`j&Z6Ed}mgXu)cN{4Z2|n`6%PZ@RubZ0#>DpF*pF;xumR^Ue ziwhzlACJq2B=bh{Tr^MCRAm45BflpI|Ziq;kc1wI$LcFPitUgKjIL{wWZ7+SG6FK) zthCffOEFDNO?Sq!OvQS#v$HP^>+%{yzViVfUh-zCRD=>|z(iU_*B_fIukVq_TP`It zK+d0WMqeDlvBb6qL@u(!-RY@Fj1^n~HCRs-b;f1yawXJ_Z6>zjfm;b3NQ+3M1ovo$ z4D)l$SgapGTQyg$rC{5nmK<*xlxYr& z|A0BkWgA1qneq);eoAk?2@3!jcfe0m?CJR#~!2uUPcOJvTAEhy3A1 zpoBv7F1os0E zJldzHi%FMn_+wBa1B&bo-PkeUs_w3iY4f11?vB}H*w6VPf>L7MSRq9CSA^GXI>gYh zyzRIT+oNAF!MiviEqjD*=qlR$W)B|jeFGbwO!_|GZmqpi{@a?_o8MCu&E?JJJKj~w zVbR@#1JkBCRrJ4K7cD0^f8u(7JAc4?i=dRR5rAQIUh-(Y8j@MQH&#F5hIPKwiGkVf zO!y%Asb_(L78awIjQPIUcMHgwo`W~2#W7@bDWO^m`8kYTD5$r5xyW0II=N3(!c_t} zF!JHL;GQl!dEyJ(tv8K&H@R?{+Sr~OX$xzpzQ5LuS-qLcvdk9f*@oTTvgefCLoNZd zm7TBd9Ct`TvPCiJ{0wjEp#k0eHP-f9c#c`imknE7N;`H?Fo9&gQ8nCY02rThgX8h+ zLY87S(qE*jlASaj((I+GzAZmV(3PPAACl-v>ghcWvrJnJR$RA7@U!JwD$P8IZXYPk z57X25`1>rz1SACxxyVuGUjPx4Ee}aV77;%AbF1&@&liXCmEAK#P5MoJLOt{56+xZz zqsM;{d>1V$V#svm#R#Rk7uRHEQJzI@zv4hYp4WwGc? zcMENNWSr^fu455gJ`+KS`LWK>qjq90NJ47p^~4##c2l+H0KSF|4WBYb6$A?_f;W*g`FhSVYn*NF7H=(;5cQWs#D5jW2O!2k5t?2oY z!gfc}*zaF3rg`NYRCZ^-7C3itEFKosA^!0iJeBF;ua@y}`3e{$&n<@VvrN;U;^hf; zqRGzDm}!~p(TPtuG-fw)x`fA=g1{`f@c`4(nWk|C8y0xnwP$!p=sU~4!isYqNMq@# zr@tO?&pC~{wYtpI?l3FEcywzMOCrwX=Sz7YG!oXY?aHw?GWxDR+`)`e&|UqoRJ|92 z&&saa?|OO51pph^d1XhJpXAnb{wk? z@@!Ig2dilDl>@+FOS))iy=!DufpE4Zj}G%vXkNFQjE9gV*5*g|rO0)U@V(f>=Mv_| zjk|43EurZ*>~~RvgDE|P-yu6Ff|3F)A?a9E-O9HS?8&iBymX#k4wR;)oTdAM0u-Sy-t#5TPPJ=fKwv;6Sw z=gN%0z*VnJ%m-zPA(;yw&znE5vNHbQbX@4tpQTW% z2mHYfby$Z(AorW&$4O|5<`|j>+}S$D7Q8T8;RP5Q=Z~yTT%o8Bp&fBjHOpX&Izd*! z_S;7sWBJ8|&@&t<{q}Z-CVsZoM9vD=qf3!tnfH+~F&{8n^RmZx2;01pI_EvBuY{q_ z=-`66)+e~WfvL}ZWq;+dw&BeZ1Bk=J`6SL!P!t3Zk8Ohg_Se*P`sJvqArKa(9^7Hi z{1oY@v8O9ySV~OirN?{|dv*T#Qgz!OFa?FzcI$YJdzzn7`hyk71#n@F!gZ(ptij_h z5yW^^lCEQh&u-9wH$x+GO>xF`6#J_HE`OshKjwpeYHFn z)Q6DCeW-?!V}U9Us#P51`_ic@Z1ZY=`)Te_b@p=7%KiIrw%(>Yjz+V2@L{hlz>lh_ zyxI@Y)=g#lyB78zfy;}c{l-p-jJ{Oy;?8`+ z@F;XmI5Q8Xevf=pQ~l+-b^+xTVns(~XY1c*GK|Z|KlfBE|9%+xe9&O5vj}L+%4Cd@g9OLC3sI#>rK4V8?vZDaT!)PQoZd~_*uN_$kB;%YM2@n}L>omh@Fl{> zD--8))vzF4b>Hy37N}S=F5KL^w)uvTogK6(UuhY;tl6;^2KgZkkxy zXWD$dos7wA{=T33?|}H;!5bSJ2M48LswCOo*C;8SMvJC51$!U-luqgYktho=R0&kY zSBTARc5FsbaxbKu1sy)HtR$~86&|YzFob)9`ie1>mogmuzRe!Xdslbmd`^;ab#ud- zgu|94B_%K2ZLfVg-jI0w-Z>A;qYGzXDW@B{JMMhi&Tx#5j#f}mcpcbf#9HEMa0&2@ zxtSigB&j*v*}-MYzD9m4m1W+b(~9jnHd1Bm#f_*=Buv31sl#RuN)bmv2H#c2vf#Y!azonX=LjiSicuoL$f!HeR*44^Qh> zh)IAK>;zzHP3az=;iIa*V-A)M8n%4%sByOa5#@)irNcWRnXYS>##4Yq_Ta1KOD03_?k%afu`2EH~V zB){=AyQcS1y50#9?!DHv>W@oENa*S5S$aWHo`MyZN9Wjf`WiFLvJWoos3?%61Wn6U zq%e=esRCl{ZM=*{^!Q`RiDc=*&-8aMbe2SZG7h)B8Y2C@pOeC@&o;Qm zLJJ^gBI&qjQ<+eb)W>&?y~0-qpXbVP^W+iq%GSq)tM)7RIx19<>J zn8p<)g*`)5m0Y@`l6pmWvREB3x<0~)Ih2e7A|)^+b4dV8`oZ^-b5G5;wHD8%9pr!7 zyQj}&^&cZ8|7La87oA2IS6wYsYYXJ z%2c-plWMESe*gYrXqdx=D6WhxuDtA~EB5RjwEHa9wUswfSe^bPY19Ua#*mp^4S%&8 ze1+M5yI+34wz+Ahs+!Pef~i>znczyQphYPjQ-CgcM?jec-ZJnDX-f?Y2Q;!~utzR_ z`Fb!{c{qG}da7yY>+0f?IEvj^U;iE*z1mL#^$P~#mp*_fYx~k-kuP5x*qwx%@kavM z^cl#?CH(AoO4@CmoSa--)c866cKCXKN(#SM2erbPy}ub4*KX97v*^txixEEkQhv&n zfuL!-!h{b)u6&M;H&51k+Hi-KjH~pTyN~`I9N2zS3I)c>W^F@&QhQ)ybU-Nv9eJKe zi0v?`Qlp%i=eX@$0a)1GBCu}?y7V~WwE*W+T55gkJuQHu-o$qvg&!!^gG&FyVp;*0 z?JTHmYmX`Y2L>kU`}agVU%wFgx8PuQ8O5R_J6Bb6v%5qgen}!a^@!vSJ~KbN;S=Cp zL222xwW&?I{QLVig6_*~7Nq9q+z#go)Jq^kTuj_PetGt0^RQ=T((Q*vGg11eb8io` zeb=j&mrKX1JLkkgKB>pNtU^NB)sz>&QayaVtXdyp1bT}wt2*=A?$4DzLmA)DLDiDu z_fa$pJaK0eF)<;8{o`YI@L_h6MFZy_AM+_xmLJ;}d!#;P4=Shh4zu>ekXxUQhr6qt zieQV4K+(_RMYcu3z!;VN)3vKkd!CYQ+?6&yooiz`IK)eczXTSio!~H61B>Fa$K7U3 zNG~8N%gEW0C@mC^U22MI`#Zi%Cf<=$E%rAX-e$~_{*d1_ zfFOVZwY8Thv*%{Qa9Z4GL#!`dJUQtBG2GdvgrKA9>gaf_9$zj$EHQ3Qnq)iCIbQ~s zAHFu^Tv%Nah6p=vVOW?wz0F{mAz`clT70HGqKtjmr`YZ74<**oRN$=o{8q-q!wkDG z`ve$hSL8oQPid}R?{7E?R)IlrRHgFqY{DMYCv!^2HzRHiFJHbymlOU9ggE6Sk{nJ> z>Ks*J?kjULcXSd!gk${PL86Q)7MBE@pp66xZ1%6JwW^^}CC;Ah#;W*zQ;fsvO4~#G z*i}6`-GqD@wY0syetQ7f$f$XhyrJ77-7n|R|I-2xhM&Q<>{9GBugq?BcqvyKHSAH5 zKLdnIl#6Km!mpFqRj|zD6|>WQH}-veCog^{Nna3Sr}N>$l^ZN?i{Ugm*ez+jD#hJA zrV0`24`gFExCAmP%VSyYp6%@lmK!r_(G6banEWIg=(MAj&e}lF#*$6yYC@JIl?jj#R3{9QxDBIb20Cop%!^K9FJ5gX~ugUU0rHv$f8{ssM`Z$YM=42c_x3f8{TK1bGILNA;!TVujpc^C=4R5 z_6W6daQH+JWo3|WSFakV=ps;Sfz0Lu`TF>~?Mj-ZJmrj60a`7kjBSsh5;cNN@%F`U zJr7m64#rLN0q$*GXJVvfRePZFBY4~)tBr0-dPEZQBRFT&V#6JWFbIVG{&mW{S}3vb z(&tq?qnBOU)_e~bmrwAHxiNUy(LvqR#Yqawa?=texG5JL<}{&z`Z&eksg_GomY>Ba zCy*5TDE@EW@b6iKu0T}wpD>9>h9R`>^pF4BjgYye@Ad<~J8Y54@_iH==8R&I)?;*a zCC$@tggqbkvilM-fh=Q<<)|BFLNOs-C5>iKTH|rmk+v?#{$}os8ot z7XwHREeeR?TO-}wNK=SR>=n#>+}yNp1E_`r`q*g0NqMrC`ZrAl-cpy29>8X+LMJTN z8#P;*g}(U{H+d5Qh5^)Pu8UPG-lm;nDNq~r@WWnPpIL4m3*2Op`W^i^UOBH~hPn9n zPaj2J9qkG)gO~Z6>{XlOT@*1UD>&|&tNp4rlA*+p@D&;vsvA2VZga-wG6 zT;@|RlIB1WlZ8#c8~bXiu_-?+ zu))3@M5Q=@ih>HfbXOLqPTh(5!7X*?urcqao_6=A2k7%m3IpBat>Pz|CkEa$xHUo; z<%AQDJPIjYy~BNZCk4A8tcDorK1y^KmzR5h2qyIpy*TgY)rUzSc@9d{HvOHIm2T2% zceQg%XL_YDaMs!K;FdB>J$%+^zr3`x6dI~;OuAeR6TUo(6FBekcIn~2lJPb z=jR?ikW6|)Cq}H$-Mk%IOYk|ho349sH&6hwyUc!;n3!oOvH`HzobO!U);9juQ*?#l z2zKUnKs%SJu;GESYT1T%XZ@ zY3!C4SN0r0jQe{A*^#dYr2uKD*g^eaJRTc4*uugBe!Qv(0!qzsQbD2HjLH6m)D+>1 zcBb$oHVdIYl0kBG*dru(Wo7$rtzjjuMe;2xTo7<-D0WU>`;zi`#3=7@LG8w8*Bmd~ zgYsAnWO6`3efY z$*db;zj@HrD_DV#*n--pzT~*n8oqEqOIF7a8|=f(YH1khK#X*Z*Y0(>-%kp*t6Nl4 zhczt{BuJyg#aVZo1jag<8#Cf=Bm|G0hJ@4>o%&-^qzkiFk9KF8Pw9evA}+srjeGMy zR^?yzS5^u;K;eYTOHXa>H+>dxNdX3(9~JpeibaSw0Qa`oSRWPor@tS?&`Jm!841xp zEe#)@VQpnKAsi4Is`n1B)q-5H3m9a`GSW~p5LUu?ExY&W0PwQ;-YBn@63oKIT~|MR z6!CNRfX<_HH^Z?*8uU|%4jcL5&URkMzOhPa_ir*&%Z>#D`P(qyG#7W%K7r-6+4>>j zMw~q+uE(PGt_IZFF&zer_xQ9<@U2$TE9U~};vqU%JGz=c06tcmCA=u@i7UI=HXPu7H*f29`3}SJ{+c061W7ANu(Cn~EO2ZQyH+UJ9ETJ((ydF)6rKi!m*d zgPT9Jq_lKzn-pr+>ZMXeHkmA)Hb>fIL5pf$Nnl24qz_LaBZ%7fV}~6#)(whMIBDwx ziEZ4B^5}H?|MCi*Zj_%bjEprEvCzx8wKb;Vgye%fy$+loyu*P9 z??fqNXcFRQhB|$AvPi81jjgT2s@(?AuB6D#3n5}?na_#&^|%vY+gN$ z{vyz0gj*CYcCh<`u)P>S{PdP-DeFw^MFiOY*yIqDOaV68oLeC}^2C-2;CmO6j#^*7 zfU0LI@DqK2_yDv4-JZz>u-bqF$k+Wk!ESCEVE511=3~d>jEQo53BE`i%@?UwuOZPwV&ST z>XwgyeBz_7VOO$B>MI~{Q8EoVvy;#7 z+r>fn1VG~uZt$bOl`A>7x1LqEEA~fB#4j*jfKdNt>`wO8%_f}GQgf@Yg5j!hfDQBV zO<-{KoG$UwH*!pUpa_8)zrdWEO-Uj&GUSP)=f~2zF1(q;$B)BLVoEOsit)Yr3|9eI zNK;c@W_vnm`@@+24Zw5qyRY;;UR(-J%wK(<&%pmmxK5;_?feg@^lk|61@(3adWz05 zt?UGL1BEEt7)P?_)j(y>lxS((fk@BLd$YamWU%yDPkAn#b-p5_l&J35TWt=$J~5`S z;ZF#29!dzVZ`*j^X(O}i4!p| z3dq##HZs1rf6*i^+{&33(5#XKlAuaHa_PldchPtnv$RmOn+LmlZdTSWAZv=_O*410 zSZAeyY>09_yQNT$BDZ!bJBs$m$va-Id!Qgda=%9A{oR3!gGj?;1_w7R=;FuwwT&47 z35Mv!2}fEm$uUpAl}Z1X7L^zaprGG82%wzfNad%nSdyAa=rL26EGIj>wV!`q>A?GQ zR(qE~yTLfaMReb{stG2iYY5J95gpV1SM{>{h7$IXq)P!$NxwXWph`syFTK=p*xp_bw+!16ECHTV4- zAZb+2=S;aIxZ^Vhx)NM1NcjZ0fNo1DOI#I3N(+ z!0Tnjd7jjluo<#p(K(IVv076^Ow7@dkqM_+4$F6mg6-TybF0eYEzDR@Gjhxu^qZSo zQP$Ki>ydL{I8*{&iCY`X#2+#6RzbJ43(-O3ACGl%JRm{c>R>YG-QwWxdrs>V7uuw zAg?sFw+Gdigthxn3a^+X)K%8oXvJHn;GS@L@~y8Vk#-GyjivV-NkMm9S#&l%7JGW! z@iORqfIqpQ8*Zewy9JoK8hMJ{x&G(Oak4FGB_%?4Wn@t>A2QPL^%bo> zRh9Z(f8Gr2vD7ZF8%AFUo_z1$Ij=Af8gFFb?kURG5_*BqK)#rs{WNPel7TFUrN~)G zyulDbgi9JFc_dxtPBqIP9}#$JdmMo|_%L_68*_Z@;|z|S>h8RmPMJb{xJU`o^y`{C z>6o>~K_3}^8a!TPSb ztdwJFvSkt*{jRp5-Ph#qa&dca4i1NxlW-EDS!>9g98jU7qn`&7KG#7T$nTBv_Ly1^ ziW~n7b8Ss}Y>aDEWido+XOTX??43nh$e9f43_PeVd%ZOrd&v9su6!8R9efKA}(^XpCOj7Mi6wxJ_>}AuZ<(yY&Z6A0An?|v4r!;gt z*c!L$r*D4Fa+zYPQ1xn|*q9>)igbKv;-b1967A540pc)7yQlX-!yLeJA2tN?is#3{ z;p(V7BmYduu-WPh6f*(<_u82FRkxsg&$2wkU0yh0>T25V{Gu0rAn4rwcnq#+p9fTh zW>@x!5-)POI657gR%iz_|@r^8I2FsTLTzx^dx&emB< zsVOnju8=@xYa1wCj#6!c#CooG;H}&?H_h24Ony=#)}NkPr1wih@zbWGNMDZ2XKmd` zl1sZiJWWC77_(!1USO$fDfy#2&UV^Zdx~7|&C62gEnC*#H5L3)vplSX9oyoG`+W1u z4h0~0j*341gj5KPMTp37DTR!o9cmm zmDV5jT}C=UPEMOhEV&H?Pi&MwC)An$kt!Ymy4C2{-Pl8zw zO2U7kjy1#RL(9^A8T8aTdc10&Bj_MYu3b$E<>7I~qHmV{=qAmZ#u(27*DHnP&qZ~o zedm?sX&@=fAebRUI01t~blE*~lsnzsKr#DX*45fDK*bD2r}sePuAp!)K(K{>aJ3xy zOg~Sg6~bD}aC#^^4q0B*>|!Fb93Dx}V&hf)Dqn>%de!z#c*{`x*E$28)4eGo0_)HE ztnHZ6GyF-ejEz7Bm|U@*wNCUW+b>o&wloyt${ni@5^g-F3 z?4&&GV__I$qKjp^u|R|fxqKt9EX2B5@Q>(yA2$*D&-tbf1<<(96+YZtS-XS~+hQkA z!5`a9_MPxyTZLc=&XX6<&X8z=U3=EX>Ia1H@0ig3WRfn%GwuE2#= z_1gAoV4w@714#Utg^!rpKPnt%N2@a8;6)jRb~JfF!R~N-VZSF7$W6q0aBMeXqn>_Z zFFxQ3A=i(hM4zgYT16Qb&#z88)rB>TpA^SLH3(f;M22?w*d85vi0#bMjH`t+<>9HV z|Gj)Y-cZ!oJc22c;4!*%k{u;^7&5?1x4G~)!|iBdtwffeKDADj#!Y|=fS0exSjw!) z`G$$c^aCdfq(a(OW^cZK`u*IE%rEDPlCy$?yRgBNz_5@jd(m_sAwx?`%c*p)tt!%B z9g4~2c;MA&9YIZ_XH(a9M+h&h9Q?t|bcESAZ?<%{rHznmY+uIr$qY5Cur!sNB`pkesH$a+3 z;hER-bnqduA(8d#L9!c?pmnk+#L;7zR(GT(v4#TdiGZN~VKp5B#oFw|(S1~?U#;nF zNvQuDms3NXNH2cd5%^#%K6CQe8)IOd=E{XNN#6O?E_OQp$O^xRh{JmlXmL>t2z~T% zl)VC-tv+u39enx}I-i0PiJSf;GxLq|Jgxaet>V%Vv{xbaXsaxx_O)if8z`MJ-d)Sk z{9d4ojX`O^Yhd}_Fke)Nl!>uDOY%H{m%iXs(iRRbNifVU`GMSIu@`#OhsQr@vF2-B;cX(NnFwP zZLQ~?-K5@64IOH#D7^cOEF2pOli|Iey(XJw%DdjWF|^>$6jLz3G)K7%9}=Bo%Rfk@ zCr7&ayC7RWKT}7NW*0pjy|Tkrez@xQ&)&_{)HY%E`tBt{Nx;BL5VZ{48ik2P9wh`< zg&88ROEh2E#nSsPi-F-Ec(PRf=6%bY7gwJ03Cz!A=@Lvh33oU zyB1DA-T}oDpi)>X3}^_!XMbWK^9q|pXlzS^-IK)<*7+$|OK7A*6~f8EFie93IW`7e zHdXxz{NHwov?kX6f1m1Y`qO$n>MuZt^AiXs7P?1YSMs zMNb@;`_Z4GCmP^$%**eEE-3Ft=GC!E`0l>3 z1F8}x()x*%(9jv*vOuD#chW)(Z(3eHiaoAuJPT#_f;I)WfSoD8IhW*m@1J{Cx)v^Y ziNHoFNy&2qWS-?8St;&BhpzfoW86fW*WCBrzAQxfrZ5(V&Cm&r+=~%>&&ZqF1J~Iq zpxShRK1-HRk;9~ouZSGM$KGSDWIQz9S8$1RM46U2J@@?!h(0c;B5paY zvC+`wZS{{WcqbMKN!G)uWu75w|C8NcFZ1$qXAso?OS+j%aTcXUqtWL*1<4}?u6FBM zP;h-z(5u3EgMu1^`6~VA?EuRrArG<>(K+4i#$i-I{xyxugHM(hmq6K`$c^I3UD~3! zl>#R|8f*6=H+*%b9$AH%;yfS?f>(2#ijW(!DSvzlG5mELY#EaC)A{y|TGR=D=Q;na z>6Qj5FS3$uINy#I`x}=Rq^@Rk_O=X&TV7pO-hWQ|?T3Ef z(t23`7**YQdOJ72_3j1*e2wHLaN0>_@aq_fBA#~hO~=#kH?6{NuR_j)wT%G@&|(xb z7!OlBgq_lQ_~!2ioAcGs`;Es=@;vavKh44>Leq$dTS*M%xf{c?!A%B3@8D2iw+okF zgR-|K=R4nFZ#0n?E#Yl9_JPi-um9fgO zotzVRSt)aFlF#HonODPrWfRVmkLJ!g?XGIh_|}@Ye!+gDUYQ$^Unzp&g_gQPR@$DK zpSyhb&ke6>Fp0f)7J%y1-tm~@MX56GN}o_|WLb-;60EGbTW!?0Cqu8+QinQo7u%J> z;VrvK%^{~%7!<_N{mRDn$yv_h6Asvq`&U?Oz@8_zgvvRY< zy9o$%+tv#KTB3hX?xphBgQ#oDg83WSn)9mGj;ndF*l@M#8flndSoo)pw(`K|H0c36)@Ko$ld5v!B25^5>|#Aao_(@s%v$qH3vk>J96H%ixZ7b4|;` z-qN*Gt>t;Y>Kj5wMsb25@3wXK@#gr-y)_nzzVf+(Oohe*T|*2?@A$nC4$Q)^nbvsS z4w&9jN+_I$cw;V=g+5w~5Ulfvt_5_*gbd>?53pr1G_(XJN2th8;S`&H<-wwh_}SfM z%$e_lBaqzi$yU_Ocn>jT#SSF}EJB`Ckaur#ceK5d&DWO|+hDv&SN!-NKd#Xah(?=d zxb4@LG+Chk!L>zDVh`v71QWnvMulZB7e{n8m z(!5!;V8a&N%-tE&&n0whgZjCpj-jEr(Fay5b#gtHQ-hh>#jm0}u=^XdB#2#B1BFGxd&shZ+G;b{_IDBqUQKrS0|d zY#Dy5EdsVmoI3K{-L?w=!ro?Jmy&W%2Pd%IJeOwcuT${)Y+bNn=qQ-iCI?b6BhE?T zPOSp3=dr-SGRtUS6e2M6VT9L(Zdi!P7KmIAZQchleoz*p%5o|UqqEPysRrQ*6FRoU z4k}Y13ldo}9Hgn4dOb4O*hx-#R*r}a_-Vl|KC=8c+xpIT!~9|(ejM0w{0Ex@@|BfT zD51X-U*E%4_2h4}^On4bC_wbVJ_*oKQCtc0Ej@KxcN)JV9nkCK7R&9E+^B`oH~Ly_ z9tF8-SlxKPS#G==31m{>gvM)q{MH;=BCTb@`-!UL5~=n=mtp zPlyf920LCEZPhSY3TKhE!DQ}%YZrR zBTt0|l~33^2l?p}D9Q{@w`BPx1Qx&X8WSOl+dy^1!==K}kO z`O2S+0!%56kcpr~Rpiy<42|NobmzPS<;Ef!gzx)=goLIjhi=C!m05g{e*1?V-v~|1 zDbbcw$biPQLV|TIi6%KR3<({FU8HZ8#4sx+9YzHSrH7A&5;OPWdlgmT>5iqrrUoB_$5nx;w*(Qhn4hhLr$F!@% zEr*QE479c_w8pfz)Y(PrP;O&BWwmm=H;s%R23?cb8z zWLgh%7?8x^$fWNNpm}dhJI!V?j?DL^CpgJ?ZrN6!0K0=uc@+2o{99-T_<8eV%+cq6 zm$0PqKXtu%Jd|JjH$1JhiLBYlZc@r_kUjerBBLxL`p6B(t@B8|1X0GL2=X}=p`F!5<5tVD6fVpD$9&T3Yqxy8=AI;R2 zB?wGG78#~6{(-8Ecq_;>NnT^qPYN$Ye>KErKBQZaH4NlS^b@>Pc*_&fu`SEeD7gdh zjY-gK@lVK{rda#p31ImNupaCjm^6#NLfiF;Zb}U$!QnsK)$tPz?L97e6P@q1_h1is#w2B zhV!E&%e)!eO=}CEN^sVnq6T|>Mx*qDeV8mWTq7&a4NTDs1#Rg&GoAj}44>L76rrL{zyF-hplkk^a^vp!mIO)Mwx58wj zRW`HzHRuPj6zc=y7p-94Xp`ZWJ;=O|wLw#<_9iJ4G{U@)GFangw0}_Uuuy4eSrHS< z`=|M+Srnh~^Ystq3t&3YR$0#}NcZY^E+rUTWFt>*WX6J;G>}$u7Zvn(C>B`-S18 z<7+Z7!;O_3CzpxYBg&^Qo99i2X7XG@&wR_QSJXNO#;|$j@DAyzYlW^c#mqzow@0~= zbA$sWfU-a0624*dN0Q@S)w|mkd%T$q25+>dH;FX1*RIQ*xu{9U$p5A!@3D>I$Oah< z_EGGW@8@gtRs|yeUrH6Q%zsNmdhuQihAe6<+j>UV=++evGQ8xTXtJ*Q_MJin_lO>Cqc$E26oUbT++z&yZaswJ6Y9Zj!A4hE?!x3dFpFh(6-x)N^KL1nKD z8N`6z-d;yslgf1;1)F`dMB&Aq2W){_;Dd%}#rU%-rmzKp{8>;l3d?_5KTNwwyNLF| zxOn};5uKE>mkh29OQtGnOJ&R1LfvLB_F78<3+3u%lgaHPYAdUPlv(sea75a zX&`D1T_$_f)CWIqqd~|$9gb9uN7{ImzBm!!J-v>SfzABlK1lFkGaPD3f|Q2oc7?H{ zg4_R%|2%873m&6=sF!~ZdfJ_s8H&RUts-3gL#Wice$x zY@<(}8U2@hJ}^_Co?A$~*V)44LG4wrhxB61)?#Ikb3L7Q47tGdu+0}b_@oR*yD_0* zh~ET8$}A3denR9+$J{j({mw;VyaXu^vcNr6>k<7cMo7l^QcJXKte8}_+8-c`UV-U^ zsmDK)sMR~X<7ZmJgN@A%f=;3`()vLLp~DGa*Zwf0rwiKPO2mId{S<8dFm(T}M>!qD zP{Wt^`ZdpCMqeMemn3wru-VleUHY3vuW?ME`x_P?cb!qS?{TCEw7+z3;Nn#>ajaWB zG`0g|5u`?fpp|h?aRyVWmHU18r{Kre|7!r+)6?uuw#0nNBy6}S6C{=7DzAf?CME1& z+jC9r|2TkT+t{zUI@n%jn3+OBEKYnG)U(4P?%ZMKdL|N;+{kDr0L}PXp%O74{!}cg zyR&NOz5%-2rg9!o@7!Yr9jeo1ZN3&GW*@J21dc+W0M-L-Cc6hx0>paNdOVNIQ|KLN z&^#rQTG$gA<8Kv;YJGSAC48>^M(^ zpDXpY)J@*%>cx?Uac5*!I(J$`0f9bS_-*LrzTMQDmg??jGDI!{HT0Hysuy2Z_vt_j zv{tVwd0^L!>#(w5;4obgssXm1Yx+TZim#J=mJOhnVG+RbNcs|05Opd>=Yjzh5gO{P zgJt*j-7E+@%J0zk5H6y5eh-&fj~0VW4lFd324x;-D~c-lo3rsD>6RKOV+Pi@T^mnZ z61B%GJIp5VI(CMR2{K%|a>FK(y~ZraFrkI3LsZZhD5?0LJsZerY|7$>f4IFnlqdm> z!e79`REXh2w+RdKDKb86*|M1D|NZ*uW81H`MZ71IQ2y24`l~YN4$#dVnN7vYLj+7= z|CDJ+qq?~~kWeic*bTamhVw0;6|Yl3FCyqMG;mEUewsPY82L3bWHxmHcplh~;_taL z;FnEDJ_BlKwaUV9QuRl#sLd`Qi-ul;H-gC+u^@GjRj*I(Y6R{&cGG5|Sx6m>1J*^S zrS!Y|;dN5x1ABT0+W$`J9(1o1cm6`HcQ_ygsV__hx7Q+0OA_SOy zwY`S$#Jdam??cwpw$*uiR#M|xp!K{{WoNALBQ_V9AU8mgbA$J8;Tj+n8A9d}5YRJI z?tguW?AB9N0$q|QWJEx_+Tkf`U|(TBcmZ1ukZ}*Pzi>TaJLul`#)ke|PIn5)rau6o zn~S)Iyb?E2LdX}q49P=HHuXC{Be4gce|`b?)-@g*AK!c-VEMHl z_EVG3LT~%Ob8~HW_X3HbQ66B!(m^uk6vL$!n4kOJ(*&x{{XblQ##jBXm9f7)v`JMB z&C>sk5=^&7b12<%jC2E3lKu~4*bfd+rNI_-GP(a$1 zUSi|F*IV9h7Pt$L8mRN)S+Mola`qGerzPW9AAXGnv%_tP*2}Amop|w|UyH?~CeKse zhV)Z66SyT$D?H}w(DuEXkUqzE%{%^>cwq{;QNCB5#KC~Kc5P!P{_xBLRR?-VuxToO zW*lA{8u;()e>=d-7RZZ2_7{o}c%(@+cnqv4oqyKoac7Gfp%_(7MY zSQ46E&Oc@nr$nJ>`^k@Fv|bzf`AInTpRl~pJ5S1d&r@_0S~$fBdPI3>ChjEuVy9P5 zVq#4jWJB5@cv>By@uEKR`P{vx`PHVKxd(Gd5UQCQ-XC2rC+eS z>!U|QT=nLRwY9TT%Nxw(%hfONMl{#fO326@E;TGqHiB1w8xa*HBqX%(xakg{a&r0s zQ1EY4-k;A)F9}c_@rFd@vK|ea|Hgo= z2&f~KmXcD)_!h+?t)%DCFwt$T57_i}Ba}GDkjYPNYyf#&JfQjuV)yX!no3SxURb?( zewLZy4S|Gim|*i;ITa}M{uB^Hb|NStt{GpvdGn@SioY1mf~_4#rZ+{gc&XR8Y}Rf>cr*R_B6oE+|k3D)S&xA__JmsN&F?`JnPNZ*m0nwl!bE_8K~2MRet zMjJ*o@axx;r%&^WTWO;@6WW#Yh8D_3&&ul>CanEyEbUVO+WD?KyWJ96$_eMkreTE( z3LB#Q>@txXFJF+X2hvsu*V^F7o%j-5{x*?rn7^l=f_wbZA>Fnf1 zRJr%oR>$W(l4ZPSCLdts9UqdPHJJagp>UfvTz2Q1yga3Oz%J^DVdNf|zmb2D43Db8jXFTLDIEpL0CTp_Eho$($r zjQ97l|4!`4KkYm<52=Q+v0S<9ZgplSC9rmE-74NHWs^y^B0ZJhhCu2otD7bkFtc=Y zot?alEL-PWzfVjwl}iu6EC!umBfZQNox@SZN|-MFUW;mU?ZkXednjYM^uGh)j`e7w zvR*L;gZb5~8QlJT))_axsDXV>n(d27EX{#~ztziV~LAiN!frb;G%VitL}$WoUq-IcbD9bWYpgPR_&t2NvFXJ%%At2${EU$ogUW6{)3A4p z$QL*~UYvO3!rVE^yOM|9`#C7{;S9G)Y%t?DMfHf+#}Y^^EG$>DT;1I{b3XLXsq?#WI*rfPW=6kl@)Aw2h8OZ( zs58X{t)<1p}^1zx$p{&XNTL z)tBt5UOpd;#m4J*yq~d7&YtfS(g_iK!`@i*%!~2ti$J6arjIA@P z_Fv)+CDN(d{!=bSTDHB66A)jiNBr>E_Mvt4ntya?2qliVV)tMUhf zaC%=@MNx^A$Fx;O!&R6R7Ot^WBJw(f($KKo&2OpVjbJP)DPCWFUMdP@f^%BDLKZyz z1i|Ve_G(cQHUBZm4kN`SryOk)q`^ zzG_B5o4wp6Yk+Vy2irSIj+4(-nLE?wMx&5_g1Q(glUyzRVS^oqcn8_>fCPPPi31@) zK|sC(H@W0+QTk=zTi89-R~EJ=m|{3TckHh)tYdN+4MUDtz^#Yz_S$^&iqC^J+r##mI`-tPI@mD2!;FO&Bczu%|1_Oeq z%g$Pfje%pcuDS_ES;;4@#@OTsnnhV}-RT`ypU42BKaR_em5PdOSHt=&m4DE6?1~<+ zhTrT|m^cj*a%h#SWQ`_qi%m^UJdBC>9HK;@e8ckiB_8}8PIqJ?y^U@0{-G?DvfiJ4 zu#2Y(LD5g_& zBjgC@VjYUnW#-a)m>E#&9Js%=7~RvdJuP)d?cH+o{*qVAK8shnI{y_tq+x=vLKt5d z7z>1+MPW%&S_U}}(om+POl+ua`NQ71XI8!Y`nRLXe1%;#7+(QE z-KHiP{+Y>1bB42O?<8=a`BUhX_ivP;PGn_?UX&{=(@e-1j2Yp5)QA<}6u?)oywvjP ze4LV5_O{9M$muKxm0j^}&|}#YZI({4*C8|t>PP}pxZo2!Bnf(^4oHFmxkf<+c6Qyz z1Y>A;-D*cr)l_2b=H7;U6oT|i2#Sv%P`lxldJJF?jnq% zIF=9#6T__4os}7lrNSSkEh$dSA&c&1byLmW+rdg)Ie+4FHdl3`0Do>NpE_>$)Ceb} z;}4Q^8_mDroI2ew_#Dc%3b<8-(>T+sC(@G=6ym2#)mpa>bA>#Z=Kw#!&rfb2%uBsM zJ^rdU^XuvP`T6N-i*>3I2uSdtSw3(Fy{yx&JA0d?6mb`K_-c$fwPT-gz3Wo%c?$g2 zx%5@A+!SwuTkko5m0sTW^Y*_RMLzz9{eWCw{hLqAW@|fKCLdZXt@r7mbRUoJp9O0TFi=S~8uy4o?2L2pj6$hvBEnAT>#{mJd zl!!mJh{3;(Ypa_oOh@pRY^(sVzPlaoBXhRP{Gm0g;u#;4$t+T`GZQIX zenn~OAp2IKImu%%;L1N3h{fvh>xVYMx+Ua9iCi?+&3RRn*JQmllE%+?@WtcrKi?8Z z)*ENsM-d77xPH-)MF`?ky>8XU{%`ZSUzcfeZU@8CIj5TG(#To8!H;#j%{E#e8LirG zXQTfzS}}KCk5swJimyuV`&kj*Wt#fe^c`eUwWCiCnSNs0_YM_KXTOGwZjB}trCd?&A@l?m>%D53Hm6?D zZfP>K=@Pg$_G>b$czw4lnBdwbCvCRQxo5cj}^UD1j2t67M+zmVPHh2Xb;kTOk!hZkx^MzsX4|D$lLVRv4*^zj)d7s1? zMPw)EiMvp|ubmUG(xTQ=+H$m~=`aFe10Hx1p)`eL%4B~1K54@gPA5+(a=aiTe(<$V zQoB0WWc}-`sY9QE%J>^06HNQ!d?tnQPStG{a@YiS*T~lR^CzoZ;&QUTn%|M)ew1)-i37d@)CkBicqh))3+Ygz zm}5Ysb=~5!MMWGMty7h~8bT(!p1ZEh=nR+~YUc|%tG({BY-`(RJpHPuhBJR+%7VFiQYabA-wbt6q>?M|Y~dvn>v0w>1ngt3jH)lwhVv&_{?5 zRlv2Uwu?B~gCv<=QR&S$vH5Gnj>;p*laOJ98()pm`-^`oWv5 z`KR-?yHbj6M+%cz272rH8W}s@581cpU5o0pYUclActpPQki0GWMJftba$SflQdn7! znN?0I#{mYT;D`PrfOU-_gDCNNIwtfxoR$kgXwal-mY$yZDPwC6IwjX;G+5t85O?~> zb5Jh0;G0lL;bmwz<71wj3mlCO8I3~k-1@ZZLqavXoAdir(z~0H!U)*tWyLXEq;T5= zbUxv_mG@~4YQ2Eu^M>ed$9<|~Pz8H5Q2eIM=`ZQbi>2?TE|Z*`oVT>vr>AEp*3ZtP zwqK0~ZuM#m+JxjF>6@3MPmR9}1HQq*%AW7)gk5p^eMwWc-XG3o(>A5sf|-b@V?9ix z*zsw61sC4FMYjlfVDQU85d_H-In}c(4%+FwoN2cV)OK5u!+XK<^)2Ze`+x^%eN;N_ z^|YqCxkQ&&OrRV!WHuX;W!0iS&)OIoCYq?e*Dz70qCyo8%~n?SQ~)i!PVqDJlh@M^ zZDJW9D_l|^jF;ve7mox8#^UmF;O$E~Iy&LO!R}%ynmj4}Un`uX0bNqbRPpI`M2n{U zg>(u5APYjpqHIYG!txu#l}}C8@#{j9=RC?EO62A7CXOd~=whTUPxT=qsFs)o+MNUt) z!$+O=7bk_%Erk{7I`M(~HCrr|vh$}sA#`xUkbuUZ6v!#sJn3iJQ#0jGcTPUPWRN+W zwD}%h`RGJgZN8MqELcPccktzuc=Cnx%l`43`7%SoV!x@@KQi7;zYhELSi|77nBEuu zF2dr`_w+6_GA+T%1VfoABc9t-LFoy#xTG3kawvnOc_W4Odv0I8B^xU4FzUAzfDj&H zpjIxI9KYi0;jw{Zab&^h!0ve^pmzU_R!+N00QTiUJ0#)r^a?PM&2wZH-()k&7F8WP zkTl9^bH@jBa=dZfmgPG~qjxPdlXJt{GYKSr*H%tH{gdSbsSZ+HYmiF~gP*Z1f8Rf6 zN}93XT^K67>Ri617XemEGKyMxz*XYk_P!f)r<>pMq>StlrROr|N*1DOHYYnXXyV(wd%i79E+gOQ!wYhmHI`&pBJSRmKwPbIY_ zj}mg`d~w8$w%aTI#hXuV|Ee!;nqB7oZEiG<^KD8aN(Av;Rv@^A=3@n}%GVkgZ=I|F z$U)FZS|5u?bk~VKX~cS;G!6b+b=j?M%;Pv?HYxugTIE*d3@4M0ze576h<=C z9*LxS1#*JVqg~{k?~FL7^+~(LFUwbh?vZo6@^I{|fTL1d+}UtvAYtatsd9Y8KO;fW znK9?1K+gYVX0}Hc3W@O9y#3A7?0$o0lvFdyZmUtwE6_iTd~68gOjL+R6~y<1w-xCq z3G`(0t>Kw9A7XNZdHUsC@5?ODOvI=7=+%}8-lx3IDux(j#6kPu6FKpBlu(8jIGn~g zt-LEP&wclhk{Lfxz0>i>r}-g#=MhJUa4uX!(faZQ{>WX|-)(up1?p^MmljTyQ0ElY zmz;|Qezsa)K+Aw1^)45OYI(jXa9PpWgix&?W>tY4ce1sK!6kC6@l2RtMA>Sb#-VI3 zPJ};v?V|D0=jazL{=kW3@@1OqkY8)7xQTa-tSz||%swJv8+2pEpZ|VwF#lI%v`fT= zpeJ{d;+0!VzoU^3si=7ygOfDHOfeBLt>fSn!5`-S>5+?Zf-b;ZQkkqG*pM-=HUM3S zPnvX8rSp?_B16?e;o+0RRB_$b>%$Px|FNM0KG!!Wn*KTYVcbAtqfv} ziT(ThqN(iw*(x{ z=I;rpVP#|UO*5uZe#eD# zBACu8r{xytV`{&^8v&=R%Vdz?NrWH}W+|02W0G6#$;^BCGaMhU55n3_M0A5Nl2GlG z60A$kk<+_=&{w}Re4m4i6=a~*!-j@-#p?+1jun5aUO(Bn2`wFM?Y7%AK~d2<&zs6h zNV78kWk@9z@O6YShW6acc=y{3jozz4p>X{3-L)B4iAMi@Pd%Cs)^^Ej@p@@1-7b_0 zKhP8A$4?@r6L$P8z!F*3nE@kM0r#Jpdl8WtdjA2+gl5Kl7rQIr$OcWTbNNGnYMGZl z9rvU>YepZXlEtM)K|uk>hY=r=3o}NBQ2vx2)5J*1$P{Dk0YxDi+1x#2m7MDXC>x(O z^KcT-+uPeLP%dO>xZ9kbJ3sNLhE?|Y57MTPPbP=o#gi0IM5}tZr50VtbMdn-xyAUF zdmR7+=BE*olCk=LdHEuT-xOP<3I^rYsH~@?R5+yW(6@=gpg!0$-PK6J3iq!g`aj>+ ze3xB90^Aaa=NtJG*KoanSge#)*00uwY4VIT9%gn|?VXa|#^=`7(tur!scqi43)@ex zQT4B9Z?39=lv{HU{7p#JZmrX}pSQta(LBAAO`ph3r*R(6Vl?Ghr7HTfQ*5jt6Djgx z`WMm&vL8TdEaq|s=Ame42$0k$;;3cpoFrS!7h&Lw%nSg&loS6O;cx=oIhkNkCVe+L z-IDjCh${|~s9^SdEH-~(dUDde?u%60L`CS|)?hMlr0Bq4QlD^(txwn^-^!#DeYXE`UATgLaFrS6}uN>^|;7g1)q{g;n&90MuwtE{XN))?fu1T)Ht1M zdd!`V{WphZK?@rNA0EI!qxM783jFQFKxXeMZRw77W?p88$CbH{5=_%)QcN96;K26B zyUV5@&-u0>5C|p7+GpSsHI>x;Qy(jzH%-Rz>Szx-x$z9>~^ z_K=bBai-`_L>J+~8wK*EEyuOe0><$v+_H#Ue*7B3ijQ~sgl zZJ+dHINn=PloK$U0kLxZ=)i~MJ|+$T4Gp0L=4Ij_%R`5`Go=Pc>RWU5hyjI>)UZ$J z3NxYV;l}~HGsk<|$NR@o=CsPO{q*UJQ(YAiq(%S-85zENeGQSwP7W~6^gI3G6e-c-O!m@Iib_r9%ODW* zyH;9+w%f3ll97`7Zo0g%=hm8?*7BW>Y`cYeXCwjmGZ&ZA64HR}#_#rUUY#_}JOfA0^}AJ) z78k(iVM-f);!}R>ed0@zI2K&Y6>q05^IfS^n^N$+339(83KFLC1QiTruXj;!le*N`@Q{c1) zK5|IQ=^1!H`37kr6YTrKYPWS0UrSb0wGIDiYkFXA2dK9h$XlWz+V#koeh8&cn3*MXAlSr_!$cw zqSmfy4Fn`7{9H)|YOVP-Mq{NO>*t!!u z+G*FFcq#BtV652HFRZk#wA%ZvtZ*&S(waq+W+&#wEam z6!^oSJ*#>3v=v3tOKwTAP({CRx3{^8FUS@xUd6ZeusZgAEuyTp77I!U4XRRSq8Jt~ zfE3P%M@U!_4N8dKS`rREfb^FsGCbM)`z2u|rO927r+|L?8}`WZPz4NQ9WyIPBLBYW@BBsLn`WarofTvMA{|O5VJFJAxyD!(E=CoTb zAg0B5_HFYjkd35};#b+-b|ROo*MU-${c{LmMDqzQ0CO}vqA6=Is_g>4OszBgV-q_vM0T_{c+nfcXn63@96Gc??u8Q zn4Fw!Wo0$bB>Yt0KHx&q?kn;96!W+<@DiF2@xE>{cy5X?q#;?oVo5HJ>D$!4vgZ_1 zljC)p@9Wgf`bk3f`0R{?n3xf4?LyPFtRW*Kv#3zT&cVd+zRdLcRfk4?euDi}qj`me zg}J%V2dNorXM*mhgwh&Ulfv(79rg3b$SMvoG>uU^rNHnt@#>5Fsm_Bh>wnv1X^@pz z^h-mYGb*V~OJwkfs85zeps;OPc4n zt26oU_N6QY?fFa07owEoAiO%ILlWx;N7$PDqXo|fPm6d)dwoypni0G~5JT&}{Hg!d zshNIwBOvDY7kc-CV1JAajKfT^EDNq$8LJ!kBS$*kXo4g=rx8iPbl9etHTANlQ(LEF)-io~LNwL2p0CbdAB@9?H<`rQQrR(8&{(bNcYRgM~ICt#(GMW zlds*y;Y=oJo-y9&F}s&-BwN8;=q(qg3jA>q&(TE(N!VWw@nj@S`O86}w0V1+rFlaf zbJrOIuRRbf9LcKf1mn{dvjMN0UZdAv9c3n-J*sa%7nZz`1Fqx~|1octigjLWnS8?F zAX{R~c%;+--OBtD1c=_Ho0uCm%p|E2(aSUKv+Nb%COmC@jsLqQsw`t0nY$!!pPR8; zIgkFD{=P&M7v|PiGDd__M8Mog8TgJAxPWLzbAQ6g6^m~djhr_lnbREg)wzAq5*kg5 zMB1z@t#N}xMj7+z@%>WTsjxTIXY!hn!1*=p@@+!2 zSFV2KT(@No4!o3X{Dfw7#Lq>r3x<^RA+jh7oG~I3d99i>{k3$eACe$$)>3>&1dS{a zfa5PF!=FJ=)KCl}D;2kbGogyj`sLZJivvgeQ8k{pwc{bEWq!ynl`VdXrZT`fe7?gN+1RbC%Bl(Vuj&12an+mg@b>mDvfJsOE!D1;CXI^! z1aCOess}g>1Vr1fp3@1YVUME}+U6Da=BGc@untUFDT$lDUc*dd`~>`K7WMAZd`V%U z`|p}Ed`L;EH_jF zz7&T=xkp&)!(MMEf+55aSOzVm8lyX_or%6Nrwg#P#;V$l#dD*V@Ct%K=ao`{h3UUn%Y&Ez6wvSMX4vBVHCTh{4pCbO|g=B5VX;ky(Sv3xe zuAWCFQ$^brtgB)tm1MHg^q$?Ft+n~>W>Q9=e4L2Q9iAGsYm*T^Y!<-aN?sMTMuC@HG}6Xr@HTHo*fzE>(?|Rp zhqXrX>^Dp?kZTYx{LV)dGBSG9LH5o(IT~EVPdLZ7(oHQ+US5-1nnZB2sa&adWHMjv zGigSlGC9=+y>8BTyKKCdxaxV*9VMeNU)MHdqGWvJ6(7upYMA>%L`xUfJ*Vp!X)sEK|}8jsA%9~ykeI%b50IkI*B`ebDW}ZK=&V7*TNK|ht|$0 z3NVo0ho8=5#6*A&?1*Y3zzd6@HHY|4B%tP4F#K0a3=c(aBvdNpn-(wwsocz}vP=|Y zNf>!HQ5Y7r?^W+Nl$8Bu~Cvn9dM@?whgL}CGL1jVT3L2!zgNf-!FAAH|Fh_~+^xbF=tjHTY#%1di$VX1VKJ>B`d zq;IGPWxS1F4RpAGgFu`<=3UG|7~kPvK7OB-ewdu@T;2%LNG%V80dfUJB<#DzG$yJT zG5#DWxiE7tFIKcfNnSEVC{n4(54wvXz-rOMQ#eO&o=uWo9Xk+H?AD z5RuJFS6d^6I~d+)%ZMQN4-uoZO2eY=?p)h0~VtdvMp1b$^%R4>FL(qTh50m)MVOG?ZRMx(=A z++0ZqhNxJu@B39rlwNxWJ5t3MwaxJpV6^@P5(O< z`y<4_9-8h@iH3Q#^kMzq9qm$LBAn8N1p=h+mu1!Ch9Y z2U!ypkAIPJUVK8vqR~6W45joGehVvx7ZwGqE1{aM?>yo_$PRQ!QeY#-)*%IV^6(K|;!S{u0 zU(6_7Y5o2*kuAYCV}J?47_8PZwNXG!M1%+v_`_c?L7~v%y~bcc3^tzKR%XYK5I0s< zes$pHWOah}XR5MLpV{o12G>u@o1%2^>oJ`jI&a9|tP*bMHcy3Y>e;hCxeV1ZAh!nH z4_*9NfvhIhcM<+ANs3mhMOQj2t*8Ufel^e|mLX3?MiEaWmTpTcku~8!5siz7hYa&M zu;W}Q#Mvr_S1ufhwgBn0w#Uf0*lth}t`Xt!<+YmJe5Pqnw21nWJvFcvRuOR-zPYVH zD8YhVfD#s>;%%z)GY;aHG(K2KxT~PC$MKt*Z?RjVi|A$+1@;qX<2XdGb7@5ZA|fIs zgQX1EO}1WINWnx{n`gFh4qT=$%dxZ#es8amfm-gt|AJ~DD>MzwmqOG)w2IsIMgDVT z1`g6Z61ZW#R8&TT!!*c=&edVONdN z!Qd~hEkB^e`nkCiOQ+85_8EsMRZs_WX=%xrBplfb26dKLg+%3>Q$l-Btv_wS-*i&A zPwIpM~?@ zEdCEIq2~-rknmKr%gWwSi^qk^K>=yVE?j~G555pu51F#xsPM;wKj+j&ht@Q@q~uhy z#6@L|RavuEwJb{(wTsXlabCaGZzpEegvKCHt*N&js(2~BC;%UT;|`xA6Q%xB0HVsP z8B>E=LStBSVFxsl^|3nu{oqedse?oaA`~-BbIs$fxt1N?RY{$ex$A}$2UrLC>FG(8 zHu2G&;TTgR>{<9;7|UJb)WY6gJpwzq_`>(*+d<_w;eL(rB`zb&uXnOPIgeSZ{;tKy z(l+eiuRa|4OMgJspl4dS3HoMSE&Ty+81s@OjyBOaBSBN^eg}Nx03=t4IpEB37fngh zY{^VTpnRVES+Ag6h4+JFO=1R5g;MyKmj@=bLPLJ(gn{Acq}sc%K%+7%T}-07$bhPt z^cb^S|Cdts_R+bg8xFU4kx}}{Jm53_CcSA`X)^Nw1z!#shmiIuQ2a9=MZKbLhCK$?c-Z$5gQju!+4OnevMj4oOpJnmP4tAVumU- z9s$?tmeWFJVSr`mU0lO$BTxeP3tJiAPl>_j3Q=~*UR2SR985^V+2=Z92T0? zv9$NWZ{-(EYoT&sT{_VE5CV6;$KNr-VF|^vKl*o(Z5IT%y1Fu|GZ>726Ur&pRLM%N zlieL1j;M*6KRvapizoAskB?vY;+(atiU#fYQ}fLFS5?=nGX2$~FJS%7w#;gDa* z%$q&_S4@yYCbG9aD$DWLlM*@t>xL~iu1c{yRz-F7J*P$xRG=d=*0gwGz(@pFb?@5M zH5ebq>J$-L2rz++E6W6?-gGv80DUkhu$JVni5z~Lm6BSVMelx=LY_wZ8Qu9x=A4L7 z)!06>hA#Ix+IPK^M6~TP_$vd5R3zBSmZzko#Do@ZeY59B4F_0LQELXMQb)Xp88J!4 zi)_CFS*(~MCX``%Bb%u-1fd}#=9Hc!+fWqdACwyq=2`#ThB2Ku{=6lNPHtnJ*6Kt}bWER2pTM($dny%1LqZ$+WoXqaMP3 zFXOm4oz^HQAxt!ExSdAkt@g7ehw~e@ALBh#wb|Ngmp9Co8GeWXvBrr@r&L@|kvDl*lXpyhYATjNTpaS=v|JCzZ4|KTd@!ti?2ZPX6Uv z`exmh{(N%`IpvVQGuqa2U@!6c3H9ypd)?K5{s^;!_#XGITR)rHk2a_;+PB%4!&B*r zAu4Yw<`&JB1Yd)EQ=WHJ@}m$R1VkTZSrrTPzw;>NnBWCyh+@mXaf^BUelQTfox&gm zIgmHf(#N=!{na$R47^|eeExgM(Hq1St|B!gu?_N135U?fY*D%_e4PqR6Hd;x$YmRV ze5E?)@;iK(g16kvJxxFoWQCKc8Vg&QWvugYoSCkbJTtfT4|A7b!w++9Yj#XDt`F>) zB5Xl1%x~9=vaN=kH_w95*C}jkd(*n(;M{lPDsYlcYn7gnHOyh_L>KbBjpruaZKYrm zbRM89G{cyRewX!8oXEM;iv#+yl_dv_?7lDl-H)CC~J`ZXX+51DEg{LudJ<>E7M z1QJv--b4l@6w0kFPKJdExfe^A-q{(Z+Q!5&Q6^)V7pf{b)ADK8*Zz_3*CM zVF(eWc#GT*bG&U0+8}~wWajOM!8w45ss8X6iqEt_vocY=sQ&1NkiNn;M0}F&iqbf~ zy2==mwRYBbOgJ=+9y)!k=o{Q|P0s|xzF~;#(?i>!cCm_1Hcoufp5>L0mtK7pQHS@WH+{Z7DGvsij? zXn&Y{zidK4m7VO-aTFaXo(0Ij>Qd4kwcMyTs|!HG@8$Xtf?^cx9221~&BGz* zT>rIX^;3)+Fuwz}0Sh)TXum~!`}#gpQ6**}xg(|U%34>tp#=sg7HI35bEaVY?%v+c zp^%E|N4_(t)F>)0K5=X6Fqm&}H0CBmfeBoDIdy-4Aj~DS%8%GB4*1ht6B%^_!fO6& zG`cc32n}GM8ncPAc`5d-4^a}t3l)YUVq#$Wp$UuY=|W|}$BBq=5<%jKK7Qgc9D&yh zZELG@96!hQy(JnrkWFpv+QG5SOQ4`fm$~3m6UOH<{@cX)MJsmvw}XsV8eF8)#oD7z zFygSBoA{>^iNSn-Na8Vhp;B^BJ~KU?II^3bo__ZI%v&Oy@V9t2NK|pT%5;c4f=@|Z-Mm)o#;b)w3KoSBO-wQQ z_jS>_Q=%0Dp0l!0kP@OqeZ;@J96w_0*-^UCXy?;qp1c4Kj{hKZdLb9ymBX20!Pkoj zE>2E?x92N39JsK)Z#dldUd@GWKp_=;V)$m)CZDfutZ}umh+3{yc{pB1-D+EbEej71udAygdD)j(d*0f? zo3cJ)@8fbRs`-v!UB-L!8$QJS8$tKRQ<&yp6dnojZ_3pteS)tQ1KqcIszQ|3vn8JA z9k6}Il^AcAOewzC*)W>ED&=pzb+(&pFDoL*sA>e3gpBmkL?J%=JT8#C}=uM_w zyU28JraJ@u1LJgLT@8k{6_1q7*BV#G4X~Z^nXT`a?@W>E$jHd|@86GROW#eJmz(?k z#NMx|wUxMidV2c){vH_oMSaVO?aIo^V$g4#byQbmM^ovMqBO`wt^Ut&9FrzB2S-Q7 zBMk}LCS-wX8Kl2TDk+hqa;n%TED{tZqzN=Js~)p^~3qIWM5cU z#~q&?1*eP2UsP;|!0qtt*1CJDcK%ahzci?w|F9 zow))Ru(jz|GsG;Zd3>Zly5Upr(FCr`@741HK%=F+?t?zk_A}~sWdMN1=(q1QPY_S` zh9*eZ8Tns9l98Ou>wcQLV&~4A20CqhIt9=%^NjCxSy=)6QtIk+h06J(sXSAYlS=yf zaup=QE`0nnm}n$voh(ufoD56g|tHpX^C%CQ350Oa>z#E!3CuE)>K?Xfe6wR0aw zr~cuG|A?8l$fpi*aU_@>h%cX_W)Cd8x9UYdt--!_9N4fWS%E-A0{RIa*}R`h5m>{P zPaWU_94T&R}rFZMF zfI3g@s=WQ0191=gk*SRyghpC{?_cCsJh_&~)eoaW8Z@t&8b*3a)qL>c@rF=R(Qfqf zLVme0P+n7mHDrPespli?`q84bB63!(2AKrO+vtbcy ztQ;IRoNdQ0=|JTax;aM_jx0bzVOigG@lhz!Tu*qOeE+R{b<*DQyT0{0-4EnlWWSex zZMU6Yesu_3hZ#_WSRiWIRM3nf3PB|yu$I|0vVset(6jAHPCUI82p##av*{%A^Ygl* z9Om&kagjiy8G?SV&kvQAl>`d0D7gq)5!#587#d=Rzj5=A< z20y3;*ZB0u>Pujf1b2N5?IA?zJE>ngbsPI<$16wW%>Bn$zdrk%VLu3?lCWnby6UT_zk)Gu+@i~G{AVgTA9I$wqYf`LSW z5&Z-iunre|l%?20zxELU{KLB4fZ~$3-LBS7nj&1gbR=s(E(ay!tP54({`!xtYom@= z%c>107YB#!OG?z8@9h{ks`h>|!Hf5`7Qf@Jg$2TZ>DFyHp8UH8s>~!G3wbU@z%Qf+ znO&xrzmKp3nW|j3i*t+FendOYz5oGeS{k4P4Nm)zQ9o3lPDUrq;Bwr`0>QHfFHFf7 z=mH#iptw*!V>G8`|91~ZQ$H+|vUBSzgO@VG$-%MX!aG;0ZC<@nApwA&I;!AG7M-Tu z!ZLB{pQ1)r^SC~2m)}&uNuEOG6rMyVqS=uLjEz@42!BI?SaAO+$jwyQByMbk$NrtxrBl<~b1uic8`(kAAYDG_YSq*fM4^b<_T-~zENuF_S z-~2rTj{O4J3G*yow(G}f?FiP+fEOuTOLSBEZ&|ldv;E3H4vV5ABrAHQ2A2 z^?siGe_8;6oB7W1X%}*D4?HF1E~;ZZ(hp@0CD?X#RV;mkYu^c&f=@%KLIT-waoYa75UoPel;>?+J~-%D zCp~RKrBkB-f6EW-3%qsv^JjgTr+W*O<^NG5)9cu#%y!|j8V^gwu{JYPJU&X26dTgP zrY~H-re=A0a?-%=SKpT3`8CNe7M9m!54rEi(K3et2ZU$kZeAmngd&?@(d~}@F9Bz8 zK3^Q{_w_&+^|C4&bc<&;Tt_2#j|Y+N1+3a9f#h+V~k4NsB%n$Og=Slk)nv zfYq2J0;Eb83)U>qI5ix?Rh0f7^T z)8>Au+I)q9p|j4`<96YoLujb99>_>qpD%|9IBnp-!XkqBPTYh}`8L|d*7urSwJBv} zl91VTPf^^?yTe?q7hw`4->YjPct*@`!H#OxB41B>SP}F|vxNF|K&XrkvoUIQh zE_zZ>;? z{Wt3t`X$@CGvB)=AWFY%;N>zgkW5>#|APT3M53 zA7jiG?py4Oa>PdEZP*C|fp%|jFP&Umc;XgU+r!9e3qZ1ZYYr+zGjI*gFEo?NnD3Mh zm-dxHdc(jlJ8Y4GgX*sYG`z>J`aGGoiy@AhVAg@00o>AK{zF79hXod11-_bLz`>Azm4xvy&K>Jp&@ zGwJ@j2I>>Q*u~4|su8MD)zy4&J_~ww%@lK%&qYh#Ps$;lVsfuYMd2M`QTju8vZN9#hMdUme-+Z8)2E2EW(aAJOZ zI4BT1JG-o`Z1Z_1BF@pF-9NWdLEPuX>alcQSA=%;w#ONOD36MY8W3dph~0rpQ)jxnS zDI;!q`LJKrV&*0%FM)apyIpRhf}9u?7imv9q9f+g|_%QO+v_yHbY5}GZ=lvJX>z67sqVdcdKrviQxq#WkMD< zHY#Pkqf0^OAH!xDURQj}{zGP6^I{A02Ts_~U`5s3_0c#cgXTUa-zBC@4A)eAy8;ik zTFc4F6?(<1y)`_@@cVuwlaNFc{c-R|)J?a!zwXYXMdUXW>d$b9Hb`H6MZ;Px^IT2Z z&Z0#Kg_l1=&kr-jtCf{M4iAG54`X5bt4h4gQ2c&#_P9oT5kv`1C^{znJcC1^)z$*xLk6h|Li!|5Ub=Y>8*A{CfpdYha-!6mboX;^PenIE3m__U z2`4}z6Pjn|MbNyJRnTX~B^@%Zdd^x{Hm#M16JB(|4ehD2v_bNhh|frs!jl6Zq|y&z z$5>A77dU%87SpMn3-JU(vEIx4OdZ`~t9=8!9DoU6VPRolV5q99f{KcY=7RwJm&<Id{5(a)65{FS&6_F9_~?K<<(F{=CETIug%9S*4uuXylZ`GTOl(owv@L zp^Qd)ZFO=o})siNMT@ojqpAR&neVxo){*Mc0< z|8~UifSCXiA|AzS(&jZdj!t3e#PUW#O3yPNG(VhG7pM}=F%+b#PmOG}cpx(D_5%cv zleJ@UMFIF0++v)W+~)ZO$)qZo*WkjqSId0C+6_%MY3bz;MWlduD9fOLRhSDV5I_K7 zNK+XQgJO*RW220Tz|kd|JcUt8If#))b=Y}vsf52>#Fh3id7RP2;_G6hCO@TpG@T=W zNs%)N^lV9({%Yap=T|5PVFnh?1`eV>YyeQ^_o)X9*Le`OI1f5a8o$=(qq*fc_NrFR)Ain4Ohn zdTlsc^w!>uL?ik6m8wk;hk?(Ixnj#Xs(uRw5~EH>CB`v= zzWVc<)<2nyDwFr2Dv&qL0^Ho(8j6aU zb4Lu=GDRHQTKo2wIHHI=vY2!kCBrh9kZBN9_A^XsY%j`MU#WfoDE1QQY*IES99c0r$K}IgGq?aVzK+gq`b5T09dnt$GvT>@+#6OGJ{f*rDta7{?Rm zO1@;-tI)w_+?mhqM@MYmy>gLw-j$`K5;%zncb<*+!o*j@J%^6Ui8BJM^K1l2Fske~ z@!EF4ir~*Vn&wO!RZh>%Ia_Nym{5k&VK3w4bsFUl(^PpOonorS_zl0!ym;#F#Ka{L zrnCN|^EO%f$*_&IKxI?3Z{h9zlqZ*>LCS>lqRvuz=!vQn8$Dl|o~&sFe+>S#^08fa=X=yyyJ-lrvrn($Ta zCUJa56HZq^ef5}A4tE;1gdTL(^wgG&(aJB+YtDhqB zfF!1!=O_a`4m&6{GdNtJJ4TZI&);Z79LAd3+RSBHviH+tg)RAkXZVl|mSOu;Zs}x4 zRU*pELC@{mZ&ul&xg#Kn>a;Xm6mD-8{;R2Ix$(X7sbsDc1SC*JhES^KJkzYK;P-gG zY>-JA>9}mLu2sOG+lOTeUWAxzmL*G}GBLebMv<45-KP8b&18IfcGgMXB8f&mqYYb} zm;A?Q`@BRi0{VxMklZ1szQ-?&W&hyXPpd*9z2}eku5Ao!Mh#X>A=!_`6?(bxt@8-4#m=?uS_bjx?{x=vv(?wzKNR z|9zZ~CO!Q2c^=zhltQkFRZ1t}5%qmkrM5l4x^5WXlnHBQDr-r3xqG_1yl$crgLjVa zuuagvpb(4?a^T{>K(u>1eux?&KW5*}1OLwoj2@icrZM$tHtEmpv4`k-qQ9cd37-gi z6O*pwEVwh=?eCLUYMf<92(-8{?8Z{Xz~^GCsjBYef}=+J<80MIB?Qe|WoNd%S5e?P z|5QNeRwXTzPBfU$!}6Jdo=I8qJzd9HFwh`EV1Xw@gVJ`SjEu>~z62GD6LQ?eCV87I z{PS{!I3YE6aA3wos+zo9uKk9l)An|U0h&c#ow%*M`C*LFu_jxDs)g&Z#crxj)aBT9 z9vt+*;ym8@KO?F1!J9qOuhDpfz>LqE;63<9JO9h~weKJp1anxP zt*x!W5br(Dy~C7)ULClTZY> z3dLbN!L#Gbfe0%@R>Sx~MS2e65tJgch#^4;AJ!)(fVfn_Hl~g^)Pwn-Vw9FINrX*F z&m~HV-kBYo!f87RfvVq7aX5?@)`c5DszDzg6a=G)Nl7zuiDHRILbAs)`S|FSi#Hr(JJ1qb3By286qU$DYGOoMPo-Ar+FS zwKH`Dvcc~EO;U>)Ph=Oy=Gk91oynRA`lzt3uKesa=5v%2Zc{_kiXD~jpcwWQmM{p| zDK^g>Y(<;#GcMJ+IV2CJa5(jyIiXxI#%ks3t={l;v)U;w>EcI4NHt%zNCw+afIztpB1X{3yl6e2S$jP)gO?d^QIDE zG%N%ML4j@-Yz$t}vt&&ID!uHsKjxF2ulm;&7AF08MGuPsI;jr<%9^T?9bopEyBDs~N@$vSb=h|a@SAA+n3n}(x zWkp`Kt$HGF+@65s4eZ#IV#C=tJsk_gnxzwbEo!N`{5(6%a|ThDSoM*;f&h>eQLXxE z;|G6FAy5jcJ@GjTXn$qCc(SubSmQA-5@;Lwr6g+kG-;LT=C49-8q^~uAtB+)n?@SK z+u}QI#A91a8!;eyDohQ>7?H1;gqS@o9N6J+ek09*>3iJl^FVJVL5@g3q&xK^2y>uv@cw)zLeKOSwSBiMrMOKUx!q?XRSl61-tc!y zrxFbr(5ND5noml2?g4VS_i1|JnpN2Ih82xEQ9b!k(Pv}kT^|vS5U}pn#7`Wtkb2Ds zKp4>LY?MUWGW48R4FN3d)1Rg0R0DCC^h^l!%5lD~V5E-(lYks9TN7TIV(iCj$9g!0 zk7DE`_E43DKzpNUDJ`&|SpYdO8^Mq0+q&>5L2&lD$yP_T7bxLAhXF*Ez{Z#@B@nl= zTkG>a`wD{MbCj(j$$`U_GhxTu1(}1tp=?flO(~R^oQzLQyxQPM?w^^N2@uZ)D&_VW z=`d(4_)lh{ih;{SWX4ujd^0#f!eseV@PDhSl%jJ&)(~E?$X}@hnI@F6&#@?Y2SX`= zD4Fc$C?pk4A;pRx#+w$d5bK1c!_`n`R%IrN>xfH8=hql5ShQJ>HFGlqx%%Uyp{Q?K z^JM}Z8;>ycB4Vt8OYDD^BO!wLpkuJujH^lnJ%+;%Xs92q_QJ%CsWGkC@J}upi2F^G znf1v;c^UqQei|I;97>(J0)6+lMHY}(G->*9`hFLkFSGwmn}?? z8o*FajBUdcv)zr)elceahAUcT-q2W6kr9%RnDg&RGxJKn3%UkDrkE;N*fNO{z~g28R+g4G{o&dH zMeEsZ${j_InTvNaSKJq8NepO*TQ+lrRd;lMZqnJddSd^rq@2inaiOF10%Mj*b$mUZ zCqZ*n@3@MB5>hyz{yqF2itwIh4nl^(*x-Mki=|<+Vey*DlEDt$=}^~q)ob(RLHDG= z4(;0-JpUWQ!z~;{p<7;3qDB?fYs3Ooj{v zA0U4I{5d%2@dq=Y^1|jUxCTG>OYW7p$9_3EIkCxZYxBEJ{{!^k(5Oa6JiYj)cd|VP zZA>c!JprnCWLMLgIX=_899gpeR^s<(bL_w0I1Hw!=}el!Z5EtXte^ori;4QqtcW`` zIoZhUmmKAy4d-yzN7l`Y22zzPk_e(FvAwB{WQ(n1;liY0qclYrcwYlEzSZSn&e&Fm zh=pMUhUVy;WKom6b6M3mMiTpOL*?H`reaJ!z$t%Ujgu;2+bK`1Uk<)?ZBJo{Me`okid~|{SsFY45cG&4BOt>%5$olrKrJ)LNj@^|Zrc@v%)5Tt(a|KIE?e5Pw-Z!&6^i(C(8)2T#%hLEz}bx3 zZoQScJfO2CDa+1%YA~*N`7|#XKY~=H+K)43Ym;kCSI-q5aLuUG{2LHx2y*$H-5c8) z>lO!91+?UG-V0BvqkkCx_nGP*keoZsf2%el9|Yt1Xdu%&08T2G1AI&t3U=C+O_DFX z2DdbMIVaH!$I{@#-IuC8l|(&#ZfiSRDrZmi7lwv_3RE8KQlUm91iI{Q?QhAXRN|rr zb(izwfBi4o{*hYx!>;Vl?z1U+NSZyj0a{O!5Z~vMO5uPMV@GeaB#S67axwu7#PmXZ z{dJ(M?O9++t>`a8o-+WDz1h8en?rl*bCc35bXT`OD_fm7$u7K52nxbx-C+7i%`S~5 z>KU`>FE``P;PrHZ9hwWAAQKY`WhEe~G+y8;Yzh%)#+4;t-lm}i0jY;&H-%^TpCU_8 zAdWq?s>8}UQ7zN7#GGg^F<$z=zO}be#Jx4A$4hfYR6h%kdyy^xF9PnW9L7>-MNp)aRXNROYMXLa@J_(8U-LDJR_*Zv5562;hR(H{c#iq)9cjGbtyHDC^ zw5o>yIK*jKEjO=5s7-baPv_U5blXp6E=h={PN?01eLUhK-TxPyMO|e%L8o3u{|_zC zo?H|SN>T3^^Cu%fGb;s;)h}%=(7;7-ah)BW@YexEPNX^h;IVU~n^d%VH1kwuEE{Qv zo|F{|RD}nn9S}p8fS{K`Bb#zQu)i|1^v6s<7nXDq&(e)Oq8yjR7XQU_WNd+S2wHVh zB>AQY_Xy_9fFQPabaRs!Z=-B{fPq_^e&sd~MCrUC7)B--#f znD0QA(eH|plhY50*lwI$XDli8bV>$^WydTj?hqiirBcC^LDJnMpqt`7IUI9$MYB zEUCA-Ye|0^QQb*O zgqmM@ug^s1D@_I&CW5S-DXL0QRxN0@dyYfbzOi3agK@xD`tI&*)0rC=M`KEIY+RHA-(&YZ!&dJ2|MHq#m^op65y+v~ zLVgc41h6qUsIccIR9kJ#5OMxfZeHZfcBPciDvtK0^o#znL{N|wEtbh42dk6mtPq<8 zoQaml4`W8=h+hl3fGMqVTSWb5TkxIO+566oAlb*4A{h20*^R7(88(2((a^_@)83@} zP&9Z52>$u5e~1iz6xYHMHCxJGQKrK372siI&z_QIAhgBTy{`QaPSQv|#)J|OnkR%S zcr0^NF7WAhw63xtwI!%C>I_UR+NWkS%wCdUS&Aeo;lCdy5$y8oJ_helF&Jc<1AD>i5H!s;kp6etO4B=;eS8>U*e6rSn9@ZMJ~H9>j`A z^I&_@)m|pEpO00fXZLP<2^M$~g%QCf?^_&em&{5M4U|L0?K;qNqFQ%7TofQ_$v+6I zO0K!F2T5AtsZ?o>E&T-$D@XXgWvk{FclV?xQ@)>4%TC5}-?j{nU4iwBn%cT5-6k*Z zC?3-w^`H`jx+GxfUq(V_sPI2zfR9-VLE5*+Jp-#Baw1(ne8RnR}b_t1Zp zjD|AEC$0D-tfx7_!5+(L8dRpOjm=?c~R;*tJ(bL5RC5ctjP-sGyw!p+u z=09_!wqKrrGC9Uz5G-Sjz`qHL;xQN*c77KeC=U z2*gCHC}whs1G~T^z|8O8}{FUY{gZNtl#QpE~izRV>zM9cnR9V z7i&u~#ZpL#H?9*u8OYu$itxuFFPDN|64FpWBR~92#zR>=yA7c>LB|^nYkwgPq7;c@ zxS+G@p^SCzR>{DAN~+B+sBz|A3U}W3b+pz&9lF_d*j2GfJm!N1fKBBd&Am4RsYc%Y z)LvG4M|emF31o!R(>2*?vH}?(sI5K|C;g({p)HsTOT0#v6U`I8x2?s9R1fMJ9|AQ; z*Dw+n%l3N@n|+1lCTS%Lw=@%+`jms|N;ftX5puL4$QOI@kRNbTyul-!b-_zr|kBNJ> zZX%31FqVg9spm1EA^|qGj(S+R;8u0?);Aw#f6MB%R_wI7+MWI0rY;aZaJaRD$b< zPpfNnt_L^S{z56e&MejW_R>x9-j1y-Um*+g0z;g3*WD-X-=!iB{)MX@K709#Qd{Jn zXeX}{iZFsfNsdo-gLjhNL}~ANlF|JvtElR)p2<({tX-pji+{><3VX!?@sn+Hm+<<~ zQKxoO=<_G{RRDC+8^baA=+#N_OrZPB7e!*6H!VrD>koBZ>%RHU#w5^6<()|N=x>gc zarNpQ420|~F&gFAUumv?&h~7=6tlRzFOj%#dLiY2%5E} zD)qv7^QynZPLYXBXrl*}3ksy9$G)bBkloRLxP-oise|amB`6n=Oz^3;b-g2|GapeO zuhVQb`~oyIP}I0HXkV8$j{KbJrOAYPDZ^4aPOGF6oiI@=$_%dNdnUh^{fb2*X>(hg z9=YE!CDM9FM@OezCu4p z7>6s4g<9cWC7PZ-ZCHK#EzZcpfD@0Wv!K1by}8*Cv_~Hu9d&mr(Ek}N&ij51p6jF| zf8*_So|>}RqU&Wf=Y{V|OS_A%sn7oQ^1gi=QRE6~tgEot5Avm^=)K8Qrp&%fWtG9y z^Qw0+N+~T~nkWh#M-~Pu2GZE7oEO?a&>RG;jzP`e0wXBwIB8coyvarJ0rff`52OPh z1-K-;vEG9UPcJOw(}=-}ii+4q9c8#sH*r>m?)g1Dif6-Shy!iE(h7T#V`ueRF;7=j zCqrPO?y{E-@#VER3rdtvh=eb_&@o)P1^3;TlN*Q2R{FujFuC>)Dv{pt;gwkj_~qzh zrmfWXs_C0472jh)&tBvGSHqPqdX|VDy?@%V?<9Ef51Ov0A~!P5d*%L>jZKooA7|cf zucd8G{2HJ+QcKY}?Q+f*Sv@SMIi@ZKOpy$t4@A|=sYbaKb}~KX#@BD?Cky`60^23S(}POf@hWlPjb~|Ix=ideB6g0`4pcUR(V@4 zh%F;h#rJw#kl@|Z+_{eku2ZQ3wt}axhyHkR8c8#6fm-i`DkM@t-`Q;5qPqf=;mjz` z`PC2_!t43R2;JPEjF|D7j<_c?Pe2*W^upP!Ud~Mu(7kx_ZDJzb%L-4m>&HPjHT7QR zp{D@F94^F$N5J;E$tm7oMCyp#Q`WyI5yZg@V;nQvj9W@Vf(@Mf+V@_}(#0GP$Ei?x zXuE!5&N90g`z5V~UrNNxT-z6@!=LXyuM!vealGx#f)2V$x;|Iqz`ylMHaHu1*S z8~x84v}$r7*j8eq`;GNS5=!0456&*awPmjKF7lwr;Zp|*?iZ?9#dxK;m`yX)SrXaW zxLy^-3^A}pi2{#>_6TcFVhVA-T`c~iGK`QN?@I`KndYo=TXo&jOJB4jQ0EVQ>* zaS>c8Udr2=RF7y>s>NnRIZ}wFy5fpL^%9gcjRzcphPekkd*>sm?nX*ascmjV-g>l| z>w4m;IWhs0FSUp!E!=_4Hzj^-19&QB!TyS32Q{6OPv~16BpQYo*Q;qDEzA6m`KgVi z=>2@4Za-t`uBJ2@>^go~q?-1G$0m8S0m^+&CRpqQ>I%e)1x z5_^F`7*Fll65?XXE}hlHeJzgK18kX~?5(e_1PWEh`+&)Y%T&<$L0t;|QQ(mB`=&zt zsZ!T7=}KCGjq8N9(0lnbS}`oImG*A7i_6`2ACYw=UzUm(kDLTqEq6&qjx;4RWRMIN zx~rgNk@C5=M;#M|eLgq!ug$o@6?+psjV_a$x?exZ-w)3X=`J_|d-t6hetF(}0X^%qlEjEpcC1oufYIG!i-iLc!fsVhup2%m@EMw22TJD>uin|4@CYlb)DU_O7A&KayZd`^){D=C`MhYcr4<R3GwBsAF46cydqZzfPn>eapF2)%MWArA6$pqV6$wX=&&(=bzuR3kCDH2X_y z&-Uat1T1a2Amn+XowU1V;OdT->4XRi>|zL|q~@$aAGk+K|0ioNPXVWdwU{&h3O#MB4?e*&4-@kJS z-^6K>__$Lai#GaYXRk9_pt-GfUc7Qq9?8-LSi+ zm&GH8X9v7Sq2gN%@kV4Rhf#5Kg@v&ix_Z6h-o9S)-_Zei-r z`;o!=S^=3_bVIiOc~z1Ty13W#fbMDxfpS~1ijEddZ4@V$ovFa)3D3A3A9fjX;>&Eg;ITB@xyn-Zy5@Xr0E zL~ZYC;T2*Yh=fiXMQARQrT&n;Lk^8G%-Qe5wp4;B#Zv?BwEE!6jAacqJxlC%Fs0$p z=mNn*Gd_PA6-+`}U zv0K2>t~qk+)a6Y~4_UF~Ccdk92O8N`sbuQ#;c-Zn*cxu3m_loVB9)CN);(X>xQhTT1u5s&e^n3!jxg0Ju)g+X&yrI zE6X@4geivm={vha+Y%N8o9^mtXR6)BLOh8rC514=(B+B{HU3=$%8>jhB#fJx!~JYu zU+PUpDSG1rL+Fd ztSaJL8rc<%aK_NtXm-mhM}9j6ZEwX4Fhy`|hiVd_m!+j3m(J1IfJKcSaKhJF^`br= z-(PE&3-h_q9@iCboXghPbW|Ca)-@wsnSx#hhuVkoku2SF?obHx}* z{|&#(>rbXh-Ccd40zzIMV!j4>{A~4d(J$|^JS(`R-HYmfypY{_KPmca2M)oHw1weo zi9VV7W@@+mPy9-SEpC}KE}~t!-x~91g+Uc$q>-_X(l(E5#?qI3XmE@qP>jBe~n6 z>DY=_oE9p#+%#Xn)j^op*LXKszk;@#;2NYN$?*{i=3WOao~t0iWrlnXpKJ28={u9B z90>TSlbuEdruoVBu*j%w&l;KRc z!S!yd=*`d#SW5$4SZXL3modh(!t~JN*V^8JQpL9z1?2DshUBpHFwS_R7B4bLadwdz+M)C%3vj4h8imF3AKF#^YDq`#vYHS>;G@ zAV$}y{X~e{$-@P}Ce~}bzLiohQ( zEr0M{zs38a*l36m>^6i0-C;j^^InjaqX8lI)DJ!0J?X=Y7TaO6JR=K70_*KWmD>tP z!2==7#CS5xx`xUjKG4HqKQm8e?Bd45p9?Gm4aKPixm1&fg|Cf%n66VH0Td>E&@?|X z*R!CVJ&rwAh>1k0w{TR?7&7+bUO1gDA>jsg^j7u&Num_hSD9ygjawC20gGW614t16oOd2M8_!N-9XMs!K&3qG+htA~QsZ|N!?JMTOk3MD! zVOei;tMm1fGSSwAiS5AizTst-80Yr0_S#A&9_6-YI#xAAT;Lcyy*_EEI0@8t(>kVO z_xWc=y5S(5F=IPIX`p3<2)m)EUpy-N%gYgh4mZK+RH1owV-EA5z-m8EpW>wvEMVZCjkMlYbDw?s1mkw8l%ND{4;LN;VP`5As~(rWwZW?Ej4W6rOJ0RhPSBG!lj7 z*qTqD^c_*v=CH>(*RgNckk&$Gco#e2N0aVKB1H8c^7vv|@IdME|HyDJ#eAUU)78e< zV|la+lUDoRh+u6&I+K^`Orq(Chghomk)`7Z0h}o`OFds;I5xh?Ji$XT>W&vA{{4<%FcD~ zBdO2OtA%JD*jc`TUyK(Fmo~0#6jbE6Yfb-%k779gb&b^XvY|QWL{}Ot`-iN6j<>eD zcVJ6u==j_HJR>peHu+9p_^0o*pB@#QC_YFt=|%k=OZxhqEaTDY8DK;c?6OL~?6=sD ziZsi4Rj^zQG5Du(s@ zz^<3lU6sCMsWIFDDyJ3JXoVV*vBj$avKypH#cS!x0uQfbpk zuwTJZH5OBE&}uETa{q8=_0Ro^>+Ay%h!NXMfm$~;Qn2>VC4>*sG*?}Vzw3(I)HryY zV2Q{2a5_+3LZaB4+E=kTXhtN^O3QGS?S$psaB2L&O{}`OI-y|wp-H|Nc*m6r%;?jn z?a!$jjOF;r8V6<`{CbRU8sPc6cVSE5<^Uex1eY6Wa4#aG1f<N4Ptf(uNhP!yAh-gIR9q*!vAIW|Cc6sG>YA~@!9f-!K_#s${}Y@ z04&eO!-7?*AQU<8yZLZ4Hmno-v@bOlR!V#WXk zb8@nG{~SP)Oo2u=>lqLsjUWk$5?jT`$4A;B?Xs-&o98HGGmw4aFGf9}3{s%LYyq>q zkS7(y5V3f?5Ci~EO7rh1V}*lSeQRs$r%xxz`RA6PQ_#VI8#Wr)UTHTyKhI#nld#09 zq)@01Dy>4Kwa2V$Gg+faLIlQbg$p7yA70%Dx$izbO+}! z4NGf9!%xmsCJw!t9}2fhWxlMRkxN0YV=#eK5prLtl3!Ts>locjq!SygQ3<5QeO0k( zmvuMMF}qM~BXaRKTGhwp&xj(Uy!ye-22}mg zKIjA8c@g+s3Yw!p${AB(-ze%g%pmn%NAu2JksVj3a~c7U5NuQ!#wz8Mzw6#-rLsSNQOJ@R()?RHk zCHGkhW~St)kk9ih&t{4x#BSB`Y=Ux0+U#um0b06*pv$wKgm*J4Q&Ur4RD}t>`~UDk zq+wJMt`?hkiFfg$-`N|MrxA3+$u=TPphA8a@)*^T8c?JMgst5V}oJ?Se4b#A(m^wn);q4*N;ueE7Wj4ck znaK6J=?Xg)AE$418Ja*pWCca1YJL()Z`6f6DWRvEdkCTSiXQ)E13 zwJ*r!;c?-ZMV;amJ-pF6)nbdR-+z1H^FU^*nIiHUr|A_exq1E&M{^M1Xi#y+C7AEJ zaq5NHX09S!>4duP9Gm(i+*2SeLD8v&-H@H&fc%)S6@Ko%L-iZ;TI#NP77{wp$)u*$ z#YJwP`b;v@#fDSXiJz+1_!DT)_22&uW2rInzT1P@|GeMw#mr@^p8IY9%?RaK_kcd8 zKG+%SGl&$S>k|jR6qjjuGR2FGg)Dbdr zECWslO_*n!UdauX z23T0MwVP>;&H3>6QG6}0pu;P#*E}Tj(@IcWVHre5F!OPjhjbO_;@ZK|UO`g~E@IzNKzJcRmu&+HYE2 z8TFOGU;!@EUBC+V{SDi~35YbLlB^seZ=eu=#q)6e(UMrgx#g&^Vqv1=Oc&~Apku8< zq-3XdbU_!;h0-urwByVjq~=URRFnXcHo|Dogr(bI+Jq=H6L9Z(vi{S11!x}91&K}=|$wLDFEkMqVN z%=#ry<@Hf2)vvP@yeOO-_AV_~#@ePLRx=HoO-=A+eIy5pL>6tsT)k_z};j@a^P>o9CgAZmP2s@U8X#E;GSe>1FR0{~TIa+(#Mv5mf?Nt zT77?7Tp0nFaKaK3L5!gs>+5s2yKzw!@CYs=tXQ;%xyZ2A2#;mKBqVf9u)^C|Zpl(m zfT&Q+_PDIotbl`sWmI^jg9wc%9b+l5uC<$KK-$GsizSeE8YKIa?YddA)ty&KUz^KB(b*bj!yM?bDdO`ov=TcJUPR9_j25K=*n}SjUF7gUtWN| z5WbWkn?z4b65NG=7bbx!lRL*K^>$5>#1eGlW|eV!o=g_lqU@CraS zrRGN>t_YD$sbk-0R9Ie{tYR7Q`wX+V$V}ShN*4k52#dNyOuVw;!z@>=(&n$O@5JmZ z&`sAP0Mk@YVImL}6*Za=A-WIy&L8t#cwpa1JWKO>EO0x5v$9m!^|Lmb#$Spivql&E z14sj~JgoHre)gapEE}px;cr#i+(>jN%zD+kIbu#P0-NV_$cpBiniKBfzIsP1XtlH) zFDexJ2)F~mSxFZKA$m#g0VKmztxdBOCc}!Fw8+jN;d4PtvT1BVRaC1RMmyvUuyFQd z0ms-{QZ>&Uqx8C-Wa6D5=D$VdOt@1Sz@1M)wWvV#EPB@%Za-{8s zeqo(W)Zr$sSCd)k23VKtD3YYSUI$h=zlHO|^-pII*9j!$b;nw=LVlx7+!hWwi z18FBqU_8McZYDl&NvDHT`Rt3EpE@N?gzMRn<4G`_Dqdj;i>-6$Td~PNN4K@TO0@qXnT)CQ*qP0|MV+=ni0Hm&@zTPgaCF@T4I8a< zG-NO_jl16ghVub2eLj4vN_4s69gu4epB9gnl&!{0CR5h%)fuh!8Lmc}yEfj9j1!pf zOlAc=3^Dh+^{n8($bCnz-*C7-6LC#C;3hMfJgKY;+S7Q~t9k6f^A)qiL_wO@k3FC# z%bqLLCl%*!cm}XipOBeLc^8hsYAgr&hEzYfB9^|Gd$$I>2PV22SH#MUdTq$$IUfLv ztSO<%@ynHF>k@w+Q^2aE@g!P_!mFT8!z7~UWePDFaeDhhDK#Uq(p_qc9CyUs@IANh zuoDZjYgdEP94TqT`eVNBLnWSzWE$=nuztfzBR8Z%zP{N8tzg81*f)X-kd1duw^5r>A#^m@tgElLwh|Q)r zflop4@T|CMlSb4+t#%we-=BxD|Y0(1y;!P$&wUi2~;J` zwfcGA4f{%lKCu81wpUZd43-Mq2{u+b1E+j;}gn)F;gk7w7i zH&wYaS;W*;xq-}kr4fa~lL1%O6kKAzd_ zI)idh^70t57Zw$`xA;KtjU~y>_IB$f=1eJx2=6+xT%x<1&T5Icu8w84|KH_G!r^_o z9_l-h9zVQM95FxnlJ~GcCDp}ntc$M3$7j;QQQ^+J+%GNhyz;NlmYC|_%6ZMs-5)v0 zB|1vQUw9m_aAOm{9qJwi@18X{4tSDvG3ATNDi#KO zFMT1-vP&^cSxH9B-@OM-&o^!9&=YZjqp!#dg%tGKn)vAh-SLn>p#-~Q{LSMyd&r47 z6q_qkcl*&b}`+;E!Qp4&%Wc6@GXszhd?do`FK{y&N|l2X|GJ!fYll{2Qlni$U~CI>1W* zxm;5Pr9MaK^E`IO9#;^q)4Y$4mM-y;4lMKk+Z|6E85wDpMe$moJB&$oVyytXspB!T zB7O>c=aFu)BrL=3uu;)Rk4$NOYJu8UB}uiEriqYY%^(Tu6C}ijicf1ClR2NK6-B^% z1*F8cHAm~*)^*s=ix$t<3*c&32?D*voK6Td-(km}iP*dnfWM5I_!BnpCY0Lr7Q#YB*vn zDIE}Rc41`d1|~4R2cx!4ZJtXJyQUXJ!^BdjRnx+X7`_Yb%<|B?_>heOPaa=!o#W?e zR(l0Tt*y)hHC&;Ia;)i28EFVBDLmdAKzbZ@t?A+Qm3p-hZoWR zCc^%et+-pQ4r4Z%rbn?#cb11tejV!MRqD@i-p*a1x~?psV@>WIOqRX%NK` zC#x_hSgv32XE`ig^Y|?SfX&s~3@<->zlz{fqkMN(DmbkgTaPq3BU8AgK@o0UgipAx!=5?5iEKg0tMf33YIyozP~(9K&_ zCllzlBuQ)L7~Umo#ijOBG|af0iZ1K1%)D}p0?6-st*8?-hmpu?kCoEjO0;3@_fL)H zuB_#G%D8TByb@#$2_Dl(36>}8BTJcB!F+#YnT5(l-G$f~m zikIpwV1T$9AD@T%6eex7*7il0$VOR@-s@?GA0Ho^KE`*C#A;eoyR0XOJxhQ*B}@~q zPzW6c*s~@rK5)Z^C5aVah45BWdnd8F(gmGuH+C+%Kp8GEefQWw9AfG3#}V5WuP-b{ z+#s8vW(s0uNa_eU2`-2-KpD>3hQ;$$9t;EE#BB-(N|rEN(d-B~I4^+ity8*!$Xi8# zfYRQ-r+Q>pqa)yTGmhPQd8>0y=>iSa)rrUwiy2)>O@$iAnHnB>b+3lTP$m*tIr!RH zAfi|^LkepvrX%fux^Q`tsX}Ej=cJ3?))I+V&4K-mK#l?>o`qyn`fe-S!T(J--aSx^ zMx3A{yy-M(udH$NpCSu{C&n&IKg*z@h*qJ~lYZuRj<*E8eq-vyc`NhO0BX~>aD<;I zl=M@A0}URjmA*AI0p&(NM(8@EjINV^532l2ZbJBOM-5M>@RFDgnN>I2?Fjf<)02R? z^?MpgtTh}zL|_C@a`Dov)|=2|Al&-wgEQo98_$3staj?<-9qcy#ILSNtN;}zMq&wL zlV&BJAhZ1xTM1fvaSfYSOsm5fPi`2 zP|e~%cv|NGfq!P0Tow|QwQ;s&UFdrLrF8M~d!^{m$icjd_MRY!^GgTlr&-M;AWPD$ zej_SS_GI!g1^mc=m=C81c3~uLjo&xoM_W(?rBq)P()9AO-Nh3NI7cMPdAUBmEaB!ROC#ur{Sx9E>{);^$XktjMv%B_q&>z@L@s}`Lv7*! zfVMSPaObCJ+AW*du1r@Hh`la=rfMZHDX43;RBSd?Y$EdT;cwX2$t!00_A%3bp0LV_ z)y|8eX0BS#iWO%@h#4EW_wS`J)%|W^ zilJS^RFdTa$%glH_Bn2qzV4s{-i_JqA)gM$RU?8#Ry#$f)?6zUZ4kyN5nu1?T3{Bi^3t zqobQ@IbxDlPb>xdYIqU~_-`T5@>FbgzT;ma|I>(k3&*Y2LbsldJJ}$3!rk!v%vgbQ5wb`!uA{>|VAp8_w}E-S({=jcrC{Ra@9 z&`+a|7}-7EhwgevM8Ivcx~YI2#GA%XbYBUz$!1xYL;74%$Q(HexEMrQ?51~*S6I53 z2!LlU{yJHV=&APDBvI|3o!L*Cjv?GwKl=1}lBI_al_KftEI-kNXCa4%_93`JCe5nP zNo7>n(>PtGmr4^GD^K72rF=hJ@K02fJ6e3WCJtzYY7*H7LT3Mk7fEvJ0LI{F6R*XO zU1FNskB0Yuxtm>iWIM(cr)S&}OIaO}i?7KAsD zrlae^G`Ec>=z9`9;f*u5L(IIrbw`DV_p!1qU4Y$BF}6<-1O@cd>Sr8Bg{=yC7(4mn zmL`t_5TL8W&dJG%CSqjUtCpwMQIe>$(Ru!S4|AbVD6kYA;X;o!&>i4ZZs>(3gwO*w z<8%S!=IK?OXKfK+{>Bv0(b4gDznt0e0!~|>kArBooN%tH_-ajCT){J>ft9tLx=6Px zT~GC9lMKl+qOG+x0Dv9rCG*=%Kgjpr1CEeR_97A1hZ(|^`SwzjaTg#gqa_<0i6fs* zOG7B0mhKz zSq&T#*9>doWdL=9)=WtFo{CT?%6cuJAXh_@lB=*{6GQ#ZtseE?tzK;DP4 zA3Yuh{(4QB+mAj%@z=yMx9w)3Ua{)YRU9hEZ%omY?8f^d;o zd=wV_6l)L61DyD|-D3e)JjjMMl;K73Xx>DFmIzvKDjBhgraw7cA1%&t@6Om-RvE2( zCMSU+wZinx|0u8@tQp*I0oVYGE>yTOR1vaKwt`ciT=!3Yn$bk8JhU@YH^DsmhdJAo zx;W76Aku(*C|Y#!0T&$xolcluPDowyja%B2#zuquSgxdZ7zv0GWT_T|q?i~TpsblA zGyXUF9A{E1^#Hz2M|nr{o_yl0T6`2RFaS4+eIp}N4ZU=|3?#vgtHw5~Tyh*PAx!G+ z+Dv$f74g@%mc_0?%78)CA%6KYlo+!rb(xQUHVo9*#ozLwa^Q01dV{s_3}g)5_496iJ>h86N?82 zteYDR%UZg(aR{dyB@b zm||8+E89*%CNhi!Y>~4wz)2?}CZ_L+Uit^l=gPigRWc|~L!nlfgo%Jf*~d^A8hTya zRbj%DWjX*87e&{D02v|RQnzDHH$f_vlCPtKp0ESp(wkHsgLLJ<9gQuSTM$oo0N_h} z`G;8U;0r#ZKLFd8!u(qT@S1czAmp37B&JT*XW_SE2YYanxr1LACN#Xi=rZZl2=s|p zGZ4-J|Nblj(~n(H`GW-fCjEN|MDE~l!ZhgOa6;~2698yl94{W)?3P5G3s^sUWb zDL3DA5ov5S<3S(}yD3bp1%d6RjyMpAo?qXm%Rf`> z40EH^$CitDSj+2u<_9@ku4zn9DfQ%4yu+IRDkn3BkkJFSW@~HwygKj|YR<$1orjlO zDnKqhxZc}D{$q195Pl%K?ZR~rQWgeo2G+{9-vSAfQqdu%Q(=^-asR=*hqkZcFrh4X z1>^2Yle`F5W<2BH<(lViRuMN%M@6t(cklNAUF3~JkfFC6Us%`EAqFqMetG>5-Hlrv UzBJ(876?R1URAC_)-2@z0Q_wY<^TWy literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp index cb29f9b3b42ea..6febd15ef8052 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp @@ -21,14 +21,18 @@ #include #include +#include #include +#include #include #include +#include #include #include #include +#include #include #include @@ -54,16 +58,15 @@ visualization_msgs::msg::Marker get_base_marker() } void add_polygons_markers( visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygons2d & polygons, const double z, const std::string & ns) + const visualization_msgs::msg::Marker & base_marker, const lanelet::BasicPolygons2d & polygons) { - auto debug_marker = get_base_marker(); - debug_marker.ns = ns; + auto debug_marker = base_marker; debug_marker.type = visualization_msgs::msg::Marker::LINE_LIST; for (const auto & f : polygons) { boost::geometry::for_each_segment(f, [&](const auto & s) { const auto & [p1, p2] = s; - debug_marker.points.push_back(universe_utils::createMarkerPosition(p1.x(), p1.y(), z + 0.5)); - debug_marker.points.push_back(universe_utils::createMarkerPosition(p2.x(), p2.y(), z + 0.5)); + debug_marker.points.push_back(universe_utils::createMarkerPosition(p1.x(), p1.y(), 0.0)); + debug_marker.points.push_back(universe_utils::createMarkerPosition(p2.x(), p2.y(), 0.0)); }); } debug_marker_array.markers.push_back(debug_marker); @@ -157,19 +160,37 @@ visualization_msgs::msg::MarkerArray create_debug_marker_array( const auto z = ego_data.pose.position.z; visualization_msgs::msg::MarkerArray debug_marker_array; - // add_polygons_markers(debug_marker_array, ego_data.trajectory_footprints, z, "footprints"); + auto base_marker = get_base_marker(); + base_marker.pose.position.z = z + 0.5; + base_marker.ns = "footprints"; + base_marker.color = universe_utils::createMarkerColor(1.0, 1.0, 1.0, 1.0); + // TODO(Maxime): move the debug marker publishing AFTER the trajectory generation + // disabled to prevent performance issues when publishing the debug markers + // add_polygons_markers(debug_marker_array, base_marker, ego_data.trajectory_footprints); lanelet::BasicPolygons2d drivable_lane_polygons; for (const auto & poly : ego_data.drivable_lane_polygons) { drivable_lane_polygons.push_back(poly.outer); } - add_polygons_markers(debug_marker_array, drivable_lane_polygons, z, "ego_lane"); + base_marker.ns = "ego_lane"; + base_marker.color = universe_utils::createMarkerColor(0.0, 0.0, 1.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, drivable_lane_polygons); lanelet::BasicPolygons2d out_of_lane_areas; for (const auto & p : out_of_lane_data.outside_points) { out_of_lane_areas.push_back(p.outside_ring); } - add_polygons_markers(debug_marker_array, out_of_lane_areas, z, "out_of_lane_areas"); + base_marker.ns = "out_of_lane_areas"; + base_marker.color = universe_utils::createMarkerColor(1.0, 0.0, 0.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, out_of_lane_areas); + for (const auto & [bbox, i] : out_of_lane_data.outside_areas_rtree) { + const auto & a = out_of_lane_data.outside_points[i]; + debug_marker_array.markers.back().points.push_back( + ego_data.trajectory_points[a.trajectory_index].pose.position); + const auto centroid = boost::geometry::return_centroid(a.outside_ring); + debug_marker_array.markers.back().points.push_back( + geometry_msgs::msg::Point().set__x(centroid.x()).set__y(centroid.y())); + } lanelet::BasicPolygons2d object_polygons; for (const auto & o : objects.objects) { @@ -184,7 +205,9 @@ visualization_msgs::msg::MarkerArray create_debug_marker_array( } } } - add_polygons_markers(debug_marker_array, object_polygons, z, "objects"); + base_marker.ns = "objects"; + base_marker.color = universe_utils::createMarkerColor(0.0, 1.0, 0.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, object_polygons); add_current_overlap_marker(debug_marker_array, ego_data.current_footprint, z); 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 e51980d60dbba..c97e10cc8706e 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 @@ -77,8 +77,6 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node) pp.mode = getOrDeclareParameter(node, ns_ + ".mode"); pp.skip_if_already_overlapping = getOrDeclareParameter(node, ns_ + ".skip_if_already_overlapping"); - pp.ignore_lane_changeable_lanelets = - getOrDeclareParameter(node, ns_ + ".ignore_overlaps_over_lane_changeable_lanelets"); pp.max_arc_length = getOrDeclareParameter(node, ns_ + ".max_arc_length"); pp.time_threshold = getOrDeclareParameter(node, ns_ + ".threshold.time_threshold"); @@ -119,9 +117,6 @@ void OutOfLaneModule::update_parameters(const std::vector & p updateParam(parameters, ns_ + ".mode", pp.mode); updateParam(parameters, ns_ + ".skip_if_already_overlapping", pp.skip_if_already_overlapping); updateParam(parameters, ns_ + ".max_arc_length", pp.max_arc_length); - updateParam( - parameters, ns_ + ".ignore_overlaps_over_lane_changeable_lanelets", - pp.ignore_lane_changeable_lanelets); updateParam(parameters, ns_ + ".threshold.time_threshold", pp.time_threshold); updateParam(parameters, ns_ + ".ttc.threshold", pp.ttc_threshold); @@ -318,7 +313,7 @@ VelocityPlanningResult OutOfLaneModule::plan( if (should_use_previous_pose) { // if the trajectory changed the prev point is no longer on the trajectory so we project it const auto new_arc_length = motion_utils::calcSignedArcLength( - ego_trajectory_points, ego_data.first_trajectory_idx, previous_slowdown_pose_->position); + ego_trajectory_points, 0LU, previous_slowdown_pose_->position); slowdown_pose = motion_utils::calcInterpolatedPose(ego_trajectory_points, new_arc_length); } if (slowdown_pose) { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp index 8067d9e8b3410..c3714c5609135 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp @@ -47,7 +47,6 @@ struct PlannerParam bool skip_if_already_overlapping; // if true, do not run the module when ego already overlaps // another lane double max_arc_length; // [m] maximum arc length along the trajectory to check for collision - bool ignore_lane_changeable_lanelets; // if true, ignore overlaps on lane changeable lanelets double time_threshold; // [s](mode="threshold") objects time threshold double ttc_threshold; // [s](mode="ttc") threshold on time to collision between ego and an object From 1604474d03ac3b91807616ef4aefce96e4203180 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 2 Sep 2024 20:38:27 +0900 Subject: [PATCH 088/217] refactor(goal_planner): initialize parameter with free function (#8712) Signed-off-by: Mamoru Sobue --- .../manager.hpp | 3 ++ .../src/manager.cpp | 37 ++++++++++--------- 2 files changed, 23 insertions(+), 17 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp index c4db636861c4f..0888f44e054e6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp @@ -29,6 +29,9 @@ namespace autoware::behavior_path_planner class GoalPlannerModuleManager : public SceneModuleManagerInterface { + static GoalPlannerParameters initGoalPlannerParameters( + rclcpp::Node * node, const std::string & base_ns); + public: GoalPlannerModuleManager() : SceneModuleManagerInterface{"goal_planner"} {} 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 9f146f0ad73d0..f9afe28d72d3a 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 @@ -25,14 +25,11 @@ namespace autoware::behavior_path_planner { -void GoalPlannerModuleManager::init(rclcpp::Node * node) -{ - // init manager interface - initInterface(node, {""}); +GoalPlannerParameters GoalPlannerModuleManager::initGoalPlannerParameters( + rclcpp::Node * node, const std::string & base_ns) +{ GoalPlannerParameters p; - - const std::string base_ns = "goal_planner."; // general params { p.th_stopped_velocity = node->declare_parameter(base_ns + "th_stopped_velocity"); @@ -71,7 +68,7 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node) p.parking_policy = ParkingPolicy::RIGHT_SIDE; } else { RCLCPP_ERROR_STREAM( - node->get_logger().get_child(name()), + node->get_logger(), "[goal_planner] invalid parking_policy: " << parking_policy_name << std::endl); exit(EXIT_FAILURE); } @@ -115,7 +112,7 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node) p.object_recognition_collision_check_soft_margins.empty() || p.object_recognition_collision_check_hard_margins.empty()) { RCLCPP_FATAL_STREAM( - node->get_logger().get_child(name()), + node->get_logger(), "object_recognition.collision_check_soft_margins and " << "object_recognition.collision_check_hard_margins must not be empty. " << "Terminating the program..."); @@ -400,22 +397,28 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node) // validation of parameters if (p.shift_sampling_num < 1) { RCLCPP_FATAL_STREAM( - node->get_logger().get_child(name()), - "shift_sampling_num must be positive integer. Given parameter: " - << p.shift_sampling_num << std::endl - << "Terminating the program..."); + node->get_logger(), "shift_sampling_num must be positive integer. Given parameter: " + << p.shift_sampling_num << std::endl + << "Terminating the program..."); exit(EXIT_FAILURE); } if (p.maximum_deceleration < 0.0) { RCLCPP_FATAL_STREAM( - node->get_logger().get_child(name()), - "maximum_deceleration cannot be negative value. Given parameter: " - << p.maximum_deceleration << std::endl - << "Terminating the program..."); + node->get_logger(), "maximum_deceleration cannot be negative value. Given parameter: " + << p.maximum_deceleration << std::endl + << "Terminating the program..."); exit(EXIT_FAILURE); } + return p; +} - parameters_ = std::make_shared(p); +void GoalPlannerModuleManager::init(rclcpp::Node * node) +{ + // init manager interface + initInterface(node, {""}); + + const std::string base_ns = "goal_planner."; + parameters_ = std::make_shared(initGoalPlannerParameters(node, base_ns)); } void GoalPlannerModuleManager::updateModuleParams( From 0adbcc2cbf46a0728799d9d9cfac375152bc77e6 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Mon, 2 Sep 2024 21:48:48 +0900 Subject: [PATCH 089/217] ci(cppcheck): change all cppcheck from daily to weekly (#8713) Signed-off-by: Ryuta Kambe --- .github/workflows/{cppcheck-daily.yaml => cppcheck-weekly.yaml} | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) rename .github/workflows/{cppcheck-daily.yaml => cppcheck-weekly.yaml} (98%) diff --git a/.github/workflows/cppcheck-daily.yaml b/.github/workflows/cppcheck-weekly.yaml similarity index 98% rename from .github/workflows/cppcheck-daily.yaml rename to .github/workflows/cppcheck-weekly.yaml index 6defc8de4894a..493a6c36228ff 100644 --- a/.github/workflows/cppcheck-daily.yaml +++ b/.github/workflows/cppcheck-weekly.yaml @@ -2,7 +2,7 @@ name: cppcheck-daily on: schedule: - - cron: 0 0 * * * + - cron: 0 0 * * 1 workflow_dispatch: jobs: From 58297a09fb448af67ef3c8a82455dabf5c474fba Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Mon, 2 Sep 2024 22:02:57 +0900 Subject: [PATCH 090/217] ci(cppcheck): fix workflow name (#8717) Signed-off-by: Ryuta Kambe --- .github/workflows/cppcheck-weekly.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/cppcheck-weekly.yaml b/.github/workflows/cppcheck-weekly.yaml index 493a6c36228ff..2022edcc57e93 100644 --- a/.github/workflows/cppcheck-weekly.yaml +++ b/.github/workflows/cppcheck-weekly.yaml @@ -1,4 +1,4 @@ -name: cppcheck-daily +name: cppcheck-weekly on: schedule: @@ -6,7 +6,7 @@ on: workflow_dispatch: jobs: - cppcheck-daily: + cppcheck-weekly: runs-on: ubuntu-latest steps: From 757a5a58046141a085e383d60c8bc1d33c013c1f Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 3 Sep 2024 09:34:55 +0900 Subject: [PATCH 091/217] refactor(ndt_scan_marcher): add namespace "autoware::ndt_scan_matcher::" (#8691) * Added namespace "autoware::ndt_scan_matcher::" Signed-off-by: Shintaro Sakoda * Added namespace "autoware::ndt_scan_matcher::" Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda --- localization/ndt_scan_matcher/CMakeLists.txt | 2 +- .../include/ndt_scan_matcher/hyper_parameters.hpp | 5 +++++ .../include/ndt_scan_matcher/map_update_module.hpp | 5 +++++ .../include/ndt_scan_matcher/ndt_scan_matcher_core.hpp | 5 +++++ .../ndt_scan_matcher/include/ndt_scan_matcher/particle.hpp | 5 +++++ localization/ndt_scan_matcher/src/map_update_module.cpp | 5 +++++ .../ndt_scan_matcher/src/ndt_scan_matcher_core.cpp | 7 ++++++- localization/ndt_scan_matcher/src/particle.cpp | 4 ++++ localization/ndt_scan_matcher/test/test_fixture.hpp | 4 ++-- 9 files changed, 38 insertions(+), 4 deletions(-) diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index c2ede4da2f543..b7a70b8442458 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -35,7 +35,7 @@ link_directories(${PCL_LIBRARY_DIRS}) target_link_libraries(ndt_scan_matcher ${PCL_LIBRARIES}) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "NDTScanMatcher" + PLUGIN "autoware::ndt_scan_matcher::NDTScanMatcher" EXECUTABLE ${PROJECT_NAME}_node EXECUTOR MultiThreadedExecutor ) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp index 5374e598ba68f..8244bb7ab4b92 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp @@ -24,6 +24,9 @@ #include #include +namespace autoware::ndt_scan_matcher +{ + enum class ConvergedParamType { TRANSFORM_PROBABILITY = 0, NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD = 1 @@ -191,4 +194,6 @@ struct HyperParameters } }; +} // namespace autoware::ndt_scan_matcher + #endif // NDT_SCAN_MATCHER__HYPER_PARAMETERS_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index ddc5e32f782f7..24ecc17ff7af1 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -40,6 +40,9 @@ #include #include +namespace autoware::ndt_scan_matcher +{ + class MapUpdateModule { using PointSource = pcl::PointXYZ; @@ -95,4 +98,6 @@ class MapUpdateModule std::mutex last_update_position_mtx_; }; +} // namespace autoware::ndt_scan_matcher + #endif // NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index aa412fab317a2..eb49711fe9270 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -69,6 +69,9 @@ #include #include +namespace autoware::ndt_scan_matcher +{ + class NDTScanMatcher : public rclcpp::Node { using PointSource = pcl::PointXYZ; @@ -209,4 +212,6 @@ class NDTScanMatcher : public rclcpp::Node HyperParameters param_; }; +} // namespace autoware::ndt_scan_matcher + #endif // NDT_SCAN_MATCHER__NDT_SCAN_MATCHER_CORE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/particle.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/particle.hpp index f1c05bfe98551..c5ecc7f2e9837 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/particle.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/particle.hpp @@ -20,6 +20,9 @@ #include +namespace autoware::ndt_scan_matcher +{ + struct Particle { Particle( @@ -38,4 +41,6 @@ void push_debug_markers( visualization_msgs::msg::MarkerArray & marker_array, const builtin_interfaces::msg::Time & stamp, const std::string & map_frame_, const Particle & particle, const size_t i); +} // namespace autoware::ndt_scan_matcher + #endif // NDT_SCAN_MATCHER__PARTICLE_HPP_ diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 012c72e6b3a46..611d15783ea38 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -14,6 +14,9 @@ #include "ndt_scan_matcher/map_update_module.hpp" +namespace autoware::ndt_scan_matcher +{ + MapUpdateModule::MapUpdateModule( rclcpp::Node * node, std::mutex * ndt_ptr_mutex, NdtPtrType & ndt_ptr, HyperParameters::DynamicMapLoading param) @@ -312,3 +315,5 @@ void MapUpdateModule::publish_partial_pcd_map() loaded_pcd_pub_->publish(map_msg); } + +} // namespace autoware::ndt_scan_matcher diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index b59686c211b53..16f297e5a1d48 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -37,6 +37,9 @@ #include #include +namespace autoware::ndt_scan_matcher +{ + tier4_debug_msgs::msg::Float32Stamped make_float32_stamped( const builtin_interfaces::msg::Time & stamp, const float data) { @@ -1111,5 +1114,7 @@ std::tuple NDTScanMatcher return std::make_tuple(result_pose_with_cov_msg, best_particle_ptr->score); } +} // namespace autoware::ndt_scan_matcher + #include -RCLCPP_COMPONENTS_REGISTER_NODE(NDTScanMatcher) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::ndt_scan_matcher::NDTScanMatcher) diff --git a/localization/ndt_scan_matcher/src/particle.cpp b/localization/ndt_scan_matcher/src/particle.cpp index b30703c2761e8..fce6cdce3326c 100644 --- a/localization/ndt_scan_matcher/src/particle.cpp +++ b/localization/ndt_scan_matcher/src/particle.cpp @@ -15,6 +15,8 @@ #include "ndt_scan_matcher/particle.hpp" #include "localization_util/util_func.hpp" +namespace autoware::ndt_scan_matcher +{ void push_debug_markers( visualization_msgs::msg::MarkerArray & marker_array, const builtin_interfaces::msg::Time & stamp, @@ -61,3 +63,5 @@ void push_debug_markers( marker.color = exchange_color_crc(static_cast(i) / 100.0); marker_array.markers.push_back(marker); } + +} // namespace autoware::ndt_scan_matcher diff --git a/localization/ndt_scan_matcher/test/test_fixture.hpp b/localization/ndt_scan_matcher/test/test_fixture.hpp index aff227d4fcfc7..c14c0b2ffe087 100644 --- a/localization/ndt_scan_matcher/test/test_fixture.hpp +++ b/localization/ndt_scan_matcher/test/test_fixture.hpp @@ -53,7 +53,7 @@ class TestNDTScanMatcher : public ::testing::Test node_options.parameter_overrides().push_back(param); } } - node_ = std::make_shared(node_options); + node_ = std::make_shared(node_options); rcl_yaml_node_struct_fini(params_st); // prepare tf_static "base_link -> sensor_frame" @@ -79,7 +79,7 @@ class TestNDTScanMatcher : public ::testing::Test sensor_pcd_publisher_ = std::make_shared(); } - std::shared_ptr node_; + std::shared_ptr node_; std::shared_ptr tf_broadcaster_; std::shared_ptr pcd_loader_; std::shared_ptr initialpose_client_; From 01bde15f76bb2db285e722f29aac759501758627 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 3 Sep 2024 11:21:54 +0900 Subject: [PATCH 092/217] fix(static_obstacle_avoidance): use wrong parameter (#8720) Signed-off-by: satoshi-ota --- .../behavior_path_static_obstacle_avoidance_module/helper.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp index bfeb942c82be3..0f3536eeb4e7c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp @@ -305,7 +305,7 @@ class AvoidanceHelper { const auto & p = parameters_; return prepare_distance > - std::max(getEgoSpeed() * p->min_prepare_distance, p->min_prepare_distance); + std::max(getEgoSpeed() * p->min_prepare_time, p->min_prepare_distance); } bool isComfortable(const AvoidLineArray & shift_lines) const From 1c2b07b8fea384d78bf772ce5611d1de85ecb41f Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 3 Sep 2024 12:02:48 +0900 Subject: [PATCH 093/217] fix(autoware_behavior_path_start_planner_module): fix unusedFunction (#8709) * fix:checkCollisionBetweenPathFootprintsAndObjects Signed-off-by: kobayu858 * fix:add const Signed-off-by: kobayu858 * fix:unusedFunction Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../CMakeLists.txt | 1 + .../pull_out_planner_base.hpp | 31 +----------- .../src/pull_out_planner_base.cpp | 50 +++++++++++++++++++ .../src/util.cpp | 1 - 4 files changed, 52 insertions(+), 31 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.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 1d0aa23200f96..2da3051702103 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 @@ -8,6 +8,7 @@ pluginlib_export_plugin_description_file(autoware_behavior_path_planner plugins. ament_auto_add_library(${PROJECT_NAME} SHARED src/start_planner_module.cpp src/manager.cpp + src/pull_out_planner_base.cpp src/freespace_pull_out.cpp src/geometric_pull_out.cpp src/shift_pull_out.cpp 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 de2e57ff23576..f606679e7f2da 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 @@ -65,37 +65,8 @@ class PullOutPlannerBase protected: bool isPullOutPathCollided( autoware::behavior_path_planner::PullOutPath & pull_out_path, - 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 pull_out_lanes = start_planner_utils::getPullOutLanes( - planner_data_, - planner_data_->parameters.backward_path_length + parameters_.max_back_distance); - const auto & vehicle_footprint = vehicle_info_.createFootprint(); - // 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); - auto [pull_out_lane_stop_objects, others] = - utils::path_safety_checker::separateObjectsByLanelets( - stop_objects, pull_out_lanes, - [](const auto & obj, const auto & lane, const auto yaw_threshold) { - return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane, yaw_threshold); - }); - utils::path_safety_checker::filterObjectsByClass( - pull_out_lane_stop_objects, parameters_.object_types_to_check_for_path_generation); + double collision_check_distance_from_end) const; - const auto collision_check_section_path = - autoware::behavior_path_planner::start_planner_utils::extractCollisionCheckSection( - pull_out_path, collision_check_distance_from_end); - if (!collision_check_section_path) return true; - - return utils::checkCollisionBetweenPathFootprintsAndObjects( - vehicle_footprint_, collision_check_section_path.value(), pull_out_lane_stop_objects, - collision_check_margin_); - }; std::shared_ptr planner_data_; autoware::vehicle_info_utils::VehicleInfo vehicle_info_; LinearRing2d vehicle_footprint_; 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 new file mode 100644 index 0000000000000..e82db8a68740e --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp @@ -0,0 +1,50 @@ +// 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/pull_out_planner_base.hpp" + +namespace autoware::behavior_path_planner +{ +bool PullOutPlannerBase::isPullOutPathCollided( + autoware::behavior_path_planner::PullOutPath & pull_out_path, + 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 pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_.max_back_distance); + const auto & vehicle_footprint = vehicle_info_.createFootprint(); + // 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); + auto [pull_out_lane_stop_objects, others] = utils::path_safety_checker::separateObjectsByLanelets( + stop_objects, pull_out_lanes, + [](const auto & obj, const auto & lane, const auto yaw_threshold) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane, yaw_threshold); + }); + utils::path_safety_checker::filterObjectsByClass( + pull_out_lane_stop_objects, parameters_.object_types_to_check_for_path_generation); + + const auto collision_check_section_path = + autoware::behavior_path_planner::start_planner_utils::extractCollisionCheckSection( + pull_out_path, collision_check_distance_from_end); + if (!collision_check_section_path) return true; + + return utils::checkCollisionBetweenPathFootprintsAndObjects( + vehicle_footprint_, collision_check_section_path.value(), pull_out_lane_stop_objects, + collision_check_margin_); +}; +} // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp index 219efb3084f1c..d386665c181d6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp @@ -92,7 +92,6 @@ lanelet::ConstLanelets getPullOutLanes( /*forward_only_in_route*/ true); } -// cppcheck-suppress unusedFunction std::optional extractCollisionCheckSection( const PullOutPath & path, const double collision_check_distance_from_end) { From 631d9672423d8c91d867d06ab24d20dbf0fde7cd Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Tue, 3 Sep 2024 12:45:36 +0900 Subject: [PATCH 094/217] refactor(autoware_lidar_transfusion): split config (#8205) * refactor(autoware_lidar_transfusion): split config Signed-off-by: Amadeusz Szymko * style(pre-commit): autofix * chore(autoware_lidar_transfusion): bypass schema CI workflow Signed-off-by: amadeuszsz --------- Signed-off-by: Amadeusz Szymko Signed-off-by: amadeuszsz Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa --- .../detector/lidar_dnn_detector.launch.xml | 3 +- .../autoware_lidar_transfusion/README.md | 8 ++- .../config/transfusion.param.yaml | 5 -- .../config/transfusion_ml_package.param.yaml | 7 ++ .../launch/lidar_transfusion.launch.xml | 6 +- ...ema.json => transfusion.schema.dummy.json} | 55 +------------- .../schema/transfusion_ml_package.schema.json | 71 +++++++++++++++++++ 7 files changed, 93 insertions(+), 62 deletions(-) create mode 100644 perception/autoware_lidar_transfusion/config/transfusion_ml_package.param.yaml rename perception/autoware_lidar_transfusion/schema/{transfusion.schema.json => transfusion.schema.dummy.json} (70%) create mode 100644 perception/autoware_lidar_transfusion/schema/transfusion_ml_package.schema.json diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml index ed2d41e95f793..c914723f69e4a 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml @@ -26,7 +26,8 @@ - + + diff --git a/perception/autoware_lidar_transfusion/README.md b/perception/autoware_lidar_transfusion/README.md index 4a55babbcba9f..095170efa66c9 100644 --- a/perception/autoware_lidar_transfusion/README.md +++ b/perception/autoware_lidar_transfusion/README.md @@ -32,9 +32,13 @@ We trained the models using . ## Parameters -### TransFusion +### TransFusion node -{{ json_to_markdown("perception/autoware_lidar_transfusion/schema/transfusion.schema.json") }} +{{ json_to_markdown("perception/autoware_lidar_transfusion/schema/transfusion.schema.dummy.json") }} + +### TransFusion model + +{{ json_to_markdown("perception/autoware_lidar_transfusion/schema/transfusion_ml_package.schema.json") }} ### Detection class remapper diff --git a/perception/autoware_lidar_transfusion/config/transfusion.param.yaml b/perception/autoware_lidar_transfusion/config/transfusion.param.yaml index af1f63c335501..47eaa800e62fc 100644 --- a/perception/autoware_lidar_transfusion/config/transfusion.param.yaml +++ b/perception/autoware_lidar_transfusion/config/transfusion.param.yaml @@ -1,13 +1,8 @@ /**: ros__parameters: # network - class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] trt_precision: fp16 cloud_capacity: 2000000 - voxels_num: [5000, 30000, 60000] # [min, opt, max] - point_cloud_range: [-92.16, -92.16, -3.0, 92.16, 92.16, 7.0] # [x_min, y_min, z_min, x_max, y_max, z_max] - voxel_size: [0.24, 0.24, 10.0] # [x, y, z] - num_proposals: 500 onnx_path: "$(var model_path)/transfusion.onnx" engine_path: "$(var model_path)/transfusion.engine" # pre-process params diff --git a/perception/autoware_lidar_transfusion/config/transfusion_ml_package.param.yaml b/perception/autoware_lidar_transfusion/config/transfusion_ml_package.param.yaml new file mode 100644 index 0000000000000..057fc0ee0db54 --- /dev/null +++ b/perception/autoware_lidar_transfusion/config/transfusion_ml_package.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + voxels_num: [5000, 30000, 60000] # [min, opt, max] + point_cloud_range: [-92.16, -92.16, -3.0, 92.16, 92.16, 7.0] # [x_min, y_min, z_min, x_max, y_max, z_max] + voxel_size: [0.24, 0.24, 10.0] # [x, y, z] + num_proposals: 500 diff --git a/perception/autoware_lidar_transfusion/launch/lidar_transfusion.launch.xml b/perception/autoware_lidar_transfusion/launch/lidar_transfusion.launch.xml index c14802dcddc55..81d9a38941fc4 100644 --- a/perception/autoware_lidar_transfusion/launch/lidar_transfusion.launch.xml +++ b/perception/autoware_lidar_transfusion/launch/lidar_transfusion.launch.xml @@ -3,8 +3,10 @@ + - + + @@ -18,6 +20,7 @@ + @@ -30,6 +33,7 @@ + diff --git a/perception/autoware_lidar_transfusion/schema/transfusion.schema.json b/perception/autoware_lidar_transfusion/schema/transfusion.schema.dummy.json similarity index 70% rename from perception/autoware_lidar_transfusion/schema/transfusion.schema.json rename to perception/autoware_lidar_transfusion/schema/transfusion.schema.dummy.json index b37de5a97e7c0..6d9029f7e6806 100644 --- a/perception/autoware_lidar_transfusion/schema/transfusion.schema.json +++ b/perception/autoware_lidar_transfusion/schema/transfusion.schema.dummy.json @@ -1,20 +1,12 @@ { "$schema": "http://json-schema.org/draft-07/schema#", "title": "Parameters for LiDAR TransFusion Node", + "$comment": "This schema is not considered in CI workflow. See https://github.com/autowarefoundation/autoware.universe/pull/8205#issuecomment-2255074224.", "type": "object", "definitions": { "transfusion": { "type": "object", "properties": { - "class_names": { - "type": "array", - "items": { - "type": "string" - }, - "description": "An array of class names will be predicted.", - "default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"], - "uniqueItems": true - }, "trt_precision": { "type": "string", "description": "A precision of TensorRT engine.", @@ -27,34 +19,6 @@ "default": 2000000, "minimum": 1 }, - "voxels_num": { - "type": "array", - "items": { - "type": "integer" - }, - "description": "A maximum number of voxels [min, opt, max].", - "default": [5000, 30000, 60000] - }, - "point_cloud_range": { - "type": "array", - "items": { - "type": "number" - }, - "description": "An array of distance ranges of each class.", - "default": [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0], - "minItems": 6, - "maxItems": 6 - }, - "voxel_size": { - "type": "array", - "items": { - "type": "number" - }, - "description": "Voxels size [x, y, z].", - "default": [0.3, 0.3, 8.0], - "minItems": 3, - "maxItems": 3 - }, "onnx_path": { "type": "string", "description": "A path to ONNX model file.", @@ -67,18 +31,6 @@ "default": "$(var model_path)/transfusion.engine", "pattern": "\\.engine$" }, - "num_proposals": { - "type": "integer", - "description": "Number of proposals at TransHead.", - "default": 500, - "minimum": 1 - }, - "down_sample_factor": { - "type": "integer", - "description": "A scale factor of downsampling points", - "default": 1, - "minimum": 1 - }, "densification_num_past_frames": { "type": "integer", "description": "A number of past frames to be considered as same input frame.", @@ -136,11 +88,8 @@ } }, "required": [ - "class_names", "trt_precision", - "voxels_num", - "point_cloud_range", - "voxel_size", + "cloud_capacity", "onnx_path", "engine_path", "densification_num_past_frames", diff --git a/perception/autoware_lidar_transfusion/schema/transfusion_ml_package.schema.json b/perception/autoware_lidar_transfusion/schema/transfusion_ml_package.schema.json new file mode 100644 index 0000000000000..f8976213f1dcb --- /dev/null +++ b/perception/autoware_lidar_transfusion/schema/transfusion_ml_package.schema.json @@ -0,0 +1,71 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for LiDAR TransFusion Node", + "type": "object", + "definitions": { + "transfusion": { + "type": "object", + "properties": { + "class_names": { + "type": "array", + "items": { + "type": "string" + }, + "description": "An array of class names will be predicted.", + "default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "voxels_num": { + "type": "array", + "items": { + "type": "integer" + }, + "description": "A maximum number of voxels [min, opt, max].", + "default": [5000, 30000, 60000] + }, + "point_cloud_range": { + "type": "array", + "items": { + "type": "number" + }, + "description": "An array of distance ranges of each class.", + "default": [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0], + "minItems": 6, + "maxItems": 6 + }, + "voxel_size": { + "type": "array", + "items": { + "type": "number" + }, + "description": "Voxels size [x, y, z].", + "default": [0.3, 0.3, 8.0], + "minItems": 3, + "maxItems": 3 + }, + "num_proposals": { + "type": "integer", + "description": "Number of proposals at TransHead.", + "default": 500, + "minimum": 1 + } + }, + "required": ["class_names", "voxels_num", "point_cloud_range", "voxel_size", "num_proposals"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/transfusion" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} From 370fcf166b9eccfe6a21a9168cc24245aa89a6df Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 3 Sep 2024 12:56:31 +0900 Subject: [PATCH 095/217] fix(autoware_behavior_path_planner_common): fix unusedFunction (#8707) * fix:createDrivableLanesMarkerArray and setDecelerationVelocity Signed-off-by: kobayu858 * fix:convertToSnakeCase Signed-off-by: kobayu858 * fix:clang format Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../CMakeLists.txt | 2 + .../interface/scene_module_interface.hpp | 6 +- .../scene_module_manager_interface.hpp | 54 +------------- .../src/interface/scene_module_interface.cpp | 24 ++++++ .../scene_module_manager_interface.cpp | 73 +++++++++++++++++++ .../src/marker_utils/utils.cpp | 1 - .../src/utils/utils.cpp | 35 --------- 7 files changed, 101 insertions(+), 94 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp create mode 100644 planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt index d3774bb004826..2c2dd723d9e3e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt @@ -10,6 +10,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/turn_signal_decider.cpp src/interface/steering_factor_interface.cpp src/interface/scene_module_visitor.cpp + src/interface/scene_module_interface.cpp + src/interface/scene_module_manager_interface.cpp src/utils/utils.cpp src/utils/path_utils.cpp src/utils/traffic_light_utils.cpp 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 54254bf13e07f..7c15dd691d56f 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 @@ -583,11 +583,7 @@ class SceneModuleInterface stop_reason_.stop_factors.push_back(stop_factor); } - void setDrivableLanes(const std::vector & drivable_lanes) - { - drivable_lanes_marker_ = - marker_utils::createDrivableLanesMarkerArray(drivable_lanes, "drivable_lanes"); - } + void setDrivableLanes(const std::vector & drivable_lanes); BehaviorModuleOutput getPreviousModuleOutput() const { return previous_module_output_; } 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 adb0fc49c3bd1..5aa413f05a893 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 @@ -256,59 +256,7 @@ class SceneModuleManagerInterface virtual void updateModuleParams(const std::vector & parameters) = 0; protected: - void initInterface(rclcpp::Node * node, const std::vector & rtc_types) - { - using autoware::universe_utils::getOrDeclareParameter; - - // init manager configuration - { - std::string ns = name_ + "."; - try { - config_.enable_rtc = getOrDeclareParameter(*node, "enable_all_modules_auto_mode") - ? false - : getOrDeclareParameter(*node, ns + "enable_rtc"); - } catch (const std::exception & e) { - config_.enable_rtc = getOrDeclareParameter(*node, ns + "enable_rtc"); - } - - config_.enable_simultaneous_execution_as_approved_module = - getOrDeclareParameter(*node, ns + "enable_simultaneous_execution_as_approved_module"); - config_.enable_simultaneous_execution_as_candidate_module = getOrDeclareParameter( - *node, ns + "enable_simultaneous_execution_as_candidate_module"); - } - - // init rtc configuration - for (const auto & rtc_type : rtc_types) { - const auto snake_case_name = utils::convertToSnakeCase(name_); - const auto rtc_interface_name = - rtc_type.empty() ? snake_case_name : snake_case_name + "_" + rtc_type; - rtc_interface_ptr_map_.emplace( - rtc_type, std::make_shared(node, rtc_interface_name, config_.enable_rtc)); - objects_of_interest_marker_interface_ptr_map_.emplace( - rtc_type, std::make_shared(node, rtc_interface_name)); - } - - // init publisher - { - pub_info_marker_ = node->create_publisher("~/info/" + name_, 20); - pub_debug_marker_ = node->create_publisher("~/debug/" + name_, 20); - pub_virtual_wall_ = node->create_publisher("~/virtual_wall/" + name_, 20); - pub_drivable_lanes_ = node->create_publisher("~/drivable_lanes/" + name_, 20); - pub_processing_time_ = node->create_publisher( - "~/processing_time/" + name_, 20); - } - - // init steering factor - { - steering_factor_interface_ptr_ = - std::make_shared(node, utils::convertToSnakeCase(name_)); - } - - // misc - { - node_ = node; - } - } + void initInterface(rclcpp::Node * node, const std::vector & rtc_types); virtual std::unique_ptr createNewSceneModuleInstance() = 0; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp new file mode 100644 index 0000000000000..b682203d3177f --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp @@ -0,0 +1,24 @@ +// 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_common/interface/scene_module_interface.hpp" + +namespace autoware::behavior_path_planner +{ +void SceneModuleInterface::setDrivableLanes(const std::vector & drivable_lanes) +{ + drivable_lanes_marker_ = + marker_utils::createDrivableLanesMarkerArray(drivable_lanes, "drivable_lanes"); +} +} // namespace autoware::behavior_path_planner 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 new file mode 100644 index 0000000000000..b83967f41d3da --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp @@ -0,0 +1,73 @@ +// 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_common/interface/scene_module_manager_interface.hpp" + +namespace autoware::behavior_path_planner +{ +void SceneModuleManagerInterface::initInterface( + rclcpp::Node * node, const std::vector & rtc_types) +{ + using autoware::universe_utils::getOrDeclareParameter; + + // init manager configuration + { + std::string ns = name_ + "."; + try { + config_.enable_rtc = getOrDeclareParameter(*node, "enable_all_modules_auto_mode") + ? false + : getOrDeclareParameter(*node, ns + "enable_rtc"); + } catch (const std::exception & e) { + config_.enable_rtc = getOrDeclareParameter(*node, ns + "enable_rtc"); + } + + config_.enable_simultaneous_execution_as_approved_module = + getOrDeclareParameter(*node, ns + "enable_simultaneous_execution_as_approved_module"); + config_.enable_simultaneous_execution_as_candidate_module = + getOrDeclareParameter(*node, ns + "enable_simultaneous_execution_as_candidate_module"); + } + + // init rtc configuration + for (const auto & rtc_type : rtc_types) { + const auto snake_case_name = utils::convertToSnakeCase(name_); + const auto rtc_interface_name = + rtc_type.empty() ? snake_case_name : snake_case_name + "_" + rtc_type; + rtc_interface_ptr_map_.emplace( + rtc_type, std::make_shared(node, rtc_interface_name, config_.enable_rtc)); + objects_of_interest_marker_interface_ptr_map_.emplace( + rtc_type, std::make_shared(node, rtc_interface_name)); + } + + // init publisher + { + pub_info_marker_ = node->create_publisher("~/info/" + name_, 20); + pub_debug_marker_ = node->create_publisher("~/debug/" + name_, 20); + pub_virtual_wall_ = node->create_publisher("~/virtual_wall/" + name_, 20); + pub_drivable_lanes_ = node->create_publisher("~/drivable_lanes/" + name_, 20); + pub_processing_time_ = node->create_publisher( + "~/processing_time/" + name_, 20); + } + + // init steering factor + { + steering_factor_interface_ptr_ = + std::make_shared(node, utils::convertToSnakeCase(name_)); + } + + // misc + { + node_ = node; + } +} +} // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp index 09a23197d8092..d57c2339041f4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp @@ -341,7 +341,6 @@ MarkerArray createObjectsMarkerArray( return msg; } -// cppcheck-suppress unusedFunction MarkerArray createDrivableLanesMarkerArray( const std::vector & drivable_lanes, std::string && ns) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp index 0785a639034d7..a48e36e3599ac 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp @@ -99,7 +99,6 @@ double l2Norm(const Vector3 vector) return std::sqrt(std::pow(vector.x, 2) + std::pow(vector.y, 2) + std::pow(vector.z, 2)); } -// cppcheck-suppress unusedFunction bool checkCollisionBetweenPathFootprintsAndObjects( const autoware::universe_utils::LinearRing2d & local_vehicle_footprint, const PathWithLaneId & ego_path, const PredictedObjects & dynamic_objects, const double margin) @@ -1044,39 +1043,6 @@ PathWithLaneId getCenterLinePath( return resampled_path_with_lane_id; } -// TODO(murooka) remove calcSignedArcLength using findNearestSegmentIndex inside the -// function -// cppcheck-suppress unusedFunction -PathWithLaneId setDecelerationVelocity( - const PathWithLaneId & input, const double target_velocity, const Pose target_pose, - const double buffer, const double deceleration_interval) -{ - auto reference_path = input; - - for (auto & point : reference_path.points) { - const auto arclength_to_target = std::max( - 0.0, autoware::motion_utils::calcSignedArcLength( - reference_path.points, point.point.pose.position, target_pose.position) + - buffer); - if (arclength_to_target > deceleration_interval) continue; - point.point.longitudinal_velocity_mps = std::min( - point.point.longitudinal_velocity_mps, - static_cast( - (arclength_to_target / deceleration_interval) * - (point.point.longitudinal_velocity_mps - target_velocity) + - target_velocity)); - } - - const auto stop_point_length = - autoware::motion_utils::calcSignedArcLength(reference_path.points, 0, target_pose.position) + - buffer; - if (std::abs(target_velocity) < eps && stop_point_length > 0.0) { - const auto stop_point = utils::insertStopPoint(stop_point_length, reference_path); - } - - return reference_path; -} - std::uint8_t getHighestProbLabel(const std::vector & classification) { std::uint8_t label = ObjectClassification::UNKNOWN; @@ -1493,7 +1459,6 @@ lanelet::ConstLanelets getLaneletsFromPath( return lanelets; } -// cppcheck-suppress unusedFunction std::string convertToSnakeCase(const std::string & input_str) { std::string output_str = std::string{static_cast(std::tolower(input_str.at(0)))}; From 602e3d068afb8b0543e579a30683a938331c3d2b Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 3 Sep 2024 13:01:10 +0900 Subject: [PATCH 096/217] fix(autoware_obstacle_stop_planner): fix unusedFunction (#8643) fix:unusedFunction Signed-off-by: kobayu858 --- .../autoware_obstacle_stop_planner/src/debug_marker.hpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp index 1b4cdfd87f81b..ac043dd895ea7 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp @@ -73,12 +73,6 @@ class DebugValues SIZE }; - /** - * @brief get the index corresponding to the given value TYPE - * @param [in] type the TYPE enum for which to get the index - * @return index of the type - */ - static int getValuesIdx(const TYPE type) { return static_cast(type); } /** * @brief get all the debug values as an std::array * @return array of all debug values From 74bd8edda40df926b437c522b986e27d37e5c451 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 3 Sep 2024 13:15:32 +0900 Subject: [PATCH 097/217] fix(static_obstacle_avoidance): change implementation the logic to remove invalid small shift lines (#8721) * Revert "fix(static_obstacle_avoidance): remove invalid small shift lines (#8344)" This reverts commit 2705a63817f02ecfa705960459438763225ea6cf. * fix(static_obstacle_avoidance): remove invalid small shift lines Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/shift_line_generator.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) 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 57a6e340bf853..e9950b56ce174 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 @@ -812,7 +812,7 @@ AvoidLineArray ShiftLineGenerator::applyFillGapProcess( // fill gap among shift lines. for (size_t i = 0; i < sorted.size() - 1; ++i) { - if (sorted.at(i + 1).start_longitudinal < sorted.at(i).end_longitudinal) { + if (sorted.at(i + 1).start_longitudinal < sorted.at(i).end_longitudinal + 1e-3) { continue; } @@ -827,8 +827,6 @@ AvoidLineArray ShiftLineGenerator::applyFillGapProcess( utils::static_obstacle_avoidance::fillAdditionalInfoFromLongitudinal( data, debug.step1_front_shift_line); - applySmallShiftFilter(ret, 1e-3); - return ret; } From 93e4e7de8e6a4808b656b90240cda262e328e64b Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 3 Sep 2024 13:18:24 +0900 Subject: [PATCH 098/217] fix(autoware_behavior_velocity_run_out_module): fix unusedFunction (#8669) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/utils.cpp | 14 -------------- .../src/utils.hpp | 4 ---- 2 files changed, 18 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp index 4f03dadc0555a..151d2616da5f9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp @@ -134,20 +134,6 @@ bool isSamePoint(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg: return false; } -// if path points have the same point as target_point, return the index -std::optional haveSamePoint( - const PathPointsWithLaneId & path_points, const geometry_msgs::msg::Point & target_point) -{ - for (size_t i = 0; i < path_points.size(); i++) { - const auto & path_point = path_points.at(i).point.pose.position; - if (isSamePoint(path_point, target_point)) { - return i; - } - } - - return {}; -} - // insert path velocity which doesn't exceed original velocity void insertPathVelocityFromIndexLimited( const size_t & start_idx, const float velocity_mps, PathPointsWithLaneId & path_points) 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 f96d9f966265f..af6d9a7bc631b 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 @@ -224,10 +224,6 @@ std::vector findLateralSameSidePoints( bool isSamePoint(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2); -// if path points have the same point as target_point, return the index -std::optional haveSamePoint( - const PathPointsWithLaneId & path_points, const geometry_msgs::msg::Point & target_point); - // insert path velocity which doesn't exceed original velocity void insertPathVelocityFromIndexLimited( const size_t & start_idx, const float velocity_mps, PathPointsWithLaneId & path_points); From 03f675e991e23347a24f79e1166e8b792c8f753f Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Tue, 3 Sep 2024 14:31:56 +0900 Subject: [PATCH 099/217] refactor(pose_initializer)!: prefix package and namespace with autoware (#8701) * add autoware_ prefix Signed-off-by: a-maumau * fix link Signed-off-by: a-maumau --------- Signed-off-by: a-maumau Co-authored-by: SakodaShintaro --- .github/CODEOWNERS | 2 +- .../pose_twist_estimator.launch.xml | 2 +- launch/tier4_localization_launch/package.xml | 2 +- .../launch/simulator.launch.xml | 4 ++-- .../CMakeLists.txt | 16 ++++++++-------- .../README.md | 10 +++++----- .../config/pose_initializer.param.yaml | 0 .../launch/pose_initializer.launch.xml | 4 ++-- .../media/diagnostic_pose_reliability.png | Bin .../package.xml | 4 ++-- .../schema/pose_initializer.schema.json | 0 .../src}/copy_vector_to_array.hpp | 9 ++++++--- .../src}/ekf_localization_trigger_module.cpp | 3 +++ .../src}/ekf_localization_trigger_module.hpp | 9 ++++++--- .../src}/gnss_module.cpp | 3 +++ .../src}/gnss_module.hpp | 9 ++++++--- .../src}/localization_module.cpp | 3 +++ .../src}/localization_module.hpp | 9 ++++++--- .../src}/ndt_localization_trigger_module.cpp | 3 +++ .../src}/ndt_localization_trigger_module.hpp | 9 ++++++--- .../src}/pose_initializer_core.cpp | 5 ++++- .../src}/pose_initializer_core.hpp | 9 ++++++--- .../src}/stop_check_module.cpp | 3 +++ .../src}/stop_check_module.hpp | 9 ++++++--- .../test/test_copy_vector_to_array.cpp | 8 ++++---- 25 files changed, 87 insertions(+), 48 deletions(-) rename localization/{pose_initializer => autoware_pose_initializer}/CMakeLists.txt (72%) rename localization/{pose_initializer => autoware_pose_initializer}/README.md (89%) rename localization/{pose_initializer => autoware_pose_initializer}/config/pose_initializer.param.yaml (100%) rename localization/{pose_initializer => autoware_pose_initializer}/launch/pose_initializer.launch.xml (86%) rename localization/{pose_initializer => autoware_pose_initializer}/media/diagnostic_pose_reliability.png (100%) rename localization/{pose_initializer => autoware_pose_initializer}/package.xml (94%) rename localization/{pose_initializer => autoware_pose_initializer}/schema/pose_initializer.schema.json (100%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/copy_vector_to_array.hpp (89%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/ekf_localization_trigger_module.cpp (96%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/ekf_localization_trigger_module.hpp (82%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/gnss_module.cpp (95%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/gnss_module.hpp (88%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/localization_module.cpp (95%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/localization_module.hpp (87%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/ndt_localization_trigger_module.cpp (96%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/ndt_localization_trigger_module.hpp (82%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/pose_initializer_core.cpp (98%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/pose_initializer_core.hpp (93%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/stop_check_module.cpp (93%) rename localization/{pose_initializer/src/pose_initializer => autoware_pose_initializer/src}/stop_check_module.hpp (87%) rename localization/{pose_initializer => autoware_pose_initializer}/test/test_copy_vector_to_array.cpp (83%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 85f0c68a35f29..33e2fc1ab8f5f 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -94,7 +94,7 @@ localization/autoware_twist2accel/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier localization/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/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/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/pose_initializer/** anh.nguyen.2@tier4.jp isamu.takagi@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_initializer/** anh.nguyen.2@tier4.jp isamu.takagi@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/yabloc/yabloc_common/** 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/yabloc/yabloc_image_processing/** 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/yabloc/yabloc_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 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 00f2406aa82d6..02d4f169cbc0d 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 @@ -120,7 +120,7 @@ - + diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 70e09bb9072d8..be22d21707cec 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -24,13 +24,13 @@ autoware_lidar_marker_localizer autoware_pointcloud_preprocessor autoware_pose_estimator_arbiter + autoware_pose_initializer autoware_pose_instability_detector eagleye_geo_pose_fusion eagleye_gnss_converter eagleye_rt ekf_localizer ndt_scan_matcher - pose_initializer topic_tools yabloc_common yabloc_image_processing diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 5dec24c66f6ca..330abaee3c839 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -141,7 +141,7 @@ - + @@ -159,7 +159,7 @@ - + diff --git a/localization/pose_initializer/CMakeLists.txt b/localization/autoware_pose_initializer/CMakeLists.txt similarity index 72% rename from localization/pose_initializer/CMakeLists.txt rename to localization/autoware_pose_initializer/CMakeLists.txt index 324488bedebfc..d07858d0b704e 100644 --- a/localization/pose_initializer/CMakeLists.txt +++ b/localization/autoware_pose_initializer/CMakeLists.txt @@ -1,20 +1,20 @@ cmake_minimum_required(VERSION 3.14) -project(pose_initializer) +project(autoware_pose_initializer) find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED - src/pose_initializer/pose_initializer_core.cpp - src/pose_initializer/gnss_module.cpp - src/pose_initializer/localization_module.cpp - src/pose_initializer/stop_check_module.cpp - src/pose_initializer/ekf_localization_trigger_module.cpp - src/pose_initializer/ndt_localization_trigger_module.cpp + src/pose_initializer_core.cpp + src/gnss_module.cpp + src/localization_module.cpp + src/stop_check_module.cpp + src/ekf_localization_trigger_module.cpp + src/ndt_localization_trigger_module.cpp ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "PoseInitializer" + PLUGIN "autoware::pose_initializer::PoseInitializer" EXECUTABLE ${PROJECT_NAME}_node EXECUTOR MultiThreadedExecutor ) diff --git a/localization/pose_initializer/README.md b/localization/autoware_pose_initializer/README.md similarity index 89% rename from localization/pose_initializer/README.md rename to localization/autoware_pose_initializer/README.md index 2928f51f7256d..e4b9bdd28b2c5 100644 --- a/localization/pose_initializer/README.md +++ b/localization/autoware_pose_initializer/README.md @@ -1,8 +1,8 @@ -# pose_initializer +# autoware_pose_initializer ## Purpose -The `pose_initializer` is the package to send an initial pose to `ekf_localizer`. +The `autoware_pose_initializer` is the package to send an initial pose to `ekf_localizer`. It receives roughly estimated initial pose from GNSS/user. Passing the pose to `ndt_scan_matcher`, and it gets a calculated ego pose from `ndt_scan_matcher` via service. Finally, it publishes the initial pose to `ekf_localizer`. @@ -13,7 +13,7 @@ This node depends on the map height fitter library. ### Parameters -{{ json_to_markdown("localization/pose_initializer/schema/pose_initializer.schema.json") }} +{{ json_to_markdown("localization/autoware_pose_initializer/schema/pose_initializer.schema.json") }} ### Services @@ -51,7 +51,7 @@ If the score of initial pose estimation result is lower than score threshold, ER ## Connection with Default AD API -This `pose_initializer` is used via default AD API. For detailed description of the API description, please refer to [the description of `autoware_default_adapi`](https://github.com/autowarefoundation/autoware.universe/blob/main/system/autoware_default_adapi/document/localization.md). +This `autoware_pose_initializer` is used via default AD API. For detailed description of the API description, please refer to [the description of `autoware_default_adapi`](https://github.com/autowarefoundation/autoware.universe/blob/main/system/autoware_default_adapi/document/localization.md). drawing @@ -136,4 +136,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/autoware_default_adapi_helpers/ad_api_adaptors), so there is no need to input them. +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. diff --git a/localization/pose_initializer/config/pose_initializer.param.yaml b/localization/autoware_pose_initializer/config/pose_initializer.param.yaml similarity index 100% rename from localization/pose_initializer/config/pose_initializer.param.yaml rename to localization/autoware_pose_initializer/config/pose_initializer.param.yaml diff --git a/localization/pose_initializer/launch/pose_initializer.launch.xml b/localization/autoware_pose_initializer/launch/pose_initializer.launch.xml similarity index 86% rename from localization/pose_initializer/launch/pose_initializer.launch.xml rename to localization/autoware_pose_initializer/launch/pose_initializer.launch.xml index 2ffdebf39c474..e2fb71bdaab06 100644 --- a/localization/pose_initializer/launch/pose_initializer.launch.xml +++ b/localization/autoware_pose_initializer/launch/pose_initializer.launch.xml @@ -1,5 +1,5 @@ - + @@ -9,7 +9,7 @@ - + diff --git a/localization/pose_initializer/media/diagnostic_pose_reliability.png b/localization/autoware_pose_initializer/media/diagnostic_pose_reliability.png similarity index 100% rename from localization/pose_initializer/media/diagnostic_pose_reliability.png rename to localization/autoware_pose_initializer/media/diagnostic_pose_reliability.png diff --git a/localization/pose_initializer/package.xml b/localization/autoware_pose_initializer/package.xml similarity index 94% rename from localization/pose_initializer/package.xml rename to localization/autoware_pose_initializer/package.xml index e1f1233b8b4f5..67079c476ac8a 100644 --- a/localization/pose_initializer/package.xml +++ b/localization/autoware_pose_initializer/package.xml @@ -1,9 +1,9 @@ - pose_initializer + autoware_pose_initializer 0.1.0 - The pose_initializer package + The autoware_pose_initializer package Yamato Ando Takagi, Isamu Masahiro Sakamoto diff --git a/localization/pose_initializer/schema/pose_initializer.schema.json b/localization/autoware_pose_initializer/schema/pose_initializer.schema.json similarity index 100% rename from localization/pose_initializer/schema/pose_initializer.schema.json rename to localization/autoware_pose_initializer/schema/pose_initializer.schema.json diff --git a/localization/pose_initializer/src/pose_initializer/copy_vector_to_array.hpp b/localization/autoware_pose_initializer/src/copy_vector_to_array.hpp similarity index 89% rename from localization/pose_initializer/src/pose_initializer/copy_vector_to_array.hpp rename to localization/autoware_pose_initializer/src/copy_vector_to_array.hpp index 33d95c58a726b..5e9531d72b5aa 100644 --- a/localization/pose_initializer/src/pose_initializer/copy_vector_to_array.hpp +++ b/localization/autoware_pose_initializer/src/copy_vector_to_array.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_INITIALIZER__COPY_VECTOR_TO_ARRAY_HPP_ -#define POSE_INITIALIZER__COPY_VECTOR_TO_ARRAY_HPP_ +#ifndef COPY_VECTOR_TO_ARRAY_HPP_ +#define COPY_VECTOR_TO_ARRAY_HPP_ #include @@ -22,6 +22,8 @@ #include #include +namespace autoware::pose_initializer +{ template void copy_vector_to_array(const std::vector & vector, std::array & array) { @@ -44,5 +46,6 @@ std::array get_covariance_parameter(NodeT * node, const std::string copy_vector_to_array(parameter, covariance); return covariance; } +} // namespace autoware::pose_initializer -#endif // POSE_INITIALIZER__COPY_VECTOR_TO_ARRAY_HPP_ +#endif // COPY_VECTOR_TO_ARRAY_HPP_ diff --git a/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.cpp b/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp similarity index 96% rename from localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.cpp rename to localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp index 9ba424f8e857f..630635da870b0 100644 --- a/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.cpp +++ b/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp @@ -20,6 +20,8 @@ #include #include +namespace autoware::pose_initializer +{ using ServiceException = component_interface_utils::ServiceException; using Initialize = localization_interface::Initialize; @@ -65,3 +67,4 @@ void EkfLocalizationTriggerModule::send_request(bool flag, bool need_spin) const Initialize::Service::Response::ERROR_ESTIMATION, "EKF " + command_name + " failed"); } } +} // namespace autoware::pose_initializer diff --git a/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.hpp b/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.hpp similarity index 82% rename from localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.hpp rename to localization/autoware_pose_initializer/src/ekf_localization_trigger_module.hpp index 901e4ec4414b5..eab455764c040 100644 --- a/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.hpp +++ b/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.hpp @@ -12,13 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_INITIALIZER__EKF_LOCALIZATION_TRIGGER_MODULE_HPP_ -#define POSE_INITIALIZER__EKF_LOCALIZATION_TRIGGER_MODULE_HPP_ +#ifndef EKF_LOCALIZATION_TRIGGER_MODULE_HPP_ +#define EKF_LOCALIZATION_TRIGGER_MODULE_HPP_ #include #include +namespace autoware::pose_initializer +{ class EkfLocalizationTriggerModule { private: @@ -33,5 +35,6 @@ class EkfLocalizationTriggerModule rclcpp::Node * node_; rclcpp::Client::SharedPtr client_ekf_trigger_; }; +} // namespace autoware::pose_initializer -#endif // POSE_INITIALIZER__EKF_LOCALIZATION_TRIGGER_MODULE_HPP_ +#endif // EKF_LOCALIZATION_TRIGGER_MODULE_HPP_ diff --git a/localization/pose_initializer/src/pose_initializer/gnss_module.cpp b/localization/autoware_pose_initializer/src/gnss_module.cpp similarity index 95% rename from localization/pose_initializer/src/pose_initializer/gnss_module.cpp rename to localization/autoware_pose_initializer/src/gnss_module.cpp index b746828e33b1c..c5fd1490b271e 100644 --- a/localization/pose_initializer/src/pose_initializer/gnss_module.cpp +++ b/localization/autoware_pose_initializer/src/gnss_module.cpp @@ -19,6 +19,8 @@ #include +namespace autoware::pose_initializer +{ GnssModule::GnssModule(rclcpp::Node * node) : fitter_(node), clock_(node->get_clock()), @@ -55,3 +57,4 @@ geometry_msgs::msg::PoseWithCovarianceStamped GnssModule::get_pose() } return pose; } +} // namespace autoware::pose_initializer diff --git a/localization/pose_initializer/src/pose_initializer/gnss_module.hpp b/localization/autoware_pose_initializer/src/gnss_module.hpp similarity index 88% rename from localization/pose_initializer/src/pose_initializer/gnss_module.hpp rename to localization/autoware_pose_initializer/src/gnss_module.hpp index bb3f6933c2aaa..59659162c81b0 100644 --- a/localization/pose_initializer/src/pose_initializer/gnss_module.hpp +++ b/localization/autoware_pose_initializer/src/gnss_module.hpp @@ -12,14 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_INITIALIZER__GNSS_MODULE_HPP_ -#define POSE_INITIALIZER__GNSS_MODULE_HPP_ +#ifndef GNSS_MODULE_HPP_ +#define GNSS_MODULE_HPP_ #include #include #include +namespace autoware::pose_initializer +{ class GnssModule { private: @@ -38,5 +40,6 @@ class GnssModule PoseWithCovarianceStamped::ConstSharedPtr pose_; double timeout_; }; +} // namespace autoware::pose_initializer -#endif // POSE_INITIALIZER__GNSS_MODULE_HPP_ +#endif // GNSS_MODULE_HPP_ diff --git a/localization/pose_initializer/src/pose_initializer/localization_module.cpp b/localization/autoware_pose_initializer/src/localization_module.cpp similarity index 95% rename from localization/pose_initializer/src/pose_initializer/localization_module.cpp rename to localization/autoware_pose_initializer/src/localization_module.cpp index 6963e5adbba3e..0b2a63a55447b 100644 --- a/localization/pose_initializer/src/pose_initializer/localization_module.cpp +++ b/localization/autoware_pose_initializer/src/localization_module.cpp @@ -20,6 +20,8 @@ #include #include +namespace autoware::pose_initializer +{ using ServiceException = component_interface_utils::ServiceException; using Initialize = localization_interface::Initialize; using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; @@ -50,3 +52,4 @@ std::tuple LocalizationModule::align_pose( // Overwrite the covariance. return std::make_tuple(res->pose_with_covariance, res->reliable); } +} // namespace autoware::pose_initializer diff --git a/localization/pose_initializer/src/pose_initializer/localization_module.hpp b/localization/autoware_pose_initializer/src/localization_module.hpp similarity index 87% rename from localization/pose_initializer/src/pose_initializer/localization_module.hpp rename to localization/autoware_pose_initializer/src/localization_module.hpp index dc8bd49a26a79..c84c1cad31b0a 100644 --- a/localization/pose_initializer/src/pose_initializer/localization_module.hpp +++ b/localization/autoware_pose_initializer/src/localization_module.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_INITIALIZER__LOCALIZATION_MODULE_HPP_ -#define POSE_INITIALIZER__LOCALIZATION_MODULE_HPP_ +#ifndef LOCALIZATION_MODULE_HPP_ +#define LOCALIZATION_MODULE_HPP_ #include @@ -23,6 +23,8 @@ #include #include +namespace autoware::pose_initializer +{ class LocalizationModule { private: @@ -37,5 +39,6 @@ class LocalizationModule rclcpp::Logger logger_; rclcpp::Client::SharedPtr cli_align_; }; +} // namespace autoware::pose_initializer -#endif // POSE_INITIALIZER__LOCALIZATION_MODULE_HPP_ +#endif // LOCALIZATION_MODULE_HPP_ diff --git a/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.cpp b/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp similarity index 96% rename from localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.cpp rename to localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp index 436b1e2df3b21..5acf0909d21cf 100644 --- a/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.cpp +++ b/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp @@ -20,6 +20,8 @@ #include #include +namespace autoware::pose_initializer +{ using ServiceException = component_interface_utils::ServiceException; using Initialize = localization_interface::Initialize; @@ -65,3 +67,4 @@ void NdtLocalizationTriggerModule::send_request(bool flag, bool need_spin) const Initialize::Service::Response::ERROR_ESTIMATION, "NDT " + command_name + " failed"); } } +} // namespace autoware::pose_initializer diff --git a/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.hpp b/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.hpp similarity index 82% rename from localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.hpp rename to localization/autoware_pose_initializer/src/ndt_localization_trigger_module.hpp index 1c820557fb8ff..c7cfcbbf20680 100644 --- a/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.hpp +++ b/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.hpp @@ -12,13 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_INITIALIZER__NDT_LOCALIZATION_TRIGGER_MODULE_HPP_ -#define POSE_INITIALIZER__NDT_LOCALIZATION_TRIGGER_MODULE_HPP_ +#ifndef NDT_LOCALIZATION_TRIGGER_MODULE_HPP_ +#define NDT_LOCALIZATION_TRIGGER_MODULE_HPP_ #include #include +namespace autoware::pose_initializer +{ class NdtLocalizationTriggerModule { private: @@ -33,5 +35,6 @@ class NdtLocalizationTriggerModule rclcpp::Node * node_; rclcpp::Client::SharedPtr client_ndt_trigger_; }; +} // namespace autoware::pose_initializer -#endif // POSE_INITIALIZER__NDT_LOCALIZATION_TRIGGER_MODULE_HPP_ +#endif // NDT_LOCALIZATION_TRIGGER_MODULE_HPP_ diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp b/localization/autoware_pose_initializer/src/pose_initializer_core.cpp similarity index 98% rename from localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp rename to localization/autoware_pose_initializer/src/pose_initializer_core.cpp index 6535863829fac..777f92826de73 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp +++ b/localization/autoware_pose_initializer/src/pose_initializer_core.cpp @@ -25,6 +25,8 @@ #include #include +namespace autoware::pose_initializer +{ PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options) : rclcpp::Node("pose_initializer", options) { @@ -221,6 +223,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped PoseInitializer::get_gnss_pose() throw ServiceException( Initialize::Service::Response::ERROR_GNSS_SUPPORT, "GNSS is not supported."); } +} // namespace autoware::pose_initializer #include -RCLCPP_COMPONENTS_REGISTER_NODE(PoseInitializer) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pose_initializer::PoseInitializer) diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp similarity index 93% rename from localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp rename to localization/autoware_pose_initializer/src/pose_initializer_core.hpp index cd82d522187c2..e8fef885cf577 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp +++ b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_INITIALIZER__POSE_INITIALIZER_CORE_HPP_ -#define POSE_INITIALIZER__POSE_INITIALIZER_CORE_HPP_ +#ifndef POSE_INITIALIZER_CORE_HPP_ +#define POSE_INITIALIZER_CORE_HPP_ #include "localization_util/diagnostics_module.hpp" @@ -26,6 +26,8 @@ #include +namespace autoware::pose_initializer +{ class StopCheckModule; class LocalizationModule; class GnssModule; @@ -69,5 +71,6 @@ class PoseInitializer : public rclcpp::Node const Initialize::Service::Response::SharedPtr res); PoseWithCovarianceStamped get_gnss_pose(); }; +} // namespace autoware::pose_initializer -#endif // POSE_INITIALIZER__POSE_INITIALIZER_CORE_HPP_ +#endif // POSE_INITIALIZER_CORE_HPP_ diff --git a/localization/pose_initializer/src/pose_initializer/stop_check_module.cpp b/localization/autoware_pose_initializer/src/stop_check_module.cpp similarity index 93% rename from localization/pose_initializer/src/pose_initializer/stop_check_module.cpp rename to localization/autoware_pose_initializer/src/stop_check_module.cpp index 683b161e14165..0ae7cde9865d4 100644 --- a/localization/pose_initializer/src/pose_initializer/stop_check_module.cpp +++ b/localization/autoware_pose_initializer/src/stop_check_module.cpp @@ -14,6 +14,8 @@ #include "stop_check_module.hpp" +namespace autoware::pose_initializer +{ StopCheckModule::StopCheckModule(rclcpp::Node * node, double buffer_duration) : VehicleStopCheckerBase(node, buffer_duration) { @@ -28,3 +30,4 @@ void StopCheckModule::on_twist(TwistWithCovarianceStamped::ConstSharedPtr msg) twist.twist = msg->twist.twist; addTwist(twist); } +} // namespace autoware::pose_initializer diff --git a/localization/pose_initializer/src/pose_initializer/stop_check_module.hpp b/localization/autoware_pose_initializer/src/stop_check_module.hpp similarity index 87% rename from localization/pose_initializer/src/pose_initializer/stop_check_module.hpp rename to localization/autoware_pose_initializer/src/stop_check_module.hpp index 31f04029bd00e..f1be03a09e4c3 100644 --- a/localization/pose_initializer/src/pose_initializer/stop_check_module.hpp +++ b/localization/autoware_pose_initializer/src/stop_check_module.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_INITIALIZER__STOP_CHECK_MODULE_HPP_ -#define POSE_INITIALIZER__STOP_CHECK_MODULE_HPP_ +#ifndef STOP_CHECK_MODULE_HPP_ +#define STOP_CHECK_MODULE_HPP_ #include #include @@ -21,6 +21,8 @@ #include #include +namespace autoware::pose_initializer +{ class StopCheckModule : public autoware::motion_utils::VehicleStopCheckerBase { public: @@ -32,5 +34,6 @@ class StopCheckModule : public autoware::motion_utils::VehicleStopCheckerBase rclcpp::Subscription::SharedPtr sub_twist_; void on_twist(TwistWithCovarianceStamped::ConstSharedPtr msg); }; +} // namespace autoware::pose_initializer -#endif // POSE_INITIALIZER__STOP_CHECK_MODULE_HPP_ +#endif // STOP_CHECK_MODULE_HPP_ diff --git a/localization/pose_initializer/test/test_copy_vector_to_array.cpp b/localization/autoware_pose_initializer/test/test_copy_vector_to_array.cpp similarity index 83% rename from localization/pose_initializer/test/test_copy_vector_to_array.cpp rename to localization/autoware_pose_initializer/test/test_copy_vector_to_array.cpp index f372a40076ffb..6205eb3b53864 100644 --- a/localization/pose_initializer/test/test_copy_vector_to_array.cpp +++ b/localization/autoware_pose_initializer/test/test_copy_vector_to_array.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "../src/pose_initializer/copy_vector_to_array.hpp" +#include "../src/copy_vector_to_array.hpp" #include @@ -20,7 +20,7 @@ TEST(CopyVectorToArray, CopyAllElements) { const std::vector vector{0, 1, 2, 3, 4}; std::array array{}; - copy_vector_to_array(vector, array); + autoware::pose_initializer::copy_vector_to_array(vector, array); EXPECT_THAT(array, testing::ElementsAre(0, 1, 2, 3, 4)); } @@ -29,7 +29,7 @@ TEST(CopyVectorToArray, CopyZeroElements) const std::vector vector{}; // just confirm that this works std::array array{}; - copy_vector_to_array(vector, array); + autoware::pose_initializer::copy_vector_to_array(vector, array); } TEST(CopyVectorToArray, ThrowsInvalidArgumentIfMoreElementsExpected) @@ -37,7 +37,7 @@ TEST(CopyVectorToArray, ThrowsInvalidArgumentIfMoreElementsExpected) auto f = [] { const std::vector vector{0, 1, 2, 3, 4}; std::array array{}; - copy_vector_to_array(vector, array); + autoware::pose_initializer::copy_vector_to_array(vector, array); }; EXPECT_THROW( From fcad0fb6fa225530a96b7eea03215ac704d09477 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 3 Sep 2024 15:06:08 +0900 Subject: [PATCH 100/217] fix(autoware_universe_utils): fix unusedFunction (#8723) fix:unusedFunction Signed-off-by: kobayu858 --- common/autoware_universe_utils/src/system/backtrace.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/common/autoware_universe_utils/src/system/backtrace.cpp b/common/autoware_universe_utils/src/system/backtrace.cpp index 7af91bdcc60dc..b21a8cfeedd72 100644 --- a/common/autoware_universe_utils/src/system/backtrace.cpp +++ b/common/autoware_universe_utils/src/system/backtrace.cpp @@ -26,6 +26,7 @@ namespace autoware::universe_utils { +// cppcheck-suppress unusedFunction void print_backtrace() { constexpr size_t max_frames = 100; From 55cb0ccae13a6ca040c99eac4c23bc73730d0613 Mon Sep 17 00:00:00 2001 From: Mitsuhiro Sakamoto <50359861+mitukou1109@users.noreply.github.com> Date: Tue, 3 Sep 2024 15:37:37 +0900 Subject: [PATCH 101/217] refactor(autoware_universe_utils): refactor Boost.Geometry alternatives (#8594) * move alternatives to separate files Signed-off-by: mitukou1109 * style(pre-commit): autofix * include missing headers Signed-off-by: mitukou1109 --------- Signed-off-by: mitukou1109 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- common/autoware_universe_utils/CMakeLists.txt | 1 + .../universe_utils/geometry/alt_geometry.hpp | 165 +++ .../universe_utils/geometry/geometry.hpp | 141 --- .../src/geometry/alt_geometry.cpp | 442 +++++++ .../src/geometry/geometry.cpp | 426 ------- .../test/src/geometry/test_alt_geometry.cpp | 1084 +++++++++++++++++ .../test/src/geometry/test_geometry.cpp | 1057 ---------------- 7 files changed, 1692 insertions(+), 1624 deletions(-) create mode 100644 common/autoware_universe_utils/include/autoware/universe_utils/geometry/alt_geometry.hpp create mode 100644 common/autoware_universe_utils/src/geometry/alt_geometry.cpp create mode 100644 common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp diff --git a/common/autoware_universe_utils/CMakeLists.txt b/common/autoware_universe_utils/CMakeLists.txt index 5ffd313b7e03b..abc7e5050d84a 100644 --- a/common/autoware_universe_utils/CMakeLists.txt +++ b/common/autoware_universe_utils/CMakeLists.txt @@ -11,6 +11,7 @@ find_package(Boost REQUIRED) find_package(fmt REQUIRED) ament_auto_add_library(autoware_universe_utils SHARED + src/geometry/alt_geometry.cpp src/geometry/geometry.cpp src/geometry/pose_deviation.cpp src/geometry/boost_polygon_utils.cpp diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/alt_geometry.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/alt_geometry.hpp new file mode 100644 index 0000000000000..38a498f69bbae --- /dev/null +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/alt_geometry.hpp @@ -0,0 +1,165 @@ +// Copyright 2020-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__UNIVERSE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ +#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ + +#include "autoware/universe_utils/geometry/boost_geometry.hpp" + +#include +#include + +namespace autoware::universe_utils +{ +// Alternatives for Boost.Geometry ---------------------------------------------------------------- +// TODO(mitukou1109): remove namespace +namespace alt +{ +class Vector2d +{ +public: + Vector2d() : x_(0.0), y_(0.0) {} + + Vector2d(const double x, const double y) : x_(x), y_(y) {} + + double cross(const Vector2d & other) const { return x_ * other.y() - y_ * other.x(); } + + double dot(const Vector2d & other) const { return x_ * other.x() + y_ * other.y(); } + + double norm2() const { return x_ * x_ + y_ * y_; } + + double norm() const { return std::sqrt(norm2()); } + + Vector2d vector_triple(const Vector2d & v1, const Vector2d & v2) const + { + const auto tmp = this->cross(v1); + return {-v2.y() * tmp, v2.x() * tmp}; + } + + const double & x() const { return x_; } + + double & x() { return x_; } + + const double & y() const { return y_; } + + double & y() { return y_; } + +private: + double x_; + double y_; +}; + +// We use Vector2d to represent points, but we do not name the class Point2d directly +// as it has some vector operation functions. +using Point2d = Vector2d; +using Points2d = std::vector; + +class ConvexPolygon2d +{ +public: + explicit ConvexPolygon2d(const Points2d & vertices) + { + if (vertices.size() < 3) { + throw std::invalid_argument("At least 3 points are required for vertices."); + } + vertices_ = vertices; + } + + explicit ConvexPolygon2d(Points2d && vertices) + { + if (vertices.size() < 3) { + throw std::invalid_argument("At least 3 points are required for vertices."); + } + vertices_ = std::move(vertices); + } + + const Points2d & vertices() const { return vertices_; } + + Points2d & vertices() { return vertices_; } + +private: + Points2d vertices_; +}; + +inline Vector2d operator+(const Vector2d & v1, const Vector2d & v2) +{ + return {v1.x() + v2.x(), v1.y() + v2.y()}; +} + +inline Vector2d operator-(const Vector2d & v1, const Vector2d & v2) +{ + return {v1.x() - v2.x(), v1.y() - v2.y()}; +} + +inline Vector2d operator-(const Vector2d & v) +{ + return {-v.x(), -v.y()}; +} + +inline Vector2d operator*(const double & s, const Vector2d & v) +{ + return {s * v.x(), s * v.y()}; +} + +Point2d from_boost(const autoware::universe_utils::Point2d & point); + +ConvexPolygon2d from_boost(const autoware::universe_utils::Polygon2d & polygon); + +autoware::universe_utils::Point2d to_boost(const Point2d & point); + +autoware::universe_utils::Polygon2d to_boost(const ConvexPolygon2d & polygon); +} // namespace alt + +double area(const alt::ConvexPolygon2d & poly); + +alt::ConvexPolygon2d convex_hull(const alt::Points2d & points); + +void correct(alt::ConvexPolygon2d & poly); + +bool covered_by(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); + +bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2); + +double distance( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end); + +double distance(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); + +bool equals(const alt::Point2d & point1, const alt::Point2d & point2); + +bool equals(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2); + +bool intersects( + const alt::Point2d & seg1_start, const alt::Point2d & seg1_end, const alt::Point2d & seg2_start, + const alt::Point2d & seg2_end); + +bool intersects(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2); + +bool is_above( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end); + +bool is_clockwise(const alt::ConvexPolygon2d & poly); + +bool touches( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end); + +bool touches(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); + +bool within(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); + +bool within( + const alt::ConvexPolygon2d & poly_contained, const alt::ConvexPolygon2d & poly_containing); +} // namespace autoware::universe_utils + +#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp index 8796de72fd1ec..e6d0363846b20 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp @@ -22,7 +22,6 @@ #include #include -#include #include #define EIGEN_MPL2_ONLY @@ -584,146 +583,6 @@ std::optional intersect( */ bool intersects_convex(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); -// Alternatives for Boost.Geometry ---------------------------------------------------------------- - -// TODO(mitukou1109): remove namespace when migrating to alternatives -namespace alt -{ -class Vector2d -{ -public: - Vector2d() : x_(0.0), y_(0.0) {} - - Vector2d(const double x, const double y) : x_(x), y_(y) {} - - double cross(const Vector2d & other) const { return x_ * other.y() - y_ * other.x(); } - - double dot(const Vector2d & other) const { return x_ * other.x() + y_ * other.y(); } - - double norm2() const { return x_ * x_ + y_ * y_; } - - double norm() const { return std::sqrt(norm2()); } - - Vector2d vector_triple(const Vector2d & v1, const Vector2d & v2) const - { - const auto tmp = this->cross(v1); - return {-v2.y() * tmp, v2.x() * tmp}; - } - - const double & x() const { return x_; } - - double & x() { return x_; } - - const double & y() const { return y_; } - - double & y() { return y_; } - -private: - double x_; - double y_; -}; - -// We use Vector2d to represent points, but we do not name the class Point2d directly -// as it has some vector operation functions. -using Point2d = Vector2d; -using Points2d = std::vector; - -class ConvexPolygon2d -{ -public: - explicit ConvexPolygon2d(const Points2d & vertices) - { - if (vertices.size() < 3) { - throw std::invalid_argument("At least 3 points are required for vertices."); - } - vertices_ = vertices; - } - - explicit ConvexPolygon2d(Points2d && vertices) - { - if (vertices.size() < 3) { - throw std::invalid_argument("At least 3 points are required for vertices."); - } - vertices_ = std::move(vertices); - } - - const Points2d & vertices() const { return vertices_; } - - Points2d & vertices() { return vertices_; } - -private: - Points2d vertices_; -}; - -inline Vector2d operator+(const Vector2d & v1, const Vector2d & v2) -{ - return {v1.x() + v2.x(), v1.y() + v2.y()}; -} - -inline Vector2d operator-(const Vector2d & v1, const Vector2d & v2) -{ - return {v1.x() - v2.x(), v1.y() - v2.y()}; -} - -inline Vector2d operator-(const Vector2d & v) -{ - return {-v.x(), -v.y()}; -} - -inline Vector2d operator*(const double & s, const Vector2d & v) -{ - return {s * v.x(), s * v.y()}; -} - -Point2d from_boost(const autoware::universe_utils::Point2d & point); - -ConvexPolygon2d from_boost(const autoware::universe_utils::Polygon2d & polygon); - -autoware::universe_utils::Point2d to_boost(const Point2d & point); - -autoware::universe_utils::Polygon2d to_boost(const ConvexPolygon2d & polygon); -} // namespace alt - -double area(const alt::ConvexPolygon2d & poly); - -alt::ConvexPolygon2d convex_hull(const alt::Points2d & points); - -void correct(alt::ConvexPolygon2d & poly); - -bool covered_by(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); - -bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2); - -double distance( - const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end); - -double distance(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); - -bool equals(const alt::Point2d & point1, const alt::Point2d & point2); - -bool equals(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2); - -bool intersects( - const alt::Point2d & seg1_start, const alt::Point2d & seg1_end, const alt::Point2d & seg2_start, - const alt::Point2d & seg2_end); - -bool intersects(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2); - -bool is_above( - const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end); - -bool is_clockwise(const alt::ConvexPolygon2d & poly); - -bool touches( - const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end); - -bool touches(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); - -bool within(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); - -bool within( - const alt::ConvexPolygon2d & poly_contained, const alt::ConvexPolygon2d & poly_containing); - } // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__GEOMETRY_HPP_ diff --git a/common/autoware_universe_utils/src/geometry/alt_geometry.cpp b/common/autoware_universe_utils/src/geometry/alt_geometry.cpp new file mode 100644 index 0000000000000..3271f6d299d3d --- /dev/null +++ b/common/autoware_universe_utils/src/geometry/alt_geometry.cpp @@ -0,0 +1,442 @@ +// 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 "autoware/universe_utils/geometry/alt_geometry.hpp" + +namespace autoware::universe_utils +{ +// Alternatives for Boost.Geometry ---------------------------------------------------------------- +namespace alt +{ +Point2d from_boost(const autoware::universe_utils::Point2d & point) +{ + return {point.x(), point.y()}; +} + +ConvexPolygon2d from_boost(const autoware::universe_utils::Polygon2d & polygon) +{ + Points2d points; + for (const auto & point : polygon.outer()) { + points.push_back(from_boost(point)); + } + + ConvexPolygon2d _polygon(points); + correct(_polygon); + return _polygon; +} + +autoware::universe_utils::Point2d to_boost(const Point2d & point) +{ + return {point.x(), point.y()}; +} + +autoware::universe_utils::Polygon2d to_boost(const ConvexPolygon2d & polygon) +{ + autoware::universe_utils::Polygon2d _polygon; + for (const auto & vertex : polygon.vertices()) { + _polygon.outer().push_back(to_boost(vertex)); + } + return _polygon; +} +} // namespace alt + +double area(const alt::ConvexPolygon2d & poly) +{ + const auto & vertices = poly.vertices(); + + double area = 0.; + for (size_t i = 1; i < vertices.size() - 1; ++i) { + area += (vertices[i + 1] - vertices.front()).cross(vertices[i] - vertices.front()) / 2; + } + + return area; +} + +alt::ConvexPolygon2d convex_hull(const alt::Points2d & points) +{ + if (points.size() < 3) { + throw std::invalid_argument("At least 3 points are required for calculating convex hull."); + } + + // QuickHull algorithm + + const auto p_minmax_itr = std::minmax_element( + points.begin(), points.end(), [](const auto & a, const auto & b) { return a.x() < b.x(); }); + const auto & p_min = *p_minmax_itr.first; + const auto & p_max = *p_minmax_itr.second; + + alt::Points2d vertices; + + if (points.size() == 3) { + std::rotate_copy( + points.begin(), p_minmax_itr.first, points.end(), std::back_inserter(vertices)); + } else { + auto make_hull = [&vertices]( + auto self, const alt::Point2d & p1, const alt::Point2d & p2, + const alt::Points2d & points) { + if (points.empty()) { + return; + } + + const auto farthest = + *std::max_element(points.begin(), points.end(), [&](const auto & a, const auto & b) { + const auto seg_vec = p2 - p1; + return seg_vec.cross(a - p1) < seg_vec.cross(b - p1); + }); + + alt::Points2d subset1, subset2; + for (const auto & point : points) { + if (is_above(point, p1, farthest)) { + subset1.push_back(point); + } else if (is_above(point, farthest, p2)) { + subset2.push_back(point); + } + } + + self(self, p1, farthest, subset1); + vertices.push_back(farthest); + self(self, farthest, p2, subset2); + }; + + alt::Points2d above_points, below_points; + for (const auto & point : points) { + if (is_above(point, p_min, p_max)) { + above_points.push_back(point); + } else if (is_above(point, p_max, p_min)) { + below_points.push_back(point); + } + } + + vertices.push_back(p_min); + make_hull(make_hull, p_min, p_max, above_points); + vertices.push_back(p_max); + make_hull(make_hull, p_max, p_min, below_points); + } + + alt::ConvexPolygon2d hull(vertices); + correct(hull); + + return hull; +} + +void correct(alt::ConvexPolygon2d & poly) +{ + auto & vertices = poly.vertices(); + + // sort points in clockwise order with respect to the first point + std::sort(vertices.begin() + 1, vertices.end(), [&](const auto & a, const auto & b) { + return (a - vertices.front()).cross(b - vertices.front()) < 0; + }); + + if (equals(vertices.front(), vertices.back())) { + vertices.pop_back(); + } +} + +bool covered_by(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) +{ + constexpr double epsilon = 1e-6; + + const auto & vertices = poly.vertices(); + const auto num_of_vertices = vertices.size(); + int64_t winding_number = 0; + + const auto [y_min_vertex, y_max_vertex] = std::minmax_element( + vertices.begin(), vertices.end(), [](const auto & a, const auto & b) { return a.y() < b.y(); }); + if (point.y() < y_min_vertex->y() || point.y() > y_max_vertex->y()) { + return false; + } + + double cross; + for (size_t i = 0; i < num_of_vertices; ++i) { + const auto & p1 = vertices[i]; + const auto & p2 = vertices[(i + 1) % num_of_vertices]; + + if (p1.y() <= point.y() && p2.y() >= point.y()) { // upward edge + cross = (p2 - p1).cross(point - p1); + if (cross > 0) { // point is to the left of edge + winding_number++; + continue; + } + } else if (p1.y() >= point.y() && p2.y() <= point.y()) { // downward edge + cross = (p2 - p1).cross(point - p1); + if (cross < 0) { // point is to the left of edge + winding_number--; + continue; + } + } else { + continue; + } + + if (std::abs(cross) < epsilon) { // point is on edge + return true; + } + } + + return winding_number != 0; +} + +bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2) +{ + if (equals(poly1, poly2)) { + return false; + } + + if (intersects(poly1, poly2)) { + return false; + } + + for (const auto & vertex : poly1.vertices()) { + if (touches(vertex, poly2)) { + return false; + } + } + + return true; +} + +double distance( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end) +{ + constexpr double epsilon = 1e-3; + + const auto seg_vec = seg_end - seg_start; + const auto point_vec = point - seg_start; + + const double seg_vec_norm = seg_vec.norm(); + const double seg_point_dot = seg_vec.dot(point_vec); + + if (seg_vec_norm < epsilon || seg_point_dot < 0) { + return point_vec.norm(); + } else if (seg_point_dot > std::pow(seg_vec_norm, 2)) { + return (point - seg_end).norm(); + } else { + return std::abs(seg_vec.cross(point_vec)) / seg_vec_norm; + } +} + +double distance(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) +{ + if (covered_by(point, poly)) { + return 0.0; + } + + // TODO(mitukou1109): Use plane sweep method to improve performance? + const auto & vertices = poly.vertices(); + double min_distance = std::numeric_limits::max(); + for (size_t i = 0; i < vertices.size(); ++i) { + min_distance = + std::min(min_distance, distance(point, vertices[i], vertices[(i + 1) % vertices.size()])); + } + + return min_distance; +} + +bool equals(const alt::Point2d & point1, const alt::Point2d & point2) +{ + constexpr double epsilon = 1e-3; + return std::abs(point1.x() - point2.x()) < epsilon && std::abs(point1.y() - point2.y()) < epsilon; +} + +bool equals(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2) +{ + return std::all_of(poly1.vertices().begin(), poly1.vertices().end(), [&](const auto & a) { + return std::any_of(poly2.vertices().begin(), poly2.vertices().end(), [&](const auto & b) { + return equals(a, b); + }); + }); +} + +bool intersects( + const alt::Point2d & seg1_start, const alt::Point2d & seg1_end, const alt::Point2d & seg2_start, + const alt::Point2d & seg2_end) +{ + constexpr double epsilon = 1e-6; + + const auto v1 = seg1_end - seg1_start; + const auto v2 = seg2_end - seg2_start; + + const auto det = v1.cross(v2); + if (std::abs(det) < epsilon) { + return false; + } + + const auto v12 = seg2_end - seg1_end; + const double t = v2.cross(v12) / det; + const double s = v1.cross(v12) / det; + if (t < 0 || 1 < t || s < 0 || 1 < s) { + return false; + } + + return true; +} + +bool intersects(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2) +{ + if (equals(poly1, poly2)) { + return true; + } + + // GJK algorithm + + auto find_support_vector = []( + const alt::ConvexPolygon2d & poly1, + const alt::ConvexPolygon2d & poly2, + const alt::Vector2d & direction) { + auto find_farthest_vertex = + [](const alt::ConvexPolygon2d & poly, const alt::Vector2d & direction) { + return std::max_element( + poly.vertices().begin(), poly.vertices().end(), + [&](const auto & a, const auto & b) { return direction.dot(a) <= direction.dot(b); }); + }; + return *find_farthest_vertex(poly1, direction) - *find_farthest_vertex(poly2, -direction); + }; + + alt::Vector2d direction = {1.0, 0.0}; + auto a = find_support_vector(poly1, poly2, direction); + direction = -a; + auto b = find_support_vector(poly1, poly2, direction); + if (b.dot(direction) <= 0.0) { + return false; + } + + direction = (b - a).vector_triple(-a, b - a); + while (true) { + auto c = find_support_vector(poly1, poly2, direction); + if (c.dot(direction) <= 0.0) { + return false; + } + + auto n_ca = (b - c).vector_triple(a - c, a - c); + if (n_ca.dot(-c) > 0.0) { + b = c; + direction = n_ca; + } else { + auto n_cb = (a - c).vector_triple(b - c, b - c); + if (n_cb.dot(-c) > 0.0) { + a = c; + direction = n_cb; + } else { + break; + } + } + } + + return true; +} + +bool is_above( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end) +{ + return (seg_end - seg_start).cross(point - seg_start) > 0; +} + +bool is_clockwise(const alt::ConvexPolygon2d & poly) +{ + return area(poly) > 0; +} + +bool touches( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end) +{ + constexpr double epsilon = 1e-6; + + // if the cross product of the vectors from the start point and the end point to the point is 0 + // and the vectors opposite each other, the point is on the segment + const auto start_vec = point - seg_start; + const auto end_vec = point - seg_end; + return std::abs(start_vec.cross(end_vec)) < epsilon && start_vec.dot(end_vec) <= 0; +} + +bool touches(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) +{ + const auto & vertices = poly.vertices(); + const auto num_of_vertices = vertices.size(); + + const auto [y_min_vertex, y_max_vertex] = std::minmax_element( + vertices.begin(), vertices.end(), [](const auto & a, const auto & b) { return a.y() < b.y(); }); + if (point.y() < y_min_vertex->y() || point.y() > y_max_vertex->y()) { + return false; + } + + for (size_t i = 0; i < num_of_vertices; ++i) { + // check if the point is on each edge of the polygon + if (touches(point, vertices[i], vertices[(i + 1) % num_of_vertices])) { + return true; + } + } + + return false; +} + +bool within(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) +{ + constexpr double epsilon = 1e-6; + + const auto & vertices = poly.vertices(); + const auto num_of_vertices = vertices.size(); + int64_t winding_number = 0; + + const auto [y_min_vertex, y_max_vertex] = std::minmax_element( + vertices.begin(), vertices.end(), [](const auto & a, const auto & b) { return a.y() < b.y(); }); + if (point.y() <= y_min_vertex->y() || point.y() >= y_max_vertex->y()) { + return false; + } + + double cross; + for (size_t i = 0; i < num_of_vertices; ++i) { + const auto & p1 = vertices[i]; + const auto & p2 = vertices[(i + 1) % num_of_vertices]; + + if (p1.y() < point.y() && p2.y() > point.y()) { // upward edge + cross = (p2 - p1).cross(point - p1); + if (cross > 0) { // point is to the left of edge + winding_number++; + continue; + } + } else if (p1.y() > point.y() && p2.y() < point.y()) { // downward edge + cross = (p2 - p1).cross(point - p1); + if (cross < 0) { // point is to the left of edge + winding_number--; + continue; + } + } else { + continue; + } + + if (std::abs(cross) < epsilon) { // point is on edge + return false; + } + } + + return winding_number != 0; +} + +bool within( + const alt::ConvexPolygon2d & poly_contained, const alt::ConvexPolygon2d & poly_containing) +{ + if (equals(poly_contained, poly_containing)) { + return true; + } + + // check if all points of poly_contained are within poly_containing + for (const auto & vertex : poly_contained.vertices()) { + if (!within(vertex, poly_containing)) { + return false; + } + } + + return true; +} +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/src/geometry/geometry.cpp b/common/autoware_universe_utils/src/geometry/geometry.cpp index 59bf913972fda..5fda8eb3f4ca4 100644 --- a/common/autoware_universe_utils/src/geometry/geometry.cpp +++ b/common/autoware_universe_utils/src/geometry/geometry.cpp @@ -390,430 +390,4 @@ bool intersects_convex(const Polygon2d & convex_polygon1, const Polygon2d & conv return gjk::intersects(convex_polygon1, convex_polygon2); } -// Alternatives for Boost.Geometry ---------------------------------------------------------------- - -namespace alt -{ - -Point2d from_boost(const autoware::universe_utils::Point2d & point) -{ - return {point.x(), point.y()}; -} - -ConvexPolygon2d from_boost(const autoware::universe_utils::Polygon2d & polygon) -{ - Points2d points; - for (const auto & point : polygon.outer()) { - points.push_back(from_boost(point)); - } - - ConvexPolygon2d _polygon(points); - correct(_polygon); - return _polygon; -} - -autoware::universe_utils::Point2d to_boost(const Point2d & point) -{ - return {point.x(), point.y()}; -} - -autoware::universe_utils::Polygon2d to_boost(const ConvexPolygon2d & polygon) -{ - autoware::universe_utils::Polygon2d _polygon; - for (const auto & vertex : polygon.vertices()) { - _polygon.outer().push_back(to_boost(vertex)); - } - return _polygon; -} -} // namespace alt - -double area(const alt::ConvexPolygon2d & poly) -{ - const auto & vertices = poly.vertices(); - - double area = 0.; - for (size_t i = 1; i < vertices.size() - 1; ++i) { - area += (vertices[i + 1] - vertices.front()).cross(vertices[i] - vertices.front()) / 2; - } - - return area; -} - -alt::ConvexPolygon2d convex_hull(const alt::Points2d & points) -{ - if (points.size() < 3) { - throw std::invalid_argument("At least 3 points are required for calculating convex hull."); - } - - // QuickHull algorithm - - const auto p_minmax_itr = std::minmax_element( - points.begin(), points.end(), [](const auto & a, const auto & b) { return a.x() < b.x(); }); - const auto & p_min = *p_minmax_itr.first; - const auto & p_max = *p_minmax_itr.second; - - alt::Points2d vertices; - - if (points.size() == 3) { - std::rotate_copy( - points.begin(), p_minmax_itr.first, points.end(), std::back_inserter(vertices)); - } else { - auto make_hull = [&vertices]( - auto self, const alt::Point2d & p1, const alt::Point2d & p2, - const alt::Points2d & points) { - if (points.empty()) { - return; - } - - const auto farthest = - *std::max_element(points.begin(), points.end(), [&](const auto & a, const auto & b) { - const auto seg_vec = p2 - p1; - return seg_vec.cross(a - p1) < seg_vec.cross(b - p1); - }); - - alt::Points2d subset1, subset2; - for (const auto & point : points) { - if (is_above(point, p1, farthest)) { - subset1.push_back(point); - } else if (is_above(point, farthest, p2)) { - subset2.push_back(point); - } - } - - self(self, p1, farthest, subset1); - vertices.push_back(farthest); - self(self, farthest, p2, subset2); - }; - - alt::Points2d above_points, below_points; - for (const auto & point : points) { - if (is_above(point, p_min, p_max)) { - above_points.push_back(point); - } else if (is_above(point, p_max, p_min)) { - below_points.push_back(point); - } - } - - vertices.push_back(p_min); - make_hull(make_hull, p_min, p_max, above_points); - vertices.push_back(p_max); - make_hull(make_hull, p_max, p_min, below_points); - } - - alt::ConvexPolygon2d hull(vertices); - correct(hull); - - return hull; -} - -void correct(alt::ConvexPolygon2d & poly) -{ - auto & vertices = poly.vertices(); - - // sort points in clockwise order with respect to the first point - std::sort(vertices.begin() + 1, vertices.end(), [&](const auto & a, const auto & b) { - return (a - vertices.front()).cross(b - vertices.front()) < 0; - }); - - if (equals(vertices.front(), vertices.back())) { - vertices.pop_back(); - } -} - -bool covered_by(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) -{ - constexpr double epsilon = 1e-6; - - const auto & vertices = poly.vertices(); - const auto num_of_vertices = vertices.size(); - int64_t winding_number = 0; - - const auto [y_min_vertex, y_max_vertex] = std::minmax_element( - vertices.begin(), vertices.end(), [](const auto & a, const auto & b) { return a.y() < b.y(); }); - if (point.y() < y_min_vertex->y() || point.y() > y_max_vertex->y()) { - return false; - } - - double cross; - for (size_t i = 0; i < num_of_vertices; ++i) { - const auto & p1 = vertices[i]; - const auto & p2 = vertices[(i + 1) % num_of_vertices]; - - if (p1.y() <= point.y() && p2.y() >= point.y()) { // upward edge - cross = (p2 - p1).cross(point - p1); - if (cross > 0) { // point is to the left of edge - winding_number++; - continue; - } - } else if (p1.y() >= point.y() && p2.y() <= point.y()) { // downward edge - cross = (p2 - p1).cross(point - p1); - if (cross < 0) { // point is to the left of edge - winding_number--; - continue; - } - } else { - continue; - } - - if (std::abs(cross) < epsilon) { // point is on edge - return true; - } - } - - return winding_number != 0; -} - -bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2) -{ - if (equals(poly1, poly2)) { - return false; - } - - if (intersects(poly1, poly2)) { - return false; - } - - for (const auto & vertex : poly1.vertices()) { - if (touches(vertex, poly2)) { - return false; - } - } - - return true; -} - -double distance( - const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end) -{ - constexpr double epsilon = 1e-3; - - const auto seg_vec = seg_end - seg_start; - const auto point_vec = point - seg_start; - - const double seg_vec_norm = seg_vec.norm(); - const double seg_point_dot = seg_vec.dot(point_vec); - - if (seg_vec_norm < epsilon || seg_point_dot < 0) { - return point_vec.norm(); - } else if (seg_point_dot > std::pow(seg_vec_norm, 2)) { - return (point - seg_end).norm(); - } else { - return std::abs(seg_vec.cross(point_vec)) / seg_vec_norm; - } -} - -double distance(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) -{ - if (covered_by(point, poly)) { - return 0.0; - } - - // TODO(mitukou1109): Use plane sweep method to improve performance? - const auto & vertices = poly.vertices(); - double min_distance = std::numeric_limits::max(); - for (size_t i = 0; i < vertices.size(); ++i) { - min_distance = - std::min(min_distance, distance(point, vertices[i], vertices[(i + 1) % vertices.size()])); - } - - return min_distance; -} - -bool equals(const alt::Point2d & point1, const alt::Point2d & point2) -{ - constexpr double epsilon = 1e-3; - return std::abs(point1.x() - point2.x()) < epsilon && std::abs(point1.y() - point2.y()) < epsilon; -} - -bool equals(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2) -{ - return std::all_of(poly1.vertices().begin(), poly1.vertices().end(), [&](const auto & a) { - return std::any_of(poly2.vertices().begin(), poly2.vertices().end(), [&](const auto & b) { - return equals(a, b); - }); - }); -} - -bool intersects( - const alt::Point2d & seg1_start, const alt::Point2d & seg1_end, const alt::Point2d & seg2_start, - const alt::Point2d & seg2_end) -{ - constexpr double epsilon = 1e-6; - - const auto v1 = seg1_end - seg1_start; - const auto v2 = seg2_end - seg2_start; - - const auto det = v1.cross(v2); - if (std::abs(det) < epsilon) { - return false; - } - - const auto v12 = seg2_end - seg1_end; - const double t = v2.cross(v12) / det; - const double s = v1.cross(v12) / det; - if (t < 0 || 1 < t || s < 0 || 1 < s) { - return false; - } - - return true; -} - -bool intersects(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2) -{ - if (equals(poly1, poly2)) { - return true; - } - - // GJK algorithm - - auto find_support_vector = []( - const alt::ConvexPolygon2d & poly1, - const alt::ConvexPolygon2d & poly2, - const alt::Vector2d & direction) { - auto find_farthest_vertex = - [](const alt::ConvexPolygon2d & poly, const alt::Vector2d & direction) { - return std::max_element( - poly.vertices().begin(), poly.vertices().end(), - [&](const auto & a, const auto & b) { return direction.dot(a) <= direction.dot(b); }); - }; - return *find_farthest_vertex(poly1, direction) - *find_farthest_vertex(poly2, -direction); - }; - - alt::Vector2d direction = {1.0, 0.0}; - auto a = find_support_vector(poly1, poly2, direction); - direction = -a; - auto b = find_support_vector(poly1, poly2, direction); - if (b.dot(direction) <= 0.0) { - return false; - } - - direction = (b - a).vector_triple(-a, b - a); - while (true) { - auto c = find_support_vector(poly1, poly2, direction); - if (c.dot(direction) <= 0.0) { - return false; - } - - auto n_ca = (b - c).vector_triple(a - c, a - c); - if (n_ca.dot(-c) > 0.0) { - b = c; - direction = n_ca; - } else { - auto n_cb = (a - c).vector_triple(b - c, b - c); - if (n_cb.dot(-c) > 0.0) { - a = c; - direction = n_cb; - } else { - break; - } - } - } - - return true; -} - -bool is_above( - const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end) -{ - return (seg_end - seg_start).cross(point - seg_start) > 0; -} - -bool is_clockwise(const alt::ConvexPolygon2d & poly) -{ - return area(poly) > 0; -} - -bool touches( - const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end) -{ - constexpr double epsilon = 1e-6; - - // if the cross product of the vectors from the start point and the end point to the point is 0 - // and the vectors opposite each other, the point is on the segment - const auto start_vec = point - seg_start; - const auto end_vec = point - seg_end; - return std::abs(start_vec.cross(end_vec)) < epsilon && start_vec.dot(end_vec) <= 0; -} - -bool touches(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) -{ - const auto & vertices = poly.vertices(); - const auto num_of_vertices = vertices.size(); - - const auto [y_min_vertex, y_max_vertex] = std::minmax_element( - vertices.begin(), vertices.end(), [](const auto & a, const auto & b) { return a.y() < b.y(); }); - if (point.y() < y_min_vertex->y() || point.y() > y_max_vertex->y()) { - return false; - } - - for (size_t i = 0; i < num_of_vertices; ++i) { - // check if the point is on each edge of the polygon - if (touches(point, vertices[i], vertices[(i + 1) % num_of_vertices])) { - return true; - } - } - - return false; -} - -bool within(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) -{ - constexpr double epsilon = 1e-6; - - const auto & vertices = poly.vertices(); - const auto num_of_vertices = vertices.size(); - int64_t winding_number = 0; - - const auto [y_min_vertex, y_max_vertex] = std::minmax_element( - vertices.begin(), vertices.end(), [](const auto & a, const auto & b) { return a.y() < b.y(); }); - if (point.y() <= y_min_vertex->y() || point.y() >= y_max_vertex->y()) { - return false; - } - - double cross; - for (size_t i = 0; i < num_of_vertices; ++i) { - const auto & p1 = vertices[i]; - const auto & p2 = vertices[(i + 1) % num_of_vertices]; - - if (p1.y() < point.y() && p2.y() > point.y()) { // upward edge - cross = (p2 - p1).cross(point - p1); - if (cross > 0) { // point is to the left of edge - winding_number++; - continue; - } - } else if (p1.y() > point.y() && p2.y() < point.y()) { // downward edge - cross = (p2 - p1).cross(point - p1); - if (cross < 0) { // point is to the left of edge - winding_number--; - continue; - } - } else { - continue; - } - - if (std::abs(cross) < epsilon) { // point is on edge - return false; - } - } - - return winding_number != 0; -} - -bool within( - const alt::ConvexPolygon2d & poly_contained, const alt::ConvexPolygon2d & poly_containing) -{ - if (equals(poly_contained, poly_containing)) { - return true; - } - - // check if all points of poly_contained are within poly_containing - for (const auto & vertex : poly_contained.vertices()) { - if (!within(vertex, poly_containing)) { - return false; - } - } - - return true; -} - } // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp b/common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp new file mode 100644 index 0000000000000..cc911f8848d03 --- /dev/null +++ b/common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp @@ -0,0 +1,1084 @@ +// Copyright 2020-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/universe_utils/geometry/alt_geometry.hpp" +#include "autoware/universe_utils/geometry/random_convex_polygon.hpp" +#include "autoware/universe_utils/system/stop_watch.hpp" + +#include +#include +#include +#include +#include + +#include + +#include +#include + +constexpr double epsilon = 1e-6; + +TEST(alt_geometry, area) +{ + using autoware::universe_utils::area; + using autoware::universe_utils::alt::ConvexPolygon2d; + using autoware::universe_utils::alt::Point2d; + + { // Clockwise + const Point2d p1 = {0.0, 0.0}; + const Point2d p2 = {0.0, 7.0}; + const Point2d p3 = {4.0, 2.0}; + const Point2d p4 = {2.0, 0.0}; + const auto result = area(ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_NEAR(result, 16.0, epsilon); + } + + { // Counter-clockwise + const Point2d p1 = {0.0, 0.0}; + const Point2d p2 = {2.0, 0.0}; + const Point2d p3 = {4.0, 2.0}; + const Point2d p4 = {0.0, 7.0}; + const auto result = area(ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_NEAR(result, -16.0, epsilon); + } +} + +TEST(alt_geometry, convexHull) +{ + using autoware::universe_utils::convex_hull; + using autoware::universe_utils::alt::Points2d; + + { + Points2d points; + points.push_back({2.0, 1.3}); + points.push_back({2.4, 1.7}); + points.push_back({2.8, 1.8}); + points.push_back({3.4, 1.2}); + points.push_back({3.7, 1.6}); + points.push_back({3.4, 2.0}); + points.push_back({4.1, 3.0}); + points.push_back({5.3, 2.6}); + points.push_back({5.4, 1.2}); + points.push_back({4.9, 0.8}); + points.push_back({2.9, 0.7}); + const auto result = convex_hull(points); + + ASSERT_EQ(result.vertices().size(), 7); + EXPECT_NEAR(result.vertices().at(0).x(), 2.0, epsilon); + EXPECT_NEAR(result.vertices().at(0).y(), 1.3, epsilon); + EXPECT_NEAR(result.vertices().at(1).x(), 2.4, epsilon); + EXPECT_NEAR(result.vertices().at(1).y(), 1.7, epsilon); + EXPECT_NEAR(result.vertices().at(2).x(), 4.1, epsilon); + EXPECT_NEAR(result.vertices().at(2).y(), 3.0, epsilon); + EXPECT_NEAR(result.vertices().at(3).x(), 5.3, epsilon); + EXPECT_NEAR(result.vertices().at(3).y(), 2.6, epsilon); + EXPECT_NEAR(result.vertices().at(4).x(), 5.4, epsilon); + EXPECT_NEAR(result.vertices().at(4).y(), 1.2, epsilon); + EXPECT_NEAR(result.vertices().at(5).x(), 4.9, epsilon); + EXPECT_NEAR(result.vertices().at(5).y(), 0.8, epsilon); + EXPECT_NEAR(result.vertices().at(6).x(), 2.9, epsilon); + EXPECT_NEAR(result.vertices().at(6).y(), 0.7, epsilon); + } +} + +TEST(alt_geometry, correct) +{ + using autoware::universe_utils::correct; + using autoware::universe_utils::alt::ConvexPolygon2d; + using autoware::universe_utils::alt::Points2d; + + { // Correctly oriented + Points2d vertices; + vertices.push_back({1.0, 1.0}); + vertices.push_back({1.0, -1.0}); + vertices.push_back({-1.0, -1.0}); + vertices.push_back({-1.0, 1.0}); + ConvexPolygon2d poly(vertices); + correct(poly); + + ASSERT_EQ(poly.vertices().size(), 4); + EXPECT_NEAR(poly.vertices().at(0).x(), 1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(0).y(), 1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(1).x(), 1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(1).y(), -1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(2).x(), -1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(2).y(), -1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(3).x(), -1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(3).y(), 1.0, epsilon); + } + + { // Wrongly oriented + Points2d vertices; + vertices.push_back({1.0, 1.0}); + vertices.push_back({-1.0, 1.0}); + vertices.push_back({1.0, -1.0}); + vertices.push_back({-1.0, -1.0}); + ConvexPolygon2d poly(vertices); + correct(poly); + + ASSERT_EQ(poly.vertices().size(), 4); + EXPECT_NEAR(poly.vertices().at(0).x(), 1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(0).y(), 1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(1).x(), 1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(1).y(), -1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(2).x(), -1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(2).y(), -1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(3).x(), -1.0, epsilon); + EXPECT_NEAR(poly.vertices().at(3).y(), 1.0, epsilon); + } +} + +TEST(alt_geometry, coveredBy) +{ + using autoware::universe_utils::covered_by; + using autoware::universe_utils::alt::ConvexPolygon2d; + using autoware::universe_utils::alt::Point2d; + + { // The point is within the polygon + const Point2d point = {0.0, 0.0}; + const Point2d p1 = {1.0, 1.0}; + const Point2d p2 = {1.0, -1.0}; + const Point2d p3 = {-1.0, -1.0}; + const Point2d p4 = {-1.0, 1.0}; + const auto result = covered_by(point, ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_TRUE(result); + } + + { // The point is outside the polygon + const Point2d point = {0.0, 0.0}; + const Point2d p1 = {2.0, 2.0}; + const Point2d p2 = {2.0, 1.0}; + const Point2d p3 = {1.0, 1.0}; + const Point2d p4 = {1.0, 2.0}; + const auto result = covered_by(point, ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_FALSE(result); + } + + { // The point is on the edge of the polygon + const Point2d point = {0.0, 0.0}; + const Point2d p1 = {2.0, 1.0}; + const Point2d p2 = {2.0, -1.0}; + const Point2d p3 = {0.0, -1.0}; + const Point2d p4 = {0.0, 1.0}; + const auto result = covered_by(point, ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_TRUE(result); + } +} + +TEST(alt_geometry, disjoint) +{ + using autoware::universe_utils::disjoint; + using autoware::universe_utils::alt::ConvexPolygon2d; + using autoware::universe_utils::alt::Point2d; + + { // Disjoint + const Point2d p1 = {0.0, 2.0}; + const Point2d p2 = {-2.0, 0.0}; + const Point2d p3 = {-4.0, 2.0}; + const Point2d p4 = {-2.0, 4.0}; + const Point2d p5 = {2.0, 2.0}; + const Point2d p6 = {4.0, 4.0}; + const Point2d p7 = {6.0, 2.0}; + const Point2d p8 = {4.0, 0.0}; + const auto result = + disjoint(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); + + EXPECT_TRUE(result); + } + + { // Not disjoint (two polygons share a vertex) + const Point2d p1 = {0.0, 2.0}; + const Point2d p2 = {-2.0, 0.0}; + const Point2d p3 = {-4.0, 2.0}; + const Point2d p4 = {-2.0, 4.0}; + const Point2d p5 = {0.0, 2.0}; + const Point2d p6 = {2.0, 4.0}; + const Point2d p7 = {4.0, 2.0}; + const Point2d p8 = {2.0, 0.0}; + const auto result = + disjoint(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); + + EXPECT_FALSE(result); + } +} + +TEST(alt_geometry, distance) +{ + using autoware::universe_utils::distance; + using autoware::universe_utils::alt::ConvexPolygon2d; + using autoware::universe_utils::alt::Point2d; + + { // Normal setting + const Point2d p = {0.0, 1.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = distance(p, p1, p2); + + EXPECT_NEAR(result, 1.0, epsilon); + } + + { + // The point is out of range of the segment to the start point side + const Point2d p = {-2.0, 1.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = distance(p, p1, p2); + + EXPECT_NEAR(result, std::sqrt(2), epsilon); + } + + { + // The point is out of range of the segment to the end point side + const Point2d p = {2.0, 1.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = distance(p, p1, p2); + + EXPECT_NEAR(result, std::sqrt(2), epsilon); + } + + { + // The point is on the segment + const Point2d p = {0.0, 0.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = distance(p, p1, p2); + + EXPECT_NEAR(result, 0.0, epsilon); + } + + { + // The point is the start point of the segment + const Point2d p = {-1.0, 0.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = distance(p, p1, p2); + + EXPECT_NEAR(result, 0.0, epsilon); + } + + { + // The point is the end point of the segment + const Point2d p = {1.0, 0.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = distance(p, p1, p2); + + EXPECT_NEAR(result, 0.0, epsilon); + } + + { // The segment is a point + const Point2d p = {0.0, 0.0}; + const Point2d p1 = {1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = distance(p, p1, p2); + + EXPECT_NEAR(result, 1.0, epsilon); + } + + { // The point is outside the polygon + const Point2d p = {0.0, 0.0}; + const Point2d p1 = {3.0, 1.0}; + const Point2d p2 = {3.0, -1.0}; + const Point2d p3 = {1.0, -1.0}; + const Point2d p4 = {1.0, 1.0}; + const auto result = distance(p, ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_NEAR(result, 1.0, epsilon); + } + + { // The point is within the polygon + const Point2d p = {0.0, 0.0}; + const Point2d p1 = {2.0, 1.0}; + const Point2d p2 = {2.0, -1.0}; + const Point2d p3 = {-1.0, -1.0}; + const Point2d p4 = {-1.0, 1.0}; + const auto result = distance(p, ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_NEAR(result, 0.0, epsilon); + } +} + +TEST(alt_geometry, intersects) +{ + using autoware::universe_utils::intersects; + using autoware::universe_utils::alt::ConvexPolygon2d; + using autoware::universe_utils::alt::Point2d; + + { // Normally crossing + const Point2d p1 = {0.0, -1.0}; + const Point2d p2 = {0.0, 1.0}; + const Point2d p3 = {-1.0, 0.0}; + const Point2d p4 = {1.0, 0.0}; + const auto result = intersects(p1, p2, p3, p4); + + EXPECT_TRUE(result); + } + + { // No crossing + const Point2d p1 = {0.0, -1.0}; + const Point2d p2 = {0.0, 1.0}; + const Point2d p3 = {1.0, 0.0}; + const Point2d p4 = {3.0, 0.0}; + const auto result = intersects(p1, p2, p3, p4); + + EXPECT_FALSE(result); + } + + { // One segment is the point on the other's segment + const Point2d p1 = {0.0, -1.0}; + const Point2d p2 = {0.0, 1.0}; + const Point2d p3 = {0.0, 0.0}; + const Point2d p4 = {0.0, 0.0}; + const auto result = intersects(p1, p2, p3, p4); + + EXPECT_FALSE(result); + } + + { // One segment is the point not on the other's segment + const Point2d p1 = {0.0, -1.0}; + const Point2d p2 = {0.0, 1.0}; + const Point2d p3 = {1.0, 0.0}; + const Point2d p4 = {1.0, 0.0}; + const auto result = intersects(p1, p2, p3, p4); + + EXPECT_FALSE(result); + } + + { // Both segments are the points which are the same position + const Point2d p1 = {0.0, 0.0}; + const Point2d p2 = {0.0, 0.0}; + const Point2d p3 = {0.0, 0.0}; + const Point2d p4 = {0.0, 0.0}; + const auto result = intersects(p1, p2, p3, p4); + + EXPECT_FALSE(result); + } + + { // Both segments are the points which are different position + const Point2d p1 = {0.0, 1.0}; + const Point2d p2 = {0.0, 1.0}; + const Point2d p3 = {1.0, 0.0}; + const Point2d p4 = {1.0, 0.0}; + const auto result = intersects(p1, p2, p3, p4); + + EXPECT_FALSE(result); + } + + { // Segments are the same + const Point2d p1 = {0.0, -1.0}; + const Point2d p2 = {0.0, 1.0}; + const Point2d p3 = {0.0, -1.0}; + const Point2d p4 = {0.0, 1.0}; + const auto result = intersects(p1, p2, p3, p4); + + EXPECT_FALSE(result); + } + + { // One's edge is on the other's segment + const Point2d p1 = {0.0, -1.0}; + const Point2d p2 = {0.0, 1.0}; + const Point2d p3 = {0.0, 0.0}; + const Point2d p4 = {1.0, 0.0}; + const auto result = intersects(p1, p2, p3, p4); + + EXPECT_TRUE(result); + } + + { // One's edge is the same as the other's edge. + const Point2d p1 = {0.0, -1.0}; + const Point2d p2 = {0.0, 1.0}; + const Point2d p3 = {0.0, -1.0}; + const Point2d p4 = {2.0, -1.0}; + const auto result = intersects(p1, p2, p3, p4); + + EXPECT_TRUE(result); + } + + { // One polygon intersects the other + const Point2d p1 = {1.0, 1.0}; + const Point2d p2 = {1.0, -1.0}; + const Point2d p3 = {-1.0, -1.0}; + const Point2d p4 = {-1.0, 1.0}; + const Point2d p5 = {2.0, 2.0}; + const Point2d p6 = {2.0, 0.0}; + const Point2d p7 = {0.0, 0.0}; + const Point2d p8 = {0.0, 2.0}; + const auto result = + intersects(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); + + EXPECT_TRUE(result); + } + + { // Two polygons do not intersect each other + const Point2d p1 = {1.0, 1.0}; + const Point2d p2 = {1.0, -1.0}; + const Point2d p3 = {-1.0, -1.0}; + const Point2d p4 = {-1.0, 1.0}; + const Point2d p5 = {3.0, 3.0}; + const Point2d p6 = {3.0, 2.0}; + const Point2d p7 = {2.0, 2.0}; + const Point2d p8 = {2.0, 3.0}; + const auto result = + intersects(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); + + EXPECT_FALSE(result); + } + + { // Two polygons share a vertex + const Point2d p1 = {1.0, 1.0}; + const Point2d p2 = {1.0, -1.0}; + const Point2d p3 = {-1.0, -1.0}; + const Point2d p4 = {-1.0, 1.0}; + const Point2d p5 = {2.0, 2.0}; + const Point2d p6 = {2.0, 1.0}; + const Point2d p7 = {1.0, 1.0}; + const Point2d p8 = {1.0, 2.0}; + const auto result = + intersects(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); + + EXPECT_FALSE(result); + } +} + +TEST(alt_geometry, isAbove) +{ + using autoware::universe_utils::is_above; + using autoware::universe_utils::alt::Point2d; + + { // The point is above the line + const Point2d point = {0.0, 1.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = is_above(point, p1, p2); + + EXPECT_TRUE(result); + } + + { // The point is below the line + const Point2d point = {0.0, -1.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = is_above(point, p1, p2); + + EXPECT_FALSE(result); + } + + { // The point is on the line + const Point2d point = {0.0, 0.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = is_above(point, p1, p2); + + EXPECT_FALSE(result); + } +} + +TEST(alt_geometry, isClockwise) +{ + using autoware::universe_utils::is_clockwise; + using autoware::universe_utils::alt::ConvexPolygon2d; + using autoware::universe_utils::alt::Point2d; + + { // Clockwise + const Point2d p1 = {0.0, 0.0}; + const Point2d p2 = {0.0, 7.0}; + const Point2d p3 = {4.0, 2.0}; + const Point2d p4 = {2.0, 0.0}; + const auto result = is_clockwise(ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_TRUE(result); + } + + { // Counter-clockwise + const Point2d p1 = {0.0, 0.0}; + const Point2d p2 = {2.0, 0.0}; + const Point2d p3 = {4.0, 2.0}; + const Point2d p4 = {0.0, 7.0}; + const auto result = is_clockwise(ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_FALSE(result); + } +} + +TEST(alt_geometry, touches) +{ + using autoware::universe_utils::touches; + using autoware::universe_utils::alt::ConvexPolygon2d; + using autoware::universe_utils::alt::Point2d; + + { + // The point is on the segment + const Point2d p = {0.0, 0.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = touches(p, p1, p2); + + EXPECT_TRUE(result); + } + + { + // The point is the start point of the segment + const Point2d p = {-1.0, 0.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = touches(p, p1, p2); + + EXPECT_TRUE(result); + } + + { + // The point is the end point of the segment + const Point2d p = {1.0, 0.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = touches(p, p1, p2); + + EXPECT_TRUE(result); + } + + { // The point is not on the segment + const Point2d p = {0.0, 1.0}; + const Point2d p1 = {-1.0, 0.0}; + const Point2d p2 = {1.0, 0.0}; + const auto result = touches(p, p1, p2); + + EXPECT_FALSE(result); + } + + { // The point is on the edge of the polygon + const Point2d point = {0.0, 0.0}; + const Point2d p1 = {2.0, 1.0}; + const Point2d p2 = {2.0, -1.0}; + const Point2d p3 = {0.0, -1.0}; + const Point2d p4 = {0.0, 1.0}; + const auto result = touches(point, ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_TRUE(result); + } + + { // The point is outside the polygon + const Point2d point = {0.0, 0.0}; + const Point2d p1 = {2.0, 2.0}; + const Point2d p2 = {2.0, 1.0}; + const Point2d p3 = {1.0, 1.0}; + const Point2d p4 = {1.0, 2.0}; + const auto result = touches(point, ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_FALSE(result); + } +} + +TEST(alt_geometry, within) +{ + using autoware::universe_utils::within; + using autoware::universe_utils::alt::ConvexPolygon2d; + using autoware::universe_utils::alt::Point2d; + + { // The point is within the polygon + const Point2d point = {0.0, 0.0}; + const Point2d p1 = {1.0, 1.0}; + const Point2d p2 = {1.0, -1.0}; + const Point2d p3 = {-1.0, -1.0}; + const Point2d p4 = {-1.0, 1.0}; + const auto result = within(point, ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_TRUE(result); + } + + { // The point is outside the polygon + const Point2d point = {0.0, 0.0}; + const Point2d p1 = {2.0, 2.0}; + const Point2d p2 = {2.0, 1.0}; + const Point2d p3 = {1.0, 1.0}; + const Point2d p4 = {1.0, 2.0}; + const auto result = within(point, ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_FALSE(result); + } + + { // The point is on the edge of the polygon + const Point2d point = {0.0, 0.0}; + const Point2d p1 = {2.0, 1.0}; + const Point2d p2 = {2.0, -1.0}; + const Point2d p3 = {0.0, -1.0}; + const Point2d p4 = {0.0, 1.0}; + const auto result = within(point, ConvexPolygon2d({p1, p2, p3, p4})); + + EXPECT_FALSE(result); + } + + { // One polygon is within the other + const Point2d p1 = {1.0, 1.0}; + const Point2d p2 = {1.0, -1.0}; + const Point2d p3 = {-1.0, -1.0}; + const Point2d p4 = {-1.0, 1.0}; + const Point2d p5 = {2.0, 2.0}; + const Point2d p6 = {2.0, -2.0}; + const Point2d p7 = {-2.0, -2.0}; + const Point2d p8 = {-2.0, 2.0}; + const auto result = + within(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); + + EXPECT_TRUE(result); + } + + { // One polygon is outside the other + const Point2d p1 = {1.0, 1.0}; + const Point2d p2 = {1.0, -1.0}; + const Point2d p3 = {-1.0, -1.0}; + const Point2d p4 = {-1.0, 1.0}; + const Point2d p5 = {3.0, 3.0}; + const Point2d p6 = {3.0, 2.0}; + const Point2d p7 = {2.0, 2.0}; + const Point2d p8 = {2.0, 3.0}; + const auto result = + within(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); + + EXPECT_FALSE(result); + } + + { // Both polygons are the same + const Point2d p1 = {1.0, 1.0}; + const Point2d p2 = {1.0, -1.0}; + const Point2d p3 = {-1.0, -1.0}; + const Point2d p4 = {-1.0, 1.0}; + const Point2d p5 = {1.0, 1.0}; + const Point2d p6 = {1.0, -1.0}; + const Point2d p7 = {-1.0, -1.0}; + const Point2d p8 = {-1.0, 1.0}; + const auto result = + within(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); + + EXPECT_TRUE(result); + } +} + +TEST(alt_geometry, areaRand) +{ + std::vector polygons; + constexpr auto polygons_nb = 500; + constexpr auto max_vertices = 10; + constexpr auto max_values = 1000; + + autoware::universe_utils::StopWatch sw; + for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { + double ground_truth_area_ns = 0.0; + double alt_area_ns = 0.0; + + polygons.clear(); + for (auto i = 0; i < polygons_nb; ++i) { + polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); + } + for (auto i = 0UL; i < polygons.size(); ++i) { + sw.tic(); + const auto ground_truth = boost::geometry::area(polygons[i]); + ground_truth_area_ns += sw.toc(); + + const auto alt_poly = autoware::universe_utils::alt::from_boost(polygons[i]); + sw.tic(); + const auto alt = autoware::universe_utils::area(alt_poly); + alt_area_ns += sw.toc(); + + if (std::abs(alt - ground_truth) > epsilon) { + std::cout << "Alt failed for the polygon: "; + std::cout << boost::geometry::wkt(polygons[i]) << std::endl; + } + EXPECT_NEAR(ground_truth, alt, epsilon); + } + std::printf("polygons_nb = %d, vertices = %ld\n", polygons_nb, vertices); + std::printf( + "\tArea:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", ground_truth_area_ns / 1e6, + alt_area_ns / 1e6); + } +} + +TEST(alt_geometry, convexHullRand) +{ + std::vector polygons; + constexpr auto polygons_nb = 500; + constexpr auto max_vertices = 10; + constexpr auto max_values = 1000; + + autoware::universe_utils::StopWatch sw; + for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { + double ground_truth_hull_ns = 0.0; + double alt_hull_ns = 0.0; + + polygons.clear(); + for (auto i = 0; i < polygons_nb; ++i) { + polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); + } + for (auto i = 0UL; i < polygons.size(); ++i) { + autoware::universe_utils::MultiPoint2d outer; + for (const auto & point : polygons[i].outer()) { + outer.push_back(point); + } + autoware::universe_utils::Polygon2d ground_truth; + sw.tic(); + boost::geometry::convex_hull(outer, ground_truth); + ground_truth_hull_ns += sw.toc(); + + const auto vertices = autoware::universe_utils::alt::from_boost(polygons[i]).vertices(); + sw.tic(); + const auto alt = autoware::universe_utils::convex_hull(vertices); + alt_hull_ns += sw.toc(); + + if (ground_truth.outer().size() - 1 != alt.vertices().size()) { + std::cout << "Alt failed for the polygon: "; + std::cout << boost::geometry::wkt(polygons[i]) << std::endl; + } + ASSERT_EQ( + ground_truth.outer().size() - 1, + alt.vertices().size()); // alt::ConvexPolygon2d does not have closing point + for (size_t i = 0; i < alt.vertices().size(); ++i) { + EXPECT_NEAR(ground_truth.outer().at(i).x(), alt.vertices().at(i).x(), epsilon); + EXPECT_NEAR(ground_truth.outer().at(i).y(), alt.vertices().at(i).y(), epsilon); + } + } + std::printf("polygons_nb = %d, vertices = %ld\n", polygons_nb, vertices); + std::printf( + "\tConvex Hull:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_hull_ns / 1e6, alt_hull_ns / 1e6); + } +} + +TEST(alt_geometry, coveredByRand) +{ + std::vector polygons; + constexpr auto polygons_nb = 500; + constexpr auto max_vertices = 10; + constexpr auto max_values = 1000; + + autoware::universe_utils::StopWatch sw; + for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { + double ground_truth_covered_ns = 0.0; + double ground_truth_not_covered_ns = 0.0; + double alt_covered_ns = 0.0; + double alt_not_covered_ns = 0.0; + int covered_count = 0; + + polygons.clear(); + for (auto i = 0; i < polygons_nb; ++i) { + polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); + } + for (auto i = 0UL; i < polygons.size(); ++i) { + for (const auto & point : polygons[i].outer()) { + for (auto j = 0UL; j < polygons.size(); ++j) { + sw.tic(); + const auto ground_truth = boost::geometry::covered_by(point, polygons[j]); + if (ground_truth) { + ++covered_count; + ground_truth_covered_ns += sw.toc(); + } else { + ground_truth_not_covered_ns += sw.toc(); + } + + const auto alt_point = autoware::universe_utils::alt::from_boost(point); + const auto alt_poly = autoware::universe_utils::alt::from_boost(polygons[j]); + sw.tic(); + const auto alt = autoware::universe_utils::covered_by(alt_point, alt_poly); + if (alt) { + alt_covered_ns += sw.toc(); + } else { + alt_not_covered_ns += sw.toc(); + } + + if (ground_truth != alt) { + std::cout << "Alt failed for the point and polygon: "; + std::cout << boost::geometry::wkt(point) << boost::geometry::wkt(polygons[j]) + << std::endl; + } + EXPECT_EQ(ground_truth, alt); + } + } + } + std::printf( + "polygons_nb = %d, vertices = %ld, %d / %ld covered pairs\n", polygons_nb, vertices, + covered_count, polygons_nb * vertices * polygons_nb); + std::printf( + "\tCovered:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_covered_ns / 1e6, alt_covered_ns / 1e6); + std::printf( + "\tNot covered:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_not_covered_ns / 1e6, alt_not_covered_ns / 1e6); + std::printf( + "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + (ground_truth_not_covered_ns + ground_truth_covered_ns) / 1e6, + (alt_not_covered_ns + alt_covered_ns) / 1e6); + } +} + +TEST(alt_geometry, disjointRand) +{ + std::vector polygons; + constexpr auto polygons_nb = 500; + constexpr auto max_vertices = 10; + constexpr auto max_values = 1000; + + autoware::universe_utils::StopWatch sw; + for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { + double ground_truth_disjoint_ns = 0.0; + double ground_truth_not_disjoint_ns = 0.0; + double alt_disjoint_ns = 0.0; + double alt_not_disjoint_ns = 0.0; + int disjoint_count = 0; + + polygons.clear(); + for (auto i = 0; i < polygons_nb; ++i) { + polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); + } + for (auto i = 0UL; i < polygons.size(); ++i) { + for (auto j = 0UL; j < polygons.size(); ++j) { + sw.tic(); + const auto ground_truth = boost::geometry::disjoint(polygons[i], polygons[j]); + if (ground_truth) { + ++disjoint_count; + ground_truth_disjoint_ns += sw.toc(); + } else { + ground_truth_not_disjoint_ns += sw.toc(); + } + + const auto alt_poly1 = autoware::universe_utils::alt::from_boost(polygons[i]); + const auto alt_poly2 = autoware::universe_utils::alt::from_boost(polygons[j]); + sw.tic(); + const auto alt = autoware::universe_utils::disjoint(alt_poly1, alt_poly2); + if (alt) { + alt_disjoint_ns += sw.toc(); + } else { + alt_not_disjoint_ns += sw.toc(); + } + + if (ground_truth != alt) { + std::cout << "Failed for the 2 polygons: "; + std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j]) + << std::endl; + } + EXPECT_EQ(ground_truth, alt); + } + } + std::printf( + "polygons_nb = %d, vertices = %ld, %d / %d disjoint pairs\n", polygons_nb, vertices, + disjoint_count, polygons_nb * polygons_nb); + std::printf( + "\tDisjoint:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_disjoint_ns / 1e6, alt_disjoint_ns / 1e6); + std::printf( + "\tNot disjoint:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_not_disjoint_ns / 1e6, alt_not_disjoint_ns / 1e6); + std::printf( + "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + (ground_truth_not_disjoint_ns + ground_truth_disjoint_ns) / 1e6, + (alt_not_disjoint_ns + alt_disjoint_ns) / 1e6); + } +} + +TEST(alt_geometry, intersectsRand) +{ + std::vector polygons; + constexpr auto polygons_nb = 500; + constexpr auto max_vertices = 10; + constexpr auto max_values = 1000; + + autoware::universe_utils::StopWatch sw; + for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { + double ground_truth_intersect_ns = 0.0; + double ground_truth_no_intersect_ns = 0.0; + double alt_intersect_ns = 0.0; + double alt_no_intersect_ns = 0.0; + int intersect_count = 0; + + polygons.clear(); + for (auto i = 0; i < polygons_nb; ++i) { + polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); + } + for (auto i = 0UL; i < polygons.size(); ++i) { + for (auto j = 0UL; j < polygons.size(); ++j) { + sw.tic(); + const auto ground_truth = boost::geometry::intersects(polygons[i], polygons[j]); + if (ground_truth) { + ++intersect_count; + ground_truth_intersect_ns += sw.toc(); + } else { + ground_truth_no_intersect_ns += sw.toc(); + } + + const auto alt_poly1 = autoware::universe_utils::alt::from_boost(polygons[i]); + const auto alt_poly2 = autoware::universe_utils::alt::from_boost(polygons[j]); + sw.tic(); + const auto alt = autoware::universe_utils::intersects(alt_poly1, alt_poly2); + if (alt) { + alt_intersect_ns += sw.toc(); + } else { + alt_no_intersect_ns += sw.toc(); + } + + if (ground_truth != alt) { + std::cout << "Failed for the 2 polygons: "; + std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j]) + << std::endl; + } + EXPECT_EQ(ground_truth, alt); + } + } + std::printf( + "polygons_nb = %d, vertices = %ld, %d / %d pairs with intersects\n", polygons_nb, vertices, + intersect_count, polygons_nb * polygons_nb); + std::printf( + "\tIntersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_intersect_ns / 1e6, alt_intersect_ns / 1e6); + std::printf( + "\tNo intersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_no_intersect_ns / 1e6, alt_no_intersect_ns / 1e6); + std::printf( + "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + (ground_truth_no_intersect_ns + ground_truth_intersect_ns) / 1e6, + (alt_no_intersect_ns + alt_intersect_ns) / 1e6); + } +} + +TEST(alt_geometry, touchesRand) +{ + std::vector polygons; + constexpr auto polygons_nb = 500; + constexpr auto max_vertices = 10; + constexpr auto max_values = 1000; + + autoware::universe_utils::StopWatch sw; + for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { + double ground_truth_touching_ns = 0.0; + double ground_truth_not_touching_ns = 0.0; + double alt_touching_ns = 0.0; + double alt_not_touching_ns = 0.0; + int touching_count = 0; + + polygons.clear(); + for (auto i = 0; i < polygons_nb; ++i) { + polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); + } + for (auto i = 0UL; i < polygons.size(); ++i) { + for (const auto & point : polygons[i].outer()) { + for (auto j = 0UL; j < polygons.size(); ++j) { + sw.tic(); + const auto ground_truth = boost::geometry::touches(point, polygons[j]); + if (ground_truth) { + ++touching_count; + ground_truth_touching_ns += sw.toc(); + } else { + ground_truth_not_touching_ns += sw.toc(); + } + + const auto alt_point = autoware::universe_utils::alt::from_boost(point); + const auto alt_poly = autoware::universe_utils::alt::from_boost(polygons[j]); + sw.tic(); + const auto alt = autoware::universe_utils::touches(alt_point, alt_poly); + if (alt) { + alt_touching_ns += sw.toc(); + } else { + alt_not_touching_ns += sw.toc(); + } + + if (ground_truth != alt) { + std::cout << "Alt failed for the point and polygon: "; + std::cout << boost::geometry::wkt(point) << boost::geometry::wkt(polygons[j]) + << std::endl; + } + EXPECT_EQ(ground_truth, alt); + } + } + } + std::printf( + "polygons_nb = %d, vertices = %ld, %d / %ld touching pairs\n", polygons_nb, vertices, + touching_count, polygons_nb * vertices * polygons_nb); + std::printf( + "\tTouching:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_touching_ns / 1e6, alt_touching_ns / 1e6); + std::printf( + "\tNot touching:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_not_touching_ns / 1e6, alt_not_touching_ns / 1e6); + std::printf( + "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + (ground_truth_not_touching_ns + ground_truth_touching_ns) / 1e6, + (alt_not_touching_ns + alt_touching_ns) / 1e6); + } +} + +TEST(alt_geometry, withinPolygonRand) +{ + std::vector polygons; + constexpr auto polygons_nb = 500; + constexpr auto max_vertices = 10; + constexpr auto max_values = 1000; + + autoware::universe_utils::StopWatch sw; + for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { + double ground_truth_within_ns = 0.0; + double ground_truth_not_within_ns = 0.0; + double alt_within_ns = 0.0; + double alt_not_within_ns = 0.0; + int within_count = 0; + + polygons.clear(); + for (auto i = 0; i < polygons_nb; ++i) { + polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); + } + for (auto i = 0UL; i < polygons.size(); ++i) { + for (auto j = 0UL; j < polygons.size(); ++j) { + sw.tic(); + const auto ground_truth = boost::geometry::within(polygons[i], polygons[j]); + if (ground_truth) { + ++within_count; + ground_truth_within_ns += sw.toc(); + } else { + ground_truth_not_within_ns += sw.toc(); + } + + const auto alt_poly1 = autoware::universe_utils::alt::from_boost(polygons[i]); + const auto alt_poly2 = autoware::universe_utils::alt::from_boost(polygons[j]); + sw.tic(); + const auto alt = autoware::universe_utils::within(alt_poly1, alt_poly2); + if (alt) { + alt_within_ns += sw.toc(); + } else { + alt_not_within_ns += sw.toc(); + } + + if (ground_truth != alt) { + std::cout << "Alt failed for the 2 polygons: "; + std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j]) + << std::endl; + } + EXPECT_EQ(ground_truth, alt); + } + } + std::printf( + "polygons_nb = %d, vertices = %ld, %d / %d pairs either of which is within the other\n", + polygons_nb, vertices, within_count, polygons_nb * polygons_nb); + std::printf( + "\tWithin:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_within_ns / 1e6, alt_within_ns / 1e6); + std::printf( + "\tNot within:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + ground_truth_not_within_ns / 1e6, alt_not_within_ns / 1e6); + std::printf( + "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", + (ground_truth_not_within_ns + ground_truth_within_ns) / 1e6, + (alt_not_within_ns + alt_within_ns) / 1e6); + } +} diff --git a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp index 55d70307f1314..6cce5d974664c 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp @@ -21,11 +21,8 @@ #include -#include #include -#include #include -#include #include @@ -2021,1057 +2018,3 @@ TEST(geometry, intersectPolygonRand) (sat_no_intersect_ns + sat_intersect_ns) / 1e6); } } - -TEST(geometry, area) -{ - using autoware::universe_utils::area; - using autoware::universe_utils::alt::ConvexPolygon2d; - using autoware::universe_utils::alt::Point2d; - - { // Clockwise - const Point2d p1 = {0.0, 0.0}; - const Point2d p2 = {0.0, 7.0}; - const Point2d p3 = {4.0, 2.0}; - const Point2d p4 = {2.0, 0.0}; - const auto result = area(ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_NEAR(result, 16.0, epsilon); - } - - { // Counter-clockwise - const Point2d p1 = {0.0, 0.0}; - const Point2d p2 = {2.0, 0.0}; - const Point2d p3 = {4.0, 2.0}; - const Point2d p4 = {0.0, 7.0}; - const auto result = area(ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_NEAR(result, -16.0, epsilon); - } -} - -TEST(geometry, convexHull) -{ - using autoware::universe_utils::convex_hull; - using autoware::universe_utils::alt::Points2d; - - { - Points2d points; - points.push_back({2.0, 1.3}); - points.push_back({2.4, 1.7}); - points.push_back({2.8, 1.8}); - points.push_back({3.4, 1.2}); - points.push_back({3.7, 1.6}); - points.push_back({3.4, 2.0}); - points.push_back({4.1, 3.0}); - points.push_back({5.3, 2.6}); - points.push_back({5.4, 1.2}); - points.push_back({4.9, 0.8}); - points.push_back({2.9, 0.7}); - const auto result = convex_hull(points); - - ASSERT_EQ(result.vertices().size(), 7); - EXPECT_NEAR(result.vertices().at(0).x(), 2.0, epsilon); - EXPECT_NEAR(result.vertices().at(0).y(), 1.3, epsilon); - EXPECT_NEAR(result.vertices().at(1).x(), 2.4, epsilon); - EXPECT_NEAR(result.vertices().at(1).y(), 1.7, epsilon); - EXPECT_NEAR(result.vertices().at(2).x(), 4.1, epsilon); - EXPECT_NEAR(result.vertices().at(2).y(), 3.0, epsilon); - EXPECT_NEAR(result.vertices().at(3).x(), 5.3, epsilon); - EXPECT_NEAR(result.vertices().at(3).y(), 2.6, epsilon); - EXPECT_NEAR(result.vertices().at(4).x(), 5.4, epsilon); - EXPECT_NEAR(result.vertices().at(4).y(), 1.2, epsilon); - EXPECT_NEAR(result.vertices().at(5).x(), 4.9, epsilon); - EXPECT_NEAR(result.vertices().at(5).y(), 0.8, epsilon); - EXPECT_NEAR(result.vertices().at(6).x(), 2.9, epsilon); - EXPECT_NEAR(result.vertices().at(6).y(), 0.7, epsilon); - } -} - -TEST(geometry, correct) -{ - using autoware::universe_utils::correct; - using autoware::universe_utils::alt::ConvexPolygon2d; - using autoware::universe_utils::alt::Points2d; - - { // Correctly oriented - Points2d vertices; - vertices.push_back({1.0, 1.0}); - vertices.push_back({1.0, -1.0}); - vertices.push_back({-1.0, -1.0}); - vertices.push_back({-1.0, 1.0}); - ConvexPolygon2d poly(vertices); - correct(poly); - - ASSERT_EQ(poly.vertices().size(), 4); - EXPECT_NEAR(poly.vertices().at(0).x(), 1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(0).y(), 1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(1).x(), 1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(1).y(), -1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(2).x(), -1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(2).y(), -1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(3).x(), -1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(3).y(), 1.0, epsilon); - } - - { // Wrongly oriented - Points2d vertices; - vertices.push_back({1.0, 1.0}); - vertices.push_back({-1.0, 1.0}); - vertices.push_back({1.0, -1.0}); - vertices.push_back({-1.0, -1.0}); - ConvexPolygon2d poly(vertices); - correct(poly); - - ASSERT_EQ(poly.vertices().size(), 4); - EXPECT_NEAR(poly.vertices().at(0).x(), 1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(0).y(), 1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(1).x(), 1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(1).y(), -1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(2).x(), -1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(2).y(), -1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(3).x(), -1.0, epsilon); - EXPECT_NEAR(poly.vertices().at(3).y(), 1.0, epsilon); - } -} - -TEST(geometry, coveredBy) -{ - using autoware::universe_utils::covered_by; - using autoware::universe_utils::alt::ConvexPolygon2d; - using autoware::universe_utils::alt::Point2d; - - { // The point is within the polygon - const Point2d point = {0.0, 0.0}; - const Point2d p1 = {1.0, 1.0}; - const Point2d p2 = {1.0, -1.0}; - const Point2d p3 = {-1.0, -1.0}; - const Point2d p4 = {-1.0, 1.0}; - const auto result = covered_by(point, ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_TRUE(result); - } - - { // The point is outside the polygon - const Point2d point = {0.0, 0.0}; - const Point2d p1 = {2.0, 2.0}; - const Point2d p2 = {2.0, 1.0}; - const Point2d p3 = {1.0, 1.0}; - const Point2d p4 = {1.0, 2.0}; - const auto result = covered_by(point, ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_FALSE(result); - } - - { // The point is on the edge of the polygon - const Point2d point = {0.0, 0.0}; - const Point2d p1 = {2.0, 1.0}; - const Point2d p2 = {2.0, -1.0}; - const Point2d p3 = {0.0, -1.0}; - const Point2d p4 = {0.0, 1.0}; - const auto result = covered_by(point, ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_TRUE(result); - } -} - -TEST(geometry, disjoint) -{ - using autoware::universe_utils::disjoint; - using autoware::universe_utils::alt::ConvexPolygon2d; - using autoware::universe_utils::alt::Point2d; - - { // Disjoint - const Point2d p1 = {0.0, 2.0}; - const Point2d p2 = {-2.0, 0.0}; - const Point2d p3 = {-4.0, 2.0}; - const Point2d p4 = {-2.0, 4.0}; - const Point2d p5 = {2.0, 2.0}; - const Point2d p6 = {4.0, 4.0}; - const Point2d p7 = {6.0, 2.0}; - const Point2d p8 = {4.0, 0.0}; - const auto result = - disjoint(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); - - EXPECT_TRUE(result); - } - - { // Not disjoint (two polygons share a vertex) - const Point2d p1 = {0.0, 2.0}; - const Point2d p2 = {-2.0, 0.0}; - const Point2d p3 = {-4.0, 2.0}; - const Point2d p4 = {-2.0, 4.0}; - const Point2d p5 = {0.0, 2.0}; - const Point2d p6 = {2.0, 4.0}; - const Point2d p7 = {4.0, 2.0}; - const Point2d p8 = {2.0, 0.0}; - const auto result = - disjoint(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); - - EXPECT_FALSE(result); - } -} - -TEST(geometry, distance) -{ - using autoware::universe_utils::distance; - using autoware::universe_utils::alt::ConvexPolygon2d; - using autoware::universe_utils::alt::Point2d; - - { // Normal setting - const Point2d p = {0.0, 1.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = distance(p, p1, p2); - - EXPECT_NEAR(result, 1.0, epsilon); - } - - { - // The point is out of range of the segment to the start point side - const Point2d p = {-2.0, 1.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = distance(p, p1, p2); - - EXPECT_NEAR(result, std::sqrt(2), epsilon); - } - - { - // The point is out of range of the segment to the end point side - const Point2d p = {2.0, 1.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = distance(p, p1, p2); - - EXPECT_NEAR(result, std::sqrt(2), epsilon); - } - - { - // The point is on the segment - const Point2d p = {0.0, 0.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = distance(p, p1, p2); - - EXPECT_NEAR(result, 0.0, epsilon); - } - - { - // The point is the start point of the segment - const Point2d p = {-1.0, 0.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = distance(p, p1, p2); - - EXPECT_NEAR(result, 0.0, epsilon); - } - - { - // The point is the end point of the segment - const Point2d p = {1.0, 0.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = distance(p, p1, p2); - - EXPECT_NEAR(result, 0.0, epsilon); - } - - { // The segment is a point - const Point2d p = {0.0, 0.0}; - const Point2d p1 = {1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = distance(p, p1, p2); - - EXPECT_NEAR(result, 1.0, epsilon); - } - - { // The point is outside the polygon - const Point2d p = {0.0, 0.0}; - const Point2d p1 = {3.0, 1.0}; - const Point2d p2 = {3.0, -1.0}; - const Point2d p3 = {1.0, -1.0}; - const Point2d p4 = {1.0, 1.0}; - const auto result = distance(p, ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_NEAR(result, 1.0, epsilon); - } - - { // The point is within the polygon - const Point2d p = {0.0, 0.0}; - const Point2d p1 = {2.0, 1.0}; - const Point2d p2 = {2.0, -1.0}; - const Point2d p3 = {-1.0, -1.0}; - const Point2d p4 = {-1.0, 1.0}; - const auto result = distance(p, ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_NEAR(result, 0.0, epsilon); - } -} - -TEST(geometry, intersects) -{ - using autoware::universe_utils::intersects; - using autoware::universe_utils::alt::ConvexPolygon2d; - using autoware::universe_utils::alt::Point2d; - - { // Normally crossing - const Point2d p1 = {0.0, -1.0}; - const Point2d p2 = {0.0, 1.0}; - const Point2d p3 = {-1.0, 0.0}; - const Point2d p4 = {1.0, 0.0}; - const auto result = intersects(p1, p2, p3, p4); - - EXPECT_TRUE(result); - } - - { // No crossing - const Point2d p1 = {0.0, -1.0}; - const Point2d p2 = {0.0, 1.0}; - const Point2d p3 = {1.0, 0.0}; - const Point2d p4 = {3.0, 0.0}; - const auto result = intersects(p1, p2, p3, p4); - - EXPECT_FALSE(result); - } - - { // One segment is the point on the other's segment - const Point2d p1 = {0.0, -1.0}; - const Point2d p2 = {0.0, 1.0}; - const Point2d p3 = {0.0, 0.0}; - const Point2d p4 = {0.0, 0.0}; - const auto result = intersects(p1, p2, p3, p4); - - EXPECT_FALSE(result); - } - - { // One segment is the point not on the other's segment - const Point2d p1 = {0.0, -1.0}; - const Point2d p2 = {0.0, 1.0}; - const Point2d p3 = {1.0, 0.0}; - const Point2d p4 = {1.0, 0.0}; - const auto result = intersects(p1, p2, p3, p4); - - EXPECT_FALSE(result); - } - - { // Both segments are the points which are the same position - const Point2d p1 = {0.0, 0.0}; - const Point2d p2 = {0.0, 0.0}; - const Point2d p3 = {0.0, 0.0}; - const Point2d p4 = {0.0, 0.0}; - const auto result = intersects(p1, p2, p3, p4); - - EXPECT_FALSE(result); - } - - { // Both segments are the points which are different position - const Point2d p1 = {0.0, 1.0}; - const Point2d p2 = {0.0, 1.0}; - const Point2d p3 = {1.0, 0.0}; - const Point2d p4 = {1.0, 0.0}; - const auto result = intersects(p1, p2, p3, p4); - - EXPECT_FALSE(result); - } - - { // Segments are the same - const Point2d p1 = {0.0, -1.0}; - const Point2d p2 = {0.0, 1.0}; - const Point2d p3 = {0.0, -1.0}; - const Point2d p4 = {0.0, 1.0}; - const auto result = intersects(p1, p2, p3, p4); - - EXPECT_FALSE(result); - } - - { // One's edge is on the other's segment - const Point2d p1 = {0.0, -1.0}; - const Point2d p2 = {0.0, 1.0}; - const Point2d p3 = {0.0, 0.0}; - const Point2d p4 = {1.0, 0.0}; - const auto result = intersects(p1, p2, p3, p4); - - EXPECT_TRUE(result); - } - - { // One's edge is the same as the other's edge. - const Point2d p1 = {0.0, -1.0}; - const Point2d p2 = {0.0, 1.0}; - const Point2d p3 = {0.0, -1.0}; - const Point2d p4 = {2.0, -1.0}; - const auto result = intersects(p1, p2, p3, p4); - - EXPECT_TRUE(result); - } - - { // One polygon intersects the other - const Point2d p1 = {1.0, 1.0}; - const Point2d p2 = {1.0, -1.0}; - const Point2d p3 = {-1.0, -1.0}; - const Point2d p4 = {-1.0, 1.0}; - const Point2d p5 = {2.0, 2.0}; - const Point2d p6 = {2.0, 0.0}; - const Point2d p7 = {0.0, 0.0}; - const Point2d p8 = {0.0, 2.0}; - const auto result = - intersects(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); - - EXPECT_TRUE(result); - } - - { // Two polygons do not intersect each other - const Point2d p1 = {1.0, 1.0}; - const Point2d p2 = {1.0, -1.0}; - const Point2d p3 = {-1.0, -1.0}; - const Point2d p4 = {-1.0, 1.0}; - const Point2d p5 = {3.0, 3.0}; - const Point2d p6 = {3.0, 2.0}; - const Point2d p7 = {2.0, 2.0}; - const Point2d p8 = {2.0, 3.0}; - const auto result = - intersects(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); - - EXPECT_FALSE(result); - } - - { // Two polygons share a vertex - const Point2d p1 = {1.0, 1.0}; - const Point2d p2 = {1.0, -1.0}; - const Point2d p3 = {-1.0, -1.0}; - const Point2d p4 = {-1.0, 1.0}; - const Point2d p5 = {2.0, 2.0}; - const Point2d p6 = {2.0, 1.0}; - const Point2d p7 = {1.0, 1.0}; - const Point2d p8 = {1.0, 2.0}; - const auto result = - intersects(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); - - EXPECT_FALSE(result); - } -} - -TEST(geometry, isAbove) -{ - using autoware::universe_utils::is_above; - using autoware::universe_utils::alt::Point2d; - - { // The point is above the line - const Point2d point = {0.0, 1.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = is_above(point, p1, p2); - - EXPECT_TRUE(result); - } - - { // The point is below the line - const Point2d point = {0.0, -1.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = is_above(point, p1, p2); - - EXPECT_FALSE(result); - } - - { // The point is on the line - const Point2d point = {0.0, 0.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = is_above(point, p1, p2); - - EXPECT_FALSE(result); - } -} - -TEST(geometry, isClockwise) -{ - using autoware::universe_utils::is_clockwise; - using autoware::universe_utils::alt::ConvexPolygon2d; - using autoware::universe_utils::alt::Point2d; - - { // Clockwise - const Point2d p1 = {0.0, 0.0}; - const Point2d p2 = {0.0, 7.0}; - const Point2d p3 = {4.0, 2.0}; - const Point2d p4 = {2.0, 0.0}; - const auto result = is_clockwise(ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_TRUE(result); - } - - { // Counter-clockwise - const Point2d p1 = {0.0, 0.0}; - const Point2d p2 = {2.0, 0.0}; - const Point2d p3 = {4.0, 2.0}; - const Point2d p4 = {0.0, 7.0}; - const auto result = is_clockwise(ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_FALSE(result); - } -} - -TEST(geometry, touches) -{ - using autoware::universe_utils::touches; - using autoware::universe_utils::alt::ConvexPolygon2d; - using autoware::universe_utils::alt::Point2d; - - { - // The point is on the segment - const Point2d p = {0.0, 0.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = touches(p, p1, p2); - - EXPECT_TRUE(result); - } - - { - // The point is the start point of the segment - const Point2d p = {-1.0, 0.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = touches(p, p1, p2); - - EXPECT_TRUE(result); - } - - { - // The point is the end point of the segment - const Point2d p = {1.0, 0.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = touches(p, p1, p2); - - EXPECT_TRUE(result); - } - - { // The point is not on the segment - const Point2d p = {0.0, 1.0}; - const Point2d p1 = {-1.0, 0.0}; - const Point2d p2 = {1.0, 0.0}; - const auto result = touches(p, p1, p2); - - EXPECT_FALSE(result); - } - - { // The point is on the edge of the polygon - const Point2d point = {0.0, 0.0}; - const Point2d p1 = {2.0, 1.0}; - const Point2d p2 = {2.0, -1.0}; - const Point2d p3 = {0.0, -1.0}; - const Point2d p4 = {0.0, 1.0}; - const auto result = touches(point, ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_TRUE(result); - } - - { // The point is outside the polygon - const Point2d point = {0.0, 0.0}; - const Point2d p1 = {2.0, 2.0}; - const Point2d p2 = {2.0, 1.0}; - const Point2d p3 = {1.0, 1.0}; - const Point2d p4 = {1.0, 2.0}; - const auto result = touches(point, ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_FALSE(result); - } -} - -TEST(geometry, within) -{ - using autoware::universe_utils::within; - using autoware::universe_utils::alt::ConvexPolygon2d; - using autoware::universe_utils::alt::Point2d; - - { // The point is within the polygon - const Point2d point = {0.0, 0.0}; - const Point2d p1 = {1.0, 1.0}; - const Point2d p2 = {1.0, -1.0}; - const Point2d p3 = {-1.0, -1.0}; - const Point2d p4 = {-1.0, 1.0}; - const auto result = within(point, ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_TRUE(result); - } - - { // The point is outside the polygon - const Point2d point = {0.0, 0.0}; - const Point2d p1 = {2.0, 2.0}; - const Point2d p2 = {2.0, 1.0}; - const Point2d p3 = {1.0, 1.0}; - const Point2d p4 = {1.0, 2.0}; - const auto result = within(point, ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_FALSE(result); - } - - { // The point is on the edge of the polygon - const Point2d point = {0.0, 0.0}; - const Point2d p1 = {2.0, 1.0}; - const Point2d p2 = {2.0, -1.0}; - const Point2d p3 = {0.0, -1.0}; - const Point2d p4 = {0.0, 1.0}; - const auto result = within(point, ConvexPolygon2d({p1, p2, p3, p4})); - - EXPECT_FALSE(result); - } - - { // One polygon is within the other - const Point2d p1 = {1.0, 1.0}; - const Point2d p2 = {1.0, -1.0}; - const Point2d p3 = {-1.0, -1.0}; - const Point2d p4 = {-1.0, 1.0}; - const Point2d p5 = {2.0, 2.0}; - const Point2d p6 = {2.0, -2.0}; - const Point2d p7 = {-2.0, -2.0}; - const Point2d p8 = {-2.0, 2.0}; - const auto result = - within(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); - - EXPECT_TRUE(result); - } - - { // One polygon is outside the other - const Point2d p1 = {1.0, 1.0}; - const Point2d p2 = {1.0, -1.0}; - const Point2d p3 = {-1.0, -1.0}; - const Point2d p4 = {-1.0, 1.0}; - const Point2d p5 = {3.0, 3.0}; - const Point2d p6 = {3.0, 2.0}; - const Point2d p7 = {2.0, 2.0}; - const Point2d p8 = {2.0, 3.0}; - const auto result = - within(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); - - EXPECT_FALSE(result); - } - - { // Both polygons are the same - const Point2d p1 = {1.0, 1.0}; - const Point2d p2 = {1.0, -1.0}; - const Point2d p3 = {-1.0, -1.0}; - const Point2d p4 = {-1.0, 1.0}; - const Point2d p5 = {1.0, 1.0}; - const Point2d p6 = {1.0, -1.0}; - const Point2d p7 = {-1.0, -1.0}; - const Point2d p8 = {-1.0, 1.0}; - const auto result = - within(ConvexPolygon2d({p1, p2, p3, p4}), ConvexPolygon2d({p5, p6, p7, p8})); - - EXPECT_TRUE(result); - } -} - -TEST(geometry, areaRand) -{ - std::vector polygons; - constexpr auto polygons_nb = 500; - constexpr auto max_vertices = 10; - constexpr auto max_values = 1000; - - autoware::universe_utils::StopWatch sw; - for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { - double ground_truth_area_ns = 0.0; - double alt_area_ns = 0.0; - - polygons.clear(); - for (auto i = 0; i < polygons_nb; ++i) { - polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); - } - for (auto i = 0UL; i < polygons.size(); ++i) { - sw.tic(); - const auto ground_truth = boost::geometry::area(polygons[i]); - ground_truth_area_ns += sw.toc(); - - const auto alt_poly = autoware::universe_utils::alt::from_boost(polygons[i]); - sw.tic(); - const auto alt = autoware::universe_utils::area(alt_poly); - alt_area_ns += sw.toc(); - - if (std::abs(alt - ground_truth) > epsilon) { - std::cout << "Alt failed for the polygon: "; - std::cout << boost::geometry::wkt(polygons[i]) << std::endl; - } - EXPECT_NEAR(ground_truth, alt, epsilon); - } - std::printf("polygons_nb = %d, vertices = %ld\n", polygons_nb, vertices); - std::printf( - "\tArea:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", ground_truth_area_ns / 1e6, - alt_area_ns / 1e6); - } -} - -TEST(geometry, convexHullRand) -{ - std::vector polygons; - constexpr auto polygons_nb = 500; - constexpr auto max_vertices = 10; - constexpr auto max_values = 1000; - - autoware::universe_utils::StopWatch sw; - for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { - double ground_truth_hull_ns = 0.0; - double alt_hull_ns = 0.0; - - polygons.clear(); - for (auto i = 0; i < polygons_nb; ++i) { - polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); - } - for (auto i = 0UL; i < polygons.size(); ++i) { - autoware::universe_utils::MultiPoint2d outer; - for (const auto & point : polygons[i].outer()) { - outer.push_back(point); - } - autoware::universe_utils::Polygon2d ground_truth; - sw.tic(); - boost::geometry::convex_hull(outer, ground_truth); - ground_truth_hull_ns += sw.toc(); - - const auto vertices = autoware::universe_utils::alt::from_boost(polygons[i]).vertices(); - sw.tic(); - const auto alt = autoware::universe_utils::convex_hull(vertices); - alt_hull_ns += sw.toc(); - - if (ground_truth.outer().size() - 1 != alt.vertices().size()) { - std::cout << "Alt failed for the polygon: "; - std::cout << boost::geometry::wkt(polygons[i]) << std::endl; - } - ASSERT_EQ( - ground_truth.outer().size() - 1, - alt.vertices().size()); // alt::ConvexPolygon2d does not have closing point - for (size_t i = 0; i < alt.vertices().size(); ++i) { - EXPECT_NEAR(ground_truth.outer().at(i).x(), alt.vertices().at(i).x(), epsilon); - EXPECT_NEAR(ground_truth.outer().at(i).y(), alt.vertices().at(i).y(), epsilon); - } - } - std::printf("polygons_nb = %d, vertices = %ld\n", polygons_nb, vertices); - std::printf( - "\tConvex Hull:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_hull_ns / 1e6, alt_hull_ns / 1e6); - } -} - -TEST(geometry, coveredByRand) -{ - std::vector polygons; - constexpr auto polygons_nb = 500; - constexpr auto max_vertices = 10; - constexpr auto max_values = 1000; - - autoware::universe_utils::StopWatch sw; - for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { - double ground_truth_covered_ns = 0.0; - double ground_truth_not_covered_ns = 0.0; - double alt_covered_ns = 0.0; - double alt_not_covered_ns = 0.0; - int covered_count = 0; - - polygons.clear(); - for (auto i = 0; i < polygons_nb; ++i) { - polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); - } - for (auto i = 0UL; i < polygons.size(); ++i) { - for (const auto & point : polygons[i].outer()) { - for (auto j = 0UL; j < polygons.size(); ++j) { - sw.tic(); - const auto ground_truth = boost::geometry::covered_by(point, polygons[j]); - if (ground_truth) { - ++covered_count; - ground_truth_covered_ns += sw.toc(); - } else { - ground_truth_not_covered_ns += sw.toc(); - } - - const auto alt_point = autoware::universe_utils::alt::from_boost(point); - const auto alt_poly = autoware::universe_utils::alt::from_boost(polygons[j]); - sw.tic(); - const auto alt = autoware::universe_utils::covered_by(alt_point, alt_poly); - if (alt) { - alt_covered_ns += sw.toc(); - } else { - alt_not_covered_ns += sw.toc(); - } - - if (ground_truth != alt) { - std::cout << "Alt failed for the point and polygon: "; - std::cout << boost::geometry::wkt(point) << boost::geometry::wkt(polygons[j]) - << std::endl; - } - EXPECT_EQ(ground_truth, alt); - } - } - } - std::printf( - "polygons_nb = %d, vertices = %ld, %d / %ld covered pairs\n", polygons_nb, vertices, - covered_count, polygons_nb * vertices * polygons_nb); - std::printf( - "\tCovered:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_covered_ns / 1e6, alt_covered_ns / 1e6); - std::printf( - "\tNot covered:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_not_covered_ns / 1e6, alt_not_covered_ns / 1e6); - std::printf( - "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - (ground_truth_not_covered_ns + ground_truth_covered_ns) / 1e6, - (alt_not_covered_ns + alt_covered_ns) / 1e6); - } -} - -TEST(geometry, disjointRand) -{ - std::vector polygons; - constexpr auto polygons_nb = 500; - constexpr auto max_vertices = 10; - constexpr auto max_values = 1000; - - autoware::universe_utils::StopWatch sw; - for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { - double ground_truth_disjoint_ns = 0.0; - double ground_truth_not_disjoint_ns = 0.0; - double alt_disjoint_ns = 0.0; - double alt_not_disjoint_ns = 0.0; - int disjoint_count = 0; - - polygons.clear(); - for (auto i = 0; i < polygons_nb; ++i) { - polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); - } - for (auto i = 0UL; i < polygons.size(); ++i) { - for (auto j = 0UL; j < polygons.size(); ++j) { - sw.tic(); - const auto ground_truth = boost::geometry::disjoint(polygons[i], polygons[j]); - if (ground_truth) { - ++disjoint_count; - ground_truth_disjoint_ns += sw.toc(); - } else { - ground_truth_not_disjoint_ns += sw.toc(); - } - - const auto alt_poly1 = autoware::universe_utils::alt::from_boost(polygons[i]); - const auto alt_poly2 = autoware::universe_utils::alt::from_boost(polygons[j]); - sw.tic(); - const auto alt = autoware::universe_utils::disjoint(alt_poly1, alt_poly2); - if (alt) { - alt_disjoint_ns += sw.toc(); - } else { - alt_not_disjoint_ns += sw.toc(); - } - - if (ground_truth != alt) { - std::cout << "Failed for the 2 polygons: "; - std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j]) - << std::endl; - } - EXPECT_EQ(ground_truth, alt); - } - } - std::printf( - "polygons_nb = %d, vertices = %ld, %d / %d disjoint pairs\n", polygons_nb, vertices, - disjoint_count, polygons_nb * polygons_nb); - std::printf( - "\tDisjoint:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_disjoint_ns / 1e6, alt_disjoint_ns / 1e6); - std::printf( - "\tNot disjoint:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_not_disjoint_ns / 1e6, alt_not_disjoint_ns / 1e6); - std::printf( - "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - (ground_truth_not_disjoint_ns + ground_truth_disjoint_ns) / 1e6, - (alt_not_disjoint_ns + alt_disjoint_ns) / 1e6); - } -} - -TEST(geometry, intersectsRand) -{ - std::vector polygons; - constexpr auto polygons_nb = 500; - constexpr auto max_vertices = 10; - constexpr auto max_values = 1000; - - autoware::universe_utils::StopWatch sw; - for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { - double ground_truth_intersect_ns = 0.0; - double ground_truth_no_intersect_ns = 0.0; - double alt_intersect_ns = 0.0; - double alt_no_intersect_ns = 0.0; - int intersect_count = 0; - - polygons.clear(); - for (auto i = 0; i < polygons_nb; ++i) { - polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); - } - for (auto i = 0UL; i < polygons.size(); ++i) { - for (auto j = 0UL; j < polygons.size(); ++j) { - sw.tic(); - const auto ground_truth = boost::geometry::intersects(polygons[i], polygons[j]); - if (ground_truth) { - ++intersect_count; - ground_truth_intersect_ns += sw.toc(); - } else { - ground_truth_no_intersect_ns += sw.toc(); - } - - const auto alt_poly1 = autoware::universe_utils::alt::from_boost(polygons[i]); - const auto alt_poly2 = autoware::universe_utils::alt::from_boost(polygons[j]); - sw.tic(); - const auto alt = autoware::universe_utils::intersects(alt_poly1, alt_poly2); - if (alt) { - alt_intersect_ns += sw.toc(); - } else { - alt_no_intersect_ns += sw.toc(); - } - - if (ground_truth != alt) { - std::cout << "Failed for the 2 polygons: "; - std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j]) - << std::endl; - } - EXPECT_EQ(ground_truth, alt); - } - } - std::printf( - "polygons_nb = %d, vertices = %ld, %d / %d pairs with intersects\n", polygons_nb, vertices, - intersect_count, polygons_nb * polygons_nb); - std::printf( - "\tIntersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_intersect_ns / 1e6, alt_intersect_ns / 1e6); - std::printf( - "\tNo intersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_no_intersect_ns / 1e6, alt_no_intersect_ns / 1e6); - std::printf( - "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - (ground_truth_no_intersect_ns + ground_truth_intersect_ns) / 1e6, - (alt_no_intersect_ns + alt_intersect_ns) / 1e6); - } -} - -TEST(geometry, touchesRand) -{ - std::vector polygons; - constexpr auto polygons_nb = 500; - constexpr auto max_vertices = 10; - constexpr auto max_values = 1000; - - autoware::universe_utils::StopWatch sw; - for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { - double ground_truth_touching_ns = 0.0; - double ground_truth_not_touching_ns = 0.0; - double alt_touching_ns = 0.0; - double alt_not_touching_ns = 0.0; - int touching_count = 0; - - polygons.clear(); - for (auto i = 0; i < polygons_nb; ++i) { - polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); - } - for (auto i = 0UL; i < polygons.size(); ++i) { - for (const auto & point : polygons[i].outer()) { - for (auto j = 0UL; j < polygons.size(); ++j) { - sw.tic(); - const auto ground_truth = boost::geometry::touches(point, polygons[j]); - if (ground_truth) { - ++touching_count; - ground_truth_touching_ns += sw.toc(); - } else { - ground_truth_not_touching_ns += sw.toc(); - } - - const auto alt_point = autoware::universe_utils::alt::from_boost(point); - const auto alt_poly = autoware::universe_utils::alt::from_boost(polygons[j]); - sw.tic(); - const auto alt = autoware::universe_utils::touches(alt_point, alt_poly); - if (alt) { - alt_touching_ns += sw.toc(); - } else { - alt_not_touching_ns += sw.toc(); - } - - if (ground_truth != alt) { - std::cout << "Alt failed for the point and polygon: "; - std::cout << boost::geometry::wkt(point) << boost::geometry::wkt(polygons[j]) - << std::endl; - } - EXPECT_EQ(ground_truth, alt); - } - } - } - std::printf( - "polygons_nb = %d, vertices = %ld, %d / %ld touching pairs\n", polygons_nb, vertices, - touching_count, polygons_nb * vertices * polygons_nb); - std::printf( - "\tTouching:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_touching_ns / 1e6, alt_touching_ns / 1e6); - std::printf( - "\tNot touching:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_not_touching_ns / 1e6, alt_not_touching_ns / 1e6); - std::printf( - "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - (ground_truth_not_touching_ns + ground_truth_touching_ns) / 1e6, - (alt_not_touching_ns + alt_touching_ns) / 1e6); - } -} - -TEST(geometry, withinPolygonRand) -{ - std::vector polygons; - constexpr auto polygons_nb = 500; - constexpr auto max_vertices = 10; - constexpr auto max_values = 1000; - - autoware::universe_utils::StopWatch sw; - for (auto vertices = 3UL; vertices < max_vertices; ++vertices) { - double ground_truth_within_ns = 0.0; - double ground_truth_not_within_ns = 0.0; - double alt_within_ns = 0.0; - double alt_not_within_ns = 0.0; - int within_count = 0; - - polygons.clear(); - for (auto i = 0; i < polygons_nb; ++i) { - polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values)); - } - for (auto i = 0UL; i < polygons.size(); ++i) { - for (auto j = 0UL; j < polygons.size(); ++j) { - sw.tic(); - const auto ground_truth = boost::geometry::within(polygons[i], polygons[j]); - if (ground_truth) { - ++within_count; - ground_truth_within_ns += sw.toc(); - } else { - ground_truth_not_within_ns += sw.toc(); - } - - const auto alt_poly1 = autoware::universe_utils::alt::from_boost(polygons[i]); - const auto alt_poly2 = autoware::universe_utils::alt::from_boost(polygons[j]); - sw.tic(); - const auto alt = autoware::universe_utils::within(alt_poly1, alt_poly2); - if (alt) { - alt_within_ns += sw.toc(); - } else { - alt_not_within_ns += sw.toc(); - } - - if (ground_truth != alt) { - std::cout << "Alt failed for the 2 polygons: "; - std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j]) - << std::endl; - } - EXPECT_EQ(ground_truth, alt); - } - } - std::printf( - "polygons_nb = %d, vertices = %ld, %d / %d pairs either of which is within the other\n", - polygons_nb, vertices, within_count, polygons_nb * polygons_nb); - std::printf( - "\tWithin:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_within_ns / 1e6, alt_within_ns / 1e6); - std::printf( - "\tNot within:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - ground_truth_not_within_ns / 1e6, alt_not_within_ns / 1e6); - std::printf( - "\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n", - (ground_truth_not_within_ns + ground_truth_within_ns) / 1e6, - (alt_not_within_ns + alt_within_ns) / 1e6); - } -} From f189d1ba3ba693024efddef5f7d3d631a2b84049 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 3 Sep 2024 15:57:15 +0900 Subject: [PATCH 102/217] fix(autoware_behavior_path_static_obstacle_avoidance_module): fix unusedFunction (#8732) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/utils.cpp | 22 ------------------- 1 file changed, 22 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 0f3e3da5b2171..58eb16b67e659 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -92,28 +92,6 @@ size_t findFirstNearestIndex(const T & points, const geometry_msgs::msg::Point & return min_idx; } -template -size_t findFirstNearestSegmentIndex(const T & points, const geometry_msgs::msg::Point & point) -{ - const size_t nearest_idx = findFirstNearestIndex(points, point); - - if (nearest_idx == 0) { - return 0; - } - if (nearest_idx == points.size() - 1) { - return points.size() - 2; - } - - const double signed_length = - autoware::motion_utils::calcLongitudinalOffsetToSegment(points, nearest_idx, point); - - if (signed_length <= 0) { - return nearest_idx - 1; - } - - return nearest_idx; -} - geometry_msgs::msg::Polygon createVehiclePolygon( const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double offset) { From 9aed21865e6d914625f545403751dfe6d855b081 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 3 Sep 2024 16:06:35 +0900 Subject: [PATCH 103/217] fix(autoware_path_sampler): fix unusedFunction (#8730) fix:unusedFunction Signed-off-by: kobayu858 --- .../utils/trajectory_utils.hpp | 4 ---- .../src/utils/trajectory_utils.cpp | 23 ------------------- 2 files changed, 27 deletions(-) diff --git a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp index c44338aa64ce8..992ad95c72bb1 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp @@ -117,10 +117,6 @@ inline std::vector convertToTrajectoryPoints( return traj_points; } -void compensateLastPose( - const PathPoint & last_path_point, std::vector & traj_points, - const double delta_dist_threshold, const double delta_yaw_threshold); - template size_t findEgoIndex( const std::vector & points, const geometry_msgs::msg::Pose & ego_pose, diff --git a/planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp index 89120eef0f76a..e8379091615f8 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp @@ -35,29 +35,6 @@ namespace autoware::path_sampler { namespace trajectory_utils { -void compensateLastPose( - const PathPoint & last_path_point, std::vector & traj_points, - const double delta_dist_threshold, const double delta_yaw_threshold) -{ - if (traj_points.empty()) { - traj_points.push_back(convertToTrajectoryPoint(last_path_point)); - return; - } - - const geometry_msgs::msg::Pose last_traj_pose = traj_points.back().pose; - - const double dist = autoware::universe_utils::calcDistance2d( - last_path_point.pose.position, last_traj_pose.position); - const double norm_diff_yaw = [&]() { - const double diff_yaw = - tf2::getYaw(last_path_point.pose.orientation) - tf2::getYaw(last_traj_pose.orientation); - return autoware::universe_utils::normalizeRadian(diff_yaw); - }(); - if (dist > delta_dist_threshold || std::fabs(norm_diff_yaw) > delta_yaw_threshold) { - traj_points.push_back(convertToTrajectoryPoint(last_path_point)); - } -} - std::vector resampleTrajectoryPoints( const std::vector & traj_points, const double interval) { From c0fa13742ea38efc2f1c88f04411b194bf5c3dec Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 3 Sep 2024 18:01:37 +0900 Subject: [PATCH 104/217] feat(autonomous_emergency_braking): increase aeb speed by getting last transform (#8734) set stamp to 0 to get the latest stamp instead of waiting for the stamp Signed-off-by: Daniel Sanchez --- control/autoware_autonomous_emergency_braking/src/node.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 49bf307db0f23..26c6decceaff7 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -250,7 +250,7 @@ void AEB::onImu(const Imu::ConstSharedPtr input_msg) geometry_msgs::msg::TransformStamped transform_stamped{}; try { transform_stamped = tf_buffer_.lookupTransform( - "base_link", input_msg->header.frame_id, input_msg->header.stamp, + "base_link", input_msg->header.frame_id, rclcpp::Time(0), rclcpp::Duration::from_seconds(0.5)); } catch (tf2::TransformException & ex) { RCLCPP_ERROR_STREAM( @@ -631,7 +631,7 @@ std::optional AEB::generateEgoPath(const Trajectory & predicted_traj) geometry_msgs::msg::TransformStamped transform_stamped{}; try { transform_stamped = tf_buffer_.lookupTransform( - "base_link", predicted_traj.header.frame_id, predicted_traj.header.stamp, + "base_link", predicted_traj.header.frame_id, rclcpp::Time(0), rclcpp::Duration::from_seconds(0.5)); } catch (tf2::TransformException & ex) { RCLCPP_ERROR_STREAM( @@ -705,7 +705,7 @@ void AEB::createObjectDataUsingPredictedObjects( geometry_msgs::msg::TransformStamped transform_stamped{}; try { transform_stamped = tf_buffer_.lookupTransform( - "base_link", predicted_objects_ptr_->header.frame_id, stamp, + "base_link", predicted_objects_ptr_->header.frame_id, rclcpp::Time(0), rclcpp::Duration::from_seconds(0.5)); } catch (tf2::TransformException & ex) { RCLCPP_ERROR_STREAM(get_logger(), "[AEB] Failed to look up transform from base_link to map"); From a5cc3bad97f54f1c72cabeb065e0c375e7638e00 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 3 Sep 2024 19:26:49 +0900 Subject: [PATCH 105/217] chore(autoware_lidar_centerpoint): add centerpoint sigma parameter (#8731) add centerpoint sigma parameter Signed-off-by: yoshiri --- .../config/centerpoint_sigma.param.yaml | 21 +++++++++++++++++++ 1 file changed, 21 insertions(+) create mode 100644 perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml diff --git a/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml b/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml new file mode 100644 index 0000000000000..bd5fc5f3567a5 --- /dev/null +++ b/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml @@ -0,0 +1,21 @@ +/**: + ros__parameters: + + # weight files + encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx" + encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine" + head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx" + head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine" + trt_precision: fp16 + cloud_capacity: 2000000 + post_process_params: + # post-process params + circle_nms_dist_threshold: 0.5 + iou_nms_target_class_names: ["CAR"] + iou_nms_search_distance_2d: 10.0 + iou_nms_threshold: 0.1 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + score_threshold: 0.35 + densification_params: + world_frame_id: map + num_past_frames: 1 From e90a127ea0c6fcd55d534456af00713a1f4e2ab7 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 3 Sep 2024 21:04:24 +0900 Subject: [PATCH 106/217] fix(mission_planner): improve condition to check if the goal is within the lane (#8710) Signed-off-by: Maxime CLEMENT --- .../src/lanelet2_plugins/default_planner.cpp | 108 +++++++++--------- .../src/lanelet2_plugins/default_planner.hpp | 22 ++-- .../lanelet2_plugins/utility_functions.cpp | 60 ---------- .../lanelet2_plugins/utility_functions.hpp | 12 -- 4 files changed, 64 insertions(+), 138 deletions(-) diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp index 3a9bfc1357798..6c42195812a74 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -17,6 +17,7 @@ #include "utility_functions.hpp" #include +#include #include #include #include @@ -27,10 +28,13 @@ #include #include +#include +#include + +#include #include +#include #include -#include -#include #include #include @@ -216,7 +220,7 @@ PlannerPlugin::MarkerArray DefaultPlanner::visualize(const LaneletRoute & route) } visualization_msgs::msg::MarkerArray DefaultPlanner::visualize_debug_footprint( - autoware::universe_utils::LinearRing2d goal_footprint) const + autoware::universe_utils::LinearRing2d goal_footprint) { visualization_msgs::msg::MarkerArray msg; auto marker = autoware::universe_utils::createDefaultMarker( @@ -244,52 +248,58 @@ visualization_msgs::msg::MarkerArray DefaultPlanner::visualize_debug_footprint( return msg; } -bool DefaultPlanner::check_goal_footprint_inside_lanes( - const lanelet::ConstLanelet & current_lanelet, - const lanelet::ConstLanelet & combined_prev_lanelet, - const autoware::universe_utils::Polygon2d & goal_footprint, double & next_lane_length, - const double search_margin) +lanelet::ConstLanelets next_lanelets_up_to( + const lanelet::ConstLanelet & start_lanelet, const double up_to_distance, + const route_handler::RouteHandler & route_handler) { - // check if goal footprint is in current lane - if (boost::geometry::within(goal_footprint, combined_prev_lanelet.polygon2d().basicPolygon())) { - return true; + lanelet::ConstLanelets lanelets; + if (up_to_distance <= 0.0) { + return lanelets; } - const auto following = route_handler_.getNextLanelets(current_lanelet); - // check if goal footprint is in between many lanelets in depth-first search manner - for (const auto & next_lane : following) { - next_lane_length += lanelet::utils::getLaneletLength2d(next_lane); - lanelet::ConstLanelets lanelets; - lanelets.push_back(combined_prev_lanelet); + for (const auto & next_lane : route_handler.getNextLanelets(start_lanelet)) { lanelets.push_back(next_lane); - lanelet::ConstLanelet combined_lanelets = - combine_lanelets_with_shoulder(lanelets, route_handler_); - - // if next lanelet length is longer than vehicle longitudinal offset - if (vehicle_info_.max_longitudinal_offset_m + search_margin < next_lane_length) { - next_lane_length -= lanelet::utils::getLaneletLength2d(next_lane); - // and if the goal_footprint is within the (accumulated) combined_lanelets, terminate the - // query - if (boost::geometry::within(goal_footprint, combined_lanelets.polygon2d().basicPolygon())) { - return true; - } - // if not, iteration continues to next next_lane, and this subtree is terminated - } else { // if next lanelet length is shorter than vehicle longitudinal offset, check the - // overlap with the polygon including the next_lane(s) until the additional lanes get - // longer than ego vehicle length - if (!check_goal_footprint_inside_lanes( - next_lane, combined_lanelets, goal_footprint, next_lane_length)) { - next_lane_length -= lanelet::utils::getLaneletLength2d(next_lane); - continue; - } else { - return true; - } + const auto next_lanelets = next_lanelets_up_to( + next_lane, up_to_distance - lanelet::geometry::length2d(next_lane), route_handler); + lanelets.insert(lanelets.end(), next_lanelets.begin(), next_lanelets.end()); + } + return lanelets; +} + +bool DefaultPlanner::check_goal_footprint_inside_lanes( + const lanelet::ConstLanelet & current_lanelet, const lanelet::ConstLanelets & path_lanelets, + const universe_utils::Polygon2d & goal_footprint) const +{ + universe_utils::MultiPolygon2d ego_lanes; + universe_utils::Polygon2d poly; + for (const auto & ll : path_lanelets) { + const auto left_shoulder = route_handler_.getLeftShoulderLanelet(ll); + if (left_shoulder) { + boost::geometry::convert(left_shoulder->polygon2d().basicPolygon(), poly); + ego_lanes.push_back(poly); + } + const auto right_shoulder = route_handler_.getRightShoulderLanelet(ll); + if (right_shoulder) { + boost::geometry::convert(right_shoulder->polygon2d().basicPolygon(), poly); + ego_lanes.push_back(poly); } + boost::geometry::convert(ll.polygon2d().basicPolygon(), poly); + ego_lanes.push_back(poly); } - return false; + const auto next_lanelets = + next_lanelets_up_to(current_lanelet, vehicle_info_.max_longitudinal_offset_m, route_handler_); + for (const auto & ll : next_lanelets) { + boost::geometry::convert(ll.polygon2d().basicPolygon(), poly); + ego_lanes.push_back(poly); + } + + // check if goal footprint is in the ego lane + universe_utils::MultiPolygon2d difference; + boost::geometry::difference(goal_footprint, ego_lanes, difference); + return boost::geometry::is_empty(difference); } bool DefaultPlanner::is_goal_valid( - const geometry_msgs::msg::Pose & goal, lanelet::ConstLanelets path_lanelets) + const geometry_msgs::msg::Pose & goal, const lanelet::ConstLanelets & path_lanelets) { const auto logger = node_->get_logger(); @@ -337,16 +347,10 @@ bool DefaultPlanner::is_goal_valid( pub_goal_footprint_marker_->publish(visualize_debug_footprint(goal_footprint)); const auto polygon_footprint = convert_linear_ring_to_polygon(goal_footprint); - double next_lane_length = 0.0; - // combine calculated route lanelets - const lanelet::ConstLanelet combined_prev_lanelet = - combine_lanelets_with_shoulder(path_lanelets, route_handler_); - // check if goal footprint exceeds lane when the goal isn't in parking_lot if ( param_.check_footprint_inside_lanes && - !check_goal_footprint_inside_lanes( - closest_lanelet, combined_prev_lanelet, polygon_footprint, next_lane_length) && + !check_goal_footprint_inside_lanes(closest_lanelet, path_lanelets, polygon_footprint) && !is_in_parking_lot( lanelet::utils::query::getAllParkingLots(route_handler_.getLaneletMapPtr()), lanelet::utils::conversion::toLaneletPoint(goal.position))) { @@ -375,11 +379,7 @@ bool DefaultPlanner::is_goal_valid( // check if goal is in parking lot const auto parking_lots = lanelet::utils::query::getAllParkingLots(route_handler_.getLaneletMapPtr()); - if (is_in_parking_lot(parking_lots, goal_lanelet_pt)) { - return true; - } - - return false; + return is_in_parking_lot(parking_lots, goal_lanelet_pt); } PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) @@ -429,7 +429,7 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) return route_msg; } - if (route_handler_.isRouteLooped(route_sections)) { + if (route_handler::RouteHandler::isRouteLooped(route_sections)) { RCLCPP_WARN(logger, "Loop detected within route!"); return route_msg; } diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp index 5394caf698664..39b7fa8909a6a 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -27,7 +27,6 @@ #include #include -#include #include namespace autoware::mission_planner::lanelet2 @@ -44,17 +43,17 @@ struct DefaultPlannerParameters class DefaultPlanner : public mission_planner::PlannerPlugin { public: - DefaultPlanner() : is_graph_ready_(false), route_handler_(), param_(), node_(nullptr) {} + DefaultPlanner() : vehicle_info_(), is_graph_ready_(false), param_(), node_(nullptr) {} void initialize(rclcpp::Node * node) override; void initialize(rclcpp::Node * node, const LaneletMapBin::ConstSharedPtr msg) override; - bool ready() const override; + [[nodiscard]] bool ready() const override; LaneletRoute plan(const RoutePoints & points) override; void updateRoute(const PlannerPlugin::LaneletRoute & route) override; void clearRoute() override; - MarkerArray visualize(const LaneletRoute & route) const override; - MarkerArray visualize_debug_footprint( - autoware::universe_utils::LinearRing2d goal_footprint) const; + [[nodiscard]] MarkerArray visualize(const LaneletRoute & route) const override; + [[nodiscard]] static MarkerArray visualize_debug_footprint( + autoware::universe_utils::LinearRing2d goal_footprint); autoware::vehicle_info_utils::VehicleInfo vehicle_info_; private: @@ -85,17 +84,16 @@ class DefaultPlanner : public mission_planner::PlannerPlugin * @param next_lane_length the accumulated total length from the start lanelet of the search to * the lanelet of current goal query */ - bool check_goal_footprint_inside_lanes( - const lanelet::ConstLanelet & current_lanelet, - const lanelet::ConstLanelet & combined_prev_lanelet, - const autoware::universe_utils::Polygon2d & goal_footprint, double & next_lane_length, - const double search_margin = 2.0); + [[nodiscard]] bool check_goal_footprint_inside_lanes( + const lanelet::ConstLanelet & current_lanelet, const lanelet::ConstLanelets & path_lanelets, + const universe_utils::Polygon2d & goal_footprint) const; /** * @brief return true if (1)the goal is in parking area or (2)the goal is on the lanes and the * footprint around the goal does not overlap the lanes */ - bool is_goal_valid(const geometry_msgs::msg::Pose & goal, lanelet::ConstLanelets path_lanelets); + bool is_goal_valid( + const geometry_msgs::msg::Pose & goal, const lanelet::ConstLanelets & path_lanelets); /** * @brief project the specified goal pose onto the goal lanelet(the last preferred lanelet of diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp index 5046b81c72b96..34b16ef35f603 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -18,9 +18,6 @@ #include -#include -#include - autoware::universe_utils::Polygon2d convert_linear_ring_to_polygon( autoware::universe_utils::LinearRing2d footprint) { @@ -41,63 +38,6 @@ void insert_marker_array( a1->markers.insert(a1->markers.end(), a2.markers.begin(), a2.markers.end()); } -lanelet::ConstLanelet combine_lanelets_with_shoulder( - const lanelet::ConstLanelets & lanelets, - const autoware::route_handler::RouteHandler & route_handler) -{ - lanelet::Points3d lefts; - lanelet::Points3d rights; - lanelet::Points3d centers; - std::vector left_bound_ids; - std::vector right_bound_ids; - - for (const auto & llt : lanelets) { - if (llt.id() != lanelet::InvalId) { - left_bound_ids.push_back(llt.leftBound().id()); - right_bound_ids.push_back(llt.rightBound().id()); - } - } - - // lambda to add bound to target_bound - const auto add_bound = [](const auto & bound, auto & target_bound) { - std::transform( - bound.begin(), bound.end(), std::back_inserter(target_bound), - [](const auto & pt) { return lanelet::Point3d(pt); }); - }; - for (const auto & llt : lanelets) { - // check if shoulder lanelets which has RIGHT bound same to LEFT bound of lanelet exist - const auto left_shared_shoulder = route_handler.getLeftShoulderLanelet(llt); - if (left_shared_shoulder) { - // if exist, add left bound of SHOULDER lanelet to lefts - add_bound(left_shared_shoulder->leftBound(), lefts); - } else if ( - // if not exist, add left bound of lanelet to lefts - // if the **left** of this lanelet does not match any of the **right** bounds of `lanelets`, - // then its left bound constitutes the left boundary of the entire merged lanelet - std::count(right_bound_ids.begin(), right_bound_ids.end(), llt.leftBound().id()) < 1) { - add_bound(llt.leftBound(), lefts); - } - - // check if shoulder lanelets which has LEFT bound same to RIGHT bound of lanelet exist - const auto right_shared_shoulder = route_handler.getRightShoulderLanelet(llt); - if (right_shared_shoulder) { - // if exist, add right bound of SHOULDER lanelet to rights - add_bound(right_shared_shoulder->rightBound(), rights); - } else if ( - // if not exist, add right bound of lanelet to rights - // if the **right** of this lanelet does not match any of the **left** bounds of `lanelets`, - // then its right bound constitutes the right boundary of the entire merged lanelet - std::count(left_bound_ids.begin(), left_bound_ids.end(), llt.rightBound().id()) < 1) { - add_bound(llt.rightBound(), rights); - } - } - - const auto left_bound = lanelet::LineString3d(lanelet::InvalId, lefts); - const auto right_bound = lanelet::LineString3d(lanelet::InvalId, rights); - auto combined_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); - return std::move(combined_lanelet); -} - std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet) { std::vector centerline_points; diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp index c8812e2c76dd6..6e3d2a0e88941 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -27,8 +27,6 @@ #include #include -#include -#include #include template @@ -47,16 +45,6 @@ autoware::universe_utils::Polygon2d convert_linear_ring_to_polygon( void insert_marker_array( visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2); -/** - * @brief create a single merged lanelet whose left/right bounds consist of the leftmost/rightmost - * bound of the original lanelets or the left/right bound of its adjacent road_shoulder respectively - * @param lanelets topologically sorted sequence of lanelets - * @param route_handler route handler to query the lanelet map - */ -lanelet::ConstLanelet combine_lanelets_with_shoulder( - const lanelet::ConstLanelets & lanelets, - const autoware::route_handler::RouteHandler & route_handler); - std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet); geometry_msgs::msg::Pose convertBasicPoint3dToPose( const lanelet::BasicPoint3d & point, const double lane_yaw); From b967b6fd70a8591e17f558aa150e80517e9d53de Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 3 Sep 2024 22:08:13 +0900 Subject: [PATCH 107/217] refactor(cuda_utils): move cuda_utils to sensing (#8729) fix: move cuda_utils to sensing Signed-off-by: yoshiri --- {common => sensing}/cuda_utils/CMakeLists.txt | 0 {common => sensing}/cuda_utils/README.md | 0 .../cuda_utils/include/cuda_utils/cuda_check_error.hpp | 0 .../cuda_utils/include/cuda_utils/cuda_unique_ptr.hpp | 0 .../cuda_utils/include/cuda_utils/stream_unique_ptr.hpp | 0 {common => sensing}/cuda_utils/package.xml | 0 6 files changed, 0 insertions(+), 0 deletions(-) rename {common => sensing}/cuda_utils/CMakeLists.txt (100%) rename {common => sensing}/cuda_utils/README.md (100%) rename {common => sensing}/cuda_utils/include/cuda_utils/cuda_check_error.hpp (100%) rename {common => sensing}/cuda_utils/include/cuda_utils/cuda_unique_ptr.hpp (100%) rename {common => sensing}/cuda_utils/include/cuda_utils/stream_unique_ptr.hpp (100%) rename {common => sensing}/cuda_utils/package.xml (100%) diff --git a/common/cuda_utils/CMakeLists.txt b/sensing/cuda_utils/CMakeLists.txt similarity index 100% rename from common/cuda_utils/CMakeLists.txt rename to sensing/cuda_utils/CMakeLists.txt diff --git a/common/cuda_utils/README.md b/sensing/cuda_utils/README.md similarity index 100% rename from common/cuda_utils/README.md rename to sensing/cuda_utils/README.md diff --git a/common/cuda_utils/include/cuda_utils/cuda_check_error.hpp b/sensing/cuda_utils/include/cuda_utils/cuda_check_error.hpp similarity index 100% rename from common/cuda_utils/include/cuda_utils/cuda_check_error.hpp rename to sensing/cuda_utils/include/cuda_utils/cuda_check_error.hpp diff --git a/common/cuda_utils/include/cuda_utils/cuda_unique_ptr.hpp b/sensing/cuda_utils/include/cuda_utils/cuda_unique_ptr.hpp similarity index 100% rename from common/cuda_utils/include/cuda_utils/cuda_unique_ptr.hpp rename to sensing/cuda_utils/include/cuda_utils/cuda_unique_ptr.hpp diff --git a/common/cuda_utils/include/cuda_utils/stream_unique_ptr.hpp b/sensing/cuda_utils/include/cuda_utils/stream_unique_ptr.hpp similarity index 100% rename from common/cuda_utils/include/cuda_utils/stream_unique_ptr.hpp rename to sensing/cuda_utils/include/cuda_utils/stream_unique_ptr.hpp diff --git a/common/cuda_utils/package.xml b/sensing/cuda_utils/package.xml similarity index 100% rename from common/cuda_utils/package.xml rename to sensing/cuda_utils/package.xml From 4cd1872ed928fedb55eca6b877538f891b2816d5 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 4 Sep 2024 00:04:32 +0900 Subject: [PATCH 108/217] fix(behavior_velocity_traffic_light): make dilemma_zone_plotter.py executable (#8684) Signed-off-by: Takayuki Murooka --- .../scripts/dilemma_zone_plotter.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) mode change 100644 => 100755 planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py old mode 100644 new mode 100755 From 69f5b7c6340da0c0eb85d87af56c072905b3a780 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Tue, 3 Sep 2024 17:55:33 +0200 Subject: [PATCH 109/217] fix(autoware_pointcloud_preprocessor): instantiate templates so that the symbols exist when linking (#8743) Signed-off-by: Esteve Fernandez --- .../src/distortion_corrector/distortion_corrector.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index 868dd96088a65..affa6d901be2d 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -422,4 +422,7 @@ inline void DistortionCorrector3D::undistortPointImplementation( prev_transformation_matrix_ = transformation_matrix_; } +template class DistortionCorrector; +template class DistortionCorrector; + } // namespace autoware::pointcloud_preprocessor From 155780654f545efc55ca426724b93f8a979bccf7 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Wed, 4 Sep 2024 01:07:34 +0900 Subject: [PATCH 110/217] fix(autoware_shape_estimation): resolve undefined reference to `~TrtShapeEstimator()` (#8738) fix: resolve undefined reference to `~TrtShapeEstimator()` Signed-off-by: ktro2828 --- .../autoware/shape_estimation/tensorrt_shape_estimator.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 5d0b7032445c8..d046e1d717b89 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 @@ -53,7 +53,7 @@ class TrtShapeEstimator const tensorrt_common::BuildConfig build_config = tensorrt_common::BuildConfig("MinMax", -1, false, false, false, 0.0)); - ~TrtShapeEstimator(); + ~TrtShapeEstimator() = default; bool inference(const DetectedObjectsWithFeature & input, DetectedObjectsWithFeature & output); From 799e4f95765a87018125dc3368af723224c50acf Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 4 Sep 2024 01:37:33 +0900 Subject: [PATCH 111/217] feat(goal_planner): extend pull over lanes inward to extract objects (#8714) * feat(goal_planner): extend pull over lanes inward to extract objects Signed-off-by: kosuke55 * update from review Signed-off-by: kosuke55 * use optionale Signed-off-by: kosuke55 * rename lamda Signed-off-by: kosuke55 * return nullopt Signed-off-by: kosuke55 * Update planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp Co-authored-by: Mamoru Sobue * pre-commit Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 Co-authored-by: Mamoru Sobue --- .../goal_planner_module.hpp | 1 + .../goal_searcher.hpp | 10 +- .../goal_searcher_base.hpp | 10 +- .../util.hpp | 13 ++ .../src/goal_planner_module.cpp | 65 ++++++++-- .../src/goal_searcher.cpp | 34 ++--- .../src/util.cpp | 121 ++++++++++++++++++ 7 files changed, 204 insertions(+), 50 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 222bc4e49ca18..2adac879a6bb2 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 @@ -275,6 +275,7 @@ struct GoalPlannerDebugData FreespacePlannerDebugData freespace_planner{}; std::vector ego_polygons_expanded{}; lanelet::ConstLanelet expanded_pull_over_lane_between_ego{}; + Polygon2d objects_extraction_polygon{}; }; struct LastApprovalData diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp index 5d056add4665e..6bdad3a3063ef 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp @@ -31,13 +31,12 @@ class GoalSearcher : public GoalSearcherBase public: GoalSearcher(const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint); - GoalCandidates search( - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) override; + GoalCandidates search(const std::shared_ptr & planner_data) override; void update( GoalCandidates & goal_candidates, const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const override; + const std::shared_ptr & planner_data, + const PredictedObjects & objects) const override; // todo(kosuke55): Functions for this specific use should not be in the interface, // so it is better to consider interface design when we implement other goal searchers. @@ -47,7 +46,8 @@ class GoalSearcher : public GoalSearcherBase bool isSafeGoalWithMarginScaleFactor( const GoalCandidate & goal_candidate, const double margin_scale_factor, const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const override; + const std::shared_ptr & planner_data, + const PredictedObjects & objects) const override; private: void countObjectsToAvoid( diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp index baead4c229efd..b7d6ffe0710fe 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp @@ -53,13 +53,12 @@ class GoalSearcherBase const Pose & getReferenceGoal() const { return reference_goal_pose_; } MultiPolygon2d getAreaPolygons() const { return area_polygons_; } - virtual GoalCandidates search( - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) = 0; + virtual GoalCandidates search(const std::shared_ptr & planner_data) = 0; virtual void update( [[maybe_unused]] GoalCandidates & goal_candidates, [[maybe_unused]] const std::shared_ptr occupancy_grid_map, - [[maybe_unused]] const std::shared_ptr & planner_data) const + [[maybe_unused]] const std::shared_ptr & planner_data, + [[maybe_unused]] const PredictedObjects & objects) const { return; } @@ -69,7 +68,8 @@ class GoalSearcherBase virtual bool isSafeGoalWithMarginScaleFactor( const GoalCandidate & goal_candidate, const double margin_scale_factor, const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const = 0; + const std::shared_ptr & planner_data, + const PredictedObjects & objects) const = 0; protected: GoalPlannerParameters parameters_{}; 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 2a48db97b1977..7d83c598a8227 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 @@ -64,6 +64,19 @@ lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes( const geometry_msgs::msg::Pose ego_pose, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double outer_road_offset, const double inner_road_offset); + +/* + * @brief generate polygon to extract objects + * @param pull_over_lanes pull over lanes + * @param left_side left side or right side + * @param outer_offset outer offset from pull over lane boundary + * @param inner_offset inner offset from pull over lane boundary + * @return polygon to extract objects + */ +std::optional generateObjectExtractionPolygon( + const lanelet::ConstLanelets & pull_over_lanes, const bool left_side, const double outer_offset, + const double inner_offset); + PredictedObjects extractObjectsInExpandedPullOverLanes( const RouteHandler & route_handler, const bool left_side, const double backward_distance, const double forward_distance, double bound_offset, const PredictedObjects & objects); 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 eb7e6e22370aa..92e15c2c4aee4 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 @@ -459,18 +459,33 @@ void GoalPlannerModule::updateData() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - // extract static and dynamic objects in expanded pull over lanes + // extract static and dynamic objects in extraction polygon for path coliision check { const auto & p = parameters_; const auto & rh = *(planner_data_->route_handler); const auto objects = *(planner_data_->dynamic_object); - const auto static_target_objects = - goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, - p->detection_bound_offset, objects, p->th_moving_object_velocity); - const auto dynamic_target_objects = goal_planner_utils::extractObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, - p->detection_bound_offset, objects); + 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 static_target_objects = utils::path_safety_checker::filterObjectsByVelocity( + dynamic_target_objects, p->th_moving_object_velocity); + + // these objects are used for path collision check not for safety check thread_safe_data_.set_static_target_objects(static_target_objects); thread_safe_data_.set_dynamic_target_objects(dynamic_target_objects); } @@ -739,7 +754,9 @@ bool GoalPlannerModule::planFreespacePath( { GoalCandidates goal_candidates{}; goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher->update(goal_candidates, occupancy_grid_map, planner_data); + goal_searcher->update( + goal_candidates, occupancy_grid_map, planner_data, + thread_safe_data_.get_static_target_objects()); thread_safe_data_.set_goal_candidates(goal_candidates); debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); debug_data_.freespace_planner.is_planning = true; @@ -824,7 +841,7 @@ GoalCandidates GoalPlannerModule::generateGoalCandidates() const // calculate goal candidates const auto & route_handler = planner_data_->route_handler; if (utils::isAllowedGoalModification(route_handler)) { - return goal_searcher_->search(occupancy_grid_map_, planner_data_); + return goal_searcher_->search(planner_data_); } // NOTE: @@ -1282,9 +1299,9 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( // check goal pose collision const auto modified_goal_opt = thread_safe_data_.get_modified_goal_pose(); if ( - modified_goal_opt && - !goal_searcher->isSafeGoalWithMarginScaleFactor( - modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map, planner_data)) { + modified_goal_opt && !goal_searcher->isSafeGoalWithMarginScaleFactor( + modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map, + planner_data, thread_safe_data_.get_static_target_objects())) { RCLCPP_DEBUG(getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. goal is not safe"); return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } @@ -1443,7 +1460,9 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() // update goal candidates auto goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher_->update(goal_candidates, occupancy_grid_map_, planner_data_); + goal_searcher_->update( + goal_candidates, occupancy_grid_map_, planner_data_, + thread_safe_data_.get_static_target_objects()); // Select a path that is as safe as possible and has a high priority. const auto pull_over_path_candidates = thread_safe_data_.get_pull_over_path_candidates(); @@ -2518,6 +2537,24 @@ void GoalPlannerModule::setDebugData() // Visualize goal candidates const auto goal_candidates = thread_safe_data_.get_goal_candidates(); add(goal_planner_utils::createGoalCandidatesMarkerArray(goal_candidates, color)); + + // Visualize objects extraction polygon + auto marker = autoware::universe_utils::createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "objects_extraction_polygon", 0, Marker::LINE_LIST, + autoware::universe_utils::createMarkerScale(0.1, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(0.0, 1.0, 1.0, 0.999)); + const double ego_z = planner_data_->self_odometry->pose.pose.position.z; + for (size_t i = 0; i < debug_data_.objects_extraction_polygon.outer().size(); ++i) { + const auto & current_point = debug_data_.objects_extraction_polygon.outer().at(i); + const auto & next_point = debug_data_.objects_extraction_polygon.outer().at( + (i + 1) % debug_data_.objects_extraction_polygon.outer().size()); + marker.points.push_back( + autoware::universe_utils::createPoint(current_point.x(), current_point.y(), ego_z)); + marker.points.push_back( + autoware::universe_utils::createPoint(next_point.x(), next_point.y(), ego_z)); + } + + debug_marker_.markers.push_back(marker); } // Visualize previous module output 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 9137e71accf87..2d49f930c2692 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 @@ -97,9 +97,7 @@ GoalSearcher::GoalSearcher( { } -GoalCandidates GoalSearcher::search( - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) +GoalCandidates GoalSearcher::search(const std::shared_ptr & planner_data) { GoalCandidates goal_candidates{}; @@ -193,8 +191,6 @@ GoalCandidates GoalSearcher::search( } createAreaPolygons(original_search_poses, planner_data); - update(goal_candidates, occupancy_grid_map, planner_data); - return goal_candidates; } @@ -268,16 +264,10 @@ void GoalSearcher::countObjectsToAvoid( void GoalSearcher::update( GoalCandidates & goal_candidates, const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const + const std::shared_ptr & planner_data, const PredictedObjects & objects) const { - const auto pull_over_lane_stop_objects = - goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, - parameters_.forward_goal_search_length, parameters_.detection_bound_offset, - *(planner_data->dynamic_object), parameters_.th_moving_object_velocity); - if (parameters_.prioritize_goals_before_objects) { - countObjectsToAvoid(goal_candidates, pull_over_lane_stop_objects, planner_data); + countObjectsToAvoid(goal_candidates, objects, planner_data); } if (parameters_.goal_priority == "minimum_weighted_distance") { @@ -297,7 +287,7 @@ void GoalSearcher::update( const Pose goal_pose = goal_candidate.goal_pose; // check collision with footprint - if (checkCollision(goal_pose, pull_over_lane_stop_objects, occupancy_grid_map)) { + if (checkCollision(goal_pose, objects, occupancy_grid_map)) { goal_candidate.is_safe = false; continue; } @@ -305,7 +295,7 @@ void GoalSearcher::update( // check longitudinal margin with pull over lane objects constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( - goal_pose, planner_data->parameters.vehicle_width, pull_over_lane_stop_objects, + goal_pose, planner_data->parameters.vehicle_width, objects, parameters_.object_recognition_collision_check_hard_margins.back(), filter_inside); if (checkCollisionWithLongitudinalDistance( goal_pose, target_objects, occupancy_grid_map, planner_data)) { @@ -323,33 +313,25 @@ void GoalSearcher::update( bool GoalSearcher::isSafeGoalWithMarginScaleFactor( const GoalCandidate & goal_candidate, const double margin_scale_factor, const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const + const std::shared_ptr & planner_data, const PredictedObjects & objects) const { if (!parameters_.use_object_recognition) { return true; } const Pose goal_pose = goal_candidate.goal_pose; - - const auto pull_over_lane_stop_objects = - goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, - parameters_.forward_goal_search_length, parameters_.detection_bound_offset, - *(planner_data->dynamic_object), parameters_.th_moving_object_velocity); - const double margin = parameters_.object_recognition_collision_check_hard_margins.back() * margin_scale_factor; if (utils::checkCollisionBetweenFootprintAndObjects( - vehicle_footprint_, goal_pose, pull_over_lane_stop_objects, margin)) { + vehicle_footprint_, goal_pose, objects, margin)) { return false; } // check longitudinal margin with pull over lane objects constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( - goal_pose, planner_data->parameters.vehicle_width, pull_over_lane_stop_objects, margin, - filter_inside); + goal_pose, planner_data->parameters.vehicle_width, objects, margin, filter_inside); if (checkCollisionWithLongitudinalDistance( goal_pose, target_objects, occupancy_grid_map, planner_data)) { return false; 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 6bceec531b653..ecb0b1be4e83e 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 @@ -39,6 +39,7 @@ namespace autoware::behavior_path_planner::goal_planner_utils { +using autoware::universe_utils::calcDistance2d; using autoware::universe_utils::calcOffsetPose; using autoware::universe_utils::createDefaultMarker; using autoware::universe_utils::createMarkerColor; @@ -138,6 +139,126 @@ lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes( -outer_road_offset); } +std::optional generateObjectExtractionPolygon( + const lanelet::ConstLanelets & pull_over_lanes, const bool left_side, const double outer_offset, + const double inner_offset) +{ + // generate base boundary poses without orientation + std::vector base_boundary_poses{}; + for (const auto & lane : pull_over_lanes) { + const auto & bound = left_side ? lane.leftBound() : lane.rightBound(); + for (const auto & p : bound) { + Pose pose{}; + pose.position = createPoint(p.x(), p.y(), p.z()); + if (std::any_of(base_boundary_poses.begin(), base_boundary_poses.end(), [&](const auto & p) { + return calcDistance2d(p.position, pose.position) < 0.1; + })) { + continue; + } + base_boundary_poses.push_back(pose); + } + } + if (base_boundary_poses.size() < 2) { + return std::nullopt; + } + + // set orientation to next point + for (auto it = base_boundary_poses.begin(); it != std::prev(base_boundary_poses.end()); ++it) { + const auto & p = it->position; + const auto & next_p = std::next(it)->position; + const double yaw = autoware::universe_utils::calcAzimuthAngle(p, next_p); + it->orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); + } + base_boundary_poses.back().orientation = + base_boundary_poses[base_boundary_poses.size() - 2].orientation; + + // generate outer and inner boundary poses + std::vector outer_boundary_points{}; + std::vector inner_boundary_points{}; + const double outer_direction_sign = left_side ? 1.0 : -1.0; + for (const auto & base_pose : base_boundary_poses) { + const Pose outer_pose = calcOffsetPose(base_pose, 0, outer_direction_sign * outer_offset, 0); + const Pose inner_pose = calcOffsetPose(base_pose, 0, -outer_direction_sign * inner_offset, 0); + outer_boundary_points.push_back(outer_pose.position); + inner_boundary_points.push_back(inner_pose.position); + } + + // remove self intersection + // if bound is intersected, remove them and insert intersection point + using BoostPoint = boost::geometry::model::d2::point_xy; + using LineString = boost::geometry::model::linestring; + const auto remove_self_intersection = [](const std::vector & bound) { + constexpr double INTERSECTION_CHECK_DISTANCE = 10.0; + std::vector modified_bound{}; + size_t i = 0; + while (i < bound.size() - 2) { + BoostPoint p1(bound.at(i).x, bound.at(i).y); + BoostPoint p2(bound.at(i + 1).x, bound.at(i + 1).y); + LineString p_line{}; + p_line.push_back(p1); + p_line.push_back(p2); + bool intersection_found = false; + for (size_t j = i + 2; j < bound.size() - 1; j++) { + const double distance = autoware::universe_utils::calcDistance2d(bound.at(i), bound.at(j)); + if (distance > INTERSECTION_CHECK_DISTANCE) { + break; + } + LineString q_line{}; + BoostPoint q1(bound.at(j).x, bound.at(j).y); + BoostPoint q2(bound.at(j + 1).x, bound.at(j + 1).y); + q_line.push_back(q1); + q_line.push_back(q2); + std::vector intersection_points; + boost::geometry::intersection(p_line, q_line, intersection_points); + if (intersection_points.empty()) { + continue; + } + modified_bound.push_back(bound.at(i)); + Point intersection_point{}; + intersection_point.x = intersection_points.at(0).x(); + intersection_point.y = intersection_points.at(0).y(); + intersection_point.z = bound.at(i).z; + modified_bound.push_back(intersection_point); + i = j + 1; + intersection_found = true; + break; + } + if (!intersection_found) { + modified_bound.push_back(bound.at(i)); + i++; + } + } + modified_bound.push_back(bound.back()); + return modified_bound; + }; + outer_boundary_points = remove_self_intersection(outer_boundary_points); + inner_boundary_points = remove_self_intersection(inner_boundary_points); + + // create clockwise polygon + Polygon2d polygon{}; + const auto & left_boundary_points = left_side ? outer_boundary_points : inner_boundary_points; + const auto & right_boundary_points = left_side ? inner_boundary_points : outer_boundary_points; + std::vector reversed_right_boundary_points = right_boundary_points; + std::reverse(reversed_right_boundary_points.begin(), reversed_right_boundary_points.end()); + for (const auto & left_point : left_boundary_points) { + autoware::universe_utils::Point2d point{left_point.x, left_point.y}; + polygon.outer().push_back(point); + } + for (const auto & right_point : reversed_right_boundary_points) { + autoware::universe_utils::Point2d point{right_point.x, right_point.y}; + polygon.outer().push_back(point); + } + autoware::universe_utils::Point2d first_point{ + left_boundary_points.front().x, left_boundary_points.front().y}; + polygon.outer().push_back(first_point); + + if (polygon.outer().size() < 3) { + return std::nullopt; + } + + return polygon; +} + PredictedObjects extractObjectsInExpandedPullOverLanes( const RouteHandler & route_handler, const bool left_side, const double backward_distance, const double forward_distance, double bound_offset, const PredictedObjects & objects) From c0e92510052e5c18270e8087a4741ecad9887e8d Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 4 Sep 2024 01:52:45 +0900 Subject: [PATCH 112/217] fix(compare_map_segmentation): use squared distance to compare threshold (#8744) fix: use square distance to compare threshold Signed-off-by: yoshiri --- .../src/distance_based_compare_map_filter/node.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 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 53183cd7dc3f0..e5ff8da4e4da9 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 @@ -59,14 +59,14 @@ bool DistanceBasedStaticMapLoader::is_close_to_map( } std::vector nn_indices(1); - std::vector nn_distances(1); + std::vector nn_sqr_distances(1); if (!isFinite(point)) { return false; } - if (!tree_->nearestKSearch(point, 1, nn_indices, nn_distances)) { + if (!tree_->nearestKSearch(point, 1, nn_indices, nn_sqr_distances)) { return false; } - if (nn_distances[0] > distance_threshold) { + if (nn_sqr_distances[0] > distance_threshold * distance_threshold) { return false; } return true; From 3a6c10ca1874f0eac996417dd70fd48136519fc2 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 4 Sep 2024 11:36:03 +0900 Subject: [PATCH 113/217] fix(autoware_behavior_path_planner_common): fix unusedFunction (#8736) fix:unusedFunction Signed-off-by: kobayu858 --- .../interface/scene_module_interface.hpp | 9 +-------- .../interface/scene_module_manager_interface.hpp | 10 +--------- .../src/interface/scene_module_interface.cpp | 9 +++++++++ .../src/interface/scene_module_manager_interface.cpp | 10 ++++++++++ 4 files changed, 21 insertions(+), 17 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 7c15dd691d56f..4420fc320daa5 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 @@ -173,14 +173,7 @@ class SceneModuleInterface /** * @brief Called on the first time when the module goes into RUNNING. */ - void onEntry() - { - RCLCPP_DEBUG(getLogger(), "%s %s", name_.c_str(), __func__); - - stop_reason_ = StopReason(); - - processOnEntry(); - } + void onEntry(); /** * @brief Called when the module exit from RUNNING. 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 5aa413f05a893..0e49fc60920c4 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 @@ -57,15 +57,7 @@ class SceneModuleManagerInterface virtual void init(rclcpp::Node * node) = 0; - void updateIdleModuleInstance() - { - if (idle_module_ptr_) { - idle_module_ptr_->onEntry(); - return; - } - - idle_module_ptr_ = createNewSceneModuleInstance(); - } + void updateIdleModuleInstance(); bool isExecutionRequested(const BehaviorModuleOutput & previous_module_output) const { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp index b682203d3177f..580b9c73888b6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp @@ -21,4 +21,13 @@ void SceneModuleInterface::setDrivableLanes(const std::vector & d drivable_lanes_marker_ = marker_utils::createDrivableLanesMarkerArray(drivable_lanes, "drivable_lanes"); } + +void SceneModuleInterface::onEntry() +{ + RCLCPP_DEBUG(getLogger(), "%s %s", name_.c_str(), __func__); + + stop_reason_ = StopReason(); + + processOnEntry(); +} } // namespace autoware::behavior_path_planner 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 b83967f41d3da..535e5cff43e33 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 @@ -70,4 +70,14 @@ void SceneModuleManagerInterface::initInterface( node_ = node; } } + +void SceneModuleManagerInterface::updateIdleModuleInstance() +{ + if (idle_module_ptr_) { + idle_module_ptr_->onEntry(); + return; + } + + idle_module_ptr_ = createNewSceneModuleInstance(); +} } // namespace autoware::behavior_path_planner From 649aecac92284800ac766e1b46be9bb3a5545859 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 4 Sep 2024 11:43:11 +0900 Subject: [PATCH 114/217] fix(static_obstacle_avoidance): ignore objects which has already been decided to avoid (#8754) Signed-off-by: satoshi-ota --- .../src/debug.cpp | 1 + .../src/shift_line_generator.cpp | 12 +++++++++++- 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index 536e350e50bf1..5c1dbd364da90 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -561,6 +561,7 @@ MarkerArray createDebugMarkerArray( addObjects(data.other_objects, ObjectInfo::DEVIATING_FROM_EGO_LANE); addObjects(data.other_objects, ObjectInfo::UNSTABLE_OBJECT); addObjects(data.other_objects, ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE); + addObjects(data.other_objects, ObjectInfo::INVALID_SHIFT_LINE); } if (parameters->enable_shift_line_marker) { 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 e9950b56ce174..10d003fcad90f 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 @@ -248,6 +248,11 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( return s.start_longitudinal > 0.0 && s.start_longitudinal < s.end_longitudinal; }; + const auto is_approved = [this](const auto & object) { + return (helper_->getShift(object.getPosition()) > 0.0 && isOnRight(object)) || + (helper_->getShift(object.getPosition()) < 0.0 && !isOnRight(object)); + }; + ObjectDataArray unavoidable_objects; // target objects are sorted by longitudinal distance. @@ -284,6 +289,11 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( // calculate feasible shift length based on behavior policy const auto feasible_shift_profile = get_shift_profile(o, desire_shift_length); if (!feasible_shift_profile.has_value()) { + if (is_approved(o)) { + // the avoidance path for this object has already approved + o.is_avoidable = true; + continue; + } if (o.avoid_required && is_forward_object(o) && is_on_path(o)) { break; } else { @@ -394,7 +404,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( outlines.emplace_back(al_avoid, std::nullopt); } else if (is_valid_shift_line(al_avoid) && is_valid_shift_line(al_return)) { outlines.emplace_back(al_avoid, al_return); - } else { + } else if (!is_approved(o)) { o.info = ObjectInfo::INVALID_SHIFT_LINE; continue; } From a6f218a050f004bd33d90ec72b582da50eafa698 Mon Sep 17 00:00:00 2001 From: Mukunda Bharatheesha Date: Wed, 4 Sep 2024 08:03:37 +0200 Subject: [PATCH 115/217] fix(autoware_obstacle_stop_planner): register obstacle stop planner node with autoware scoping (#8512) Register node plugin with autoware scoping Signed-off-by: Mukunda Bharatheesha --- .../lane_driving/motion_planning/motion_planning.launch.xml | 2 +- planning/autoware_obstacle_stop_planner/CMakeLists.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) 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 63353459fa16c..b303134ab80c3 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 @@ -179,7 +179,7 @@ - + diff --git a/planning/autoware_obstacle_stop_planner/CMakeLists.txt b/planning/autoware_obstacle_stop_planner/CMakeLists.txt index 9e663820b02f1..4026fa1626388 100644 --- a/planning/autoware_obstacle_stop_planner/CMakeLists.txt +++ b/planning/autoware_obstacle_stop_planner/CMakeLists.txt @@ -25,7 +25,7 @@ target_link_libraries(${PROJECT_NAME} ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "motion_planning::ObstacleStopPlannerNode" + PLUGIN "autoware::motion_planning::ObstacleStopPlannerNode" EXECUTABLE ${PROJECT_NAME}_node ) From 6d0a454f667960790fc2b2583699394739e6cf10 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 4 Sep 2024 18:31:36 +0900 Subject: [PATCH 116/217] feat(behavior_planning): update test map for BusStopArea and bicycle_lanes (#8694) Signed-off-by: Mamoru Sobue --- .../CMakeLists.txt | 2 +- .../test_map/road_shoulder/lanelet2_map.osm | 93 +- .../test_map/intersection/lanelet2_map.osm | 7112 +++++++++-------- 3 files changed, 3805 insertions(+), 3402 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt index 2c2dd723d9e3e..4a2891e116cc8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt @@ -58,4 +58,4 @@ if(BUILD_TESTING) ) endif() -ament_auto_package() +ament_auto_package(INSTALL_TO_SHARE test_map) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test_map/road_shoulder/lanelet2_map.osm b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test_map/road_shoulder/lanelet2_map.osm index 53954c3ca47aa..8539aec143d67 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test_map/road_shoulder/lanelet2_map.osm +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test_map/road_shoulder/lanelet2_map.osm @@ -1,6 +1,6 @@ - + @@ -6793,6 +6793,66 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -9012,6 +9072,25 @@ + + + + + + + + + + + + + + + + + + + @@ -9042,6 +9121,7 @@ + @@ -9963,6 +10043,7 @@ + @@ -9974,4 +10055,14 @@ + + + + + + + + + + diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test_map/intersection/lanelet2_map.osm b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test_map/intersection/lanelet2_map.osm index f6ed497461c2e..70ebd23ae88ee 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test_map/intersection/lanelet2_map.osm +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test_map/intersection/lanelet2_map.osm @@ -1,6 +1,6 @@ - + @@ -7139,5793 +7139,5958 @@ - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - + - - + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - - - - - - - - - - - - - - - - - - - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -17803,6 +17968,85 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -17928,10 +18172,6 @@ - - - - @@ -19766,6 +20006,78 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 0efb3159054e736476a3b9a683f4c8f743c0e578 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Wed, 4 Sep 2024 18:36:11 +0900 Subject: [PATCH 117/217] fix(pid_longitudinal_controller): fix the same point error (#8758) * fix same point Signed-off-by: Yuki Takagi --- .../src/pid_longitudinal_controller.cpp | 2 ++ 1 file changed, 2 insertions(+) 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 96e2796a91d22..e3cdc4505c037 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -507,6 +507,8 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData // calculate the target motion for delay compensation constexpr double min_running_dist = 0.01; if (control_data.state_after_delay.running_distance > min_running_dist) { + control_data.interpolated_traj.points = + autoware::motion_utils::removeOverlapPoints(control_data.interpolated_traj.points); const auto target_pose = longitudinal_utils::findTrajectoryPoseAfterDistance( control_data.nearest_idx, control_data.state_after_delay.running_distance, control_data.interpolated_traj); From 223d06a988e6435cdaa279278632fa92e8a8eb42 Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Wed, 4 Sep 2024 22:50:06 +0900 Subject: [PATCH 118/217] feat(perception_utils)!: move perception_utils from common to perception folder (#8748) feat: move perception utils which is only used in perception Signed-off-by: yoshiri Co-authored-by: yoshiri --- {common => perception}/perception_utils/CMakeLists.txt | 0 {common => perception}/perception_utils/README.md | 0 .../include/perception_utils/prime_synchronizer.hpp | 0 .../include/perception_utils/run_length_encoder.hpp | 0 {common => perception}/perception_utils/package.xml | 0 .../perception_utils/src/run_length_encoder.cpp | 0 6 files changed, 0 insertions(+), 0 deletions(-) rename {common => perception}/perception_utils/CMakeLists.txt (100%) rename {common => perception}/perception_utils/README.md (100%) rename {common => perception}/perception_utils/include/perception_utils/prime_synchronizer.hpp (100%) rename {common => perception}/perception_utils/include/perception_utils/run_length_encoder.hpp (100%) rename {common => perception}/perception_utils/package.xml (100%) rename {common => perception}/perception_utils/src/run_length_encoder.cpp (100%) diff --git a/common/perception_utils/CMakeLists.txt b/perception/perception_utils/CMakeLists.txt similarity index 100% rename from common/perception_utils/CMakeLists.txt rename to perception/perception_utils/CMakeLists.txt diff --git a/common/perception_utils/README.md b/perception/perception_utils/README.md similarity index 100% rename from common/perception_utils/README.md rename to perception/perception_utils/README.md diff --git a/common/perception_utils/include/perception_utils/prime_synchronizer.hpp b/perception/perception_utils/include/perception_utils/prime_synchronizer.hpp similarity index 100% rename from common/perception_utils/include/perception_utils/prime_synchronizer.hpp rename to perception/perception_utils/include/perception_utils/prime_synchronizer.hpp diff --git a/common/perception_utils/include/perception_utils/run_length_encoder.hpp b/perception/perception_utils/include/perception_utils/run_length_encoder.hpp similarity index 100% rename from common/perception_utils/include/perception_utils/run_length_encoder.hpp rename to perception/perception_utils/include/perception_utils/run_length_encoder.hpp diff --git a/common/perception_utils/package.xml b/perception/perception_utils/package.xml similarity index 100% rename from common/perception_utils/package.xml rename to perception/perception_utils/package.xml diff --git a/common/perception_utils/src/run_length_encoder.cpp b/perception/perception_utils/src/run_length_encoder.cpp similarity index 100% rename from common/perception_utils/src/run_length_encoder.cpp rename to perception/perception_utils/src/run_length_encoder.cpp From 1ae6082995d3e66b1662b0e933462881df6a6a36 Mon Sep 17 00:00:00 2001 From: oguzkaganozt Date: Wed, 4 Sep 2024 17:19:04 +0300 Subject: [PATCH 119/217] refactor(evaluator/localization_evaluator): rework parameters (#6744) * add param file and schema Signed-off-by: oguzkaganozt * style(pre-commit): autofix * . Signed-off-by: Oguz Ozturk * . Signed-off-by: Oguz Ozturk * . Signed-off-by: Oguz Ozturk --------- Signed-off-by: oguzkaganozt Signed-off-by: Oguz Ozturk Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../localization_evaluator/CMakeLists.txt | 2 +- evaluator/localization_evaluator/README.md | 6 +++- .../localization_evaluator.param.yaml} | 0 .../launch/localization_evaluator.launch.xml | 2 +- .../schema/localization_evaluator.schema.json | 35 +++++++++++++++++++ .../test/test_localization_evaluator_node.cpp | 2 +- 6 files changed, 43 insertions(+), 4 deletions(-) rename evaluator/localization_evaluator/{param/localization_evaluator.defaults.yaml => config/localization_evaluator.param.yaml} (100%) create mode 100644 evaluator/localization_evaluator/schema/localization_evaluator.schema.json diff --git a/evaluator/localization_evaluator/CMakeLists.txt b/evaluator/localization_evaluator/CMakeLists.txt index d465e78801953..0cdcc420eb797 100644 --- a/evaluator/localization_evaluator/CMakeLists.txt +++ b/evaluator/localization_evaluator/CMakeLists.txt @@ -40,6 +40,6 @@ endif() ament_auto_package( INSTALL_TO_SHARE - param + config launch ) diff --git a/evaluator/localization_evaluator/README.md b/evaluator/localization_evaluator/README.md index 1aada473d8e56..18d887e075be1 100644 --- a/evaluator/localization_evaluator/README.md +++ b/evaluator/localization_evaluator/README.md @@ -1,3 +1,7 @@ # Localization Evaluator -TBD +The Localization Evaluator evaluates the performance of the localization system and provides metrics + +## Parameters + +{{ json_to_markdown("evaluator/localization_evaluator/schema/localization_evaluator.schema.json") }} diff --git a/evaluator/localization_evaluator/param/localization_evaluator.defaults.yaml b/evaluator/localization_evaluator/config/localization_evaluator.param.yaml similarity index 100% rename from evaluator/localization_evaluator/param/localization_evaluator.defaults.yaml rename to evaluator/localization_evaluator/config/localization_evaluator.param.yaml diff --git a/evaluator/localization_evaluator/launch/localization_evaluator.launch.xml b/evaluator/localization_evaluator/launch/localization_evaluator.launch.xml index 30232e917bfa6..f8595f9d23c37 100644 --- a/evaluator/localization_evaluator/launch/localization_evaluator.launch.xml +++ b/evaluator/localization_evaluator/launch/localization_evaluator.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/evaluator/localization_evaluator/schema/localization_evaluator.schema.json b/evaluator/localization_evaluator/schema/localization_evaluator.schema.json new file mode 100644 index 0000000000000..f186e569e8f4d --- /dev/null +++ b/evaluator/localization_evaluator/schema/localization_evaluator.schema.json @@ -0,0 +1,35 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Localization Evaluator", + "type": "object", + "definitions": { + "localization_evaluator": { + "type": "object", + "properties": { + "output_file": { + "type": "string", + "default": "loc_metrics.results", + "description": "if empty, metrics are not written to file" + }, + "selected_metrics": { + "type": "array", + "default": "['lateral_error', 'absolute_error']", + "description": "metrics to be calculated" + } + }, + "required": ["output_file", "selected_metrics"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/localization_evaluator" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp b/evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp index 4fbc88294d26c..cd6a7b80fd35b 100644 --- a/evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp +++ b/evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp @@ -47,7 +47,7 @@ class EvalTest : public ::testing::Test rclcpp::NodeOptions options; const auto share_dir = ament_index_cpp::get_package_share_directory("localization_evaluator"); options.arguments( - {"--ros-args", "--params-file", share_dir + "/param/localization_evaluator.defaults.yaml"}); + {"--ros-args", "--params-file", share_dir + "/config/localization_evaluator.param.yaml"}); dummy_node = std::make_shared("localization_evaluator_test_node"); eval_node = std::make_shared(options); From 959fddf72fb9f66b37ce296b65a33292c459c915 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 5 Sep 2024 10:20:26 +0900 Subject: [PATCH 120/217] fix(autoware_shape_estimation): fix unusedFunction (#8575) * fix:unusedFunction Signed-off-by: kobayu858 * fix:unusedFunction Signed-off-by: kobayu858 * fix:end of file issues Signed-off-by: kobayu858 * fix:copyright Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../autoware_shape_estimation/CMakeLists.txt | 2 ++ .../reference_shape_size_corrector.hpp | 5 +-- .../corrector/vehicle_corrector.hpp | 11 +----- .../reference_shape_size_corrector.cpp | 28 +++++++++++++++ .../lib/corrector/vehicle_corrector.cpp | 35 +++++++++++++++++++ 5 files changed, 67 insertions(+), 14 deletions(-) create mode 100644 perception/autoware_shape_estimation/lib/corrector/reference_shape_size_corrector.cpp create mode 100644 perception/autoware_shape_estimation/lib/corrector/vehicle_corrector.cpp diff --git a/perception/autoware_shape_estimation/CMakeLists.txt b/perception/autoware_shape_estimation/CMakeLists.txt index 96bf946ab11db..56f14ad9d2b48 100644 --- a/perception/autoware_shape_estimation/CMakeLists.txt +++ b/perception/autoware_shape_estimation/CMakeLists.txt @@ -33,6 +33,8 @@ set(${PROJECT_NAME}_SOURCES lib/filter/utils.cpp lib/corrector/utils.cpp lib/corrector/no_corrector.cpp + lib/corrector/vehicle_corrector.cpp + lib/corrector/reference_shape_size_corrector.cpp ) if(${CUDA_FOUND} AND ${CUDNN_FOUND} AND ${TENSORRT_FOUND}) diff --git a/perception/autoware_shape_estimation/include/autoware/shape_estimation/corrector/reference_shape_size_corrector.hpp b/perception/autoware_shape_estimation/include/autoware/shape_estimation/corrector/reference_shape_size_corrector.hpp index a05027a3348b6..7efa45a775c64 100644 --- a/perception/autoware_shape_estimation/include/autoware/shape_estimation/corrector/reference_shape_size_corrector.hpp +++ b/perception/autoware_shape_estimation/include/autoware/shape_estimation/corrector/reference_shape_size_corrector.hpp @@ -37,10 +37,7 @@ class ReferenceShapeBasedVehicleCorrector : public ShapeEstimationCorrectorInter virtual ~ReferenceShapeBasedVehicleCorrector() = default; bool correct( - autoware_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) override - { - return corrector_utils::correctWithReferenceYawAndShapeSize(ref_shape_size_info_, shape, pose); - } + autoware_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) override; }; } // namespace corrector diff --git a/perception/autoware_shape_estimation/include/autoware/shape_estimation/corrector/vehicle_corrector.hpp b/perception/autoware_shape_estimation/include/autoware/shape_estimation/corrector/vehicle_corrector.hpp index e1b292eb5318a..45a14e8aac74d 100644 --- a/perception/autoware_shape_estimation/include/autoware/shape_estimation/corrector/vehicle_corrector.hpp +++ b/perception/autoware_shape_estimation/include/autoware/shape_estimation/corrector/vehicle_corrector.hpp @@ -38,16 +38,7 @@ class VehicleCorrector : public ShapeEstimationCorrectorInterface virtual ~VehicleCorrector() = default; bool correct( - autoware_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) override - { - // Guard - if (!params_) return false; - - if (use_reference_yaw_) - return corrector_utils::correctWithReferenceYaw(params_.get(), shape, pose); - else - return correctWithDefaultValue(params_.get(), shape, pose); - } + autoware_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) override; void setParams(const corrector_utils::CorrectionBBParameters & params) { params_ = params; } }; diff --git a/perception/autoware_shape_estimation/lib/corrector/reference_shape_size_corrector.cpp b/perception/autoware_shape_estimation/lib/corrector/reference_shape_size_corrector.cpp new file mode 100644 index 0000000000000..3eff18221856f --- /dev/null +++ b/perception/autoware_shape_estimation/lib/corrector/reference_shape_size_corrector.cpp @@ -0,0 +1,28 @@ +// 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/shape_estimation/corrector/reference_shape_size_corrector.hpp" + +namespace autoware::shape_estimation +{ +namespace corrector +{ +bool ReferenceShapeBasedVehicleCorrector::correct( + autoware_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) +{ + return corrector_utils::correctWithReferenceYawAndShapeSize(ref_shape_size_info_, shape, pose); +} + +} // namespace corrector +} // namespace autoware::shape_estimation diff --git a/perception/autoware_shape_estimation/lib/corrector/vehicle_corrector.cpp b/perception/autoware_shape_estimation/lib/corrector/vehicle_corrector.cpp new file mode 100644 index 0000000000000..795e5112c7cf2 --- /dev/null +++ b/perception/autoware_shape_estimation/lib/corrector/vehicle_corrector.cpp @@ -0,0 +1,35 @@ +// 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/shape_estimation/corrector/vehicle_corrector.hpp" + +namespace autoware::shape_estimation +{ +namespace corrector + +{ +bool VehicleCorrector::correct( + autoware_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) +{ + // Guard + if (!params_) return false; + + if (use_reference_yaw_) + return corrector_utils::correctWithReferenceYaw(params_.get(), shape, pose); + else + return corrector_utils::correctWithDefaultValue(params_.get(), shape, pose); +} + +} // namespace corrector +} // namespace autoware::shape_estimation From 47214da2611c1ade509f81da40d307af27741f16 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 5 Sep 2024 11:28:24 +0900 Subject: [PATCH 121/217] fix(goal_planner): fix typo (#8763) Signed-off-by: Fumiya Watanabe --- .../src/goal_planner_module.cpp | 2 +- 1 file changed, 1 insertion(+), 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 92e15c2c4aee4..f8195ecfea7ec 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 @@ -459,7 +459,7 @@ void GoalPlannerModule::updateData() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - // extract static and dynamic objects in extraction polygon for path coliision check + // extract static and dynamic objects in extraction polygon for path collision check { const auto & p = parameters_; const auto & rh = *(planner_data_->route_handler); From f02bd5d18abcfdadea7fec97ff5b5df72311d29c Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 5 Sep 2024 11:48:57 +0900 Subject: [PATCH 122/217] fix(pointcloud_preprocessor): fix typo (#8762) Signed-off-by: Fumiya Watanabe --- .../launch/vector_map_inside_area_filter_node.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml index 21eded98595ba..795234e185cdd 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml @@ -1,7 +1,7 @@ - + @@ -9,6 +9,6 @@ - + From 98e2a716dd007898c4b552ed7f78a132819f5e0b Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 5 Sep 2024 12:03:05 +0900 Subject: [PATCH 123/217] fix(autoware_motion_utils): fix unusedFunction (#8733) refactor:remove Path/Trajectory length calculation between designated points Signed-off-by: kobayu858 --- common/autoware_motion_utils/README.md | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/common/autoware_motion_utils/README.md b/common/autoware_motion_utils/README.md index df4808a6f68d7..993ec7a3ea7c3 100644 --- a/common/autoware_motion_utils/README.md +++ b/common/autoware_motion_utils/README.md @@ -97,19 +97,6 @@ const size_t traffic_obj_nearest_idx = findNearestIndexFromLaneId(path_with_lane const size_t traffic_obj_nearest_seg_idx = findNearestSegmentIndexFromLaneId(path_with_lane_id, traffic_obj_pos, lane_id); ``` -## Path/Trajectory length calculation between designated points - -Based on the discussion so far, the nearest index search algorithm is different depending on the object type. -Therefore, we recommended using the wrapper utility functions which require the nearest index search (e.g., calculating the path length) with each nearest index search. - -For example, when we want to calculate the path length between the ego and the dynamic object, the implementation is as follows. - -```cpp -const size_t ego_nearest_seg_idx = findFirstNearestSegmentIndex(points, ego_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); -const size_t dyn_obj_nearest_seg_idx = findFirstNearestSegmentIndex(points, dyn_obj_pose, dyn_obj_nearest_dist_threshold); -const double length_from_ego_to_obj = calcSignedArcLength(points, ego_pose, ego_nearest_seg_idx, dyn_obj_pose, dyn_obj_nearest_seg_idx); -``` - ## For developers Some of the template functions in `trajectory.hpp` are mostly used for specific types (`autoware_planning_msgs::msg::PathPoint`, `autoware_planning_msgs::msg::PathPoint`, `autoware_planning_msgs::msg::TrajectoryPoint`), so they are exported as `extern template` functions to speed-up compilation time. From 4cc1f75374eebc52c5a81bee208f107101c5e604 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 5 Sep 2024 12:43:04 +0900 Subject: [PATCH 124/217] fix(autoware_behavior_path_lane_change_module): fix unusedFunction (#8653) fix:unusedFunction Signed-off-by: kobayu858 --- .../utils/utils.hpp | 11 ----- .../src/utils/utils.cpp | 45 ------------------- 2 files changed, 56 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 ca13318aeeb81..83043aa061f81 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 @@ -97,11 +97,6 @@ std::vector> getSortedLaneIds( const RouteHandler & route_handler, const Pose & current_pose, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes); -lanelet::ConstLanelets getTargetPreferredLanes( - const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, const Direction & direction, - const LaneChangeModuleType & type); - lanelet::ConstLanelets getTargetNeighborLanes( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const LaneChangeModuleType & type); @@ -146,12 +141,6 @@ bool hasEnoughLengthToLaneChangeAfterAbort( const Pose & curent_pose, const double abort_return_dist, const LaneChangeParameters & lane_change_parameters, const Direction direction); -double calcLateralBufferForFiltering(const double vehicle_width, const double lateral_buffer = 0.0); - -double calcLateralBufferForFiltering(const double vehicle_width, const double lateral_buffer); - -std::string getStrDirection(const std::string & name, const Direction direction); - CandidateOutput assignToCandidate( const LaneChangePath & lane_change_path, const Point & ego_position); std::optional getLaneChangeTargetLane( 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 e4a482def7b3d..297d04a657cea 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 @@ -240,35 +240,6 @@ std::vector getAccelerationValues( return sampled_values; } -lanelet::ConstLanelets getTargetPreferredLanes( - const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, const Direction & direction, - const LaneChangeModuleType & type) -{ - if (type != LaneChangeModuleType::NORMAL) { - return target_lanes; - } - - const auto target_lane = - utils::lane_change::getLaneChangeTargetLane(route_handler, current_lanes, type, direction); - if (!target_lane) { - return target_lanes; - } - - const auto itr = std::find_if( - target_lanes.begin(), target_lanes.end(), - [&](const lanelet::ConstLanelet & lane) { return lane.id() == target_lane->id(); }); - - if (itr == target_lanes.end()) { - return target_lanes; - } - - const int target_id = std::distance(target_lanes.begin(), itr); - const lanelet::ConstLanelets target_preferred_lanes( - target_lanes.begin() + target_id, target_lanes.end()); - return target_preferred_lanes; -} - lanelet::ConstLanelets getTargetNeighborLanes( const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const LaneChangeModuleType & type) @@ -671,22 +642,6 @@ bool hasEnoughLengthToLaneChangeAfterAbort( return true; } -double calcLateralBufferForFiltering(const double vehicle_width, const double lateral_buffer) -{ - return lateral_buffer + 0.5 * vehicle_width; -} - -std::string getStrDirection(const std::string & name, const Direction direction) -{ - if (direction == Direction::LEFT) { - return name + "_left"; - } - if (direction == Direction::RIGHT) { - return name + "_right"; - } - return ""; -} - std::vector> getSortedLaneIds( const RouteHandler & route_handler, const Pose & current_pose, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) From 6b6708cf08a49037c0130de7bc8e1e5f13827a7a Mon Sep 17 00:00:00 2001 From: beyzanurkaya <32412808+beyzanurkaya@users.noreply.github.com> Date: Thu, 5 Sep 2024 09:58:35 +0300 Subject: [PATCH 125/217] feat(autoware_behavior_path_dynamic_obstacle_avoidance): expand drivable area (#8295) * add expansion drivable area feature Signed-off-by: beyza * make expansion optional Signed-off-by: beyza * style(pre-commit): autofix * clean the code Signed-off-by: beyza * style(pre-commit): autofix --------- Signed-off-by: beyza Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../dynamic_obstacle_avoidance.param.yaml | 1 + .../scene.hpp | 12 ++ .../package.xml | 5 + .../src/manager.cpp | 2 + .../src/scene.cpp | 194 +++++++++++++++++- 5 files changed, 210 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/config/dynamic_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/config/dynamic_obstacle_avoidance.param.yaml index c1f4646ef7736..3236bf8d0ade7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/config/dynamic_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/config/dynamic_obstacle_avoidance.param.yaml @@ -51,6 +51,7 @@ max_object_vel: 0.5 # [m/s] The object will be determined as stopped if the velocity is smaller than this value. drivable_area_generation: + expand_drivable_area: false polygon_generation_method: "ego_path_base" # choose "ego_path_base" and "object_path_base" object_path_base: min_longitudinal_polygon_margin: 3.0 # [m] 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 48c6084a4f424..d02648f4ccfd4 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 @@ -95,6 +95,8 @@ struct DynamicAvoidanceParameters bool enable_debug_info{true}; bool use_hatched_road_markings{true}; + std::string use_lane_type{"opposite_direction_lane"}; + // obstacle types to avoid bool avoid_car{true}; bool avoid_truck{true}; @@ -130,6 +132,7 @@ struct DynamicAvoidanceParameters // drivable area generation PolygonGenerationMethod polygon_generation_method{}; + bool expand_drivable_area; double min_obj_path_based_lon_polygon_margin{0.0}; double lat_offset_from_obstacle{0.0}; double margin_distance_around_pedestrian{0.0}; @@ -169,6 +172,10 @@ struct LatFeasiblePaths class DynamicObstacleAvoidanceModule : public SceneModuleInterface { public: + static constexpr const char * logger_namespace = + "planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.dynamic_" + "obstacle_avoidance"; + struct DynamicAvoidanceObject { DynamicAvoidanceObject( @@ -439,6 +446,11 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface std::optional calcPredictedPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object, const EgoPathReservePoly & ego_path_poly) const; EgoPathReservePoly calcEgoPathReservePoly(const PathWithLaneId & ego_path) const; + lanelet::ConstLanelets getCurrentLanesFromPath( + const PathWithLaneId & path, const std::shared_ptr & planner_data); + DrivableLanes generateExpandedDrivableLanes( + const lanelet::ConstLanelet & lanelet, const std::shared_ptr & planner_data, + const std::shared_ptr & parameters); void printIgnoreReason(const std::string & obj_uuid, const std::string & reason) { 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 af9a042cc4a79..5bf00292d061e 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 @@ -30,6 +30,11 @@ pluginlib rclcpp signal_processing + tf2 + tf2_eigen + tf2_geometry_msgs + tf2_ros + tier4_planning_msgs visualization_msgs ament_cmake_ros diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp index cdf878fb62c63..87038e1b2f474 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp @@ -108,6 +108,7 @@ void DynamicObstacleAvoidanceModuleManager::init(rclcpp::Node * node) { // drivable_area_generation const std::string ns = "dynamic_avoidance.drivable_area_generation."; + p.expand_drivable_area = node->declare_parameter(ns + "expand_drivable_area"); p.polygon_generation_method = convertToPolygonGenerationMethod( node->declare_parameter(ns + "polygon_generation_method")); p.min_obj_path_based_lon_polygon_margin = @@ -238,6 +239,7 @@ void DynamicObstacleAvoidanceModuleManager::updateModuleParams( p->polygon_generation_method = convertToPolygonGenerationMethod(polygon_generation_method_str); } + updateParam(parameters, ns + "expand_drivable_area", p->expand_drivable_area); updateParam( parameters, ns + "object_path_base.min_longitudinal_polygon_margin", p->min_obj_path_based_lon_polygon_margin); 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 8aba7d4f0ae93..d91b3fb9aa346 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 @@ -20,6 +20,7 @@ #include "object_recognition_utils/predicted_path_utils.hpp" #include "signal_processing/lowpass_filter_1d.hpp" +#include #include #include @@ -99,6 +100,22 @@ void appendExtractedPolygonMarker( marker_array.markers.push_back(marker); } +bool isEndPointsConnected( + const lanelet::ConstLanelet & left_lane, const lanelet::ConstLanelet & right_lane) +{ + const auto & left_back_point_2d = right_lane.leftBound2d().back().basicPoint(); + const auto & right_back_point_2d = left_lane.rightBound2d().back().basicPoint(); + + constexpr double epsilon = 1e-5; + return (right_back_point_2d - left_back_point_2d).norm() < epsilon; +} + +template +void pushUniqueVector(T & base_vector, const T & additional_vector) +{ + base_vector.insert(base_vector.end(), additional_vector.begin(), additional_vector.end()); +} + template std::optional getObjectFromUuid(const std::vector & objects, const std::string & target_uuid) { @@ -384,7 +401,7 @@ void DynamicObstacleAvoidanceModule::updateData() bool DynamicObstacleAvoidanceModule::canTransitSuccessState() { - return target_objects_.empty(); + return planner_data_->dynamic_object->objects.empty(); } BehaviorModuleOutput DynamicObstacleAvoidanceModule::plan() @@ -420,10 +437,19 @@ BehaviorModuleOutput DynamicObstacleAvoidanceModule::plan() appendExtractedPolygonMarker(debug_marker_, obstacle_poly.value(), object.pose.position.z); } } - + // generate drivable lanes DrivableAreaInfo current_drivable_area_info; - current_drivable_area_info.drivable_lanes = - getPreviousModuleOutput().drivable_area_info.drivable_lanes; + if (parameters_->expand_drivable_area) { + auto current_lanelets = + getCurrentLanesFromPath(getPreviousModuleOutput().reference_path, planner_data_); + std::for_each(current_lanelets.begin(), current_lanelets.end(), [&](const auto & lanelet) { + current_drivable_area_info.drivable_lanes.push_back( + generateExpandedDrivableLanes(lanelet, planner_data_, parameters_)); + }); + } else { + current_drivable_area_info.drivable_lanes = + getPreviousModuleOutput().drivable_area_info.drivable_lanes; + } current_drivable_area_info.obstacles = obstacles_for_drivable_area; current_drivable_area_info.enable_expanding_hatched_road_markings = parameters_->use_hatched_road_markings; @@ -1932,4 +1958,164 @@ DynamicObstacleAvoidanceModule::calcEgoPathReservePoly(const PathWithLaneId & eg return {left_avoid_poly, right_avoid_poly}; } +lanelet::ConstLanelets DynamicObstacleAvoidanceModule::getCurrentLanesFromPath( + const PathWithLaneId & path, const std::shared_ptr & planner_data) +{ + if (path.points.empty()) { + throw std::logic_error("empty path."); + } + + const auto idx = planner_data->findEgoIndex(path.points); + + if (path.points.at(idx).lane_ids.empty()) { + throw std::logic_error("empty lane ids."); + } + + const auto start_id = path.points.at(idx).lane_ids.front(); + const auto start_lane = planner_data->route_handler->getLaneletsFromId(start_id); + const auto & p = planner_data->parameters; + + return planner_data->route_handler->getLaneletSequence( + start_lane, p.backward_path_length, p.forward_path_length); +} + +DrivableLanes DynamicObstacleAvoidanceModule::generateExpandedDrivableLanes( + const lanelet::ConstLanelet & lanelet, const std::shared_ptr & planner_data, + const std::shared_ptr & parameters) +{ + const auto & route_handler = planner_data->route_handler; + + DrivableLanes current_drivable_lanes; + current_drivable_lanes.left_lane = lanelet; + current_drivable_lanes.right_lane = lanelet; + + if (parameters->use_lane_type == "current_lane") { + return current_drivable_lanes; + } + + const auto use_opposite_lane = parameters->use_lane_type == "opposite_direction_lane"; + + // 1. get left/right side lanes + const auto update_left_lanelets = [&](const lanelet::ConstLanelet & target_lane) { + const auto all_left_lanelets = + route_handler->getAllLeftSharedLinestringLanelets(target_lane, use_opposite_lane, true); + if (!all_left_lanelets.empty()) { + current_drivable_lanes.left_lane = all_left_lanelets.back(); // leftmost lanelet + pushUniqueVector( + current_drivable_lanes.middle_lanes, + lanelet::ConstLanelets(all_left_lanelets.begin(), all_left_lanelets.end() - 1)); + } + }; + const auto update_right_lanelets = [&](const lanelet::ConstLanelet & target_lane) { + const auto all_right_lanelets = + route_handler->getAllRightSharedLinestringLanelets(target_lane, use_opposite_lane, true); + if (!all_right_lanelets.empty()) { + current_drivable_lanes.right_lane = all_right_lanelets.back(); // rightmost lanelet + pushUniqueVector( + current_drivable_lanes.middle_lanes, + lanelet::ConstLanelets(all_right_lanelets.begin(), all_right_lanelets.end() - 1)); + } + }; + + update_left_lanelets(lanelet); + update_right_lanelets(lanelet); + + // 2.1 when there are multiple lanes whose previous lanelet is the same + const auto get_next_lanes_from_same_previous_lane = + [&route_handler](const lanelet::ConstLanelet & lane) { + // get previous lane, and return false if previous lane does not exist + lanelet::ConstLanelets prev_lanes; + if (!route_handler->getPreviousLaneletsWithinRoute(lane, &prev_lanes)) { + return lanelet::ConstLanelets{}; + } + + lanelet::ConstLanelets next_lanes; + for (const auto & prev_lane : prev_lanes) { + const auto next_lanes_from_prev = route_handler->getNextLanelets(prev_lane); + pushUniqueVector(next_lanes, next_lanes_from_prev); + } + return next_lanes; + }; + + const auto next_lanes_for_right = + get_next_lanes_from_same_previous_lane(current_drivable_lanes.right_lane); + const auto next_lanes_for_left = + get_next_lanes_from_same_previous_lane(current_drivable_lanes.left_lane); + + // 2.2 look for neighbor lane recursively, where end line of the lane is connected to end line + // of the original lane + const auto update_drivable_lanes = + [&](const lanelet::ConstLanelets & next_lanes, const bool is_left) { + for (const auto & next_lane : next_lanes) { + const auto & edge_lane = + is_left ? current_drivable_lanes.left_lane : current_drivable_lanes.right_lane; + if (next_lane.id() == edge_lane.id()) { + continue; + } + + const auto & left_lane = is_left ? next_lane : edge_lane; + const auto & right_lane = is_left ? edge_lane : next_lane; + if (!isEndPointsConnected(left_lane, right_lane)) { + continue; + } + + if (is_left) { + current_drivable_lanes.left_lane = next_lane; + } else { + current_drivable_lanes.right_lane = next_lane; + } + + const auto & middle_lanes = current_drivable_lanes.middle_lanes; + const auto has_same_lane = std::any_of( + middle_lanes.begin(), middle_lanes.end(), + [&edge_lane](const auto & lane) { return lane.id() == edge_lane.id(); }); + + if (!has_same_lane) { + if (is_left) { + if (current_drivable_lanes.right_lane.id() != edge_lane.id()) { + current_drivable_lanes.middle_lanes.push_back(edge_lane); + } + } else { + if (current_drivable_lanes.left_lane.id() != edge_lane.id()) { + current_drivable_lanes.middle_lanes.push_back(edge_lane); + } + } + } + + return true; + } + return false; + }; + + const auto expand_drivable_area_recursively = + [&](const lanelet::ConstLanelets & next_lanes, const bool is_left) { + // NOTE: set max search num to avoid infinity loop for drivable area expansion + constexpr size_t max_recursive_search_num = 3; + for (size_t i = 0; i < max_recursive_search_num; ++i) { + const bool is_update_kept = update_drivable_lanes(next_lanes, is_left); + if (!is_update_kept) { + break; + } + if (i == max_recursive_search_num - 1) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "Drivable area expansion reaches max iteration."); + } + } + }; + expand_drivable_area_recursively(next_lanes_for_right, false); + expand_drivable_area_recursively(next_lanes_for_left, true); + + // 3. update again for new left/right lanes + update_left_lanelets(current_drivable_lanes.left_lane); + update_right_lanelets(current_drivable_lanes.right_lane); + + // 4. compensate that current_lane is in either of left_lane, right_lane or middle_lanes. + if ( + current_drivable_lanes.left_lane.id() != lanelet.id() && + current_drivable_lanes.right_lane.id() != lanelet.id()) { + current_drivable_lanes.middle_lanes.push_back(lanelet); + } + + return current_drivable_lanes; +} } // namespace autoware::behavior_path_planner From 58c99fe21d305301ca32da0e1c0b3affaba8759c Mon Sep 17 00:00:00 2001 From: Mitsuhiro Sakamoto <50359861+mitukou1109@users.noreply.github.com> Date: Thu, 5 Sep 2024 16:03:11 +0900 Subject: [PATCH 126/217] feat(surround_obstacle_checker): integrate generate_parameter_library (#8719) * add generate_parameter_library to package Signed-off-by: mitukou1109 * add parameter file generator script Signed-off-by: mitukou1109 * use mapped parameters Signed-off-by: mitukou1109 * integrate generate_parameter_library Signed-off-by: mitukou1109 * style(pre-commit): autofix * check to use dynamic object Signed-off-by: mitukou1109 * remove default values Signed-off-by: mitukou1109 * fix variable shadowing Signed-off-by: mitukou1109 --------- Signed-off-by: mitukou1109 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CMakeLists.txt | 5 + .../package.xml | 1 + ...ound_obstacle_checker_node_parameters.yaml | 57 +++++++ .../src/node.cpp | 150 ++++++------------ .../src/node.hpp | 29 +--- 5 files changed, 120 insertions(+), 122 deletions(-) create mode 100644 planning/autoware_surround_obstacle_checker/param/surround_obstacle_checker_node_parameters.yaml diff --git a/planning/autoware_surround_obstacle_checker/CMakeLists.txt b/planning/autoware_surround_obstacle_checker/CMakeLists.txt index 141b2c7ce4aa2..1b13843de511c 100644 --- a/planning/autoware_surround_obstacle_checker/CMakeLists.txt +++ b/planning/autoware_surround_obstacle_checker/CMakeLists.txt @@ -13,6 +13,10 @@ include_directories( ${EIGEN3_INCLUDE_DIR} ) +generate_parameter_library(surround_obstacle_checker_node_parameters + param/surround_obstacle_checker_node_parameters.yaml +) + ament_auto_add_library(${PROJECT_NAME} SHARED src/debug_marker.cpp src/node.cpp @@ -20,6 +24,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED target_link_libraries(${PROJECT_NAME} ${PCL_LIBRARIES} + surround_obstacle_checker_node_parameters ) rclcpp_components_register_node(${PROJECT_NAME} diff --git a/planning/autoware_surround_obstacle_checker/package.xml b/planning/autoware_surround_obstacle_checker/package.xml index fb5ea169b9c88..8362962f3dadb 100644 --- a/planning/autoware_surround_obstacle_checker/package.xml +++ b/planning/autoware_surround_obstacle_checker/package.xml @@ -22,6 +22,7 @@ autoware_vehicle_info_utils diagnostic_msgs eigen + generate_parameter_library libpcl-all-dev pcl_conversions rclcpp diff --git a/planning/autoware_surround_obstacle_checker/param/surround_obstacle_checker_node_parameters.yaml b/planning/autoware_surround_obstacle_checker/param/surround_obstacle_checker_node_parameters.yaml new file mode 100644 index 0000000000000..f786b46fb35fa --- /dev/null +++ b/planning/autoware_surround_obstacle_checker/param/surround_obstacle_checker_node_parameters.yaml @@ -0,0 +1,57 @@ +surround_obstacle_checker_node: + pointcloud: + enable_check: + type: bool + description: Enable to check surrounding obstacle + object_types: + type: string_array + default_value: [unknown, car, truck, bus, trailer, motorcycle, bicycle, pedestrian] + __map_object_types: + enable_check: + type: bool + description: Enable to check surrounding obstacle + obstacle_types: + type: string_array + default_value: [pointcloud, unknown, car, truck, bus, trailer, motorcycle, bicycle, pedestrian] + __map_obstacle_types: + surround_check_front_distance: + type: double + description: If objects exist in this distance, transit to 'exist-surrounding-obstacle' status. [m] + validation: + gt_eq<>: [0.0] + surround_check_side_distance: + type: double + description: If objects exist in this distance, transit to 'exist-surrounding-obstacle' status. [m] + validation: + gt_eq<>: [0.0] + surround_check_back_distance: + type: double + description: If objects exist in this distance, transit to 'exist-surrounding-obstacle' status. [m] + validation: + gt_eq<>: [0.0] + surround_check_hysteresis_distance: + type: double + description: + If no object exists in this hysteresis distance added to the above distance, transit to + 'non-surrounding-obstacle' status [m] + validation: + gt_eq<>: [0.0] + state_clear_time: + type: double + description: Threshold to clear stop state [s] + validation: + gt_eq<>: [0.0] + stop_state_ego_speed: + type: double + description: Threshold to check ego vehicle stopped [m/s] + validation: + gt_eq<>: [0.0] + publish_debug_footprints: + type: bool + description: Publish vehicle footprint & footprints with surround_check_distance and + surround_check_recover_distance offsets. + debug_footprint_label: + type: string + description: Select the label for debug footprint + validation: + one_of<>: [[pointcloud, unknown, car, truck, bus, trailer, motorcycle, bicycle, pedestrian]] diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index a3e7088d1e88f..d841e152cd596 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -151,47 +151,14 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio : Node("surround_obstacle_checker_node", node_options) { label_map_ = { - {"unknown", ObjectClassification::UNKNOWN}, {"car", ObjectClassification::CAR}, - {"truck", ObjectClassification::TRUCK}, {"bus", ObjectClassification::BUS}, - {"trailer", ObjectClassification::TRAILER}, {"motorcycle", ObjectClassification::MOTORCYCLE}, - {"bicycle", ObjectClassification::BICYCLE}, {"pedestrian", ObjectClassification::PEDESTRIAN}}; + {ObjectClassification::UNKNOWN, "unknown"}, {ObjectClassification::CAR, "car"}, + {ObjectClassification::TRUCK, "truck"}, {ObjectClassification::BUS, "bus"}, + {ObjectClassification::TRAILER, "trailer"}, {ObjectClassification::MOTORCYCLE, "motorcycle"}, + {ObjectClassification::BICYCLE, "bicycle"}, {ObjectClassification::PEDESTRIAN, "pedestrian"}}; // Parameters { - auto & p = node_param_; - - // for object label - use_dynamic_object_ = false; - for (const auto & label_pair : label_map_) { - const bool check_current_label = - this->declare_parameter(label_pair.first + ".enable_check"); - p.enable_check_map.emplace(label_pair.second, check_current_label); - use_dynamic_object_ = use_dynamic_object_ || check_current_label; - p.surround_check_front_distance_map.emplace( - label_pair.second, - this->declare_parameter(label_pair.first + ".surround_check_front_distance")); - p.surround_check_side_distance_map.emplace( - label_pair.second, - this->declare_parameter(label_pair.first + ".surround_check_side_distance")); - p.surround_check_back_distance_map.emplace( - label_pair.second, - this->declare_parameter(label_pair.first + ".surround_check_back_distance")); - } - - // for pointcloud - p.pointcloud_enable_check = this->declare_parameter("pointcloud.enable_check"); - p.pointcloud_surround_check_front_distance = - this->declare_parameter("pointcloud.surround_check_front_distance"); - p.pointcloud_surround_check_side_distance = - this->declare_parameter("pointcloud.surround_check_side_distance"); - p.pointcloud_surround_check_back_distance = - this->declare_parameter("pointcloud.surround_check_back_distance"); - - p.surround_check_hysteresis_distance = - this->declare_parameter("surround_check_hysteresis_distance"); - - p.state_clear_time = this->declare_parameter("state_clear_time"); - p.publish_debug_footprints = this->declare_parameter("publish_debug_footprints"); - p.debug_footprint_label = this->declare_parameter("debug_footprint_label"); + param_listener_ = std::make_shared( + this->get_node_parameters_interface()); logger_configure_ = std::make_unique(this); } @@ -206,10 +173,6 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio pub_velocity_limit_ = this->create_publisher( "~/output/max_velocity", rclcpp::QoS{1}.transient_local()); - // Parameter callback - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&SurroundObstacleCheckerNode::onParam, this, std::placeholders::_1)); - using std::chrono_literals::operator""ms; timer_ = rclcpp::create_timer( this, get_clock(), 100ms, std::bind(&SurroundObstacleCheckerNode::onTimer, this)); @@ -219,54 +182,34 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio // Debug odometry_ptr_ = std::make_shared(); - - const auto check_distances = getCheckDistances(node_param_.debug_footprint_label); - debug_ptr_ = std::make_shared( - vehicle_info_, vehicle_info_.max_longitudinal_offset_m, node_param_.debug_footprint_label, - check_distances.at(0), check_distances.at(1), check_distances.at(2), - node_param_.surround_check_hysteresis_distance, odometry_ptr_->pose.pose, this->get_clock(), - *this); + { + const auto param = param_listener_->get_params(); + const auto check_distances = getCheckDistances(param.debug_footprint_label); + debug_ptr_ = std::make_shared( + vehicle_info_, vehicle_info_.max_longitudinal_offset_m, param.debug_footprint_label, + check_distances.at(0), check_distances.at(1), check_distances.at(2), + param.surround_check_hysteresis_distance, odometry_ptr_->pose.pose, this->get_clock(), *this); + } } std::array SurroundObstacleCheckerNode::getCheckDistances( const std::string & str_label) const { - if (str_label == "pointcloud") { - return { - node_param_.pointcloud_surround_check_front_distance, - node_param_.pointcloud_surround_check_side_distance, - node_param_.pointcloud_surround_check_back_distance}; - } - - const int int_label = label_map_.at(str_label); + const auto param = param_listener_->get_params(); + const auto & obstacle_param = param.obstacle_types_map.at(str_label); return { - node_param_.surround_check_front_distance_map.at(int_label), - node_param_.surround_check_side_distance_map.at(int_label), - node_param_.surround_check_back_distance_map.at(int_label)}; + obstacle_param.surround_check_front_distance, obstacle_param.surround_check_side_distance, + obstacle_param.surround_check_back_distance}; } -rcl_interfaces::msg::SetParametersResult SurroundObstacleCheckerNode::onParam( - const std::vector & parameters) +bool SurroundObstacleCheckerNode::getUseDynamicObject() const { - use_dynamic_object_ = false; + const auto param = param_listener_->get_params(); + bool use_dynamic_object = false; for (const auto & label_pair : label_map_) { - bool & check_current_label = node_param_.enable_check_map.at(label_pair.second); - autoware::universe_utils::updateParam( - parameters, label_pair.first + ".enable_check", check_current_label); - use_dynamic_object_ = use_dynamic_object_ || check_current_label; + use_dynamic_object |= param.object_types_map.at(label_pair.second).enable_check; } - - autoware::universe_utils::updateParam( - parameters, "debug_footprint_label", node_param_.debug_footprint_label); - const auto check_distances = getCheckDistances(node_param_.debug_footprint_label); - debug_ptr_->updateFootprintMargin( - node_param_.debug_footprint_label, check_distances.at(0), check_distances.at(1), - check_distances.at(2)); - - rcl_interfaces::msg::SetParametersResult result; - result.successful = true; - result.reason = "success"; - return result; + return use_dynamic_object; } void SurroundObstacleCheckerNode::onTimer() @@ -281,21 +224,24 @@ void SurroundObstacleCheckerNode::onTimer() return; } - if (node_param_.publish_debug_footprints) { + const auto param = param_listener_->get_params(); + const auto use_dynamic_object = getUseDynamicObject(); + + if (param.publish_debug_footprints) { debug_ptr_->publishFootprints(); } - if (node_param_.pointcloud_enable_check && !pointcloud_ptr_) { + if (param.pointcloud.enable_check && !pointcloud_ptr_) { RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for pointcloud info..."); } - if (use_dynamic_object_ && !object_ptr_) { + if (use_dynamic_object && !object_ptr_) { RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for dynamic object info..."); } - if (!node_param_.pointcloud_enable_check && !use_dynamic_object_) { + if (!param.pointcloud.enable_check && !use_dynamic_object) { RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), 5000 /* ms */, "Surround obstacle check is disabled for all dynamic object types and for pointcloud check."); @@ -331,10 +277,9 @@ void SurroundObstacleCheckerNode::onTimer() } case State::STOP: { - const auto is_obstacle_found = - !nearest_obstacle - ? false - : nearest_obstacle.value().first < node_param_.surround_check_hysteresis_distance; + const auto is_obstacle_found = !nearest_obstacle ? false + : nearest_obstacle.value().first < + param.surround_check_hysteresis_distance; if (isStopRequired(is_obstacle_found, is_vehicle_stopped)) { break; @@ -392,7 +337,9 @@ std::optional SurroundObstacleCheckerNode::getNearestObstacle() const std::optional SurroundObstacleCheckerNode::getNearestObstacleByPointCloud() const { - if (!node_param_.pointcloud_enable_check || !pointcloud_ptr_) { + const auto param = param_listener_->get_params(); + + if (!param.pointcloud.enable_check || !pointcloud_ptr_) { return std::nullopt; } @@ -414,9 +361,10 @@ std::optional SurroundObstacleCheckerNode::getNearestObstacleByPointCl autoware::universe_utils::transformPointCloud( transformed_pointcloud, transformed_pointcloud, isometry); - const double front_margin = node_param_.pointcloud_surround_check_front_distance; - const double side_margin = node_param_.pointcloud_surround_check_side_distance; - const double back_margin = node_param_.pointcloud_surround_check_back_distance; + const auto & pointcloud_param = param.obstacle_types_map.at("pointcloud"); + const double front_margin = pointcloud_param.surround_check_front_distance; + const double side_margin = pointcloud_param.surround_check_side_distance; + const double back_margin = pointcloud_param.surround_check_back_distance; const auto ego_polygon = createSelfPolygon(vehicle_info_, front_margin, side_margin, back_margin); geometry_msgs::msg::Point nearest_point; @@ -442,7 +390,7 @@ std::optional SurroundObstacleCheckerNode::getNearestObstacleByPointCl std::optional SurroundObstacleCheckerNode::getNearestObstacleByDynamicObject() const { - if (!object_ptr_ || !use_dynamic_object_) return std::nullopt; + if (!object_ptr_ || !getUseDynamicObject()) return std::nullopt; const auto transform_stamped = getTransform(object_ptr_->header.frame_id, "base_link", object_ptr_->header.stamp, 0.5); @@ -451,6 +399,8 @@ std::optional SurroundObstacleCheckerNode::getNearestObstacleByDynamic return std::nullopt; } + const auto param = param_listener_->get_params(); + tf2::Transform tf_src2target; tf2::fromMsg(transform_stamped.value().transform, tf_src2target); @@ -461,13 +411,15 @@ std::optional SurroundObstacleCheckerNode::getNearestObstacleByDynamic for (const auto & object : object_ptr_->objects) { const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; const int label = object.classification.front().label; + const auto & str_label = label_map_.at(label); - if (!node_param_.enable_check_map.at(label)) { + if (!param.object_types_map.at(str_label).enable_check) { continue; } - const double front_margin = node_param_.surround_check_front_distance_map.at(label); - const double side_margin = node_param_.surround_check_side_distance_map.at(label); - const double back_margin = node_param_.surround_check_back_distance_map.at(label); + const auto & object_param = param.obstacle_types_map.at(str_label); + const double front_margin = object_param.surround_check_front_distance; + const double side_margin = object_param.surround_check_side_distance; + const double back_margin = object_param.surround_check_back_distance; const auto ego_polygon = createSelfPolygon(vehicle_info_, front_margin, side_margin, back_margin); @@ -529,10 +481,12 @@ bool SurroundObstacleCheckerNode::isStopRequired( return false; } + const auto param = param_listener_->get_params(); + // Keep stop state if (last_obstacle_found_time_) { const auto elapsed_time = this->now() - *last_obstacle_found_time_; - if (elapsed_time.seconds() <= node_param_.state_clear_time) { + if (elapsed_time.seconds() <= param.state_clear_time) { return true; } } diff --git a/planning/autoware_surround_obstacle_checker/src/node.hpp b/planning/autoware_surround_obstacle_checker/src/node.hpp index b559e159a78ec..2e40eac3dfdfc 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.hpp +++ b/planning/autoware_surround_obstacle_checker/src/node.hpp @@ -18,6 +18,7 @@ #include "autoware/universe_utils/ros/logger_level_configure.hpp" #include "autoware/universe_utils/ros/polling_subscriber.hpp" #include "debug_marker.hpp" +#include "surround_obstacle_checker_node_parameters.hpp" #include #include @@ -62,29 +63,11 @@ class SurroundObstacleCheckerNode : public rclcpp::Node public: explicit SurroundObstacleCheckerNode(const rclcpp::NodeOptions & node_options); - struct NodeParam - { - bool is_surround_obstacle; - std::unordered_map enable_check_map; - std::unordered_map surround_check_front_distance_map; - std::unordered_map surround_check_side_distance_map; - std::unordered_map surround_check_back_distance_map; - bool pointcloud_enable_check; - double pointcloud_surround_check_front_distance; - double pointcloud_surround_check_side_distance; - double pointcloud_surround_check_back_distance; - double surround_check_hysteresis_distance; - double state_clear_time; - bool publish_debug_footprints; - std::string debug_footprint_label; - }; - private: - rcl_interfaces::msg::SetParametersResult onParam( - const std::vector & parameters); - std::array getCheckDistances(const std::string & str_label) const; + bool getUseDynamicObject() const; + void onTimer(); void onPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); @@ -131,7 +114,7 @@ class SurroundObstacleCheckerNode : public rclcpp::Node std::shared_ptr debug_ptr_; // parameter - NodeParam node_param_; + std::shared_ptr param_listener_; autoware::vehicle_info_utils::VehicleInfo vehicle_info_; // data @@ -145,9 +128,7 @@ class SurroundObstacleCheckerNode : public rclcpp::Node std::unique_ptr logger_configure_; - bool use_dynamic_object_; - - std::unordered_map label_map_; + std::unordered_map label_map_; }; } // namespace autoware::surround_obstacle_checker From 8213bdf169175f70824ddd26c182ee02b352a9e9 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 5 Sep 2024 18:00:54 +0900 Subject: [PATCH 127/217] fix(goal_planner): fix object extraction area (#8764) Signed-off-by: kosuke55 --- .../autoware_behavior_path_goal_planner_module/src/util.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 ecb0b1be4e83e..49f70bb8e661b 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 @@ -191,7 +191,7 @@ std::optional generateObjectExtractionPolygon( constexpr double INTERSECTION_CHECK_DISTANCE = 10.0; std::vector modified_bound{}; size_t i = 0; - while (i < bound.size() - 2) { + while (i < bound.size() - 1) { BoostPoint p1(bound.at(i).x, bound.at(i).y); BoostPoint p2(bound.at(i + 1).x, bound.at(i + 1).y); LineString p_line{}; From 71b4b8ddfda54b37c01427a0e000a4d2398be2a5 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 5 Sep 2024 18:08:19 +0900 Subject: [PATCH 128/217] refactor(behavior_path_planner): planner data parameter initializer function (#8767) Signed-off-by: Mamoru Sobue --- .../behavior_path_planner_node.hpp | 3 - .../src/behavior_path_planner_node.cpp | 72 +----------------- .../data_manager.hpp | 74 +++++++++++++++++++ 3 files changed, 75 insertions(+), 74 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 11f9d9f140214..1965a0f909927 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 @@ -147,9 +147,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node void takeData(); bool isDataReady(); - // parameters - BehaviorPathPlannerParameters getCommonParam(); - // callback void onOdometry(const Odometry::ConstSharedPtr msg); void onAcceleration(const AccelWithCovarianceStamped::ConstSharedPtr msg); 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 135e420d113f3..8e2cf7f93c871 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 @@ -40,8 +40,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod // data_manager { planner_data_ = std::make_shared(); - planner_data_->parameters = getCommonParam(); - planner_data_->drivable_area_expansion_parameters.init(*this); + planner_data_->init_parameters(*this); } // publisher @@ -153,75 +152,6 @@ std::vector BehaviorPathPlannerNode::getRunningModules() return running_modules; } -BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() -{ - BehaviorPathPlannerParameters p{}; - - p.traffic_light_signal_timeout = declare_parameter("traffic_light_signal_timeout"); - - // vehicle info - const auto vehicle_info = VehicleInfoUtils(*this).getVehicleInfo(); - p.vehicle_info = vehicle_info; - p.vehicle_width = vehicle_info.vehicle_width_m; - p.vehicle_length = vehicle_info.vehicle_length_m; - p.wheel_tread = vehicle_info.wheel_tread_m; - p.wheel_base = vehicle_info.wheel_base_m; - p.front_overhang = vehicle_info.front_overhang_m; - p.rear_overhang = vehicle_info.rear_overhang_m; - p.left_over_hang = vehicle_info.left_overhang_m; - p.right_over_hang = vehicle_info.right_overhang_m; - p.base_link2front = vehicle_info.max_longitudinal_offset_m; - p.base_link2rear = p.rear_overhang; - - // NOTE: backward_path_length is used not only calculating path length but also calculating the - // size of a drivable area. - // The drivable area has to cover not the base link but the vehicle itself. Therefore - // rear_overhang must be added to backward_path_length. In addition, because of the - // calculation of the drivable area in the autoware_path_optimizer package, the drivable - // area has to be a little longer than the backward_path_length parameter by adding - // min_backward_offset. - constexpr double min_backward_offset = 1.0; - const double backward_offset = vehicle_info.rear_overhang_m + min_backward_offset; - - // ROS parameters - p.backward_path_length = declare_parameter("backward_path_length") + backward_offset; - p.forward_path_length = declare_parameter("forward_path_length"); - - // acceleration parameters - p.min_acc = declare_parameter("normal.min_acc"); - p.max_acc = declare_parameter("normal.max_acc"); - - p.max_vel = declare_parameter("max_vel"); - p.backward_length_buffer_for_end_of_pull_over = - declare_parameter("backward_length_buffer_for_end_of_pull_over"); - p.backward_length_buffer_for_end_of_pull_out = - declare_parameter("backward_length_buffer_for_end_of_pull_out"); - - p.minimum_pull_over_length = declare_parameter("minimum_pull_over_length"); - p.refine_goal_search_radius_range = declare_parameter("refine_goal_search_radius_range"); - p.turn_signal_intersection_search_distance = - declare_parameter("turn_signal_intersection_search_distance"); - p.turn_signal_intersection_angle_threshold_deg = - declare_parameter("turn_signal_intersection_angle_threshold_deg"); - p.turn_signal_minimum_search_distance = - declare_parameter("turn_signal_minimum_search_distance"); - p.turn_signal_search_time = declare_parameter("turn_signal_search_time"); - p.turn_signal_shift_length_threshold = - declare_parameter("turn_signal_shift_length_threshold"); - p.turn_signal_remaining_shift_length_threshold = - declare_parameter("turn_signal_remaining_shift_length_threshold"); - p.turn_signal_on_swerving = declare_parameter("turn_signal_on_swerving"); - - p.enable_akima_spline_first = declare_parameter("enable_akima_spline_first"); - p.enable_cog_on_centerline = declare_parameter("enable_cog_on_centerline"); - p.input_path_interval = declare_parameter("input_path_interval"); - p.output_path_interval = declare_parameter("output_path_interval"); - p.ego_nearest_dist_threshold = declare_parameter("ego_nearest_dist_threshold"); - p.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); - - return p; -} - void BehaviorPathPlannerNode::takeData() { // route diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp index 12fb872ded9ac..27f0dc4e58178 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp @@ -170,6 +170,80 @@ struct PlannerData mutable std::vector drivable_area_expansion_prev_curvatures{}; mutable TurnSignalDecider turn_signal_decider; + void init_parameters(rclcpp::Node & node) + { + parameters.traffic_light_signal_timeout = + node.declare_parameter("traffic_light_signal_timeout"); + + // vehicle info + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); + parameters.vehicle_info = vehicle_info; + parameters.vehicle_width = vehicle_info.vehicle_width_m; + parameters.vehicle_length = vehicle_info.vehicle_length_m; + parameters.wheel_tread = vehicle_info.wheel_tread_m; + parameters.wheel_base = vehicle_info.wheel_base_m; + parameters.front_overhang = vehicle_info.front_overhang_m; + parameters.rear_overhang = vehicle_info.rear_overhang_m; + parameters.left_over_hang = vehicle_info.left_overhang_m; + parameters.right_over_hang = vehicle_info.right_overhang_m; + parameters.base_link2front = vehicle_info.max_longitudinal_offset_m; + parameters.base_link2rear = parameters.rear_overhang; + + // NOTE: backward_path_length is used not only calculating path length but also calculating the + // size of a drivable area. + // The drivable area has to cover not the base link but the vehicle itself. Therefore + // rear_overhang must be added to backward_path_length. In addition, because of the + // calculation of the drivable area in the autoware_path_optimizer package, the drivable + // area has to be a little longer than the backward_path_length parameter by adding + // min_backward_offset. + constexpr double min_backward_offset = 1.0; + const double backward_offset = vehicle_info.rear_overhang_m + min_backward_offset; + + // ROS parameters + parameters.backward_path_length = + node.declare_parameter("backward_path_length") + backward_offset; + parameters.forward_path_length = node.declare_parameter("forward_path_length"); + + // acceleration parameters + parameters.min_acc = node.declare_parameter("normal.min_acc"); + parameters.max_acc = node.declare_parameter("normal.max_acc"); + + parameters.max_vel = node.declare_parameter("max_vel"); + parameters.backward_length_buffer_for_end_of_pull_over = + node.declare_parameter("backward_length_buffer_for_end_of_pull_over"); + parameters.backward_length_buffer_for_end_of_pull_out = + node.declare_parameter("backward_length_buffer_for_end_of_pull_out"); + + parameters.minimum_pull_over_length = + node.declare_parameter("minimum_pull_over_length"); + parameters.refine_goal_search_radius_range = + node.declare_parameter("refine_goal_search_radius_range"); + parameters.turn_signal_intersection_search_distance = + node.declare_parameter("turn_signal_intersection_search_distance"); + parameters.turn_signal_intersection_angle_threshold_deg = + node.declare_parameter("turn_signal_intersection_angle_threshold_deg"); + parameters.turn_signal_minimum_search_distance = + node.declare_parameter("turn_signal_minimum_search_distance"); + parameters.turn_signal_search_time = node.declare_parameter("turn_signal_search_time"); + parameters.turn_signal_shift_length_threshold = + node.declare_parameter("turn_signal_shift_length_threshold"); + parameters.turn_signal_remaining_shift_length_threshold = + node.declare_parameter("turn_signal_remaining_shift_length_threshold"); + parameters.turn_signal_on_swerving = node.declare_parameter("turn_signal_on_swerving"); + + parameters.enable_akima_spline_first = + node.declare_parameter("enable_akima_spline_first"); + parameters.enable_cog_on_centerline = node.declare_parameter("enable_cog_on_centerline"); + parameters.input_path_interval = node.declare_parameter("input_path_interval"); + parameters.output_path_interval = node.declare_parameter("output_path_interval"); + parameters.ego_nearest_dist_threshold = + node.declare_parameter("ego_nearest_dist_threshold"); + parameters.ego_nearest_yaw_threshold = + node.declare_parameter("ego_nearest_yaw_threshold"); + + drivable_area_expansion_parameters.init(node); + } + std::pair getBehaviorTurnSignalInfo( const PathWithLaneId & path, const size_t shift_start_idx, const size_t shift_end_idx, const lanelet::ConstLanelets & current_lanelets, const double current_shift_length, From 55cc82de40d9daf59dc1ed1e3352bda360016239 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Thu, 5 Sep 2024 22:26:19 +0900 Subject: [PATCH 129/217] fix(pure_pursuit): add autoware_ prefix in launch file (#8687) Signed-off-by: Ryohsuke Mitsudome --- control/autoware_pure_pursuit/launch/pure_pursuit.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/control/autoware_pure_pursuit/launch/pure_pursuit.launch.xml b/control/autoware_pure_pursuit/launch/pure_pursuit.launch.xml index 9452542aa2905..8d69cf3a7a891 100644 --- a/control/autoware_pure_pursuit/launch/pure_pursuit.launch.xml +++ b/control/autoware_pure_pursuit/launch/pure_pursuit.launch.xml @@ -1,11 +1,11 @@ - + - + From 8f7919503e93aa74e69a2d8cf1e9903bcbbc9aee Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 5 Sep 2024 22:50:32 +0900 Subject: [PATCH 130/217] fix(goal_planner): fix time_keeper race (#8780) Signed-off-by: Mamoru Sobue --- .../src/goal_planner_module.cpp | 4 ---- 1 file changed, 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 f8195ecfea7ec..dd37d1b30a2a8 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 @@ -1243,8 +1243,6 @@ bool GoalPlannerModule::hasNotDecidedPath( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - return checkDecidingPathStatus( planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, goal_searcher) @@ -2360,8 +2358,6 @@ std::pair GoalPlannerModule::isSafePath( const std::shared_ptr & objects_filtering_params, const std::shared_ptr & safety_check_params) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - if (!thread_safe_data_.get_pull_over_path()) { return {false, false}; } From 6e31ed8061a89daaa07662c90cbe5f8d2765de1b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 6 Sep 2024 00:17:48 +0900 Subject: [PATCH 131/217] feat(behavior_path_goal planner): add example plot for development (#8772) Signed-off-by: Mamoru Sobue --- .../CMakeLists.txt | 25 ++ .../examples/plot_map.cpp | 293 ++++++++++++++++++ .../manager.hpp | 1 + 3 files changed, 319 insertions(+) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.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 5d3af19c51dbf..36013c5aa0fb9 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 @@ -1,6 +1,10 @@ cmake_minimum_required(VERSION 3.14) project(autoware_behavior_path_goal_planner_module) +set(ament_cmake_lint_cmake_FOUND TRUE) + +option(BUILD_EXAMPLES "Build examples" OFF) + find_package(autoware_cmake REQUIRED) autoware_package() pluginlib_export_plugin_description_file(autoware_behavior_path_planner plugins.xml) @@ -16,4 +20,25 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/manager.cpp ) +if(BUILD_EXAMPLES) + message(STATUS "Building examples") + include(FetchContent) + FetchContent_Declare( + matplotlibcpp17 + GIT_REPOSITORY https://github.com/soblin/matplotlibcpp17.git + GIT_TAG master + ) + FetchContent_MakeAvailable(matplotlibcpp17) + + file(GLOB_RECURSE example_files examples/*.cpp) + + foreach(example_file ${example_files}) + get_filename_component(example_name ${example_file} NAME_WE) + ament_auto_add_executable(${example_name} ${example_file}) + target_include_directories(${example_name} SYSTEM INTERFACE matplotlibcpp17::matplotlibcpp17) + set_source_files_properties(${example_file} PROPERTIES COMPILE_FLAGS -Wno-error -Wno-attributes -Wno-unused-parameter) + target_link_libraries(${example_name} matplotlibcpp17::matplotlibcpp17) + endforeach() +endif() + ament_auto_package(INSTALL_TO_SHARE config) 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.cpp new file mode 100644 index 0000000000000..6b750bc9674f3 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp @@ -0,0 +1,293 @@ +// 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 +#include +#include +#include + +#include +#include + +#include +#include + +using namespace std::chrono_literals; // NOLINT + +void plot_path_with_lane_id( + matplotlibcpp17::axes::Axes & axes, const tier4_planning_msgs::msg::PathWithLaneId path) +{ + std::vector xs, ys; + for (const auto & point : path.points) { + xs.push_back(point.point.pose.position.x); + ys.push_back(point.point.pose.position.y); + } + axes.plot(Args(xs, ys), Kwargs("color"_a = "red", "linewidth"_a = 1.0)); +} + +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")); +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + + const auto road_shoulder_test_map_path = + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner_common") + + "/test_map/road_shoulder/lanelet2_map.osm"; + + lanelet::ErrorMessages errors{}; + lanelet::projection::MGRSProjector projector{}; + const lanelet::LaneletMapPtr lanelet_map_ptr = + lanelet::load(road_shoulder_test_map_path, projector, &errors); + if (!errors.empty()) { + for (const auto & error : errors) { + std::cout << error << std::endl; + } + return 1; + } + + autoware_planning_msgs::msg::LaneletRoute route_msg; + route_msg.start_pose = geometry_msgs::build() + .position(geometry_msgs::build() + .x(530.707103865218) + .y(436.8758309382301) + .z(100.0)) + .orientation(geometry_msgs::build() + .x(0.0) + .y(0.0) + .z(0.2187392230193602) + .w(0.9757833531644647)); + route_msg.goal_pose = geometry_msgs::build() + .position(geometry_msgs::build() + .x(571.8018955394537) + .y(435.6819504507543) + .z(100.0)) + .orientation(geometry_msgs::build() + .x(0.0) + .y(0.0) + .z(-0.3361155457734493) + .w(0.9418207578352774)); + /* + route_msg.goal_pose = + geometry_msgs::build() + .position( + geometry_msgs::build().x(568.836731).y(437.871904).z(100.0)) + .orientation( + geometry_msgs::build().x(0.0).y(0.0).z(-0.292125).w( + 0.956380)); + */ + + route_msg.segments = std::vector{ + autoware_planning_msgs::build() + .preferred_primitive( + autoware_planning_msgs::build() + .id(17757) + .primitive_type("")) + .primitives(std::vector{ + autoware_planning_msgs::build() + .id(17756) + .primitive_type("lane"), + autoware_planning_msgs::build() + .id(17757) + .primitive_type("lane"), + }), + autoware_planning_msgs::build() + .preferred_primitive( + autoware_planning_msgs::build() + .id(18494) + .primitive_type("")) + .primitives(std::vector{ + autoware_planning_msgs::build() + .id(18494) + .primitive_type("lane"), + autoware_planning_msgs::build() + .id(18493) + .primitive_type("lane"), + }), + autoware_planning_msgs::build() + .preferred_primitive( + autoware_planning_msgs::build() + .id(18496) + .primitive_type("")) + .primitives(std::vector{ + autoware_planning_msgs::build() + .id(18496) + .primitive_type("lane"), + autoware_planning_msgs::build() + .id(18497) + .primitive_type("lane"), + }), + }; + route_msg.allow_modification = false; + autoware_map_msgs::msg::LaneletMapBin map_bin; + lanelet::utils::conversion::toBinMsg( + lanelet_map_ptr, &map_bin); // TODO(soblin): pass lanelet_map_ptr to RouteHandler + + /* + reference: + https://github.com/ros2/rclcpp/blob/ee94bc63e4ce47a502891480a2796b53d54fcdfc/rclcpp/test/rclcpp/test_parameter_client.cpp#L927 + */ + /* + auto node = rclcpp::Node::make_shared( + "node", "namespace", rclcpp::NodeOptions().allow_undeclared_parameters(true)); + auto param_node = std::make_shared(node, ""); + { + auto future = param_node->load_parameters( + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner") + + "/config/behavior_path_planner.param.yaml"); + if (rclcpp::spin_until_future_complete(node, future) != rclcpp::FutureReturnCode::SUCCESS) { + RCLCPP_INFO(node->get_logger(), "failed to load behavior_path_planner.param.yaml"); + } + } + { + auto future = param_node->load_parameters( + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner") + + "/config/drivable_area_expansion.param.yaml"); + if (rclcpp::spin_until_future_complete(node, future) != rclcpp::FutureReturnCode::SUCCESS) { + RCLCPP_INFO(node->get_logger(), "failed to load drivable_area_expansion.param.yaml"); + } + } + { + auto future = param_node->load_parameters( + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner") + + "/config/scene_module_manager.param.yaml"); + if (rclcpp::spin_until_future_complete(node, future) != rclcpp::FutureReturnCode::SUCCESS) { + RCLCPP_INFO(node->get_logger(), "failed to load scene_module_manager.param.yaml"); + } + } + */ + 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 = std::make_shared(); + planner_data->init_parameters(*node); + planner_data->route_handler->setMap(map_bin); + planner_data->route_handler->setRoute(route_msg); + nav_msgs::msg::Odometry odom; + odom.pose.pose = route_msg.start_pose; + auto odometry = std::make_shared(odom); + planner_data->self_odometry = odometry; + lanelet::ConstLanelet current_route_lanelet; + planner_data->route_handler->getClosestLaneletWithinRoute( + route_msg.start_pose, ¤t_route_lanelet); + std::cout << "current_route_lanelet is " << current_route_lanelet.id() << std::endl; + const auto reference_path = + autoware::behavior_path_planner::utils::getReferencePath(current_route_lanelet, planner_data); + auto goal_planner_parameter = + 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_depature_checker_params; + lane_depature_checker_params.footprint_extra_margin = + goal_planner_parameter.lane_departure_check_expansion_margin; + lane_departure_checker.setParam(lane_depature_checker_params); + auto shift_pull_over_planner = autoware::behavior_path_planner::ShiftPullOver( + *node, goal_planner_parameter, lane_departure_checker); + const auto pull_over_path_opt = + shift_pull_over_planner.plan(planner_data, reference_path, route_msg.goal_pose); + + pybind11::scoped_interpreter guard{}; + auto plt = matplotlibcpp17::pyplot::import(); + auto [fig, ax] = plt.subplots(); + + const std::vector ids{17756, 17757, 18493, 18494, 18496, 18497, + 18492, 18495, 18498, 18499, 18500}; + for (const auto & id : ids) { + const auto lanelet = lanelet_map_ptr->laneletLayer.get(id); + plot_lanelet(ax, lanelet); + } + + plot_path_with_lane_id(ax, reference_path.path); + std::cout << pull_over_path_opt.has_value() << std::endl; + if (pull_over_path_opt) { + const auto & pull_over_path = pull_over_path_opt.value(); + const auto full_path = pull_over_path.getFullPath(); + plot_path_with_lane_id(ax, full_path); + } + ax.set_aspect(Args("equal")); + plt.show(); + + rclcpp::shutdown(); + return 0; +} diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp index 0888f44e054e6..8ba6239630497 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp @@ -29,6 +29,7 @@ namespace autoware::behavior_path_planner class GoalPlannerModuleManager : public SceneModuleManagerInterface { +public: static GoalPlannerParameters initGoalPlannerParameters( rclcpp::Node * node, const std::string & base_ns); From 301e36b493724356195902516d5955bcce626f26 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Fri, 6 Sep 2024 02:03:47 +0900 Subject: [PATCH 132/217] fix(autoware_image_projection_based_fusion): resolve issue with segmentation pointcloud fusion node failing with multiple mask inputs (#8769) --- .../segmentation_pointcloud_fusion/node.hpp | 2 + .../segmentation_pointcloud_fusion/node.cpp | 53 ++++++++++--------- 2 files changed, 30 insertions(+), 25 deletions(-) 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 af7a4cb18ad61..152829ea769d3 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 @@ -21,6 +21,7 @@ #include #include +#include #include #include @@ -47,6 +48,7 @@ class SegmentPointCloudFusionNode : public FusionNode filter_global_offset_set_; public: explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options); 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 e9e3387324754..1965aca86074b 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 @@ -49,10 +49,31 @@ void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 return; } -void SegmentPointCloudFusionNode::postprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg) +void SegmentPointCloudFusionNode::postprocess(PointCloud2 & pointcloud_msg) { + 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, __attribute__((unused)) const std::size_t image_id, [[maybe_unused]] const Image & input_mask, __attribute__((unused)) const CameraInfo & camera_info, @@ -101,15 +122,7 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( 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; - size_t output_pointcloud_size = 0; - output_cloud.data.clear(); - output_cloud.data.resize(input_pointcloud_msg.data.size()); - output_cloud.fields = input_pointcloud_msg.fields; - output_cloud.header = input_pointcloud_msg.header; - output_cloud.height = input_pointcloud_msg.height; - output_cloud.point_step = input_pointcloud_msg.point_step; - output_cloud.is_bigendian = input_pointcloud_msg.is_bigendian; - output_cloud.is_dense = input_pointcloud_msg.is_dense; + for (size_t global_offset = 0; global_offset < transformed_cloud.data.size(); global_offset += point_step) { float transformed_x = @@ -120,8 +133,6 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( *reinterpret_cast(&transformed_cloud.data[global_offset + z_offset]); // skip filtering pointcloud behind the camera or too far from camera if (transformed_z <= 0.0 || transformed_z > filter_distance_threshold_) { - copyPointCloud( - input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size); continue; } @@ -131,28 +142,20 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( 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) { - copyPointCloud( - input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size); continue; } // skip filtering pointcloud where semantic id out of the defined list uint8_t semantic_id = mask.at( static_cast(projected_point.y()), static_cast(projected_point.x())); - if (static_cast(semantic_id) >= filter_semantic_label_target_list_.size()) { - copyPointCloud( - input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size); + if ( + static_cast(semantic_id) >= filter_semantic_label_target_list_.size() || + !filter_semantic_label_target_list_.at(semantic_id).second) { continue; } - if (!filter_semantic_label_target_list_.at(semantic_id).second) { - copyPointCloud( - input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size); - } - } - output_cloud.data.resize(output_pointcloud_size); - output_cloud.row_step = output_pointcloud_size / output_cloud.height; - output_cloud.width = output_pointcloud_size / output_cloud.point_step / output_cloud.height; + filter_global_offset_set_.insert(global_offset); + } } bool SegmentPointCloudFusionNode::out_of_scope(__attribute__((unused)) From ed3b321f8028a33ebf1b52de6a993c3762ff8479 Mon Sep 17 00:00:00 2001 From: Giovanni Muhammad Raditya Date: Fri, 6 Sep 2024 09:29:15 +0900 Subject: [PATCH 133/217] feat(universe_utils): add Triangulation (ear clipping) implementation for 2D concave polygon with/without holes (#8609) * added random_concave_polygon and triangulation * disable some test with GJK * pre-commit fix * fully fixed convexHull issue and styling fix * fix conflict * cleaning up the code Signed-off-by: Maxime CLEMENT * cleanup the code Signed-off-by: Maxime CLEMENT * cleanup the code Signed-off-by: Maxime CLEMENT * fix spelling Signed-off-by: Maxime CLEMENT * last cleanup Signed-off-by: Maxime CLEMENT * more spellcheck fix Signed-off-by: Maxime CLEMENT * more spellcheck fixes Signed-off-by: Maxime CLEMENT --------- Signed-off-by: Maxime CLEMENT Co-authored-by: Maxime CLEMENT --- common/autoware_universe_utils/CMakeLists.txt | 2 + .../universe_utils/geometry/ear_clipping.hpp | 107 ++++ .../geometry/random_concave_polygon.hpp | 45 ++ .../src/geometry/ear_clipping.cpp | 538 ++++++++++++++++++ .../src/geometry/random_concave_polygon.cpp | 410 +++++++++++++ .../src/geometry/random_convex_polygon.cpp | 3 +- .../test/src/geometry/test_geometry.cpp | 300 ++++++++++ 7 files changed, 1404 insertions(+), 1 deletion(-) create mode 100644 common/autoware_universe_utils/include/autoware/universe_utils/geometry/ear_clipping.hpp create mode 100644 common/autoware_universe_utils/include/autoware/universe_utils/geometry/random_concave_polygon.hpp create mode 100644 common/autoware_universe_utils/src/geometry/ear_clipping.cpp create mode 100644 common/autoware_universe_utils/src/geometry/random_concave_polygon.cpp diff --git a/common/autoware_universe_utils/CMakeLists.txt b/common/autoware_universe_utils/CMakeLists.txt index abc7e5050d84a..f295662e69091 100644 --- a/common/autoware_universe_utils/CMakeLists.txt +++ b/common/autoware_universe_utils/CMakeLists.txt @@ -16,6 +16,7 @@ ament_auto_add_library(autoware_universe_utils SHARED src/geometry/pose_deviation.cpp src/geometry/boost_polygon_utils.cpp src/geometry/random_convex_polygon.cpp + src/geometry/random_concave_polygon.cpp src/geometry/gjk_2d.cpp src/geometry/sat_2d.cpp src/math/sin_table.cpp @@ -25,6 +26,7 @@ ament_auto_add_library(autoware_universe_utils SHARED src/ros/logger_level_configure.cpp src/system/backtrace.cpp src/system/time_keeper.cpp + src/geometry/ear_clipping.cpp ) target_link_libraries(autoware_universe_utils diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/ear_clipping.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/ear_clipping.hpp new file mode 100644 index 0000000000000..5ba6501a1ec18 --- /dev/null +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/ear_clipping.hpp @@ -0,0 +1,107 @@ +// 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__UNIVERSE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ +#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ + +#include "autoware/universe_utils/geometry/boost_geometry.hpp" + +#include +#include + +namespace autoware::universe_utils +{ + +class EarClipping +{ +public: + std::vector indices; + std::size_t vertices = 0; + using Polygon2d = autoware::universe_utils::Polygon2d; + using Point2d = autoware::universe_utils::Point2d; + using LinearRing2d = autoware::universe_utils::LinearRing2d; + + void operator()(const Polygon2d & polygon); + + ~EarClipping() + { + for (auto * p : points_) { + delete p; + } + } + +private: + struct Point + { + Point(const std::size_t index, Point2d point) : i(index), pt(std::move(point)) {} + + const std::size_t i; // Index of the point in the original polygon + const Point2d pt; // The Point2d object representing the coordinates + + // Previous and next vertices (Points) in the polygon ring + Point * prev = nullptr; + Point * next = nullptr; + bool steiner = false; + + [[nodiscard]] double x() const { return pt.x(); } + [[nodiscard]] double y() const { return pt.y(); } + }; + + std::vector points_; + + Point * linked_list(const LinearRing2d & points, bool clockwise); + static Point * filter_points(Point * start, Point * end = nullptr); + Point * cure_local_intersections(Point * start); + static Point * get_leftmost(Point * start); + Point * split_polygon(Point * a, Point * b); + Point * insert_point(std::size_t i, const Point2d & p, Point * last); + Point * eliminate_holes( + const std::vector & inners, EarClipping::Point * outer_point); + Point * eliminate_hole(Point * hole, Point * outer_point); + static Point * find_hole_bridge(Point * hole, Point * outer_point); + void ear_clipping_linked(Point * ear, int pass = 0); + void split_ear_clipping(Point * start); + static void remove_point(Point * p); + static bool is_ear(Point * ear); + static bool sector_contains_sector(const Point * m, const Point * p); + [[nodiscard]] static bool point_in_triangle( + double ax, double ay, double bx, double by, double cx, double cy, double px, double py); + static bool is_valid_diagonal(Point * a, Point * b); + static bool equals(const Point * p1, const Point * p2); + static bool intersects(const Point * p1, const Point * q1, const Point * p2, const Point * q2); + static bool on_segment(const Point * p, const Point * q, const Point * r); + static bool intersects_polygon(const Point * a, const Point * b); + static bool locally_inside(const Point * a, const Point * b); + static bool middle_inside(const Point * a, const Point * b); + static int sign(double val); + static double area(const Point * p, const Point * q, const Point * r); + + // Function to construct a new Point object + EarClipping::Point * construct_point(std::size_t index, const Point2d & point) + { + auto * new_point = new Point(index, point); + points_.push_back(new_point); + return new_point; + } +}; + +/// @brief Triangulate based on ear clipping algorithm +/// @param polygon concave/convex polygon with/without holes +/// @details algorithm based on https://github.com/mapbox/earclipping with modification +std::vector triangulate( + const autoware::universe_utils::Polygon2d & poly); + +} // namespace autoware::universe_utils + +#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/random_concave_polygon.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/random_concave_polygon.hpp new file mode 100644 index 0000000000000..297201e925399 --- /dev/null +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/random_concave_polygon.hpp @@ -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. + +#ifndef AUTOWARE__UNIVERSE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ +#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ + +#include + +#include +namespace autoware::universe_utils +{ +/// @brief generate a random non-convex polygon +/// @param vertices number of vertices for the desired polygon +/// @param max points will be generated in the range [-max, max] +/// @details algorithm from +/// https://digitalscholarship.unlv.edu/cgi/viewcontent.cgi?article=3183&context=thesesdissertations +Polygon2d random_concave_polygon(const size_t vertices, const double max); + +/// @brief checks for collisions between two vectors of convex polygons using a specified collision +/// detection algorithm +/// @param polygons1 A vector of convex polygons to check for collisions. +/// @param polygons2 A vector of convex polygons to check for collisions. +/// @param intersection_func A function that takes two polygons and returns true if they intersect, +/// otherwise false. +/// @return True if at least one pair of polygons intersects, otherwise false. +bool test_intersection( + const std::vector & polygons1, + const std::vector & polygons2, + const std::function &); + +} // namespace autoware::universe_utils + +#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ diff --git a/common/autoware_universe_utils/src/geometry/ear_clipping.cpp b/common/autoware_universe_utils/src/geometry/ear_clipping.cpp new file mode 100644 index 0000000000000..741f6fb901c07 --- /dev/null +++ b/common/autoware_universe_utils/src/geometry/ear_clipping.cpp @@ -0,0 +1,538 @@ +// 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/universe_utils/geometry/ear_clipping.hpp" + +#ifndef EAR_CUT_IMPL_HPP +#define EAR_CUT_IMPL_HPP + +namespace autoware::universe_utils +{ + +void EarClipping::operator()(const Polygon2d & polygon) +{ + indices.clear(); + vertices = 0; + + if (polygon.outer().size() == 0) return; + + std::size_t len = 0; + + const auto & outer_ring = polygon.outer(); + len = outer_ring.size(); + points_.reserve(len * 3 / 2); + indices.reserve(len + outer_ring.size()); + + EarClipping::Point * outer_point = linked_list(outer_ring, true); + if (!outer_point || outer_point->prev == outer_point->next) return; + if (polygon.inners().size() > 0) outer_point = eliminate_holes(polygon.inners(), outer_point); + ear_clipping_linked(outer_point); + points_.clear(); +} + +/// @brief create a circular doubly linked list from polygon points in the specified winding order +EarClipping::Point * EarClipping::linked_list(const LinearRing2d & points, bool clockwise) +{ + double sum = 0; + const std::size_t len = points.size(); + EarClipping::Point * last = nullptr; + + for (size_t i = 0, j = len > 0 ? len - 1 : 0; i < len; j = i++) { + const auto & p1 = points[i]; + const auto & p2 = points[j]; + const double p10 = p1.x(); + const double p11 = p1.y(); + const double p20 = p2.x(); + const double p21 = p2.y(); + sum += (p20 - p10) * (p11 + p21); + } + + if (clockwise == (sum > 0)) { + for (size_t i = 0; i < len; i++) { + last = insert_point(vertices + i, points[i], last); + } + } else { + for (size_t i = len; i-- > 0;) { + last = insert_point(vertices + i, points[i], last); + } + } + + if (last && equals(last, last->next)) { + remove_point(last); + last = last->next; + } + + vertices += len; + + return last; +} + +/// @brief eliminate colinear or duplicate points +EarClipping::Point * EarClipping::filter_points( + EarClipping::Point * start, EarClipping::Point * end) +{ + if (!end) end = start; + + EarClipping::Point * p = start; + bool again = false; + do { + again = false; + + if (!p->steiner && (equals(p, p->next) || area(p->prev, p, p->next) == 0)) { + remove_point(p); + p = end = p->prev; + + if (p == p->next) break; + again = true; + + } else { + p = p->next; + } + } while (again || p != end); + + return end; +} + +/// @brief find a bridge between vertices that connects hole with an outer ring and and link it +EarClipping::Point * EarClipping::eliminate_hole( + EarClipping::Point * hole, EarClipping::Point * outer_point) +{ + EarClipping::Point * bridge = find_hole_bridge(hole, outer_point); + if (!bridge) { + return outer_point; + } + EarClipping::Point * bridge_reverse = split_polygon(bridge, hole); + + // filter collinear points around the cuts + filter_points(bridge_reverse, bridge_reverse->next); + + // Check if input node was removed by the filtering + return filter_points(bridge, bridge->next); +} + +EarClipping::Point * EarClipping::eliminate_holes( + const std::vector & inners, EarClipping::Point * outer_point) +{ + const size_t len = inners.size(); + + std::vector queue; + for (size_t i = 0; i < len; i++) { + Point * list = linked_list(inners[i], false); + if (list) { + if (list == list->next) list->steiner = true; + queue.push_back(get_leftmost(list)); + } + } + std::sort( + queue.begin(), queue.end(), [](const Point * a, const Point * b) { return a->x() < b->x(); }); + for (const auto & q : queue) { + outer_point = eliminate_hole(q, outer_point); + } + + return outer_point; +} + +// cspell: ignore Eberly +/// @brief David Eberly's algorithm for finding a bridge between hole and outer polygon +EarClipping::Point * EarClipping::find_hole_bridge(Point * hole, Point * outer_point) +{ + Point * p = outer_point; + double hx = hole->x(); + double hy = hole->y(); + double qx = -std::numeric_limits::infinity(); + Point * m = nullptr; + do { + if (hy <= p->y() && hy >= p->next->y() && p->next->y() != p->y()) { + double x = p->x() + (hy - p->y()) * (p->next->x() - p->x()) / (p->next->y() - p->y()); + if (x <= hx && x > qx) { + qx = x; + m = p->x() < p->next->x() ? p : p->next; + if (x == hx) return m; + } + } + p = p->next; + } while (p != outer_point); + + if (!m) return nullptr; + + const Point * stop = m; + double tan_min = std::numeric_limits::infinity(); + + p = m; + double mx = m->x(); + double my = m->y(); + + do { + if ( + hx >= p->x() && p->x() >= mx && hx != p->x() && + point_in_triangle(hy < my ? hx : qx, hy, mx, my, hy < my ? qx : hx, hy, p->x(), p->y())) { + const auto tan_cur = std::abs(hy - p->y()) / (hx - p->x()); + + if ( + locally_inside(p, hole) && + (tan_cur < tan_min || + (tan_cur == tan_min && (p->x() > m->x() || sector_contains_sector(m, p))))) { + m = p; + tan_min = tan_cur; + } + } + + p = p->next; + } while (p != stop); + + return m; +} + +/// @brief main ear slicing loop which triangulates a polygon using linked list +void EarClipping::ear_clipping_linked(EarClipping::Point * ear, int pass) +{ + if (!ear) return; + + EarClipping::Point * stop = ear; + EarClipping::Point * next = nullptr; + + // Iterate through ears, slicing them one by one + while (ear->prev != ear->next) { + next = ear->next; + + if (is_ear(ear)) { + // Cut off the triangle + indices.emplace_back(ear->prev->i); + indices.emplace_back(ear->i); + indices.emplace_back(next->i); + + remove_point(ear); + ear = next->next; + stop = next->next; + + continue; + } + + ear = next; + if (ear == stop) { + if (!pass) { + ear_clipping_linked(filter_points(ear), 1); + } else if (pass == 1) { + ear = cure_local_intersections(filter_points(ear)); + ear_clipping_linked(ear, 2); + } else if (pass == 2) { + split_ear_clipping(ear); + } + break; + } + } +} + +/// @brief check whether ear is valid +bool EarClipping::is_ear(EarClipping::Point * ear) +{ + const EarClipping::Point * a = ear->prev; + const EarClipping::Point * b = ear; + const EarClipping::Point * c = ear->next; + + if (area(a, b, c) >= 0) return false; // Reflex, can't be an ear + + EarClipping::Point * p = ear->next->next; + + while (p != ear->prev) { + if ( + point_in_triangle(a->x(), a->y(), b->x(), b->y(), c->x(), c->y(), p->x(), p->y()) && + area(p->prev, p, p->next) >= 0) + return false; + p = p->next; + } + + return true; +} + +/// @brief go through all polygon Points and cure small local self-intersections +EarClipping::Point * EarClipping::cure_local_intersections(EarClipping::Point * start) +{ + EarClipping::Point * p = start; + do { + EarClipping::Point * a = p->prev; + EarClipping::Point * b = p->next->next; + + if ( + !equals(a, b) && intersects(a, p, p->next, b) && locally_inside(a, b) && + locally_inside(b, a)) { + indices.emplace_back(a->i); + indices.emplace_back(p->i); + indices.emplace_back(b->i); + remove_point(p); + remove_point(p->next); + + p = start = b; + } + p = p->next; + } while (p != start); + + return filter_points(p); +} + +/// @brief splitting polygon into two and triangulate them independently +void EarClipping::split_ear_clipping(EarClipping::Point * start) +{ + EarClipping::Point * a = start; + do { + EarClipping::Point * b = a->next->next; + while (b != a->prev) { + if (a->i != b->i && is_valid_diagonal(a, b)) { + EarClipping::Point * c = split_polygon(a, b); + + a = filter_points(a, a->next); + c = filter_points(c, c->next); + + ear_clipping_linked(a); + ear_clipping_linked(c); + return; + } + b = b->next; + } + a = a->next; + } while (a != start); +} + +/// @brief check whether sector in vertex m contains sector in vertex p in the same coordinates +bool EarClipping::sector_contains_sector(const EarClipping::Point * m, const EarClipping::Point * p) +{ + return area(m->prev, m, p->prev) < 0 && area(p->next, m, m->next) < 0; +} + +/// @brief find the leftmost Point of a polygon ring +EarClipping::Point * EarClipping::get_leftmost(EarClipping::Point * start) +{ + EarClipping::Point * p = start; + EarClipping::Point * leftmost = start; + do { + if (p->x() < leftmost->x() || (p->x() == leftmost->x() && p->y() < leftmost->y())) leftmost = p; + p = p->next; + } while (p != start); + + return leftmost; +} + +/// @brief check if a point lies within a convex triangle +bool EarClipping::point_in_triangle( + double ax, double ay, double bx, double by, double cx, double cy, double px, double py) +{ + return (cx - px) * (ay - py) >= (ax - px) * (cy - py) && + (ax - px) * (by - py) >= (bx - px) * (ay - py) && + (bx - px) * (cy - py) >= (cx - px) * (by - py); +} + +/// @brief check if a diagonal between two polygon Points is valid +bool EarClipping::is_valid_diagonal(EarClipping::Point * a, EarClipping::Point * b) +{ + return a->next->i != b->i && a->prev->i != b->i && !intersects_polygon(a, b) && + ((locally_inside(a, b) && locally_inside(b, a) && middle_inside(a, b) && + (area(a->prev, a, b->prev) != 0.0 || area(a, b->prev, b) != 0.0)) || + (equals(a, b) && area(a->prev, a, a->next) > 0 && area(b->prev, b, b->next) > 0)); +} + +/// @brief signed area of a triangle +double EarClipping::area( + const EarClipping::Point * p, const EarClipping::Point * q, const EarClipping::Point * r) +{ + return (q->y() - p->y()) * (r->x() - q->x()) - (q->x() - p->x()) * (r->y() - q->y()); +} + +/// @brief check if two points are equal +bool EarClipping::equals(const EarClipping::Point * p1, const EarClipping::Point * p2) +{ + return p1->x() == p2->x() && p1->y() == p2->y(); +} + +/// @brief check if two segments intersect +bool EarClipping::intersects( + const EarClipping::Point * p1, const EarClipping::Point * q1, const EarClipping::Point * p2, + const EarClipping::Point * q2) +{ + int o1 = sign(area(p1, q1, p2)); + int o2 = sign(area(p1, q1, q2)); + int o3 = sign(area(p2, q2, p1)); + int o4 = sign(area(p2, q2, q1)); + + if (o1 != o2 && o3 != o4) return true; + + if (o1 == 0 && on_segment(p1, p2, q1)) return true; + if (o2 == 0 && on_segment(p1, q2, q1)) return true; + if (o3 == 0 && on_segment(p2, p1, q2)) return true; + if (o4 == 0 && on_segment(p2, q1, q2)) return true; + + return false; +} + +/// @brief for collinear points p, q, r, check if point q lies on segment pr +bool EarClipping::on_segment( + const EarClipping::Point * p, const EarClipping::Point * q, const EarClipping::Point * r) +{ + return q->x() <= std::max(p->x(), r->x()) && q->x() >= std::min(p->x(), r->x()) && + q->y() <= std::max(p->y(), r->y()) && q->y() >= std::min(p->y(), r->y()); +} + +/// @brief Sign function for area calculation +int EarClipping::sign(double val) +{ + return (0.0 < val) - (val < 0.0); +} + +/// @brief Check if a polygon diagonal intersects any polygon segments +bool EarClipping::intersects_polygon(const EarClipping::Point * a, const EarClipping::Point * b) +{ + const EarClipping::Point * p = a; + do { + if ( + p->i != a->i && p->next->i != a->i && p->i != b->i && p->next->i != b->i && + intersects(p, p->next, a, b)) + return true; + p = p->next; + } while (p != a); + + return false; +} + +/// @brief Check if a polygon diagonal is locally inside the polygon +bool EarClipping::locally_inside(const EarClipping::Point * a, const EarClipping::Point * b) +{ + return area(a->prev, a, a->next) < 0 ? area(a, b, a->next) >= 0 && area(a, a->prev, b) >= 0 + : area(a, b, a->prev) < 0 || area(a, a->next, b) < 0; +} + +/// @brief Check if the middle vertex of a polygon diagonal is inside the polygon +bool EarClipping::middle_inside(const EarClipping::Point * a, const EarClipping::Point * b) +{ + const EarClipping::Point * p = a; + bool inside = false; + double px = (a->x() + b->x()) / 2; + double py = (a->y() + b->y()) / 2; + do { + if ( + ((p->y() > py) != (p->next->y() > py)) && p->next->y() != p->y() && + (px < (p->next->x() - p->x()) * (py - p->y()) / (p->next->y() - p->y()) + p->x())) + inside = !inside; + p = p->next; + } while (p != a); + + return inside; +} + +/// @brief Link two polygon vertices with a bridge +EarClipping::Point * EarClipping::split_polygon(EarClipping::Point * a, EarClipping::Point * b) +{ + Point2d a_point(a->x(), a->y()); + Point2d b_point(b->x(), b->y()); + + // Use construct_point to create new Point objects + EarClipping::Point * a2 = construct_point(a->i, a_point); + EarClipping::Point * b2 = construct_point(b->i, b_point); + + EarClipping::Point * an = a->next; + EarClipping::Point * bp = b->prev; + + // Update the linked list connections + a->next = b; + b->prev = a; + + a2->next = an; + if (an) { + an->prev = a2; + } + + b2->next = a2; + a2->prev = b2; + + if (bp) { + bp->next = b2; + } + b2->prev = bp; + + return b2; +} + +/// @brief create a Point and optionally link it with the previous one (in a circular doubly linked +/// list) +EarClipping::Point * EarClipping::insert_point( + std::size_t i, const Point2d & pt, EarClipping::Point * last) +{ + EarClipping::Point * p = construct_point(static_cast(i), pt); + + if (!last) { + p->prev = p; + p->next = p; + } else { + assert(last); + p->next = last->next; + p->prev = last; + last->next->prev = p; + last->next = p; + } + return p; +} + +/// @brief remove a Point from the linked list +void EarClipping::remove_point(EarClipping::Point * p) +{ + p->next->prev = p->prev; + p->prev->next = p->next; +} + +/// @brief main triangulate function +std::vector triangulate(const Polygon2d & poly) +{ + autoware::universe_utils::EarClipping triangulate; + triangulate(poly); + + std::vector triangles; + + const auto & indices = triangulate.indices; + const std::size_t num_indices = indices.size(); + + if (num_indices % 3 != 0) { + throw std::runtime_error("Indices size should be a multiple of 3"); + } + + // Gather all vertices from outer and inner rings + std::vector all_vertices; + const auto & outer_ring = poly.outer(); + all_vertices.insert(all_vertices.end(), outer_ring.begin(), outer_ring.end()); + + for (const auto & inner_ring : poly.inners()) { + all_vertices.insert(all_vertices.end(), inner_ring.begin(), inner_ring.end()); + } + + const std::size_t total_vertices = all_vertices.size(); + + for (std::size_t i = 0; i < num_indices; i += 3) { + if ( + indices[i] >= total_vertices || indices[i + 1] >= total_vertices || + indices[i + 2] >= total_vertices) { + throw std::runtime_error("Index out of range"); + } + + Polygon2d triangle; + triangle.outer().push_back(all_vertices[indices[i]]); + triangle.outer().push_back(all_vertices[indices[i + 1]]); + triangle.outer().push_back(all_vertices[indices[i + 2]]); + triangle.outer().push_back(all_vertices[indices[i]]); // Close the triangle + + triangles.push_back(triangle); + } + + return triangles; +} + +} // namespace autoware::universe_utils + +#endif // EAR_CUT_IMPL_HPP diff --git a/common/autoware_universe_utils/src/geometry/random_concave_polygon.cpp b/common/autoware_universe_utils/src/geometry/random_concave_polygon.cpp new file mode 100644 index 0000000000000..5cf5dbb3bfdfd --- /dev/null +++ b/common/autoware_universe_utils/src/geometry/random_concave_polygon.cpp @@ -0,0 +1,410 @@ +// 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/universe_utils/geometry/random_concave_polygon.hpp" + +#include "autoware/universe_utils/geometry/boost_geometry.hpp" + +#include +#include +#include +#include + +#include + +namespace autoware::universe_utils +{ +namespace +{ +/// @brief define Edge as a pair of Points +struct Edge +{ + Point2d first; + Point2d second; + bool valid = true; + bool operator==(const Edge & other) const + { + return (first == other.first && second == other.second) || + (first == other.second && second == other.first); + } +}; + +/// @brief structure to hold a polygon and its edges +struct PolygonWithEdges +{ + Polygon2d polygon; + std::vector edges; +}; + +/// @brief prepares coordinate vectors for a given number of vertices +std::vector prepare_coordinate_vectors( + const size_t nb_vertices, + std::uniform_real_distribution & + random_double, // cppcheck-suppress constParameterReference + std::uniform_int_distribution & random_bool, // cppcheck-suppress constParameterReference + std::default_random_engine & random_engine) +{ + std::vector v; + v.reserve(nb_vertices); + for (auto i = 0UL; i < nb_vertices; ++i) { + v.push_back(random_double(random_engine)); + } + std::sort(v.begin(), v.end()); + const auto min_v = v.front(); + const auto max_v = v.back(); + std::vector v1; + v1.push_back(min_v); + std::vector v2; + v2.push_back(min_v); + for (auto i = 1UL; i + 1 < v.size(); ++i) { + if (random_bool(random_engine) == 0) { + v1.push_back((v[i])); + } else { + v2.push_back((v[i])); + } + } + v1.push_back(max_v); + v2.push_back(max_v); + std::vector diffs; + for (auto i = 0UL; i + 1 < v1.size(); ++i) { + diffs.push_back(v1[i + 1] - v1[i]); + } + for (auto i = 0UL; i + 1 < v2.size(); ++i) { + diffs.push_back(v2[i] - v2[i + 1]); + } + std::vector vectors; + vectors = diffs; + return vectors; +} + +/// @brief calculates the distance from a point to an edge +double dist(const Edge & edge, const Point2d & point) +{ + double x = point.x(); + double y = point.y(); + double x1 = edge.first.x(); + double y1 = edge.first.y(); + double x2 = edge.second.x(); + double y2 = edge.second.y(); + + double dx = x2 - x1; + double dy = y2 - y1; + + if (dx == 0.0 && dy == 0.0) { + dx = x - x1; + dy = y - y1; + return std::sqrt(dx * dx + dy * dy); + } + + double t = ((x - x1) * dx + (y - y1) * dy) / (dx * dx + dy * dy); + t = std::max(0.0, std::min(1.0, t)); + dx = x - (x1 + t * dx); + dy = y - (y1 + t * dy); + return std::sqrt(dx * dx + dy * dy); +} + +/// @brief checks if an edge intersects with a polygon +bool intersecting(const Edge & e, const Polygon2d & polygon) +{ + Segment2d edge_segment{e.first, e.second}; + if (boost::geometry::intersects(edge_segment, polygon)) { + // additional check: ensure it's not just a single point intersection + for (size_t i = 0; i < polygon.outer().size(); ++i) { + const Point2d & p1 = polygon.outer()[i]; + const Point2d & p2 = polygon.outer()[(i + 1) % polygon.outer().size()]; + Segment2d poly_segment{p1, p2}; + + if (boost::geometry::intersects(edge_segment, poly_segment)) { + if (!(e.first == p1 || e.first == p2 || e.second == p1 || e.second == p2)) { + return true; + } + } + } + return false; + } + + return false; +} + +/// @brief checks if an edge is valid for a given polygon and set of points +bool is_valid(const Edge & e, const Polygon2d & P, const std::vector & Q) +{ + bool valid = false; + size_t i = 0; + + while (!valid && i < Q.size()) { + const Point2d & q = Q[i]; + Edge e1 = {e.first, q}; + Edge e2 = {q, e.second}; + bool intersects_e1 = intersecting(e1, P); + bool intersects_e2 = intersecting(e2, P); + + if (!intersects_e1 && !intersects_e2) { + valid = true; + } + + ++i; + } + + return valid; +} + +/// @brief finds the nearest node from a set of points to an edge +Point2d get_nearest_node(const std::vector & Q, const Edge & e) +{ + double min_distance = std::numeric_limits::max(); + Point2d nearest_node(0, 0); + + for (const auto & node : Q) { + double distance = dist(e, node); + + if (distance < min_distance) { + min_distance = distance; + nearest_node = node; + } + } + return nearest_node; +} + +/// @brief finds the edge that is closest to the given set of points +Edge get_breaking_edge(const PolygonWithEdges & polygon_with_edges, const std::vector & Q) +{ + double min_distance = std::numeric_limits::max(); + Edge e_breaking; + e_breaking.valid = false; + + for (const auto & edge : polygon_with_edges.edges) { + if (is_valid(edge, polygon_with_edges.polygon, Q)) { + Point2d nearest_node = get_nearest_node(Q, edge); + double distance = dist(edge, nearest_node); + if (distance < min_distance) { + min_distance = distance; + e_breaking = edge; + } + } + } + return e_breaking; +} + +/// @brief updates the polygon's outer ring based on its edges +void update_polygon_from_edges(PolygonWithEdges & polygon_with_edges) +{ + LinearRing2d new_outer_ring; + + for (const auto & edge : polygon_with_edges.edges) { + if (edge.valid) { + new_outer_ring.push_back(edge.first); + } + } + + polygon_with_edges.polygon.outer() = new_outer_ring; + boost::geometry::correct(polygon_with_edges.polygon); +} + +/// @brief inserts a node into the polygon's edges +void insert_node(PolygonWithEdges & polygon_with_edges, const Point2d & w, const Edge & e) +{ + std::vector new_edges; + for (const Edge & current_edge : polygon_with_edges.edges) { + if (current_edge == e) { + new_edges.push_back({e.first, w}); + new_edges.push_back({w, e.second}); + } else { + new_edges.push_back(current_edge); + } + } + + polygon_with_edges.edges = std::move(new_edges); +} + +/// @brief removes a node from a set of points +void remove_node(std::vector & Q, const Point2d & w) +{ + const double epsilon = 1e-9; + + Q.erase( + std::remove_if( + Q.begin(), Q.end(), + [&](const Point2d & p) { + return std::abs(p.x() - w.x()) < epsilon && std::abs(p.y() - w.y()) < epsilon; + }), + Q.end()); +} + +/// @brief marks edges as valid if they are valid according to the polygon and points +void mark_valid_edges(PolygonWithEdges & polygon_with_edges, const std::vector & Q) +{ + for (auto & edge : polygon_with_edges.edges) { + if (is_valid(edge, polygon_with_edges.polygon, Q)) { + edge.valid = true; + } + } +} + +/// @brief performs inward denting on a linear ring to create a new polygon +Polygon2d inward_denting(LinearRing2d & ring) +{ + LinearRing2d convex_ring; + std::vector q; + q.reserve(ring.size()); + boost::geometry::strategy::convex_hull::graham_andrew strategy; + boost::geometry::convex_hull(ring, convex_ring, strategy); + PolygonWithEdges polygon_with_edges; + polygon_with_edges.polygon.outer() = convex_ring; + polygon_with_edges.edges.resize(polygon_with_edges.polygon.outer().size()); + + for (const auto & point : ring) { + if (boost::geometry::within(point, polygon_with_edges.polygon)) { + q.push_back(point); + } + } + for (size_t i = 0; i < polygon_with_edges.edges.size(); ++i) { + polygon_with_edges.edges[i] = { + polygon_with_edges.polygon.outer()[i], + polygon_with_edges.polygon.outer()[(i + 1) % polygon_with_edges.polygon.outer().size()]}; + } + while (!q.empty()) { + Edge e = get_breaking_edge(polygon_with_edges, q); + Point2d w = get_nearest_node(q, e); + insert_node(polygon_with_edges, w, e); + remove_node(q, w); + mark_valid_edges(polygon_with_edges, q); + update_polygon_from_edges(polygon_with_edges); + } + + return polygon_with_edges.polygon; +} + +} // namespace + +/// @brief checks if a polygon is convex +bool is_convex(const autoware::universe_utils::Polygon2d & polygon) +{ + const auto & outer_ring = polygon.outer(); + size_t num_points = outer_ring.size(); + + if (num_points < 4) { + return true; + } + + bool is_positive = false; + bool is_negative = false; + + for (size_t i = 0; i < num_points; ++i) { + auto p1 = outer_ring[i]; + auto p2 = outer_ring[(i + 1) % num_points]; + auto p3 = outer_ring[(i + 2) % num_points]; + + double cross_product = + (p2.x() - p1.x()) * (p3.y() - p2.y()) - (p2.y() - p1.y()) * (p3.x() - p2.x()); + + if (cross_product > 0) { + is_positive = true; + } else if (cross_product < 0) { + is_negative = true; + } + + if (is_positive && is_negative) { + return false; + } + } + + return true; +} + +/// @brief checks for collisions between two vectors of convex polygons using a specified collision +/// detection algorithm +bool test_intersection( + const std::vector & polygons1, + const std::vector & polygons2, + const std::function & + intersection_func) +{ + for (const auto & poly1 : polygons1) { + for (const auto & poly2 : polygons2) { + if (intersection_func(poly1, poly2)) { + return true; + } + } + } + return false; +} + +Polygon2d random_concave_polygon(const size_t vertices, const double max) +{ + if (vertices < 4) { + return Polygon2d(); + } + + std::random_device r; + std::default_random_engine random_engine(r()); + std::uniform_real_distribution uniform_dist(-max, max); + std::uniform_int_distribution random_bool(0, 1); + + Polygon2d poly; + bool is_non_convex = false; + int max_attempts = 100; + int attempt = 0; + + while (!is_non_convex && attempt < max_attempts) { + auto xs = prepare_coordinate_vectors(vertices, uniform_dist, random_bool, random_engine); + auto ys = prepare_coordinate_vectors(vertices, uniform_dist, random_bool, random_engine); + + std::shuffle(ys.begin(), ys.end(), random_engine); + + LinearRing2d vectors; + for (size_t i = 0; i < xs.size(); ++i) { + vectors.emplace_back(xs[i], ys[i]); + } + + LinearRing2d points; + for (const auto & p : vectors) { + points.emplace_back(p.x(), p.y()); + } + // apply inward denting algorithm + poly = inward_denting(points); + // check for convexity + if (!is_convex(poly)) { + is_non_convex = true; + } + LinearRing2d poly_outer = poly.outer(); + poly.outer() = poly_outer; + + // shift polygon to ensure all coordinates are positive + double min_x = std::numeric_limits::max(); + double min_y = std::numeric_limits::max(); + for (const auto & point : poly.outer()) { + if (point.x() < min_x) { + min_x = point.x(); + } + if (point.y() < min_y) { + min_y = point.y(); + } + } + + double shift_x = -min_x + std::abs(min_x - (-max)); + double shift_y = -min_y + std::abs(min_y - (-max)); + + for (auto & point : poly.outer()) { + point.x() += shift_x; + point.y() += shift_y; + } + + boost::geometry::correct(poly); + ++attempt; + } + return poly; +} +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/src/geometry/random_convex_polygon.cpp b/common/autoware_universe_utils/src/geometry/random_convex_polygon.cpp index 3096964c6fd01..7b1c778d179e6 100644 --- a/common/autoware_universe_utils/src/geometry/random_convex_polygon.cpp +++ b/common/autoware_universe_utils/src/geometry/random_convex_polygon.cpp @@ -27,7 +27,7 @@ namespace struct VectorsWithMin { std::vector vectors; - double min; + double min{}; }; VectorsWithMin prepare_coordinate_vectors( @@ -38,6 +38,7 @@ VectorsWithMin prepare_coordinate_vectors( std::default_random_engine & random_engine) { std::vector v; + v.reserve(nb_vertices); for (auto i = 0UL; i < nb_vertices; ++i) { v.push_back(random_double(random_engine)); } diff --git a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp index 6cce5d974664c..ab5e9f4236bad 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp @@ -13,7 +13,9 @@ // limitations under the License. #include "autoware/universe_utils/geometry/boost_geometry.hpp" +#include "autoware/universe_utils/geometry/ear_clipping.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" +#include "autoware/universe_utils/geometry/random_concave_polygon.hpp" #include "autoware/universe_utils/geometry/random_convex_polygon.hpp" #include "autoware/universe_utils/geometry/sat_2d.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" @@ -2018,3 +2020,301 @@ TEST(geometry, intersectPolygonRand) (sat_no_intersect_ns + sat_intersect_ns) / 1e6); } } + +TEST(geometry, intersectPolygonWithHoles) +{ + using autoware::universe_utils::Polygon2d; + using autoware::universe_utils::triangulate; + + { // quadrilateral inside the hole of another quadrilateral (not intersecting) + Polygon2d outerConcave; + Polygon2d innerConcave; + + outerConcave.outer().emplace_back(0.0, 0.0); + outerConcave.outer().emplace_back(4.0, 0.0); + outerConcave.outer().emplace_back(4.0, 4.0); + outerConcave.outer().emplace_back(2.0, 2.0); + outerConcave.outer().emplace_back(0.0, 4.0); + + outerConcave.inners().emplace_back(); + outerConcave.inners().back().emplace_back(1.0, 1.0); + outerConcave.inners().back().emplace_back(3.0, 1.0); + outerConcave.inners().back().emplace_back(3.0, 3.0); + outerConcave.inners().back().emplace_back(1.0, 3.0); + + innerConcave.outer().emplace_back(1.5, 1.5); + innerConcave.outer().emplace_back(2.5, 1.5); + innerConcave.outer().emplace_back(2.5, 2.5); + innerConcave.outer().emplace_back(1.5, 2.5); + + const auto triangles1 = triangulate(outerConcave); + const auto triangles2 = triangulate(innerConcave); + + const bool gjk_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::intersects_convex); + const bool sat_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::sat::intersects); + + EXPECT_FALSE(gjk_intersect); + EXPECT_FALSE(sat_intersect); + } + + { // quadrilateral inside the hole of another quadrilateral (intersecting) + Polygon2d outerConcave; + Polygon2d intersectingInnerConcave; + + outerConcave.outer().emplace_back(0.0, 0.0); + outerConcave.outer().emplace_back(4.0, 0.0); + outerConcave.outer().emplace_back(4.0, 4.0); + outerConcave.outer().emplace_back(2.0, 2.0); + outerConcave.outer().emplace_back(0.0, 4.0); + + outerConcave.inners().emplace_back(); + outerConcave.inners().back().emplace_back(1.0, 1.0); + outerConcave.inners().back().emplace_back(3.0, 1.0); + outerConcave.inners().back().emplace_back(3.0, 3.0); + outerConcave.inners().back().emplace_back(1.0, 3.0); + + intersectingInnerConcave.outer().emplace_back(0.5, 0.5); + intersectingInnerConcave.outer().emplace_back(2.5, 0.5); + intersectingInnerConcave.outer().emplace_back(2.5, 2.0); + intersectingInnerConcave.outer().emplace_back(0.5, 2.0); + + const auto triangles1 = triangulate(outerConcave); + const auto triangles2 = triangulate(intersectingInnerConcave); + const auto gjk_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::intersects_convex); + const auto sat_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::sat::intersects); + + EXPECT_TRUE(gjk_intersect); + EXPECT_TRUE(sat_intersect); + } +} + +TEST( + geometry, + DISABLED_intersectConcavePolygon) // GJK give different result for edge test (point sharing and + // edge sharing) compared to SAT and boost::geometry::intersect +{ + using autoware::universe_utils::Polygon2d; + using autoware::universe_utils::triangulate; + + { // 2 Concave quadrilateral with intersection + Polygon2d poly1; + Polygon2d poly2; + poly1.outer().emplace_back(4, 11); + poly1.outer().emplace_back(4, 5); + poly1.outer().emplace_back(9, 9); + poly1.outer().emplace_back(2, 2); + poly2.outer().emplace_back(5, 7); + poly2.outer().emplace_back(7, 3); + poly2.outer().emplace_back(9, 6); + poly2.outer().emplace_back(12, 7); + + boost::geometry::correct(poly1); + boost::geometry::correct(poly2); + + const auto triangles1 = triangulate(poly1); + const auto triangles2 = triangulate(poly2); + + const auto gjk_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::intersects_convex); + const auto sat_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::sat::intersects); + + EXPECT_TRUE(gjk_intersect); + EXPECT_TRUE(sat_intersect); + } + + { // 2 concave polygons with no intersection (but they share an edge) + Polygon2d poly1; + Polygon2d poly2; + poly1.outer().emplace_back(0, 2); + poly1.outer().emplace_back(2, 2); + poly1.outer().emplace_back(2, 0); + poly1.outer().emplace_back(0, 0); + + poly2.outer().emplace_back(0, 0); + poly2.outer().emplace_back(2, 0); + poly2.outer().emplace_back(2, -2); + poly2.outer().emplace_back(0, -2); + + boost::geometry::correct(poly1); + boost::geometry::correct(poly2); + + const auto triangles1 = triangulate(poly1); + const auto triangles2 = triangulate(poly2); + + const auto gjk_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::intersects_convex); + const auto sat_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::sat::intersects); + + EXPECT_FALSE(gjk_intersect); + EXPECT_FALSE(sat_intersect); + } + + { // 2 concave polygons with no intersection (but they share a point) + Polygon2d poly1; + Polygon2d poly2; + poly1.outer().emplace_back(0, 2); + poly1.outer().emplace_back(2, 2); + poly1.outer().emplace_back(0, 0); + + poly2.outer().emplace_back(4, 4); + poly2.outer().emplace_back(4, 2); + poly2.outer().emplace_back(2, 2); + poly2.outer().emplace_back(2, 4); + + boost::geometry::correct(poly1); + boost::geometry::correct(poly2); + + auto triangles1 = triangulate(poly1); + auto triangles2 = triangulate(poly2); + + const auto gjk_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::intersects_convex); + const auto sat_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::sat::intersects); + + EXPECT_FALSE(gjk_intersect); + EXPECT_FALSE(sat_intersect); + } + + { // 2 concave polygons sharing a point and then with very small intersection + Polygon2d poly1; + Polygon2d poly2; + poly1.outer().emplace_back(0, 0); + poly1.outer().emplace_back(2, 2); + poly1.outer().emplace_back(4, 0); + poly1.outer().emplace_back(2, -2); + + poly2.outer().emplace_back(0, 4); + poly2.outer().emplace_back(2, 2); + poly2.outer().emplace_back(4, 4); + poly2.outer().emplace_back(2, 6); + + boost::geometry::correct(poly1); + boost::geometry::correct(poly2); + + const auto triangles1 = triangulate(poly1); + const auto triangles2 = triangulate(poly2); + + const auto gjk_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::intersects_convex); + const auto sat_intersect = autoware::universe_utils::test_intersection( + triangles1, triangles2, autoware::universe_utils::sat::intersects); + + EXPECT_FALSE(gjk_intersect); + EXPECT_FALSE(sat_intersect); + + // small intersection test + poly1.outer()[1].y() += 1e-12; + { + const auto triangles = triangulate(poly1); + const bool gjk_intersect = autoware::universe_utils::test_intersection( + triangles, triangles2, autoware::universe_utils::intersects_convex); + const bool sat_intersect = autoware::universe_utils::test_intersection( + triangles, triangles2, autoware::universe_utils::sat::intersects); + EXPECT_TRUE(gjk_intersect); + EXPECT_TRUE(sat_intersect); + } + } +} + +TEST(geometry, intersectConcavePolygonRand) +{ + std::vector polygons; + std::vector> triangulations; + constexpr auto polygons_nb = 500; + constexpr auto max_vertices = 10; + constexpr auto max_values = 1000; + + autoware::universe_utils::StopWatch sw; + + for (auto vertices = 4UL; vertices < max_vertices; ++vertices) { + double ground_truth_intersect_ns = 0.0; + double ground_truth_no_intersect_ns = 0.0; + double gjk_intersect_ns = 0.0; + double gjk_no_intersect_ns = 0.0; + double sat_intersect_ns = 0.0; + double sat_no_intersect_ns = 0.0; + double triangulation_ns = 0.0; + int intersect_count = 0; + polygons.clear(); + triangulations.clear(); + + for (auto i = 0; i < polygons_nb; ++i) { + polygons.push_back(autoware::universe_utils::random_concave_polygon(vertices, max_values)); + } + + for (const auto & polygon : polygons) { + sw.tic(); + std::vector triangles = + autoware::universe_utils::triangulate(polygon); + triangulation_ns += sw.toc(); + triangulations.push_back(triangles); + } + + for (auto i = 0UL; i < polygons.size(); ++i) { + for (auto j = 0UL; j < polygons.size(); ++j) { + sw.tic(); + const auto ground_truth = boost::geometry::intersects(polygons[i], polygons[j]); + if (ground_truth) { + ++intersect_count; + ground_truth_intersect_ns += sw.toc(); + } else { + ground_truth_no_intersect_ns += sw.toc(); + } + + sw.tic(); + bool gjk_intersect = autoware::universe_utils::test_intersection( + triangulations[i], triangulations[j], autoware::universe_utils::intersects_convex); + if (!gjk_intersect) { + gjk_no_intersect_ns += sw.toc(); + } else { + gjk_intersect_ns += sw.toc(); + } + + sw.tic(); + bool sat_intersect = autoware::universe_utils::test_intersection( + triangulations[i], triangulations[j], autoware::universe_utils::sat::intersects); + if (!sat_intersect) { + sat_no_intersect_ns += sw.toc(); + } else { + sat_intersect_ns += sw.toc(); + } + + EXPECT_EQ(ground_truth, gjk_intersect); + EXPECT_EQ(ground_truth, sat_intersect); + + if (ground_truth != gjk_intersect) { + std::cout << "Failed for the 2 polygons with GJK: "; + std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j]) + << std::endl; + } + + if (ground_truth != sat_intersect) { + std::cout << "Failed for the 2 polygons with SAT: "; + std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j]) + << std::endl; + } + } + } + + std::printf( + "polygons_nb = %d, vertices = %ld, %d / %d pairs with intersects\n", polygons_nb, vertices, + intersect_count, polygons_nb * polygons_nb); + + std::printf( + "\tIntersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n\t\tSAT = %2.2f ms\n", + ground_truth_intersect_ns / 1e6, gjk_intersect_ns / 1e6, sat_intersect_ns / 1e6); + + std::printf( + "\tNo Intersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n\t\tSAT = %2.2f ms\n", + ground_truth_no_intersect_ns / 1e6, gjk_no_intersect_ns / 1e6, sat_no_intersect_ns / 1e6); + + std::printf("\tTotal:\n\t\tTriangulation = %2.2f ms\n", triangulation_ns / 1e6); + } +} From eda5011cff8382e6be8d6ace7fff22e216051811 Mon Sep 17 00:00:00 2001 From: Khalil Selyan <36904941+KhalilSelyan@users.noreply.github.com> Date: Fri, 6 Sep 2024 03:48:47 +0300 Subject: [PATCH 134/217] refactor(custom_button): improve drop shadow effect (#8781) Signed-off-by: KhalilSelyan --- common/tier4_state_rviz_plugin/src/custom_button.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/common/tier4_state_rviz_plugin/src/custom_button.cpp b/common/tier4_state_rviz_plugin/src/custom_button.cpp index 26d9d699038d8..7ad43190b0f41 100644 --- a/common/tier4_state_rviz_plugin/src/custom_button.cpp +++ b/common/tier4_state_rviz_plugin/src/custom_button.cpp @@ -34,12 +34,13 @@ CustomElevatedButton::CustomElevatedButton( font.setFamily("Roboto"); setFont(font); + QColor shadowColor = QColor(autoware::state_rviz_plugin::colors::default_colors.shadow.c_str()); + shadowColor.setAlpha(255 * 0.6); // Set up drop shadow effect QGraphicsDropShadowEffect * shadowEffect = new QGraphicsDropShadowEffect(this); - shadowEffect->setBlurRadius(15); - shadowEffect->setOffset(3, 3); - shadowEffect->setColor( - QColor(autoware::state_rviz_plugin::colors::default_colors.shadow.c_str())); + shadowEffect->setBlurRadius(5); + shadowEffect->setOffset(0, 1); + shadowEffect->setColor(shadowColor); setGraphicsEffect(shadowEffect); } From 6bcde92c1c476dcb99935f39d31a167a1dac64e6 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 6 Sep 2024 09:51:26 +0900 Subject: [PATCH 135/217] fix(autoware_surround_obstacle_checker): fix unusedFunction (#8774) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/debug_marker.cpp | 10 ---------- .../src/debug_marker.hpp | 3 --- 2 files changed, 13 deletions(-) diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp index 7897a868ee172..92429504c7d5e 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp @@ -236,14 +236,4 @@ PolygonStamped SurroundObstacleCheckerDebugNode::boostPolygonToPolygonStamped( return polygon_stamped; } -void SurroundObstacleCheckerDebugNode::updateFootprintMargin( - const std::string & object_label, const double front_distance, const double side_distance, - const double back_distance) -{ - object_label_ = object_label; - surround_check_front_distance_ = front_distance; - surround_check_side_distance_ = side_distance; - surround_check_back_distance_ = back_distance; -} - } // namespace autoware::surround_obstacle_checker diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp index 058bf964e7dc4..ba8877b539e81 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp @@ -66,9 +66,6 @@ class SurroundObstacleCheckerDebugNode bool pushObstaclePoint(const geometry_msgs::msg::Point & obstacle_point, const PointType & type); void publish(); void publishFootprints(); - void updateFootprintMargin( - const std::string & object_label, const double front_distance, const double side_distance, - const double back_distance); private: rclcpp::Publisher::SharedPtr debug_viz_pub_; From abfa71ea20cb1d2b1c57f55febaa8ecc5f352d59 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 6 Sep 2024 09:51:41 +0900 Subject: [PATCH 136/217] fix(autoware_behavior_path_goal_planner_module): fix unusedFunction (#8775) fix:unusedFunction Signed-off-by: kobayu858 --- .../behavior_path_goal_planner_module/util.hpp | 4 ---- .../src/util.cpp | 11 ----------- 2 files changed, 15 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 7d83c598a8227..8fbe2facc87d1 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 @@ -83,10 +83,6 @@ PredictedObjects extractObjectsInExpandedPullOverLanes( PredictedObjects filterObjectsByLateralDistance( const Pose & ego_pose, const double vehicle_width, const PredictedObjects & objects, const double distance_thresh, const bool filter_inside); -PredictedObjects extractStaticObjectsInExpandedPullOverLanes( - const RouteHandler & route_handler, const bool left_side, const double backward_distance, - const double forward_distance, double bound_offset, const PredictedObjects & objects, - const double velocity_thresh); double calcLateralDeviationBetweenPaths( const PathWithLaneId & reference_path, const PathWithLaneId & target_path); 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 49f70bb8e661b..656cdf91c0c54 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 @@ -274,17 +274,6 @@ PredictedObjects extractObjectsInExpandedPullOverLanes( return objects_in_lanes; } -PredictedObjects extractStaticObjectsInExpandedPullOverLanes( - const RouteHandler & route_handler, const bool left_side, const double backward_distance, - const double forward_distance, double bound_offset, const PredictedObjects & objects, - const double velocity_thresh) -{ - const auto objects_in_lanes = extractObjectsInExpandedPullOverLanes( - route_handler, left_side, backward_distance, forward_distance, bound_offset, objects); - - return utils::path_safety_checker::filterObjectsByVelocity(objects_in_lanes, velocity_thresh); -} - PredictedObjects filterObjectsByLateralDistance( const Pose & ego_pose, const double vehicle_width, const PredictedObjects & objects, const double distance_thresh, const bool filter_inside) From 41f7e6008cfce98229153595fb72ca71b7bbb5ee Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 6 Sep 2024 09:52:21 +0900 Subject: [PATCH 137/217] fix(autoware_behavior_path_static_obstacle_avoidance_module): fix unusedFunction (#8776) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/utils.cpp | 26 ------------------- 1 file changed, 26 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 58eb16b67e659..a7166b52fc4e5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -66,32 +66,6 @@ geometry_msgs::msg::Polygon toMsg( return ret; } -template -size_t findFirstNearestIndex(const T & points, const geometry_msgs::msg::Point & point) -{ - autoware::motion_utils::validateNonEmpty(points); - - double min_dist = std::numeric_limits::max(); - size_t min_idx = 0; - bool decreasing = false; - - for (size_t i = 0; i < points.size(); ++i) { - const auto dist = autoware::universe_utils::calcSquaredDistance2d(points.at(i), point); - if (dist < min_dist) { - decreasing = true; - min_dist = dist; - min_idx = i; - continue; - } - - if (decreasing) { - return min_idx; - } - } - - return min_idx; -} - geometry_msgs::msg::Polygon createVehiclePolygon( const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double offset) { From 3012a36759a9165f01ba4a5bc8f43025d872651f Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 6 Sep 2024 09:52:56 +0900 Subject: [PATCH 138/217] fix(autoware_behavior_velocity_run_out_module): fix unusedFunction (#8779) fix:unusedFunction Signed-off-by: kobayu858 --- .../autoware_behavior_velocity_run_out_module/src/debug.hpp | 6 ------ 1 file changed, 6 deletions(-) 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 65eda86a9a8b8..3e913f57f30c0 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 @@ -49,12 +49,6 @@ class DebugValues SIZE, // this is the number of enum elements }; - /** - * @brief get the index corresponding to the given value TYPE - * @param [in] type the TYPE enum for which to get the index - * @return index of the type - */ - static int getValuesIdx(const TYPE type) { return static_cast(type); } /** * @brief get all the debug values as an std::array * @return array of all debug values From 46bf5ec7da18024cb08fefaec0e214bcde11e189 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Fri, 6 Sep 2024 13:02:34 +0900 Subject: [PATCH 139/217] feat(autonomous_emergency_braking): speed up aeb (#8778) * add missing rclcpp::Time(0) Signed-off-by: Daniel Sanchez * refactor to reduce cropping to once per iteration Signed-off-by: Daniel Sanchez * add LookUpTransform to utils Signed-off-by: Daniel Sanchez * separate object creation and clustering Signed-off-by: Daniel Sanchez * error handling of empty pointcloud Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../autonomous_emergency_braking/node.hpp | 25 +- .../autonomous_emergency_braking/utils.hpp | 8 +- .../src/node.cpp | 268 +++++++++--------- .../src/utils.cpp | 20 +- .../test/test.cpp | 7 +- 5 files changed, 192 insertions(+), 136 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp index 3f9a793acb200..aa3db3d8e92e4 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp @@ -410,6 +410,16 @@ class AEB : public rclcpp::Node */ std::optional generateEgoPath(const Trajectory & predicted_traj); + /** + * @brief Generate the footprint of the path with extra width margin + * @param path Ego vehicle path + * @param extra_width_margin Extra width margin for the footprint + * @param polygons vector to be filled with the polygons + * @return Vector of polygons representing the path footprint + */ + void generatePathFootprint( + const Path & path, const double extra_width_margin, std::vector & polygons); + /** * @brief Generate the footprint of the path with extra width margin * @param path Ego vehicle path @@ -426,10 +436,19 @@ class AEB : public rclcpp::Node * @param objects Vector to store the created object data * @param obstacle_points_ptr Pointer to the point cloud of obstacles */ - void createObjectDataUsingPointCloudClusters( + void getClosestObjectsOnPath( const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, - std::vector & objects, - const pcl::PointCloud::Ptr obstacle_points_ptr); + const PointCloud::Ptr points_belonging_to_cluster_hulls, std::vector & objects); + + /** + * @brief Create object data using point cloud clusters + * @param obstacle_points_ptr Pointer to the point cloud of obstacles + * @param points_belonging_to_cluster_hulls output: pointer to the point cloud of points belonging + * to cluster hulls + */ + void getPointsBelongingToClusterHulls( + const PointCloud::Ptr obstacle_points_ptr, + const PointCloud::Ptr points_belonging_to_cluster_hulls); /** * @brief Create object data using predicted objects diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp index d2ec1763ca4dd..85a20caac9287 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp @@ -24,6 +24,8 @@ #include #include + +#include #ifdef ROS_DISTRO_GALACTIC #include #include @@ -48,7 +50,7 @@ using geometry_msgs::msg::TransformStamped; * @param transform_stamped the tf2 transform */ PredictedObject transformObjectFrame( - const PredictedObject & input, geometry_msgs::msg::TransformStamped & transform_stamped); + const PredictedObject & input, const geometry_msgs::msg::TransformStamped & transform_stamped); /** * @brief Get the predicted objects polygon as a geometry polygon @@ -80,6 +82,10 @@ Polygon2d convertBoundingBoxObjectToGeometryPolygon( * @param obj the object */ Polygon2d convertObjToPolygon(const PredictedObject & obj); + +std::optional getTransform( + const std::string & target_frame, const std::string & source_frame, + const tf2_ros::Buffer & tf_buffer, const rclcpp::Logger & logger); } // namespace autoware::motion::control::autonomous_emergency_braking::utils #endif // AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_ diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 26c6decceaff7..938ed388c9ec9 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include @@ -45,6 +46,7 @@ #include #include #include +#include #ifdef ROS_DISTRO_GALACTIC #include #include @@ -247,20 +249,13 @@ void AEB::onTimer() void AEB::onImu(const Imu::ConstSharedPtr input_msg) { // transform imu - geometry_msgs::msg::TransformStamped transform_stamped{}; - try { - transform_stamped = tf_buffer_.lookupTransform( - "base_link", input_msg->header.frame_id, rclcpp::Time(0), - rclcpp::Duration::from_seconds(0.5)); - } catch (tf2::TransformException & ex) { - RCLCPP_ERROR_STREAM( - get_logger(), - "[AEB] Failed to look up transform from base_link to" << input_msg->header.frame_id); - return; - } + const auto logger = get_logger(); + const auto transform_stamped = + utils::getTransform("base_link", input_msg->header.frame_id, tf_buffer_, logger); + if (!transform_stamped.has_value()) return; angular_velocity_ptr_ = std::make_shared(); - tf2::doTransform(input_msg->angular_velocity, *angular_velocity_ptr_, transform_stamped); + tf2::doTransform(input_msg->angular_velocity, *angular_velocity_ptr_, transform_stamped.value()); } void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg) @@ -274,22 +269,15 @@ void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg) get_logger(), "[AEB]: Input point cloud frame is not base_link and it is " << input_msg->header.frame_id); // transform pointcloud - geometry_msgs::msg::TransformStamped transform_stamped{}; - try { - transform_stamped = tf_buffer_.lookupTransform( - "base_link", input_msg->header.frame_id, input_msg->header.stamp, - rclcpp::Duration::from_seconds(0.5)); - } catch (tf2::TransformException & ex) { - RCLCPP_ERROR_STREAM( - get_logger(), - "[AEB] Failed to look up transform from base_link to" << input_msg->header.frame_id); - return; - } + const auto logger = get_logger(); + const auto transform_stamped = + utils::getTransform("base_link", input_msg->header.frame_id, tf_buffer_, logger); + if (!transform_stamped.has_value()) return; // transform by using eigen matrix PointCloud2 transformed_points{}; const Eigen::Matrix4f affine_matrix = - tf2::transformToEigen(transform_stamped.transform).matrix().cast(); + tf2::transformToEigen(transform_stamped.value().transform).matrix().cast(); pcl_ros::transformPointCloud(affine_matrix, *input_msg, transformed_points); pcl::fromROSMsg(transformed_points, *pointcloud_ptr); } @@ -442,29 +430,48 @@ bool AEB::checkCollision(MarkerArray & debug_markers) return false; } - auto check_collision = [&]( - const auto & path, const colorTuple & debug_colors, - const std::string & debug_ns, - pcl::PointCloud::Ptr filtered_objects) { + auto merge_expanded_path_polys = [&](const std::vector & paths) { + std::vector merged_expanded_path_polygons; + for (const auto & path : paths) { + generatePathFootprint( + path, expand_width_ + path_footprint_extra_margin_, merged_expanded_path_polygons); + } + return merged_expanded_path_polygons; + }; + + auto get_objects_on_path = [&]( + const auto & path, PointCloud::Ptr points_belonging_to_cluster_hulls, + const colorTuple & debug_colors, const std::string & debug_ns) { // Check which points of the cropped point cloud are on the ego path, and get the closest one const auto ego_polys = generatePathFootprint(path, expand_width_); - auto objects = std::invoke([&]() { - std::vector objects; - // Crop out Pointcloud using an extra wide ego path - if (use_pointcloud_data_) { - const auto expanded_ego_polys = - generatePathFootprint(path, expand_width_ + path_footprint_extra_margin_); - cropPointCloudWithEgoFootprintPath(expanded_ego_polys, filtered_objects); - const auto current_time = obstacle_ros_pointcloud_ptr_->header.stamp; - createObjectDataUsingPointCloudClusters( - path, ego_polys, current_time, objects, filtered_objects); - } - if (use_predicted_object_data_) { - createObjectDataUsingPredictedObjects(path, ego_polys, objects); - } - return objects; - }); + std::vector objects; + // Crop out Pointcloud using an extra wide ego path + if (use_pointcloud_data_ && !points_belonging_to_cluster_hulls->empty()) { + const auto current_time = obstacle_ros_pointcloud_ptr_->header.stamp; + getClosestObjectsOnPath( + path, ego_polys, current_time, points_belonging_to_cluster_hulls, objects); + } + if (use_predicted_object_data_) { + createObjectDataUsingPredictedObjects(path, ego_polys, objects); + } + // Add debug markers + if (publish_debug_markers_) { + const auto [color_r, color_g, color_b, color_a] = debug_colors; + addMarker( + this->get_clock()->now(), path, ego_polys, objects, collision_data_keeper_.get(), color_r, + color_g, color_b, color_a, debug_ns, debug_markers); + } + return objects; + }; + + auto check_collision = [&]( + const Path & path, const colorTuple & debug_colors, + const std::string & debug_ns, + PointCloud::Ptr points_belonging_to_cluster_hulls) { + time_keeper_->start_track("has_collision_with_" + debug_ns); + auto objects = + get_objects_on_path(path, points_belonging_to_cluster_hulls, debug_colors, debug_ns); // Get only the closest object and calculate its speed const auto closest_object_point = std::invoke([&]() -> std::optional { const auto closest_object_point_itr = @@ -490,53 +497,61 @@ bool AEB::checkCollision(MarkerArray & debug_markers) ? hasCollision(current_v, closest_object_point.value()) : false; - // Add debug markers - if (publish_debug_markers_) { - const auto [color_r, color_g, color_b, color_a] = debug_colors; - addMarker( - this->get_clock()->now(), path, ego_polys, objects, collision_data_keeper_.get(), color_r, - color_g, color_b, color_a, debug_ns, debug_markers); - } + time_keeper_->end_track("has_collision_with_" + debug_ns); // check collision using rss distance return has_collision; }; // step3. make function to check collision with ego path created with sensor data - time_keeper_->start_track("has_collision_imu_path"); - const auto has_collision_ego = [&](pcl::PointCloud::Ptr filtered_objects) -> bool { + const auto ego_imu_path = (!use_imu_path_ || !angular_velocity_ptr_) + ? Path{} + : generateEgoPath(current_v, angular_velocity_ptr_->z); + + const auto ego_mpc_path = (!use_predicted_trajectory_ || !predicted_traj_ptr_) + ? std::nullopt + : generateEgoPath(*predicted_traj_ptr_); + + PointCloud::Ptr filtered_objects = pcl::make_shared(); + if (use_pointcloud_data_) { + const std::vector paths = [&]() { + std::vector paths; + if (use_imu_path_) paths.push_back(ego_imu_path); + if (ego_mpc_path.has_value()) { + paths.push_back(ego_mpc_path.value()); + } + return paths; + }(); + + if (paths.empty()) return false; + const std::vector merged_path_polygons = merge_expanded_path_polys(paths); + // Data of filtered point cloud + cropPointCloudWithEgoFootprintPath(merged_path_polygons, filtered_objects); + } + + PointCloud::Ptr points_belonging_to_cluster_hulls = pcl::make_shared(); + getPointsBelongingToClusterHulls(filtered_objects, points_belonging_to_cluster_hulls); + + const auto has_collision_imu_path = + [&](const PointCloud::Ptr points_belonging_to_cluster_hulls) -> bool { if (!use_imu_path_ || !angular_velocity_ptr_) return false; - const double current_w = angular_velocity_ptr_->z; constexpr colorTuple debug_color = {0.0 / 256.0, 148.0 / 256.0, 205.0 / 256.0, 0.999}; - const std::string ns = "ego"; - const auto ego_path = generateEgoPath(current_v, current_w); - - return check_collision(ego_path, debug_color, ns, filtered_objects); + const std::string ns = "imu"; + return check_collision(ego_imu_path, debug_color, ns, points_belonging_to_cluster_hulls); }; - time_keeper_->end_track("has_collision_imu_path"); // step4. make function to check collision with predicted trajectory from control module - time_keeper_->start_track("has_collision_mpc_path"); - const auto has_collision_predicted = - [&](pcl::PointCloud::Ptr filtered_objects) -> bool { - if (!use_predicted_trajectory_ || !predicted_traj_ptr_) return false; - const auto predicted_traj_ptr = predicted_traj_ptr_; - const auto predicted_path_opt = generateEgoPath(*predicted_traj_ptr); - - if (!predicted_path_opt) return false; + const auto has_collision_mpc_path = + [&](const PointCloud::Ptr points_belonging_to_cluster_hulls) -> bool { + if (!use_predicted_trajectory_ || !ego_mpc_path.has_value()) return false; constexpr colorTuple debug_color = {0.0 / 256.0, 100.0 / 256.0, 0.0 / 256.0, 0.999}; - const std::string ns = "predicted"; - const auto & predicted_path = predicted_path_opt.value(); - - return check_collision(predicted_path, debug_color, ns, filtered_objects); + const std::string ns = "mpc"; + return check_collision( + ego_mpc_path.value(), debug_color, ns, points_belonging_to_cluster_hulls); }; - time_keeper_->end_track("has_collision_mpc_path"); - // Data of filtered point cloud - pcl::PointCloud::Ptr filtered_objects = - pcl::make_shared>(); // evaluate if there is a collision for both paths - const bool has_collision = - has_collision_ego(filtered_objects) || has_collision_predicted(filtered_objects); + const bool has_collision = has_collision_imu_path(points_belonging_to_cluster_hulls) || + has_collision_mpc_path(points_belonging_to_cluster_hulls); // Debug print if (!filtered_objects->empty() && publish_debug_pointcloud_) { @@ -627,27 +642,17 @@ std::optional AEB::generateEgoPath(const Trajectory & predicted_traj) if (predicted_traj.points.empty()) { return std::nullopt; } - time_keeper_->start_track("lookUpTransform"); - geometry_msgs::msg::TransformStamped transform_stamped{}; - try { - transform_stamped = tf_buffer_.lookupTransform( - "base_link", predicted_traj.header.frame_id, rclcpp::Time(0), - rclcpp::Duration::from_seconds(0.5)); - } catch (tf2::TransformException & ex) { - RCLCPP_ERROR_STREAM( - get_logger(), - "[AEB] Failed to look up transform from base_link to " + predicted_traj.header.frame_id); - return std::nullopt; - } - time_keeper_->end_track("lookUpTransform"); - + const auto logger = get_logger(); + const auto transform_stamped = + utils::getTransform("base_link", predicted_traj.header.frame_id, tf_buffer_, logger); + if (!transform_stamped.has_value()) return std::nullopt; // create path time_keeper_->start_track("createPath"); Path path; path.reserve(predicted_traj.points.size()); for (size_t i = 0; i < predicted_traj.points.size(); ++i) { geometry_msgs::msg::Pose map_pose; - tf2::doTransform(predicted_traj.points.at(i).pose, map_pose, transform_stamped); + tf2::doTransform(predicted_traj.points.at(i).pose, map_pose, transform_stamped.value()); path.push_back(map_pose); if (i * mpc_prediction_time_interval_ > mpc_prediction_time_horizon_) { @@ -658,11 +663,21 @@ std::optional AEB::generateEgoPath(const Trajectory & predicted_traj) return path; } +void AEB::generatePathFootprint( + const Path & path, const double extra_width_margin, std::vector & polygons) +{ + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + for (size_t i = 0; i < path.size() - 1; ++i) { + polygons.push_back( + createPolygon(path.at(i), path.at(i + 1), vehicle_info_, extra_width_margin)); + } +} + std::vector AEB::generatePathFootprint( const Path & path, const double extra_width_margin) { - autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); std::vector polygons; + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); for (size_t i = 0; i < path.size() - 1; ++i) { polygons.push_back( createPolygon(path.at(i), path.at(i + 1), vehicle_info_, extra_width_margin)); @@ -702,19 +717,14 @@ void AEB::createObjectDataUsingPredictedObjects( return obj_vel_norm * std::cos(obj_yaw - path_yaw); }; - geometry_msgs::msg::TransformStamped transform_stamped{}; - try { - transform_stamped = tf_buffer_.lookupTransform( - "base_link", predicted_objects_ptr_->header.frame_id, rclcpp::Time(0), - rclcpp::Duration::from_seconds(0.5)); - } catch (tf2::TransformException & ex) { - RCLCPP_ERROR_STREAM(get_logger(), "[AEB] Failed to look up transform from base_link to map"); - return; - } - + const auto logger = get_logger(); + const auto transform_stamped_opt = + utils::getTransform("base_link", predicted_objects_ptr_->header.frame_id, tf_buffer_, logger); + if (!transform_stamped_opt.has_value()) return; // Check which objects collide with the ego footprints std::for_each(objects.begin(), objects.end(), [&](const auto & predicted_object) { // get objects in base_link frame + const auto & transform_stamped = transform_stamped_opt.value(); const auto t_predicted_object = utils::transformObjectFrame(predicted_object, transform_stamped); const auto & obj_pose = t_predicted_object.kinematics.initial_pose_with_covariance.pose; @@ -758,18 +768,14 @@ void AEB::createObjectDataUsingPredictedObjects( }); } -void AEB::createObjectDataUsingPointCloudClusters( - const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, - std::vector & objects, const pcl::PointCloud::Ptr obstacle_points_ptr) +void AEB::getPointsBelongingToClusterHulls( + const PointCloud::Ptr obstacle_points_ptr, + const PointCloud::Ptr points_belonging_to_cluster_hulls) { autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - // check if the predicted path has valid number of points - if (ego_path.size() < 2 || ego_polys.empty() || obstacle_points_ptr->empty()) { - return; - } - // eliminate noisy points by only considering points belonging to clusters of at least a certain // size + if (obstacle_points_ptr->empty()) return; const std::vector cluster_indices = std::invoke([&]() { std::vector cluster_idx; pcl::search::KdTree::Ptr tree(new pcl::search::KdTree); @@ -783,8 +789,6 @@ void AEB::createObjectDataUsingPointCloudClusters( ec.extract(cluster_idx); return cluster_idx; }); - - PointCloud::Ptr points_belonging_to_cluster_hulls(new PointCloud); for (const auto & indices : cluster_indices) { PointCloud::Ptr cluster(new PointCloud); bool cluster_surpasses_threshold_height{false}; @@ -801,12 +805,23 @@ void AEB::createObjectDataUsingPointCloudClusters( hull.setDimension(2); hull.setInputCloud(cluster); std::vector polygons; - PointCloud::Ptr surface_hull(new pcl::PointCloud); + PointCloud::Ptr surface_hull(new PointCloud); hull.reconstruct(*surface_hull, polygons); for (const auto & p : *surface_hull) { points_belonging_to_cluster_hulls->push_back(p); } } +} + +void AEB::getClosestObjectsOnPath( + const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, + const PointCloud::Ptr points_belonging_to_cluster_hulls, std::vector & objects) +{ + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + // check if the predicted path has valid number of points + if (ego_path.size() < 2 || ego_polys.empty() || points_belonging_to_cluster_hulls->empty()) { + return; + } // select points inside the ego footprint path const auto current_p = [&]() { @@ -845,7 +860,7 @@ void AEB::createObjectDataUsingPointCloudClusters( } void AEB::cropPointCloudWithEgoFootprintPath( - const std::vector & ego_polys, pcl::PointCloud::Ptr filtered_objects) + const std::vector & ego_polys, PointCloud::Ptr filtered_objects) { autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); PointCloud::Ptr full_points_ptr(new PointCloud); @@ -863,7 +878,7 @@ void AEB::cropPointCloudWithEgoFootprintPath( hull.setDimension(2); hull.setInputCloud(path_polygon_points); std::vector polygons; - pcl::PointCloud::Ptr surface_hull(new pcl::PointCloud); + PointCloud::Ptr surface_hull(new PointCloud); hull.reconstruct(*surface_hull, polygons); // Filter out points outside of the path's convex hull pcl::CropHull path_polygon_hull_filter; @@ -946,20 +961,15 @@ void AEB::addVirtualStopWallMarker(MarkerArray & markers) { autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto ego_map_pose = std::invoke([this]() -> std::optional { - geometry_msgs::msg::TransformStamped tf_current_pose; + const auto logger = get_logger(); + const auto tf_current_pose = utils::getTransform("map", "base_link", tf_buffer_, logger); + if (!tf_current_pose.has_value()) return std::nullopt; + const auto transform = tf_current_pose.value().transform; geometry_msgs::msg::Pose p; - try { - tf_current_pose = tf_buffer_.lookupTransform( - "map", "base_link", rclcpp::Time(0), rclcpp::Duration::from_seconds(1.0)); - } catch (tf2::TransformException & ex) { - RCLCPP_ERROR(get_logger(), "%s", ex.what()); - return std::nullopt; - } - - p.orientation = tf_current_pose.transform.rotation; - p.position.x = tf_current_pose.transform.translation.x; - p.position.y = tf_current_pose.transform.translation.y; - p.position.z = tf_current_pose.transform.translation.z; + p.orientation = transform.rotation; + p.position.x = transform.translation.x; + p.position.y = transform.translation.y; + p.position.z = transform.translation.z; return std::make_optional(p); }); diff --git a/control/autoware_autonomous_emergency_braking/src/utils.cpp b/control/autoware_autonomous_emergency_braking/src/utils.cpp index 1b9fad6af9860..16174bff3b489 100644 --- a/control/autoware_autonomous_emergency_braking/src/utils.cpp +++ b/control/autoware_autonomous_emergency_braking/src/utils.cpp @@ -14,6 +14,8 @@ #include +#include + namespace autoware::motion::control::autonomous_emergency_braking::utils { using autoware::universe_utils::Polygon2d; @@ -25,7 +27,7 @@ using geometry_msgs::msg::TransformStamped; using geometry_msgs::msg::Vector3; PredictedObject transformObjectFrame( - const PredictedObject & input, geometry_msgs::msg::TransformStamped & transform_stamped) + const PredictedObject & input, const geometry_msgs::msg::TransformStamped & transform_stamped) { PredictedObject output = input; const auto & linear_twist = input.kinematics.initial_twist_with_covariance.twist.linear; @@ -149,4 +151,20 @@ Polygon2d convertObjToPolygon(const PredictedObject & obj) } return object_polygon; } + +std::optional getTransform( + const std::string & target_frame, const std::string & source_frame, + const tf2_ros::Buffer & tf_buffer, const rclcpp::Logger & logger) +{ + geometry_msgs::msg::TransformStamped tf_current_pose; + try { + tf_current_pose = tf_buffer.lookupTransform( + target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration::from_seconds(1.0)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM( + logger, "[AEB] Failed to look up transform from " + source_frame + " to " + target_frame); + return std::nullopt; + } + return std::make_optional(tf_current_pose); +} } // namespace autoware::motion::control::autonomous_emergency_braking::utils diff --git a/control/autoware_autonomous_emergency_braking/test/test.cpp b/control/autoware_autonomous_emergency_braking/test/test.cpp index 42054e718d09c..6203e12a78194 100644 --- a/control/autoware_autonomous_emergency_braking/test/test.cpp +++ b/control/autoware_autonomous_emergency_braking/test/test.cpp @@ -156,9 +156,12 @@ TEST_F(TestAEB, checkImuPathGeneration) obstacle_points_ptr->push_back(p2); } } + PointCloud::Ptr points_belonging_to_cluster_hulls = pcl::make_shared(); + aeb_node_->getPointsBelongingToClusterHulls( + obstacle_points_ptr, points_belonging_to_cluster_hulls); std::vector objects; - aeb_node_->createObjectDataUsingPointCloudClusters( - imu_path, footprint, stamp, objects, obstacle_points_ptr); + aeb_node_->getClosestObjectsOnPath( + imu_path, footprint, stamp, points_belonging_to_cluster_hulls, objects); ASSERT_FALSE(objects.empty()); } From c654a038e379582c8c111cf52c9c018391e3ffe6 Mon Sep 17 00:00:00 2001 From: Atto <168620037+AA-T4@users.noreply.github.com> Date: Fri, 6 Sep 2024 13:53:26 +0900 Subject: [PATCH 140/217] docs(static_obstacle_avoidance): light edits. Typos, grammar fixes (#8759) * Light edit: Typos, grammar fixes. Additional changes to follow * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md Paragraph revised to correct typos Co-authored-by: Go Sakayori * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md Paragraph revised to correct typos Co-authored-by: Go Sakayori * fix typo in avoidance.png Signed-off-by: Go Sakayori * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md * fix pre-commit Signed-off-by: Go Sakayori * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md --------- Signed-off-by: Go Sakayori Co-authored-by: Go Sakayori Co-authored-by: Go Sakayori Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- .../README.md | 301 +++++++++--------- .../images/purpose/avoidance.png | Bin 47953 -> 60242 bytes 2 files changed, 151 insertions(+), 150 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md index 81c76eaa2c02c..e1a914b488790 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md @@ -2,31 +2,31 @@ ![fig](./images/purpose/rviz.png) -## Purpose / Role +## Purpose/Role -This is a rule-based avoidance module, which is running based on perception output data, HDMap, current path and route. This module is designed for creating avoidance path for static (=stopped) objects in simple situation. On the other hand, this module doesn't support dynamic (=moving) objects for now. +This is a rule-based avoidance module, which runs based on perception output data, HDMap, current path and route. This module is designed to create avoidance paths for static (=stopped) objects in simple situations. Currently, this module doesn't support dynamic (=moving) objects. ![fig](./images/purpose/avoidance.png) -This module has [RTC interface](../../autoware_rtc_interface/README.md), and user can select operation mode from MANUAL/AUTO depending on the vehicle sensor performance. If user selects MANUAL mode, this module outputs avoidance path as candidate and waits operator approval. In the case where the sensor/perception performance is not enough and false positive maybe occurs, we recommend to use this module with MANUAL mode in order to prevent unnecessary avoidance maneuver. +This module has an [RTC interface](../../autoware_rtc_interface/README.md), and the user can select operation mode from MANUAL/AUTO depending on the performance of the vehicle's sensors. If the user selects MANUAL mode, this module outputs a candidate avoidance path and awaits operator approval. In the case where the sensor/perception performance is insufficient and false positives occur, we recommend MANUAL mode to prevent unnecessary avoidance maneuvers. -On the other hand, if user selects AUTO mode, this module modifies current following path without operator approval. If the sensor/perception performance is good enough, user can use this module with AUTO mode. +If the user selects AUTO mode, this module modifies the current following path without operator approval. If the sensor/perception performance is sufficient, use AUTO mode. ### Limitations -This module allows developers to design vehicle behavior in avoidance planning using specific rules. Due to the property of rule-based planning, the algorithm can not compensate for not colliding with obstacles in complex cases. This is a trade-off between "be intuitive and easy to design" and "be hard to tune but can handle many cases". This module adopts the former policy and therefore this output should be checked more strictly in the later stage. In the .iv reference implementation, there is another avoidance module in motion planning module that uses optimization to handle the avoidance in complex cases. (Note that, the motion planner needs to be adjusted so that the behavior result will not be changed much in the simple case and this is a typical challenge for the behavior-motion hierarchical architecture.) +This module allows developers to design vehicle behavior in avoidance planning using specific rules. Due to the property of rule-based planning, the algorithm cannot compensate for not colliding with obstacles in complex cases. This is a trade-off between "be intuitive and easy to design" and "be hard to tune but can handle many cases". This module adopts the former policy and therefore this output should be checked more strictly in the later stage. In the .iv reference implementation, there is another avoidance module in the motion planning module that uses optimization to handle the avoidance in complex cases. (Note that, the motion planner needs to be adjusted so that the behavior result will not be changed much in the simple case and this is a typical challenge for the behavior-motion hierarchical architecture.) ### Why is avoidance in behavior module? -This module executes avoidance over lanes, and the decision requires the lane structure information to take care of traffic rules (e.g. it needs to send an indicator signal when the vehicle crosses a lane). The difference between motion and behavior module in the planning stack is whether the planner takes traffic rules into account, which is why this avoidance module exists in the behavior module. +This module executes avoidance over lanes, and the decision requires the lane structure information to take care of traffic rules (e.g. it needs to send an indicator signal when the vehicle crosses a lane). The difference between the motion and behavior modules in the planning stack is whether the planner takes traffic rules into account, which is why this avoidance module exists in the behavior module.
If you would like to know the overview rather than the detail, please skip the next section and refer to [FAQ](#frequently-asked-questions). -## Inner-workings / Algorithms +## Inner workings/Algorithms -This module mainly has two parts, target filtering part and path generation part. At first, all objects are filtered by several conditions. In this step, this module checks avoidance feasibility and necessity as well. After that, this module generates avoidance path outline, whom we call **shift line**, based on filtered objects. The shift lines are set into [path shifter](../autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md), which is a library for path generation, to create smooth shift path. Additionally, this module has feature to check non-target objects so that the ego can avoid target object safely. This feature receives generated avoidance path and surround objects and judges current situation. Lastly, this module update current ego behavior. +This module mainly has two parts, target filtering and path generation. At first, all objects are filtered by several conditions. In this step, the module checks avoidance feasibility and necessity. After that, this module generates avoidance path outline, which we call **shift line**, based on filtered objects. The shift lines are set into [path shifter](../autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md), which is a library for path generation, to create a smooth shift path. Additionally, this module has a feature to check non-target objects so that the ego can avoid target objects safely. This feature receives a generated avoidance path and surrounding objects, and judges the current situation. Lastly, this module updates current ego behavior. ```plantuml @startuml @@ -47,15 +47,15 @@ note right - drivable bounds - avoidance start point calculate the point where the ego should start avoidance maneuver - depending on traffic siganl. + depending on traffic signal. - avoidance return point calculate the point where the ego should return original lane - depending on traffic siganl and goal position. + depending on traffic signal and goal position. end note :fillAvoidanceTargetObjects(); note right - This module checks following conditions: + This module checks the following conditions: - target object type - being stopped - being around the ego-driving lane @@ -76,7 +76,7 @@ partition fillShiftLine() { :check candidate path; note right This module checks following conditions: - - is there enough distance between surround moving vehicle and ego path to avoid target safely? + - is there enough distance between surrounding moving vehicles and ego path to avoid target safely? - is the path jerky? - is the path within drivable area? end note @@ -86,9 +86,9 @@ partition fillEgoStatus() { :getCurrentModuleState(); note right This module has following status: - - RUNNING: target object is still remaining. Or, the ego hasn't returned original lane. + - RUNNING: target object is still remaining. Or, the ego hasn't returned to original lane. - CANCEL: target object has gone. And, the ego hasn't initiated avoidance maneuver. - - SUCCEEDED: the ego finishes avoiding all objects and returns original lane. + - SUCCEEDED: the ego finishes avoiding all objects and returns to original lane. end note if (canYieldManeuver()) then (yes) @@ -110,7 +110,7 @@ stop start partition isExecutionRequested() { -if (Is there object that should/can be avoid immediately?) then (yes) +if (Is there an object that should/can be avoided immediately?) then (yes) :return true; stop else (no) @@ -125,8 +125,8 @@ endif if (Is there object that is potentially avoidable?) then (yes) :return true; note right - Sometimes, we meet the situation where there is enough space to avoid - but ego speed is to high to avoid target object under lateral jerk constraints. + Sometimes, there are situations where there is enough space to avoid + but ego speed is too high to avoid target object under lateral jerk constraints. This module keeps running in this case in order to decelerate ego speed. end note stop @@ -210,30 +210,30 @@ stop ### Overview -The module uses following conditions to filter avoidance target objects. - -| Check condition | Target class | Details | If conditions are not met | -| -------------------------------------------------------------------------------------------- | ------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------- | -| Is an avoidance target class object? | All | Use can select avoidance target class from config file. | Never avoid it. | -| Is a stopped object? | All | Objects keep higher speed than `th_moving_speed` for longer period of time than `th_moving_time` is judged as moving. | Never avoid it. | -| Is within detection area? | All | The module creates detection area to filter target objects roughly based on lateral margin in config file. (see [here](#width-of-detection-area)) | Never avoid it. | -| Isn't there enough lateral distance between the object and path? | All | - | Never avoid it. | -| Is near the centerline of ego lane? | All | - | It depends on other conditions. | -| Is there a crosswalk near the object? | Pedestrian, Bicycle | The module don't avoid the Pedestrian and Bicycle nearer the crosswalk because the ego should stop in front of it if they're crossing road. (see [here](#for-crosswalk-users)) | Never avoid it. | -| Is the distance between the object and traffic light along the path longer than threshold? | Car, Truck, Bus, Trailer | The module used this condition if there is ambiguity as to whether the vehicle is a parked vehicle or not. | It depends on other conditions. | -| Is the distance between the object and crosswalk light along the path longer than threshold? | Car, Truck, Bus, Trailer | Same as above. | It depends on other conditions. | -| Is the stopping time longer than threshold? | Car, Truck, Bus, Trailer | Same as above. | It depends on other conditions. | -| Is within intersection? | Car, Truck, Bus, Trailer | The module assumes that there isn't any parked vehicle within intersection. | It depends on other conditions. | -| Is on ego lane? | Car, Truck, Bus, Trailer | - | It depends on other conditions. | -| Is a parked vehicle? | Car, Truck, Bus, Trailer | The module judges whether the vehicle is a parked vehicle based on its lateral offset. (see [here](#judge-if-its-a-parked-vehicle)) | It depends on other conditions. | -| Is merging to ego lane from other lane? | Car, Truck, Bus, Trailer | The module judges the vehicle behavior based on its yaw angle and offset direction. (see [here](#judge-vehicle-behavior)) | It depends on other conditions. | -| Is merging to other lane from ego lane? | Car, Truck, Bus, Trailer | Same as above. | It depends on other conditions. | +The module uses the following conditions to filter avoidance target objects. + +| Check condition | Target class | Details | If conditions are not met | +| ---------------------------------------------------------------------------------------------- | ------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------- | +| Is an avoidance target class object? | All | Use can select avoidance target class from config file. | Never avoid it. | +| Is a stopped object? | All | Objects keep higher speed than `th_moving_speed` for longer period of time than `th_moving_time` is judged as moving. | Never avoid it. | +| Is within detection area? | All | The module creates detection area to filter target objects roughly based on lateral margin in config file. (see [here](#width-of-detection-area)) | Never avoid it. | +| Isn't there enough lateral distance between the object and path? | All | - | Never avoid it. | +| Is near the centerline of ego lane? | All | - | It depends on other conditions. | +| Is there a crosswalk near the object? | Pedestrian, Bicycle | The module doesn't avoid the Pedestrian and Bicycle nearer the crosswalk because the ego should stop in front of it if they're crossing the road. (see [here](#for-crosswalk-users)) | Never avoid it. | +| Is the distance between the object and traffic light along the path longer than the threshold? | Car, Truck, Bus, Trailer | The module uses this condition when there is ambiguity about whether the vehicle is parked. | It depends on other conditions. | +| Is the distance between the object and crosswalk light along the path longer than threshold? | Car, Truck, Bus, Trailer | Same as above. | It depends on other conditions. | +| Is the stopping time longer than threshold? | Car, Truck, Bus, Trailer | Same as above. | It depends on other conditions. | +| Is within intersection? | Car, Truck, Bus, Trailer | The module assumes that there isn't any parked vehicle within intersection. | It depends on other conditions. | +| Is on ego lane? | Car, Truck, Bus, Trailer | - | It depends on other conditions. | +| Is a parked vehicle? | Car, Truck, Bus, Trailer | The module judges whether the vehicle is a parked vehicle based on its lateral offset. (see [here](#judge-if-its-a-parked-vehicle)) | It depends on other conditions. | +| Is merging into ego lane from other lane? | Car, Truck, Bus, Trailer | The module judges the vehicle behavior based on its yaw angle and offset direction. (see [here](#judge-vehicle-behavior)) | It depends on other conditions. | +| Is merging into other lane from ego lane? | Car, Truck, Bus, Trailer | Same as above. | It depends on other conditions. | ### Common conditions #### Detection area -The module generates detection area for target filtering based on following params: +The module generates detection area for target filtering based on the following parameters: ```yaml # avoidance is performed for the object type with true @@ -257,14 +257,14 @@ The module generates detection area for target filtering based on following para ##### Width of detection area -1. get the largest lateral margin of all classes (Car, Truck, ...). The margin is sum of `soft_margin` and `hard_margin_for_parked_vehicle`. -2. the detection area width is sum of ego vehicle width and the largest lateral margin. +1. Get the largest lateral margin of all classes (Car, Truck, ...). The margin is the sum of `soft_margin` and `hard_margin_for_parked_vehicle`. +2. The detection area width is the sum of ego vehicle width and the largest lateral margin. ##### Longitudinal distance of detection area If the parameter `detection_area.static` is set to `true`, the module creates detection area whose longitudinal distance is `max_forward_distance`. -If the parameter `detection_area.static` is set to `false`, the module creates detection area so that the ego can avoid objects with minimum lateral jerk value. Thus, the longitudinal distance is depends on lateral maximum shift length, lateral jerk constraints and current ego speed. Additionally, it has to consider distance used for prepare phase. +If the parameter `detection_area.static` is set to `false`, the module creates a detection area so that the ego can avoid objects with minimum lateral jerk value. Thus, the longitudinal distance depends on maximum lateral shift length, lateral jerk constraints and current ego speed. Additionally, it has to consider the distance used for the preparation phase. ```c++ ... @@ -295,7 +295,7 @@ If Pedestrian and Bicycle are closer to crosswalk than threshold 2.0m (hard code #### Judge vehicle behavior -The module classifies vehicles into following three behavior based on its yaw angle and offset direction. +The module classifies vehicles into the following three behaviors based on yaw angle and offset direction. ```yaml # params for filtering objects that are in intersection @@ -354,7 +354,7 @@ stop #### Judge if it's a parked vehicle -Not only the length from the centerline, but also the length from the road shoulder is calculated and used for the filtering process. In this logic, it calculates ratio of **actual shift length** to **shiftable shift length** as follow. If the result is larger than threshold `th_shiftable_ratio`, the module judges the vehicle as a parked vehicle. +Not only the length from the centerline, but also the length from the road shoulder is calculated and used for the filtering process. In this logic, it calculates ratio of **actual shift length** to **shiftable shift length** as follows. If the result is larger than threshold `th_shiftable_ratio`, the module judges the vehicle is a parked vehicle. $$ L_{d} = \frac{W_{lane} - W_{obj}}{2}, \\ @@ -370,22 +370,22 @@ $$ ### Target object filtering -| Situation | Details | Ego behavior | -| -------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------- | -| Vehicle is within intersection area defined in HDMap. The module ignores vehicle which is following lane or merging to ego lane. | ![fig](./images/target_filter/never_avoid_intersection.png) | Never avoid it. | -| Vehicle is on ego lane. There are adjacent lanes for both side. | ![fig](./images/target_filter/never_avoid_not_edge.png) | Never avoid it. | -| Vehicle is merging to other lane from ego lane. Most part of its footprint is on ego lane. | ![fig](./images/target_filter/never_avoid_deviating.png) | Never avoid it. | -| Vehicle is merging to ego lane from other lane. Most part of its footprint is on ego lane. | ![fig](./images/target_filter/never_avoid_merging.png) | Never avoid it. | -| Vehicle is not a obvious parked vehicle and stopping in front of the crosswalk or traffic light. | ![fig](./images/target_filter/never_avoid_stop_factor.png) | Never avoid it. | -| Vehicle stops on ego lane with pulling over to the side of the road. | ![fig](./images/target_filter/avoid_on_ego_lane.png) | Avoid it immediately. | -| Vehicle stops on adjacent lane. | ![fig](./images/target_filter/avoid_not_on_ego_lane.png) | Avoid it immediately. | -| Vehicle stops on ego lane without pulling over to the side of the road. | ![fig](./images/target_filter/ambiguous_parallel.png) | Set the parameter `avoidance_for_ambiguous_vehicle.enable` to `true`, the module avoids ambiguous vehicle. | -| Vehicle is merging to ego lane from other lane. | ![fig](./images/target_filter/ambiguous_merging.png) | Set the parameter `avoidance_for_ambiguous_vehicle.enable` to `true`, the module avoids ambiguous vehicle. | -| Vehicle is merging to other lane from ego lane. | ![fig](./images/target_filter/ambiguous_deviating.png) | Set the parameter `avoidance_for_ambiguous_vehicle.enable` to `true`, the module avoids ambiguous vehicle. | +| Situation | Details | Ego behavior | +| ---------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------- | +| Vehicle is within intersection area defined in HDMap. The module ignores vehicles following a lane or merging into ego lane. | ![fig](./images/target_filter/never_avoid_intersection.png) | Never avoid it. | +| Vehicle is on ego lane. There are adjacent lanes for both sides. | ![fig](./images/target_filter/never_avoid_not_edge.png) | Never avoid it. | +| Vehicle is merging into other lane from ego lane. Most of its footprint is on ego lane. | ![fig](./images/target_filter/never_avoid_deviating.png) | Never avoid it. | +| Vehicle is merging into ego lane from other lane. Most of its footprint is on ego lane. | ![fig](./images/target_filter/never_avoid_merging.png) | Never avoid it. | +| Vehicle does not appear to be parked and is stopped in front of a crosswalk or traffic light. | ![fig](./images/target_filter/never_avoid_stop_factor.png) | Never avoid it. | +| Vehicle stops on ego lane while pulling over to the side of the road. | ![fig](./images/target_filter/avoid_on_ego_lane.png) | Avoid it immediately. | +| Vehicle stops on adjacent lane. | ![fig](./images/target_filter/avoid_not_on_ego_lane.png) | Avoid it immediately. | +| Vehicle stops on ego lane without pulling over to the side of the road. | ![fig](./images/target_filter/ambiguous_parallel.png) | Set the parameter `avoidance_for_ambiguous_vehicle.enable` to `true`, the module avoids ambiguous vehicle. | +| Vehicle is merging into ego lane from other lane. | ![fig](./images/target_filter/ambiguous_merging.png) | Set the parameter `avoidance_for_ambiguous_vehicle.enable` to `true`, the module avoids ambiguous vehicle. | +| Vehicle is merging into other lane from ego lane. | ![fig](./images/target_filter/ambiguous_deviating.png) | Set the parameter `avoidance_for_ambiguous_vehicle.enable` to `true`, the module avoids ambiguous vehicle. | ### Flowchart -There are three main filtering functions `isSatisfiedWithCommonCondition()`, `isSatisfiedWithVehicleCondition()` and `isSatisfiedWithNonVehicleCondition()`. The filtering process is executed according to following flowchart. Additionally, the module checks avoidance necessity in `isNoNeedAvoidanceBehavior()` based on the object pose, ego path and lateral margin in config file. +There are three main filtering functions `isSatisfiedWithCommonCondition()`, `isSatisfiedWithVehicleCondition()` and `isSatisfiedWithNonVehicleCondition()`. The filtering process is executed according to the following flowchart. Additionally, the module checks avoidance necessity in `isNoNeedAvoidanceBehavior()` based on the object pose, ego path and lateral margin in the config file. ```plantuml @startuml @@ -434,7 +434,7 @@ stop #### Common conditions -At first, the function `isSatisfiedWithCommonCondition()` includes conditions used for all object class. +At first, the function `isSatisfiedWithCommonCondition()` includes conditions used for all object classes. ```plantuml @startuml @@ -451,11 +451,11 @@ if(Is moving object?) then (yes) #00FFB1 :return false; stop else (\n no) -if(Is object farther than forward distance threshold ?) then (yes) +if(Is object farther than forward distance threshold?) then (yes) #00FFB1 :return false; stop else (\n no) -If(Is object farther than backward distance threshold ?) then (yes) +If(Is object farther than backward distance threshold?) then (yes) #00FFB1 :return false; stop else (\n no) @@ -487,7 +487,7 @@ Target class: - Bus - Trailer -As a next step, object is filtered by condition specialized for its class. +As a next step, the object is filtered by a condition specialized for its class. ```plantuml @startuml @@ -522,7 +522,7 @@ else (\n no) endif else (\n no) -if(Is object merging to ego lane?) then (yes) +if(Is object merging into ego lane?) then (yes) #FF006C :return true(ambiguous); stop else (\n no) @@ -570,7 +570,7 @@ stop else (\n no) endif -if(Is object merging to ego lane?) then (yes) +if(Is object merging into ego lane?) then (yes) #00FFB1 :return true; stop else (\n no) @@ -579,7 +579,7 @@ endif else (\n no) endif -if(Is object merging to ego lane?) then (yes) +if(Is object merging into ego lane?) then (yes) if(Is overhang distance larger than threshold?) then (yes) #00FFB1 :return true; stop @@ -607,7 +607,7 @@ else (\n no) endif if(isCloseToStopFactor()) then (yes) -if(Is object on ego lane? AND Isn't object a parked vehile?) then (no) +if(Is object on ego lane? AND Isn't object a parked vehicle?) then (no) #00FFB1 :return true; stop else (\n no) @@ -721,24 +721,24 @@ cancel: enable: true # [-] ``` -If above parameter is `true`, this module reverts avoidance path when following conditions are met. +If the above parameter is `true`, this module reverts avoidance path when the following conditions are met. -- all target objects have gone. -- the ego vehicle hasn't initiated avoidance maneuver yet. +- All target objects have gone. +- The ego vehicle hasn't initiated avoidance maneuver yet. ![fig](./images/cancel/cancel.png) -If the parameter is `false`, this module keeps running even after target object has gone. +If the parameter is `false`, this module keeps running even after the target object has gone. ## Path generation ### How to prevent shift line chattering that is caused by perception noise -Since object recognition result contains noise related to position, orientation and polygon shape, if the module uses the raw object recognition results in path generation, the output path will be directly affected by the noise. Therefore, in order to reduce the influence of the noise, this module generates polygon for each target objects, and the output path is generated based on that. +Since the object recognition result contains noise related to position, orientation and polygon shape, if the module uses the raw object recognition results in path generation, the output path will be directly affected by the noise. Therefore, in order to reduce the influence of the noise, this module generates a polygon for each target object, and the output path is generated based on that. ![fig](./images/path_generation/envelope_polygon_rviz.png) -The envelope polygon is a rectangle box, whose size depends on object's polygon and buffer parameter `envelope_buffer_margin`. Additionally, it is always parallel to reference path. When the module finds target object for the first time, it initializes the polygon. +The envelope polygon is a rectangle box, whose size depends on the object's polygon and buffer parameter `envelope_buffer_margin`. Additionally, it is always parallel to the reference path. When the module finds a target object for the first time, it initializes the polygon. ```yaml car: @@ -748,15 +748,15 @@ The envelope polygon is a rectangle box, whose size depends on object's polygon ![fig](./images/path_generation/envelope_polygon.png) -The module creates one-shot envelope polygon by using latest object pose and raw polygon in every planning cycle. On the other hand, the module envelope polygon information which is created in last planning cycle as well in order to update envelope polygon according to following logic. If the one-shot envelope polygon is not within previous envelope polygon, the module creates new envelope polygon. Otherwise, it keeps previous envelope polygon. By doing this process, the envelope polygon size and pose will converge even if perception output includes noise in object pose or shape. +The module creates a one-shot envelope polygon by using the latest object pose and raw polygon in every planning cycle. On the other hand, the module uses the envelope polygon information created in the last planning cycle in order to update the envelope polygon according to the following logic. If the one-shot envelope polygon is not within the previous envelope polygon, the module creates a new envelope polygon. Otherwise, it keeps the previous envelope polygon. By doing this process, the envelope polygon size and pose will converge even if perception output includes noise in object pose or shape. ![fig](./images/path_generation/polygon_update.png) ### Relationship between envelope polygon and avoidance path -The avoidance path has two shift section, whose start or end point position depends on envelope polygon. The end point of avoidance shift section and start point of return shift section are fixed based on envelope polygon and the other side edges are dynamically changed based on ego speed, shift length, lateral jerk constraints, etc... +The avoidance path has two shift sections, whose start or end point position depends on the envelope polygon. The end point of the avoidance shift section and start point of the return shift section are fixed based on the envelope polygon and the other side edges are dynamically changed based on ego speed, shift length, lateral jerk constraints, etc. -The lateral positions of the two points are decided so that there can be enough space (=lateral margin) between ego body and the most overhang point of envelope polygon edge points. User can adjust lateral margin with following parameters. +The lateral positions of the two points are decided so that there can be enough space (=lateral margin) between ego body and the most overhang point of the envelope polygon edge points. User can adjust lateral margin with the following parameters. ```yaml car: @@ -767,7 +767,7 @@ The lateral positions of the two points are decided so that there can be enough hard_margin_for_parked_vehicle: 0.7 # [m] ``` -The longitudinal positions depends on envelope polygon, ego vehicle specification and following parameters. The longitudinal distance between avoidance shift section end point and envelope polygon (=front longitudinal buffer) is sum of `front_overhang` defined in `vehicle_info.param.yaml` and `longitudinal_margin` if the parameter `consider_front_overhang` is `true`. If `consider_front_overhang` is `false`, only `longitudinal_margin` is considered. Similarly, the distance between return shift section start point and envelope polygon (=rear longitudinal buffer) is sum of `rear_overhang` and `longitudinal_margin`. +The longitudinal positions depends on the envelope polygon, ego vehicle specification and the following parameters. The longitudinal distance between avoidance shift section end point and envelope polygon (=front longitudinal buffer) is the sum of `front_overhang` defined in `vehicle_info.param.yaml` and `longitudinal_margin` if the parameter `consider_front_overhang` is `true`. If `consider_front_overhang` is `false`, only `longitudinal_margin` is considered. Similarly, the distance between the return shift section start point and envelope polygon (=rear longitudinal buffer) is the sum of `rear_overhang` and `longitudinal_margin`. ```yaml @@ -789,7 +789,7 @@ The longitudinal positions depends on envelope polygon, ego vehicle specificatio ### Lateral margin -As mentioned above, user can adjust lateral margin by changing following two types parameter. The `soft_margin` is a soft constraint parameter for lateral margin. The `hard_margin` and `hard_margin_for_parked_vehicle` are hard constraint parameter. +As mentioned above, user can adjust lateral margin by changing the following two types of parameters. The `soft_margin` is a soft constraint parameter for lateral margin. The `hard_margin` and `hard_margin_for_parked_vehicle` are hard constraint parameters. ```yaml car: @@ -800,61 +800,61 @@ As mentioned above, user can adjust lateral margin by changing following two typ hard_margin_for_parked_vehicle: 0.7 # [m] ``` -Basically, this module tries to generate avoidance path in order to keep lateral distance, which is sum of `soft_margin` and `hard_margin`/`hard_margin_for_parked_vehicle`, from avoidance target object. +Basically, this module tries to generate an avoidance path in order to keep lateral distance, which is the sum of `soft_margin` and `hard_margin`/`hard_margin_for_parked_vehicle`, from the avoidance target object. ![fig](./images/path_generation/soft_hard.png) But if there isn't enough space to keep `soft_margin` distance, this module shortens soft constraint lateral margin. The parameter `soft_margin` is a maximum value of soft constraint, and actual soft margin can be a value between 0.0 and `soft_margin`. On the other hand, this module definitely keeps `hard_margin` or `hard_margin_for_parked_vehicle` depending on the situation. Thus, the minimum value of total lateral margin is `hard_margin`/`hard_margin_for_parked_vehicle`, and the maximum value is the sum of `hard_margin`/`hard_margin_for_parked_vehicle` and `soft_margin`. -Following figure shows the situation where this module shortens lateral soft constraint in order not to drive opposite direction lane when user set a parameter `use_lane_type` to `same_direction_lane`. +The following figure shows the situation where this module shortens lateral soft constraint in order not to drive in the opposite lane when user sets parameter `use_lane_type` to `same_direction_lane`. ![fig](./images/path_generation/adjust_margin.png) -This module avoids not only parked vehicle but also non-parked vehicle which stops temporarily for some reason (e.g. waiting for traffic light to change red to green.). Additionally, this module has two types hard margin parameters, `hard_margin` and `hard_margin_for_parked_vehicle` and judges if it's a parked vehicle or not for each vehicles because it takes the risk of vehicle doors opening suddenly and people getting out from parked vehicle into consideration. +This module avoids not only parked vehicles but also non-parked vehicles that stop temporarily for some reason (e.g. waiting for traffic light to change from red to green). Additionally, this module has two types of hard margin parameters, `hard_margin` and `hard_margin_for_parked_vehicle` and judges if it is a parked vehicle or not for each vehicle because it takes the risk of vehicle doors opening suddenly and people getting out from parked vehicles into consideration. -Basically, user had better make `hard_margin_for_parked_vehicle` larger than `hard_margin` to prevent collision with doors or people who suddenly get out from vehicle. +Users should set `hard_margin_for_parked_vehicle` larger than `hard_margin` to prevent collisions with doors or people who suddenly exit a vehicle. -On the other hand, this module has only one parameter `soft_margin` for soft lateral margin constraint. +This module has only one parameter `soft_margin` for soft lateral margin constraint. ![fig](./images/path_generation/hard_margin.png) -As the hard margin parameters the distance which the user definitely want to keep, they are used in the logic to check whether the ego can pass side of the target object without avoidance maneuver as well. +As the hard margin parameters define the distance the user definitely wants to maintain, they are used in the logic to check whether the ego can pass the side of the target object without executing an avoidance maneuver as well. -If the lateral distance is less than `hard_margin`/`hard_margin_for_parked_vehicle` when assuming that the ego follows current lane without avoidance maneuver, this module thinks the ego can not pass the side of the object safely and the ego must avoid it. In this case, this module inserts stop point until the avoidance maneuver is allowed to execute so that the ego can avoid the object after approval. (e.g. The ego keeps stopping in front of such a object until operator approves avoidance maneuver if user uses this module in MANUAL mode.) +If the lateral distance is less than `hard_margin`/`hard_margin_for_parked_vehicle` when assuming that the ego follows the current lane without an avoidance maneuver, this module thinks the ego can not pass the side of the object safely and the ego must avoid it. In this case, this module inserts a stop point until the avoidance maneuver is allowed to execute so that the ego can avoid the object after approval. (For example, the ego keeps stopping in front of such an object until the operator approves the avoidance maneuver if the module is in MANUAL mode.) ![fig](./images/path_generation/must_avoid.png) -On the other hand, if the lateral distance is larger than `hard_margin`/`hard_margin_for_parked_vehicle`, this module doesn't insert stop point even when it's waiting approval because it thinks it's possible to pass the side of the object safely. +On the other hand, if the lateral distance is larger than `hard_margin`/`hard_margin_for_parked_vehicle`, this module doesn't insert a stop point even when it is waiting for approval because it thinks it is possible to pass the side of the object safely. ![fig](./images/path_generation/pass_through.png) ### When there is not enough space -This module inserts stop point only when the ego can potentially avoid the object. So, if it is not able to keep distance more than `hard_margin`/`hard_margin_for_parked_vehicle`, this module does nothing. Following figure shows the situation where this module is not able to keep enough lateral distance when user set a parameter `use_lane_type` to `same_direction_lane`. +This module inserts a stop point only when the ego can potentially avoid the object. So, if it is not able to keep a distance more than `hard_margin`/`hard_margin_for_parked_vehicle`, this module does nothing. The following figure shows the situation where this module is not able to keep enough lateral distance when the user sets parameter `use_lane_type` to `same_direction_lane`. ![fig](./images/path_generation/do_nothing.png) !!! info - In this situation, obstacle stop feature in [obstacle_cruise_planner](../../autoware_obstacle_cruise_planner/README.md) is responsible for ego vehicle safety. + In this situation, the obstacle stop feature in [obstacle_cruise_planner](../../autoware_obstacle_cruise_planner/README.md) is responsible for ego vehicle safety. ![fig](./images/path_generation/insufficient_drivable_space.png) ### Shift length calculation -The lateral shift length is sum of `overhang_distance`, lateral margin, whose value is set in config file, and the half of ego vehicle width defined in `vehicle_info.param.yaml`. On the other hand, the module limits the shift length depending on the space which the module can use for avoidance maneuver and the parameters `soft_drivable_bound_margin` `hard_drivable_bound_margin`. Basically, the shift length is limited so that the ego doesn't get closer than `soft_drivable_bound_margin` to drivable boundary. But it allows to relax the threshold `soft_drivable_bound_margin` to `hard_drivable_bound_margin` when the road is narrow. +The lateral shift length is the sum of `overhang_distance`, lateral margin, whose value is set in the config file, and half of ego vehicle width defined in `vehicle_info.param.yaml`. On the other hand, the module limits the shift length depending on the space the module can use for an avoidance maneuver and the parameters `soft_drivable_bound_margin` `hard_drivable_bound_margin`. Basically, the shift length is limited so that the ego doesn't get closer than `soft_drivable_bound_margin` to the drivable boundary. But the module allows the threshold to be relaxed from `soft_drivable_bound_margin` to `hard_drivable_bound_margin` when the road is narrow. ![fig](./images/path_generation/lateral.png) -Usable lane for avoidance module can be selected by config file. +Usable lanes for the avoidance module can be selected using the config file. ```yaml ... - # drivable lane setting. this module is able to use not only current lane but also right/left lane - # if the current lane(=lanelt::Lanelet) and the rignt/left lane share the boundary(=lanelet::Linestring) in HDMap. - # "current_lane" : use only current lane. this module doesn't use adjacent lane to avoid object. - # "same_direction_lane" : this module uses same direction lane to avoid object if need. - # "opposite_direction_lane": this module uses both same direction and opposite direction lane. + # drivable lane setting. This module is able to use not only current lane but also right/left lane + # if the current lane(=lanelet::Lanelet) and the right/left lane share the boundary(=lanelet::Linestring) in HDMap. + # "current_lane" : use only current lane. This module doesn't use adjacent lane to avoid object. + # "same_direction_lane" : this module uses same direction lane to avoid object if needed. + # "opposite_direction_lane": this module uses both same direction and opposite direction lanes. use_lane_type: "opposite_direction_lane" ``` @@ -868,9 +868,9 @@ When user set parameter `use_lane_type` to `same_direction_lane`, the module doe ### Shift line generation -As mentioned above, the end point of avoidance shift path and the start point of return shift path, which are FIXED points, are calculated from envelope polygon. As a next step, the module adjusts the other side points depending on shift length, current ego speed and lateral jerk constrain params defined in config file. +As mentioned above, the end point of the avoidance shift path and the start point of the return shift path, which are FIXED points, are calculated from envelope polygon. As a next step, the module adjusts the other side points depending on shift length, current ego speed and lateral jerk constrain params defined in the config file. -Since the two points are always on centerline of ego lane, the module only calculates longitudinal distance between shift start and end point based on following function. This function is defined in path shifter library, so please see [this](../autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md) page as well. +Since the two points are always on the centerline of the ego lane, the module only calculates longitudinal distance between the shift start and end point based on the following function. This function is defined in the path shifter library. See [this](../autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md) page as well. ```c++ double PathShifter::calcLongitudinalDistFromJerk( @@ -886,9 +886,9 @@ double PathShifter::calcLongitudinalDistFromJerk( } ``` -We call the line which connects shift start and end point `shift_line`, whom the avoidance path is generated from with spline completion. +We call the line that connects shift start and end point `shift_line`, which the avoidance path is generated from with spline completion. -The start point of avoidance has another longitudinal constraint. In order to keep turning on the blinker for few seconds before starting avoidance maneuver, the avoidance start point must be further than the value (we call the distance `prepare_length`.) depending on ego speed from ego position. +The start point of avoidance has another longitudinal constraint. In order to keep turning on the blinker for a few seconds before starting the avoidance maneuver, the avoidance start point must be further than the value (we call the distance `prepare_length`.) depending on ego speed from ego position. ```yaml longitudinal: @@ -903,35 +903,35 @@ The `prepare_length` is calculated as the product of ego speed and `max_prepare_ ## Planning at RED traffic light -This module takes traffic light information into account so that the ego can behave properly. Sometimes, the ego straddles lane boundary but we want to prevent the ego from stopping in front of red traffic signal in such a situation. This is because the ego will block adjacent lane and it's inconvenient for other vehicles. +This module takes traffic light information into account so that the ego can behave properly. Sometimes, the ego straddles the lane boundary but we want to prevent the ego from stopping in front of a red traffic signal in such a situation. This is because the ego will block adjacent lanes and it is inconvenient for other vehicles. ![fig](./images/traffic_light/traffic_light.png) -So, this module controls shift length and shift start/end point in order to prevent above situation. +So, this module controls shift length and shift start/end point in order to prevent the above situation. ### Control shift length -At first, if the ego hasn't initiated avoidance maneuver yet, this module limits maximum shift length and uses **ONLY** current lane during red traffic signal. This prevents the ego from blocking other vehicles even if this module executes avoidance maneuver and the ego is caught by red traffic signal. +At first, if the ego hasn't initiated an avoidance maneuver yet, this module limits maximum shift length and uses **ONLY** current lane during a red traffic signal. This prevents the ego from blocking other vehicles even if this module executes the avoidance maneuver and the ego is caught by a red traffic signal. ![fig](./images/traffic_light/limit_shift_length.png) ### Control avoidance shift start point -Additionally, if the target object is farther than stop line for traffic light, this module set avoidance shift start point on the stop line in order to prevent the ego from stopping by red traffic signal in middle of avoidance maneuver. +Additionally, if the target object is farther than the stop line of the traffic light, this module sets the avoidance shift start point on the stop line in order to prevent the ego from stopping at a red traffic signal in the middle of an avoidance maneuver. ![fig](./images/traffic_light/shift_from_current_pos.png) ![fig](./images/traffic_light/shift_from_stop_line.png) ### Control return shift end point -If the ego has already initiated avoidance maneuver, this module tries to set return shift end point on the stop line. +If the ego has already initiated an avoidance maneuver, this module tries to set the return shift end point on the stop line. ![fig](./images/traffic_light/return_after_stop_line.png) ![fig](./images/traffic_light/return_before_stop_line.png) ## Safety check -This feature can be enable by setting following parameter to `true`. +This feature can be enabled by setting the following parameter to `true`. ```yaml safety_check: @@ -939,15 +939,15 @@ This feature can be enable by setting following parameter to `true`. enable: true # [-] ``` -This module pay attention not only avoidance target objects but also non-target objects that are near the avoidance path, and if avoidance path is unsafe due to surround objects, it reverts avoidance maneuver and yields lane to them. +This module pays attention not only to avoidance target objects but also non-target objects that are near the avoidance path, and if the avoidance path is unsafe due to surrounding objects, it reverts the avoidance maneuver and yields the lane to them. ![fig](./images/safety_check/safety_check_flow.png) ### Yield maneuver -Additionally, this module basically inserts stop point in front of avoidance target during yielding maneuver in order to keep enough distance to avoid the target after it is safe situation. If the shift side lane is congested, the ego stops the point and waits. +Additionally, this module basically inserts a stop point in front of an avoidance target during yielding maneuvers in order to keep enough distance to avoid the target when it is safe to do so. If the shift side lane is congested, the ego stops at a point and waits. -This feature can be enable by setting following parameter to `true`. +This feature can be enabled by setting the following parameter to `true`. ```yaml yield: @@ -956,13 +956,13 @@ yield: ![fig](./images/safety_check/stop.png) -But if the lateral margin is larger than `hard_margin` (or `hard_margin_for_parked_vehicle`), this module doesn't insert stop point because the ego can pass side of the object safely without avoidance maneuver. +But if the lateral margin is larger than `hard_margin` (or `hard_margin_for_parked_vehicle`), this module doesn't insert a stop point because the ego can pass the side of the object safely without an avoidance maneuver. ![fig](./images/safety_check/not_stop.png) ### Safety check target lane -User can select safety check area by following params. Basically, we recommend following configuration to check only sift side lane. But if user want to confirm safety strictly, please set `check_current_lane` and/or `check_other_side_lane` to `true`. +User can select the safety check area with the following parameters. Basically, we recommend the following configuration to check only the shift side lane. If users want to confirm safety strictly, please set `check_current_lane` and/or `check_other_side_lane` to `true`. ```yaml safety_check: @@ -972,7 +972,7 @@ User can select safety check area by following params. Basically, we recommend f check_other_side_lane: false # [-] ``` -In avoidance module, the function `path_safety_checker::isCentroidWithinLanelet` is used for filtering objects by lane. +In the avoidance module, the function `path_safety_checker::isCentroidWithinLanelet` is used for filtering objects by lane. ```c++ bool isCentroidWithinLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet) @@ -985,7 +985,7 @@ bool isCentroidWithinLanelet(const PredictedObject & object, const lanelet::Cons !!! info - If it set `check_current_lane` and/or `check_other_side_lane` to `true`, maybe the possibility of false positive occurring and unnecessary yield maneuver execution increases. + If `check_current_lane` and/or `check_other_side_lane` are set to `true`, the possibility of false positives and unnecessary yield maneuvers increase. ### Safety check algorithm @@ -995,38 +995,38 @@ This module uses common safety check logic implemented in `path_safety_checker` #### Limitation-1 -The current behavior when the module judges it's unsafe is so conservative because it is difficult to achieve aggressive (e.g. increase speed in order to increase the distance to behind vehicle.) for current planning architecture. +The current behavior when the module judges it is unsafe is so conservative because it is difficult to achieve aggressive maneuvers (e.g. increase speed in order to increase the distance from rear vehicle) for current planning architecture. #### Limitation-2 -The yield maneuver is executed **ONLY** when the vehicle has **NOT** initiated avoidance maneuver yet. (This module checks objects on opposite lane but it's necessary to find very far objects to judge unsafe before avoidance maneuver.) If it detects vehicle which is closing to ego during avoidance maneuver, this module doesn't neither revert the path nor insert stop point. For now, there is no feature to deal with this situation in this module. Thus, new module is needed to adjust path to avoid moving objects, or operator should do override. +The yield maneuver is executed **ONLY** when the vehicle has **NOT** initiated avoidance maneuver yet. (This module checks objects in the opposite lane but it is necessary to find very far objects to judge whether it is unsafe before avoidance maneuver.) If it detects a vehicle which is approaching the ego during an avoidance maneuver, this module doesn't revert the path or insert a stop point. For now, there is no feature to deal with this situation in this module. Thus, a new module is needed to adjust the path to avoid moving objects, or an operator must override. !!! info - This module has a threshold parameter `th_avoid_execution` for the shift length, and judge that the vehicle is initiating avoidance if the vehicle current shift exceeds the value. + This module has a threshold parameter `th_avoid_execution` for the shift length, and judges that the vehicle is initiating avoidance if the vehicle current shift exceeds the value. ## Other features ### Compensation for detection lost -In order to prevent chattering of recognition results, once an obstacle is targeted, it is hold for a while even if it disappears. This is effective when recognition is unstable. However, since it will result in over-detection (increase a number of false-positive), it is necessary to adjust parameters according to the recognition accuracy (if `object_last_seen_threshold = 0.0`, the recognition result is 100% trusted). +In order to prevent chattering of recognition results, once an obstacle is targeted, it is held for a while even if it disappears. This is effective when recognition is unstable. However, since it will result in over-detection (increases number of false-positives), it is necessary to adjust parameters according to the recognition accuracy (if `object_last_seen_threshold = 0.0`, the recognition result is 100% trusted). ### Drivable area expansion This module supports drivable area expansion for following polygons defined in HDMap. -- intersection area -- hatched road marking -- freespace area +- Intersection area +- Hatched road marking +- Freespace area -Please set the flags to `true` when user wants to make it possible to use those areas in avoidance maneuver. +Please set the flags to `true` when user wants to make it possible to use those areas in avoidance maneuvers. ```yaml -# drivable lane setting. this module is able to use not only current lane but also right/left lane -# if the current lane(=lanelt::Lanelet) and the rignt/left lane share the boundary(=lanelet::Linestring) in HDMap. -# "current_lane" : use only current lane. this module doesn't use adjacent lane to avoid object. -# "same_direction_lane" : this module uses same direction lane to avoid object if need. -# "opposite_direction_lane": this module uses both same direction and opposite direction lane. +# drivable lane setting. This module is able to use not only current lane but also right/left lane +# if the current lane(=lanelet::Lanelet) and the right/left lane share the boundary(=lanelet::Linestring) in HDMap. +# "current_lane" : use only current lane. This module doesn't use adjacent lane to avoid object. +# "same_direction_lane" : this module uses the same direction lane to avoid object if needed. +# "opposite_direction_lane": this module uses both same direction and opposite direction lanes. use_lane_type: "opposite_direction_lane" # drivable area setting use_intersection_areas: true @@ -1042,12 +1042,12 @@ use_freespace_areas: true | hatched road markings | ![fig](./images/advanced/avoidance_zebra.png) | The hatched road marking is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_lanelet2_extension/blob/main/autoware_lanelet2_extension/docs/lanelet2_format_extension.md#hatched-road-markings-area) | | freespace area | ![fig](./images/advanced/avoidance_freespace.png) | The freespace area is defined on Lanelet map. (unstable) | -## Future extensions / Unimplemented parts +## Future extensions/Unimplemented parts - **Consideration of the speed of the avoidance target** - In the current implementation, only stopped vehicle is targeted as an avoidance target. It is needed to support the overtaking function for low-speed vehicles, such as a bicycle. (It is actually possible to overtake the low-speed objects by changing the parameter, but the logic is not supported and thus the safety cannot be guaranteed.) - - The overtaking (e.g., to overtake a vehicle running in front at 20 km/h at 40 km/h) may need to be handled outside the avoidance module. It should be discussed which module should handle it. + - Overtaking (e.g., to overtake a vehicle running in front at 20 km/h at 40 km/h) may need to be handled outside the avoidance module. It should be discussed which module should handle it. - **Cancel avoidance when target disappears** @@ -1055,21 +1055,21 @@ use_freespace_areas: true - **Improved performance of avoidance target selection** - - Essentially, avoidance targets are judged based on whether they are static objects or not. For example, a vehicle waiting at a traffic light should not be avoided because we know that it will start moving in the future. However this decision cannot be made in the current Autoware due to the lack of the perception functions. Therefore, the current avoidance module limits the avoidance target to vehicles parked on the shoulder of the road, and executes avoidance only for vehicles that are stopped away from the center of the lane. However, this logic cannot avoid a vehicle that has broken down and is stopped in the center of the lane, which should be recognized as a static object by the perception module. There is room for improvement in the performance of this decision. + - Essentially, avoidance targets are judged based on whether they are static objects or not. For example, a vehicle waiting at a traffic light should not be avoided because we know that it will start moving in the future. However this decision cannot be made in the current Autoware due to the lack of perception functions. Therefore, the current avoidance module limits the avoidance target to vehicles parked on the shoulder of the road, and executes avoidance only for vehicles that are stopped away from the center of the lane. However, this logic cannot avoid a vehicle that has broken down and is stopped in the center of the lane, which should be recognized as a static object by the perception module. There is room for improvement in the performance of this decision. - **Resampling path** - - Now the rough resolution resampling is processed to the output path in order to reduce the computational cost for the later modules. This resolution is set to a uniformly large value (e.g. `5m`), but small resolution should be applied for complex paths. + - Now the rough resolution resampling is processed to the output path in order to reduce the computational cost for the later modules. This resolution is set to a uniformly large value (e.g. `5m`), but a small resolution should be applied for complex paths. ## Debug ### Show `RCLCPP_DEBUG` on console -All of debug messages are logged in following namespaces. +All debug messages are logged in the following namespaces. - `planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.static_obstacle_avoidance` or, - `planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.static_obstacle_avoidance.utils` -User can see debug information by following command. +User can see debug information with the following command. ```bash ros2 service call /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/config_logger logging_demo/srv/ConfigLogger "{logger_name: 'planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.static_obstacle_avoidance', level: DEBUG}" @@ -1077,7 +1077,7 @@ ros2 service call /planning/scenario_planning/lane_driving/behavior_planning/beh ### Visualize debug markers -Use can enable to publish debug markers by following parameters. +User can enable publishing of debug markers with the following parameters. ```yaml debug: @@ -1111,24 +1111,25 @@ ros2 topic echo /planning/scenario_planning/lane_driving/behavior_planning/behav #### Does it avoid static objects and dynamic objects? -This module avoids static (stopped) objects and does not support dynamic (moving) objects avoidance. Dynamic objects are coped within the [dynamic obstacle avoidance module](../autoware_behavior_path_dynamic_obstacle_avoidance_module/README.md). +This module avoids static (stopped) objects and does not support dynamic (moving) objects avoidance. Dynamic objects are handled within the [dynamic obstacle avoidance module](../autoware_behavior_path_dynamic_obstacle_avoidance_module/README.md). #### What type (class) of object would it avoid? -It avoids car, truck, bus, trailer, bicycle, motorcycle, pedestrian, and unknown objects by default. Details are in the [Target object filtering section](#target-object-filtering). +It avoids cars, trucks, buses, trailers, bicycles, motorcycles, pedestrians, and unknown objects by default. Details are in the [Target object filtering section](#target-object-filtering). The above objects are divided into vehicle type objects and non-vehicle type objects; the target object filtering would differ for vehicle types and non-vehicle types. --Vehicle type objects: Car, Truck, Bus, Trailer, Motorcycle --Non-vehicle type objects: Pedestrian, Bicycle + +- Vehicle type objects: Car, Truck, Bus, Trailer, Motorcycle +- Non-vehicle type objects: Pedestrian, Bicycle #### How does it judge if it is a target object or not? -The conditions for vehicle type objects and non-vehicle type objects are different, though the main idea is that static objects on road shoulders within the planned path would be avoided. -Below are some examples when avoidance path is generated for vehicle type objects. +The conditions for vehicle type objects and non-vehicle type objects are different. However, the main idea is that static objects on road shoulders within the planned path would be avoided. +Below are some examples when an avoidance path is generated for vehicle type objects. -- Vehicle stopping on ego lane with pulling over to the side of the road +- Vehicle stopping on ego lane while pulling over to the side of the road - Vehicle stopping on adjacent lane -For more detail refer to [vehicle type object](#conditions-for-vehicle-type-objects) and [non-vehicle object](#conditions-for-non-vehicle-type-objects). +For more details refer to [vehicle type object](#conditions-for-vehicle-type-objects) and [non-vehicle object](#conditions-for-non-vehicle-type-objects). #### What is an ambiguous target? @@ -1154,13 +1155,13 @@ Details are explained in the [How to decide path shape section](#multiple-obstac #### Which lanes are used to avoid objects? -This module is able to use not only current lane but also adjacent lanes and opposite lanes. Usable lanes could be selected by the configuration file as noted in the [shift length calculation section](#shift-length-calculation). -It is assumed that there is no parking vehicles on the central lane in a situation where there are lanes on the left and right. +This module is able to use not only the current lane but also adjacent lanes and opposite lanes. Usable lanes can be selected by the configuration file as noted in the [shift length calculation section](#shift-length-calculation). +It is assumed that there are no parked vehicles on the central lane in a situation where there are lanes on the left and right. #### Would it avoid objects inside intersections? -Basically the module assumes that there isn't any parked vehicle within intersection. Vehicles that follow the lane or merging to ego lane are non-target objects. -Vehicles waiting to make a right/left turn within the intersection could be avoided by expanding the drivable area in the configuration file, as noted in the [drivable area expansion section](#drivable-area-expansion). +Basically, the module assumes that there are no parked vehicles within intersections. Vehicles that follow the lane or merge into ego lane are non-target objects. +Vehicles waiting to make a right/left turn within an intersection can be avoided by expanding the drivable area in the configuration file, as noted in the [drivable area expansion section](#drivable-area-expansion). #### Does it generate avoidance paths for any road type? @@ -1182,8 +1183,8 @@ Currently, avoiding left-shifted obstacles from the left side is not supported ( #### Why is an envelope polygon used for the target object? -It is employed to reduce the influence of the perception/tracking noise for each target objects. -The envelope polygon is a rectangle box, whose size depends on object's polygon and buffer parameter and is always parallel to the reference path. +It is employed to reduce the influence of the perception/tracking noise for each target object. +The envelope polygon is a rectangle, whose size depends on the object's polygon and buffer parameter and it is always parallel to the reference path. The envelope polygon is created by using the latest one-shot envelope polygon and the previous envelope polygon. Details are explained in [How to prevent shift line chattering that is caused by perception noise section](#how-to-prevent-shift-line-chattering-that-is-caused-by-perception-noise). @@ -1193,11 +1194,11 @@ If the module cannot find a safe avoidance path, the vehicle may stop or continu If there is a target object and there is enough space to avoid, the ego vehicle would stop at a position where an avoidance path could be generated; this is called the [yield manuever](#yield-maneuver). On the other hand, where there is not enough space, this module has nothing to do and the [obstacle cruise planner](../../autoware_obstacle_cruise_planner/README.md) would be in charge of the object. -#### There seems to be an avoidance path, though the vehicle stops. What is happening? +#### There seems to be an avoidance path, but the vehicle stops. What is happening? -This situation occurs when the module is operating in AUTO mode and the target object is ambiguous or when operated in MANUAL mode. +This situation occurs when the module is operating in AUTO mode and the target object is ambiguous or when operating in MANUAL mode. The generated avoidance path is presented as a candidate and requires operator approval before execution. -If the operator does not approve the path the ego vehicle would stop where it is possible to generate a avoidance path. +If the operator does not approve the path the ego vehicle would stop where it is possible to generate an avoidance path. ### Operation @@ -1214,7 +1215,7 @@ The avoidance manuever would not be changed by specific vehicle types. ## Appendix: Shift line generation pipeline -### Flow-chart of the process +### Flow chart of the process @@ -1321,7 +1322,7 @@ stop ### How to decide the path shape -Generate shift points for obstacles with given lateral jerk. These points are integrated to generate an avoidance path. The detailed process flow for each case corresponding to the obstacle placement are described below. The actual implementation is not separated for each case, but the function corresponding to `multiple obstacle case (both directions)` is always running. +Generate shift points for obstacles with a given lateral jerk. These points are integrated to generate an avoidance path. The detailed process flow for each case corresponding to the obstacle placement are described below. The actual implementation is not separated for each case, but the function corresponding to `multiple obstacle case (both directions)` is always running. #### One obstacle case @@ -1331,12 +1332,12 @@ Additionally, the following processes are executed in special cases. #### Lateral jerk relaxation conditions -- If the ego vehicle is close to the avoidance target, the lateral jerk will be relaxed up to the maximum jerk +- If the ego vehicle is close to the avoidance target, the lateral jerk will be relaxed up to the maximum jerk. - When returning to the center line after avoidance, if there is not enough distance left to the goal (end of path), the jerk condition will be relaxed as above. #### Minimum velocity relaxation conditions -There is a problem that we can not know the actual speed during avoidance in advance. This is especially critical when the ego vehicle speed is 0. +There is a problem that we cannot know the actual speed during avoidance in advance. This is especially critical when the ego vehicle speed is 0. To solve that, this module provides a parameter for the minimum avoidance speed, which is used for the lateral jerk calculation when the vehicle speed is low. - If the ego vehicle speed is lower than "nominal" minimum speed, use the minimum speed in the calculation of the jerk. @@ -1348,7 +1349,7 @@ To solve that, this module provides a parameter for the minimum avoidance speed, Generate shift points for multiple obstacles. All of them are merged to generate new shift points along the reference path. The new points are filtered (e.g. remove small-impact shift points), and the avoidance path is computed for the filtered shift points. -**Merge process of raw shift points**: check the shift length on each path points. If the shift points are overlapped, the maximum shift value is selected for the same direction. +**Merge process of raw shift points**: check the shift length on each path point. If the shift points are overlapped, the maximum shift value is selected for the same direction. For the details of the shift point filtering, see [filtering for shift points](#filtering-for-shift-points). @@ -1371,6 +1372,6 @@ The shift points are modified by a filtering process in order to get the expecte ## Appendix: All parameters -The avoidance specific parameter configuration file can be located at `src/autoware/launcher/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml`. +Location of the avoidance specific parameter configuration file: `src/autoware/launcher/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml`. {{ json_to_markdown("planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json") }} diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/purpose/avoidance.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/purpose/avoidance.png index e12665b7aca81fd893e43935c68fe41278874a8a..85c6e481b6e43946789952642ecd6b6ff41ecf76 100644 GIT binary patch literal 60242 zcmeFa2UwF?*DgF`@90<zVnvzf9L!Db5t)$_VYZuti9HKueJ6{_)SYg`QSd* zecycZ%|Vqb3fkX%v$O4+Z@!(~vkSBcYG-zWAKzlNmF2$4XgWFe%{RQARQbmIU!0yy!@c69}NWrIH7Xj zl{(VV)gAnF7ZtV;7Q6snU3PMEfE&QA)R16YB_XH?FI1TEh}sohm^vp!9=vuyqTt|% zGTa)4VLT#l=Zryv79|0Q2rob5FKE=Uw6%0bZs~%t1~<4f7Kw4(Sb`w0Ft6bHWZ^EB zi1k(@XDes4f}o`p9HQ%DEGndZT@JN=j|<)jzJ3n^gF!fe0U2Fltu4XJHMt3_w^(7E zZQ#!9O<*PvPN*U$|7CD1;~!LhL$ctFqa~R2+LN4$P)<=Or`Y9<7jp7zFCd(9q8pte zH{^~tQh^bKTu_1{dP;T<))>?!L)*WOu{jdjUD?^v$qt6GfjfZVY~0regFyI!L>Y6p z!LPT72?`3Ww;-H12ih2y(V&AQY_4!^JrI6`E7AszU4MAvMi&gm!3F8`=SFLcqa)mU zLkl);v~+gH;QoA@EyiJEc^mgQ0p*iyHadE+*fekw_F34G0qY%y*S4SIpj01+D`ZjP|OIHUVu8%!jc0eK+hUbED z0s9ZuGR!6K`UhkS4#pv((;NnzqJC!O&w|jwZRKPVR#`oYqYf+Ocy1jsUx<2A6^9k zR~EopIl{zL(02SbS1t>yoQlF_1WZ>^NZtM_L`C5$4qSIKR^UhKDk}*Y8>-sEkSbuFTFTlE#*Q$?t1BA( za07P-Eu@gW)fJcv%+SRi%onF_C}(G*j1aalRK=>vYpk_dD=YC^%A-VVbvEvGbU|Ah zxMMZZLT*-Qy-)2(oU0MUouIC(Az}^H##=#L9MlbMoQ$t%V>IpMaBu||F?F;C)*8=G zfJ2O(tdw!WDg+e*%)kf_1J|_V#RxW69I(c^f})@wCu^m(xgabJt^%28U@Z;ha7KpO z7!`X#QERlmy^Xva#@N8Y(eetoZojr>sHK56za>~VkcEJ{y`npi14BNp8agTn(5Ia> zlp)`>Ip9^0q6|sMi><9vkFiPxK~Z(cM;R$wuaE7Z>Sko1P5AP-ib$0!>uUt#5Y+AU zzh>rs%>J^g zh5^Dw122e&85+633=mLtdlh#ZdnHRN9e#HWc|m@d4i0B2&%fS|T&x1w|}O`M-CZe<+vF_V-_qGuUq! zQqUdt`Cbz?_8RQyU$nq|ZC91Wuy6w#H!GwZ&I;n-YI6l>i9N6=uydL^mw|P`Ts3r6 z5HKA<91MAxvCDWB1w~hw0%*gp-Qy0^MF5E!eg2+c#E>+2_A)^O$=JEe?w~&i*dYW= ze!XqYdI{F+_kFZt7}(vb;9f;{O&vjg4di7!7*}ZR-nDssrqP?LloxZquFi?a|-cq^kuoh*ocqgF-G`TSPk5> zL5hFBCWb5e7w&}q-%VJ5Lsa&caWDorqpbm;89Nyp+Q?f$0kAPlME)|rru=0*!|2w4 z8s%;WH_*o$0%g>)cSji;7!$zHO<><32qh6?v;)>k!O7JMBIKY6)!?^Ai#Z$XV(ek| z)_7oQ0w3FS1Y9f)wH>U{?oL()4*Z(-ia1RuKSQzC35=oW%KB()pzMHr*GNxqgM17j z4)&n`t-y_k>+&Ok8R9kNRS?#Wj5Qbm;6xx*lH5lX!p8I=1 zS6m15b>RBf#?dv}It~H0F%AQEHi&DTM3gnKMur*$KoaX@t)t=wWV%j<$_#SkcLy*8 zhymvgKwb!DfCB`e!mq9)D5Rkbb6+C^9YF#h4FDks0niTCw04is+G_{`z>%FjfHy(V zj#FpA9dJ5e_C{C@9YFywAE>4Q4#1ufL46JO0I~h+a{|v@7P3;f3i`Y1s;R5Z7ze=M zmigFUg{rSzM*#@5!GQe{G$JUvYARS`Ve*V|tqEYBcnu^Dkh&foy#6#FT?P#Q!}(w> z4TKy3A>#o#yMun$jCJIM7|#O| z{!(8+zKRgW-ob#rtc~$yIc=R6*sC>1fiXusOkNPOt_O^{D1v=iyT+L3$7`Qa*t#R5 z3@ik#2Q*b>>ywOL382?C3x(@4dSy_*3d1#F^!oAIKj?LXOc+k5)>=@yMkUS|7t0Oj zTj2i~m52f25ZgfEk8C0+AokDL1Vrru8fWs7$n2E z{@n-$kc_IEB}C6<%}@=T+$;?Qg#ob$SfQ_eic)koqZHMDfrR)s2ut--L}MV}WTUK) z2V($Yx+)C3b`e`$9Ei%ag{+kI)+35d+H+J?}Smdg50#t=JxaGe3`42gV5$$ z(ZQNazyNJV1cKTGZ9Ib_{sCYsYdBeh2p1658tJX|rmVrxG9kw3YwKEbc>dy4AQ?`@ z|B$FbOjH2mO+iu@A|N0lEGV*(EBXZbB7(dE8%eZ3#SKtiK?vjvk%KUl7b>#R{@)Tj zY>fSPcn^29xy;B$f?&-N;|OwMa&|5tu>@6MWT)5iS!?NT2Hj#^oG~c)W_pVg0_Epd zQj%lbw|-?a4GCf*s2s@FIpYmMKOf&1G2VaxYvY;%BUbx(QGp?4#=G@!2X6CO^7B*v z?>`L=x9pkF1`BUx=FK)|xC8Jq-2R+={nGaReJr;gpRWJUi0ia4NN^VLF+>#;=7;hM z3w#Pl{}QhX3JUOwYzbKZqDEMZtFtwHqtAaW4E<*lVrajp@P9fX7fWXZ+~q%*5EL9| zfav&R5dZg5-MD)#Nd9Mceiln_r2PNR9IRcP-PRPIq1OMlZT!gs{;|1$ewDys(1yli zf#_WRVuSzBSOF9`(tl$GLL&TM^0POs@xQrf&Cu@pN(_5ui&$B zQn^XD|9uoJD*8{%LHLV7{-$aEe-Az&Z7uY7XecPi|93vY|7`FP75R^#{@*kIe+Ye| z!h-*aX#c&@|L1}ah{qXD;@^SKzwPY&i-ExZE3VA{I5ZLa-}9~hV>J0c$f+B__}{7Z z|DUTlzUDL6j`6sOLJLY6V$0_$SVQ~>0Z`WR@7a;1^cPC z57eA63i7t3I4w77@~lC^l2N1bS+O1(X=B4E4V1&#Azk1)PL|e;%peX_m4dcECrJNV z>S7B@Up5LyA)?^!wf7s7VdR$>@3(kSN=p3v!t!gqemv*=loDl>A^z7@%!u&|KzK!j zAP_MzL17`t#zEmnRS^W5B=~viTMQJ;@bg0<{Gvia!U7;$xi0XnA)TNo=ytt%GjRH^ zsGnJLI{ra*>ZU{TsStQ;YGCc^WBjT7vsX3(r>;w{S8nrU3c^MeY+pA z>#c|kV)otJ7Wd0{dpKt=vMU@;xp@1mV#L|fUw1w}$F6WzUrYAtF`n47KO3%|zPRTK z^W%$qUVHHQYH9c5rp`y^skwgaR|>IHKYXcM##Q#ihm&#N)bjp= zu4QAVPJVs#tC+Uvz*m)67Y6&`cTTZoltU7up^=y=*&w$wU$9(;iM8%~UrLr1n@Nth zZ#=7&Nu3>&{HuYl+3EP1(^{D|l4G1-yt-%h=})qyeq6HnzktKKjUP_-1D8)x9*2F| zl3OYPMx2WNW@PUd5hnH&xJ+mWGXHMNPH*%KT4b5_?`iXJ-xkdE#Wng8_Uvh!5YQy3 ze0pRn7D@4()*`>zs};Sq@zXs2>B41W_O@DI*I9PEJC(N%pw5m=JuL|Eo3) zv+#IZA$!bfk~Gm49+Q`Gq&2@U6pd@gOt5y{mr>T6yKbwbL&rIf%S?FHCTmbcsWH@y zN6PS3{KKxoj(%zZ_t3-Tfzt4ml~`^x?vLbiOV8SCa*5^=Y!36QDVl}dUVWIiZRb+W zXs!>xEW|y!=YaZD8y)`#>QM;PWAte9(kDr5v|3CPFiI>gboX zLkL{9f28+i1MrOix`UGTE&2!h)edwg^}7DeFE7iU7p!Vw$GG&DjpFN~Kkd>c5PaR~ z&w$~pdVgkJUv2s`k^Ch470CWd4`0#y3w-*OvOaSnzw-2FBKhi(eeNwLe|1j2IwuT{ z`Rb8<=6-zj$UYOvSC8!Tu=lG+_Fw9eeaP6xBt3ual=r*1k`HhF@ncoYl(`DV`5)I+`PoI9B-$ z%<=HsndnlBYgNY$8WJPXp`~;E67shWjIC@JmfO0dS;)7(1inbEN=81#ca+(k6os1! z;-HHT&{t`c(ax;Kfj3V)Ix{UG*R9(1xYP41w(TE&8GpAf)Wp#UX;$^89L}|l9XrNz zMoD&SBeY!b1@qwan9Ne1DqEV;U?(QIO>OsG99~$S*EbnKB}GSkyM5Pe$^~J=tut!V zlZ`behPPrEjmc3JM>QqyOSuh51xnAn6!fxiZP&|rvs?OJZig}VIpw##`FscNN>4%4%^ys~w(`}=3QpW9lr{whf5PtTRGTYEnPl!PiKYar8^m3CZ zMP02zuY|{W7TXX{>O3gF>`(7L_@Wn(Af}KuNl(;EUi!MotlMxZ=p24 z$2w5T`H!&j_bz{Oc6`sDIGijpJ^YT9v5?tAzA^Ooh=uW5uKYu`6Y2R)#IjZDDUMz? zOv!zTse*HSrL)@R_=S;U6UBjSA{okyuG3Y_q*|_MyEfj?iiHX#HtH3bBJF2}bkDMd z(R$BHKLog;d8VFkAkKCly-%7F-s?&%;ojxz7@l!e+rpWg4$*SRPo2B!C`PMD<4ykeekrN1S~G>0P|-8ZoC z%AHw^x@brN5;yc;=ttA~uod6#wrLrBKKY&LG)ac^6Q6e$bp_)^lIU`-za*h(i`c5N zhm)0n&IaUMTpM)v&fAAQCWVL%omtjw@dMsVla!E5?_B5KipgaXyE$C6PI(RAuS4Nd zuJP?{;|lajNeHdeY?9zRr*y|IEZ+UvWGSt`$K7W#m)OL|TM(<}a_G;(bq2y6S+tL0 z5ZL0=3N%RmYEC}WNv%+1w&*pSNvNA#oXDsr$XE>5tc%75ENU0^mmT}g_}w45!Y5}QXk zmam;Kb$ZTHJ>6*?IFiB@(@?%j&FporJP74U(s@P+!ZtSo!4MOlXZlc6Px|y;51`$a z=%M3#&@9WmxLn+U*XCQ1>vT&WfUc<%?Wfjk@8J(0`dT%cjS$gY^BH@dVhY9*RnffV z@3T)5UY=={v~%fvYAN<1_Qp(#rq{)l+k-`s`7+C^G%;$M4rTeV(DULp&!aoX(Nv%M zKrbGP)tNAzUxp{qL{luR%yalY{>=i(1Q(9VD4gk0<3;{LX~k&DthflTR_r#mkfx;N zWOt25;(lws{HGaeMT0E0q{$^l8X6ew{9ER-d*!Cr73D1}nLJO+h?5@GDP%0w$Yc|v zJv4O4@*Jy98luyG9Aj#HKb5|xg=z717?4Q53$7K`WqzGDf3@aht6_CgX}bI1yVa%1 zFkp)Du3_*{qw~z>E>~|IV1ZOxPGshr-?qLzskWOvxOuAFN9V3t(pH3R2?KlYg`W#p z+kDmIonAyU>`;J+u)RahWFE^(Zf1xv#(5}Ea@i@b$E^pTS7L7e8NX8zUUPlTwhse;1DswMhjcr>~HG*fPn5M02s_U(eN@jL!Sh z$xrNlu-Uw^V!y2UTrLXNmL~J+&2W9~ovxXsv?fbGj{f_Vw#XQfe)n@d=p5K7!n?Q* zH*fbQv4slV`rjI~ea8;1Hv6mwF|em(aXhuP1pDEP-*8Y5#-gt8LthuY>6t4)y3w{* z@mN4$8raSb6HHX5*UH4Cu%2YFo8M%9^GeW*8LJxZ)kPvpsP_f$3)d?TiU@XhS^BX% zzpmxNC3?(p{t3hO0WLd!n)~t^hUr}ELFd($lM9ms=1XZ^Tz;qA495;9c~Vmsx-@;d zjgyj%+IX$GL%A-zSW1c}Jjq=+u5WlI$%j^KWYv}oQ59B7S!3s68a_ZZ$WRdoCpP+4{+D2GSf5;#As+56R z24-HayAHCp+2Z_jM`entPNb8g7O9z}qb8WX#ZuW)7KBmER_owT|4FuwWo^TDsD76W z(c+s@wLnbfGTfMeSHXq0OOcqeaF_^?%mcovybmw-lO6!>0oI`Nz=k3$u`n(v!^W*N1)!>DtjnH^v5xN^7u<+2mY~Mc#Xwt{AC&eH> z#p6%hioISw-%Zl=S+*Wp3DGycz)YXQ0eQ#RtZa27Ds+LoleTZlyH3_?_CnHd5-E!K zeeKWtc^{%yrvo1-g`9M+_;!IZ5+>5kC%1IAgk0Z4<|`HS)1+2((TkU7cyimc(GQL> zK`%|&^W`Zj-E9cbxk(Q79IHp%&)RbSro{}rL^E4enZ1XT6|Px5`0c`K`Fw9SY{AsC zJu`roJC@ESBZLM!V%b82gG7JFGfHcg7y6n!KHJ1{NdP$JUvG_GqfhLqdgS4cFVyw1%R={K<} zhGoBhw}K#C8gJ-@`It@Iel^PUF?9Nt5b!l%Xi~N3|Z4``mO`1zSvoQbFh(KiK1Fj}}4|Zyy4^~I%NxK#t0(M8k4j_a5{0k0C%gkY{L!kHD;V8OL>WF#)|Ezw)LE9 zp1@ywU9-Xxw0lPBcC+SixW#Vl-p{5f@nzO1S&rrL$MyA)lwZD3w!qVJ6kGafslNLhZ)Q9HrL zYoR)s!WKpAMP(1Z8xS#P&Ho^|FwkD}%t$BJd{OsDEqUMPEcf1$zjN)soq+7#-{UXQ zt88;uoJn)wBkd-BcQ{#seb3={_hd198wb!&w^0v8?QrJ^8E9@64Ic_DfO&2ReBb=Ot)1hX)4$t z->5h;RkNqJm$^UqNR7I29lYssAw4f>=XkZIRe zRg}E0-%ia-%qocYQhh0{IW)04w!rypvEl;a*UjBE0upNeF6PGGHj_c>o#p`i1(DGz zl^BchR@AS2!CjO)oEGC=+9F2eo#P|0mmhLgBNjA^OL8l?doqGZObd3^m-r19OQF)0 z%>`#G%jx+YG>er^R{VHR4DXhy)H?)_(mNlxzWy#vbJb8-K5LV-_Xvgq+o(OSfZG#% z!Aa8`^$SU4WMmo2N3y^tG&tv?JQQ|~jIpLKm`e;wcUt-q@Iht6%H{XFINTGj4pM1+ zF*QEf%?GMZh>tyJp!iQ1Ta?o+EE<1_8%eX~(c;5o`EKy@sBv%qPvYaQnh@kc?5%(CJx_B95-Q?7}~uk-eioW8O55vURHnjaKu1TGQ4v} zt&((i-q5@kHNe zvyC!Wg~sD#OG|2v9RfLQU%JxK$G!)^fFFLrXWJ`>)zopyGAoNYBSO!F$1ITQ=ovC) z&kg|*#J4+f95#f=&uI0(+kP(H@z?FGd>jow2RM}$`1f^Bw0ET{tczjR8<0FX#`;`Z zVMQh0I^yt(5$aB;aJ;{*)2aMh1Z0_47DEklq=_+(&1ZM7{GMAOagNleR_t>cQ-;WD zSp9$vCxwaFw6F)}mC;`?OFtwr%{w94ze^5NN_``J`lZf z8Z6=7QpAHHo3K?X2S9;4@zrTUr0n$JS1DwLm}{42RTJH_4m4SBqpGGYsUGnq6hcd1 z`pPt$hV==wp2egWTsc)ZuNE#EOIN2&jvv}a&8QQ*E1PY4YqT6ZqH!|>YT(vzw(Ekw zZP$VH$BAb*0igdppa3+~UNZN1fn;;ut#|Y~?p$`|D2X!nU8JkNgs7yaV~f06d^lBx znfssokkhb`@6mlp_m?rv=+*ENDSKaSiE~c0j@NhUNz`H=`wTf!&zjP& zoOqH~V81!oW?hm6#@A{g)MDhf>Y9W2l>QrIJ4-Fj-k|&{Tgu#ELpg9c*1XZQ0lVtT zkfiNhx^%m-Q}3^Zl$kklqkl|KNt;9~7xS@X11RyytcI^1ga=1z?-wgzy<>l)fk+@O zZaZaTe1oM`aox6JlR&sACAEE=rs8{6GUnuClcS}04d1IQ53Cvq09?OIzNp19-@t7| zsLXukw)D!v=ZrP+`*yR+hlx>m-U8|UQBK!~a;GVW8n=r?8LCEQ2#S9gGk^>x5TTY$ zVlz!vmBp_W!UDrd%M&>*zXh4zY7XD+C>qz8H(K^?^p5EGi)xRfx0>!R(W&hnD<}FU zlvxOqUIAo_F2^WIDMAe|t;To9_zzEwZ;c%CB?M}A$%V&LGpICp*(q}1p-sz(0QtcF zG-$jY$~Lo~4$u+o=8g{*6Mno@}F9jRlS9OaJcrL38<9^PMi21a1D& zMM{*>u)honS!_|>iz5@+VwM(#>Bum|ypa!@za+Q!S4m*3JwJp4a)$r$svKD&V)^oY zA$?BAn07RoM$Jhk-}MP-V6X2JA};$#p3C+LeR@(I3-j;am>TTtX)Vly-&z9txt%cP z^_dhK?+`8>Pc+KhHvuBZMEKE|qM>!rLtih}yoIND@#+}8y60d*QhAZQd6##e_8+?j z7PU?cEHrfF(Q$p(S@J8MuK8z2lr0_te+(O6pNV;DdP)X2AY9C+mD!p$j?&wPLQE~U zQmmi6ozjh(%()^R#+h^d$%=tY)cE75O)EMM{1)zA1{vf%$8d3)<{b$I5`7)ZAOs(c zi7%o)1+hX(qcS2-*~0E{>9d|&__=qQ!7tkB?O8@{Q9}=YyF|?8YU-A<7Pd$THg>gl zX{#w~FS@nl?}2{AK)fE`#WuCF2B9Bm0|e&@?6bTvUbYWJ)UJ^ND`@*~nOM-{W8p|rXl;w+J)#be`K!!ndKD=YT}OJG z`Ww1LhB|SHod4`qM_EvhLwWjLBDy@iDbP~Y1RaR89g6NiRWCwWa}g5heGTJzE8fIv z{+z;zhVLKv<%ylg^iiC)yUj~;)XVuz_BIs?PJS;ggIk%YAeDzR)1B4gI|kv*_2WK^ z`bg5ir5MSxnY|0L@f|Nr9PjCsV_zP~6_>dc9_16YK3p_1*7E^6s*Wiy{7|BG7a|eTu~07jj|SM&6SNar@JwesUwn}lQL}N^z1%A z%KcY5e>>_}) zR4Asm?;^kO5T#Tym^}Ji^1euM?qpear)Rhn1(C;d4+NS+6I~|d=GR`+u(sEBJ+>IK z9(>#!R30-UmcFFkl~32rge`enP=%+QcjWciMlLT!d$0zOOPi&|W}k-s^z6>$3k$k< z4ZDW}s+C?aRn$;ku?-$vha6bY@cytu7U_;g=XE((S(Yft269doElKMrJ=eoJ+1#{ii#2&|dGYuB0qC=HL z@h4e?#n z(UcAc8I*#M_k;3>YRi@;4feeW0_PAgk*>!;lqXlEXItbKUi!)O+GkZBk{Es*l*BUx zS=sSEZz7`*Wb)bgFnJ53Vj#6>j60GX=3HbSEStYqQpT)e^;&h_tx3(f=WG{m!LOau z<&zG5dCw8sad<6~2L}RO0J0mUtr0TOH0X?c-Ci*b$v3|&&-}dK zIH26C8@cdKS*CkvRL^ZNK&1a=9!Qe;aX1=vAO19LN7^XpeR$ew606XUzWD-7~OdKd5J(f`{X5yfoKDY3m;PtbHm9l8MWbG z(ppNBjW<&jf+@hqRN+#}k1&Yc)8c=+bWht-cb?NO*uHxISWne!(qghWO}vG~xjQ)9 zZF;-MnIHLhYlu(((c#GM^5JCeLhFD z8X9+t3`kZvi&f<@PTaaDG9qoSfHY9J<;rQTvWoHMh})B6jl^tygP3d;`Z!pXeC zrKw^zvn~Xf$jdmt(EfBb$AU8+@AFJhQ46Dye2nz;2{RXvJn*3o2T>?7D-IEPBK4yYWU)}91g&U9}TKIUy zr%Jppu+~_tGq^Z5XP_Z|fkc1HoSv(6=llCupT*W=xT|4VQBKR#3+;S9V)CuvfWS7d z%dwazYyK@fI6bZL?3MDj%|1;dVHVK_7EyEGwpIEuHH*nCsOXzsuX0<$uDB8t_SAE! zKWynt+SAWh{`U5P@A0*G_HsLYen?S1r+gZgK-?TAo{EkLdC;du>) zyOyQ+1Yzak-S^ueX-A$gt3B`hxIPuIzDV0v!y?#V5}s$EiLT8<(Wa%l|M-pz^82)9 zS7=dl;wlj~*aEPvg&c_6<4Eg6#4HbWqf91_l%Vmpw4eVc!IpjH3A3LFSG< zE{yPGFHiBDqpupp<(zuCL}t5VtUUB|B;41Nf4`vIY!#%y&AP>MTj|w7rgFO1p-B6_ zSs61oqfm3gSlun--s4_>yzwK=)bmEhjrvJ1zbOGHCzxI_3m%i#Q9S^?$;%_Rxmlkt z4hs!Sw0oC(*FL^hs8bVCKmkeWpo7Alr`a5zUCo>S;0LvH>LGS9o4cP0GxfX<1XLnP z@5Q#x+HIT?T}w()j~wi!j7J9VcTI|TTuOgKZtDZBZ?86 zd@A|$88S(!W?lb$HTJoPYSCvkByibd(S0k+7L5g=sOGt3njYhjn$p**k-1WF{=oYf z37nx2z5mGy6%%>=UX?bl;;&`M(Pn*?`)76YUCm-0i3J&f&k%v{QN&TAxyPl6^kT>A zKny?d{?yh+gh%f*;dVbiG`d-VUt}tx z7oC&@t~qj8lD>&36I%3QU|P9CO0I3fbci=SCe8c#WX@}a;+j(*61JOUHYOZvv6HXJ zEsQw&Jh#x3bTOlGB=GkI?gHU38D;C5yN&%GZHU5`dIly!%AO1LBbC91ah1M{Np772 zA_Jb--^|9!62mMk7na9n>WeckU&_6pwLEA+D_0LN!-SW(zYN7=qX@k_3p7TNy*JH& zd8hc$aYEYnt!ea0TUU!z;|TLXUq6mRzUc~dXA=&wqbN|R8>Wl6E6vJ5a)j#yT(7ZkhjYdE~%lHf1sI;^K?S-2~DKDg# zCb_l9=j$EOO0oUvk0yonX|gK`%|1_$Br@Yp3sZ!b9_HutJgT=X=6S?~cy2popT2bd zS&HrAqLm%CJ;cD4-t3)s+`T5st?oCjC|%b1hK$C5YhHst9gB%{o7m~Q_`5%EM3h^< zSn;umwEP^&1{*p%uJa78S9-*;@$J;?TV7X_db4}pT}G?nEzFsXBdHoDaY=HKXVv-S zK@YjtGmPA5sZubVRtmhYU`^H8?b6X8o(s8+lgT_kJ(EgDUE+ikjPx~HvP zB)aTpiMCV`ve0qFiEhCO*#TqZs}lEj%9QFvZV?nS+X|~^V zw=PzHe_K87L~Xux-|2b?aQ|2DpJ8U7?9<-2a(pv}b;5#d`DeFK9 zUJ0LZoxVdBH7Kkv|Ft~dbX+4dDm{>cm_6m0<7grIq2i=_OIT5FsTFMD=v@h3fO(cE zwyNzYzQWnp4bn^R%^dUd+23`WHr|t z*z=(=Zt$5g#@n_RZ`~a*|8EQL`8~NJjodwzPmv{1faz3w4U>^8pP3*-F;!(s5Kluk|2nBFG#nKb3gr_ z;jW&r@SJv(U?#}RXEe4qSXq<_8=UJk1vOIw;92H4=eoEZM&aDrf?@+!nXY`n@qcNjC7rzM2;M*~d>vJ_=92Wzh3gLNp zfT>AZf(?_cBII)zrCSByvUYreIC?QSQtTNXm2e-AFNZ-#k4pIr)xM34deF5>Qx8j0 zuxo`EX|RKd9y17Yn}c2p>lF9Wf?7mMNIg6+4KR1P76esW^pIUHGK*{?-0bZUcE`j$ zI`MkUWE=@X)68t@C7JcaNiWpv`aQJ8bHz3C9Cb_nHV(#WIli}sV<3^}(NBryDf{EQ zfZf_|u3dp#r+g&KOW)94^V};qBuA=>%E{+*rDXg+(NbOsO%fS)M5@Zu%`7O<_-9z zbL-y=U~o9u0Mn1UDC`ltx;V;B8pF<^S;^n>-K_=73@Y>?pcl($l>C-P_;lD4BNEte z3g`Smd~@Tb@FiUXGd!FTS4o138TPyh9f=dQi+}u9>iv>CGh0>3XA))PSU5shF)S9B zC5~p)xlV}^N1O1jaB|Tv!bcHo_rhpBY1eBOe<|FBgD3YnH@uB}^yuyR;3h}8$fnz_ zXdhn!u~!@$9P_P2d^^=^!WliaxF>Sx3UPFX1X7x1)3e7J1!1&^+l?oa1H0_gB`JMo zkuQn{3igICB@t~p@kE=v8uNE9F#s-FZOp`F?OHkWG&p{E79N`BetKjC@qdht5`(0dnj z94x7}$OTxsnnRTM%jTb=-j2^SxfToK@Uc>!u_)}q(bHOd1Aw$juV# zbNYuT0oPUlHNGT)Tre)Z4`AF{-*0@D~ zi^VJF4@IPVrlnkLpasal`=OcdoM3S;5#SJn6=rWJ)v5^yF3KRKLW%^S+zaxloW*-KcZ3|`SBK`wy zREgI;tl5;pqg-;#xbz;O4FAga)0L0vM>H?zm_^oeTyNGjq?MA7CmYC;yG_4!{thTw zlz+?UXr$xCa;@KvM;jsIdW&iz@c1meY8u44mCb7<;!errZ-?3?2i0~HUSjBr54xvvUOphh)G;fgT;?5`GQs&~i zafqO_ll5@wGE404^^~0~_!vI!RGaxV>arAWxcwAcO|+3@4ZM)&{u!x`-8VM_sU3TC zIi2jLYV&8xpVYwv8lrrLS6Ci=8`7@(>t?JEs@3`mucCbMSR?Z$2`R`eI8?9(zVQBm zqQ~R1-!~G3Ajw2f9bA@-?xSShssBT@NUQgcnV~dul}n17!RLC+)~0`L)ij!U#w~Ex zXMpGaP>$z`+SpSmnLlo%sX(o8^obuse=?FGj+Wg?dCYB5yHD)A)KbG^)m=~atl!kq z22#$6(WjzNnuA`2!Xl#yb-wxykHn<8ZEAS5@#vkORwo!=!CQE#ihV-Qq5NgU!ZV*U z#yfLaH$)`CsB}@9+~L-UUcf8*SjMoDC`Q>?`inn@$Gh2zt8X0Qf!vw8?^!LrpQ+jT z#~}!7De9Z>()Zfko8Kbv>;e$ARh#PI@UlqFXus-GiTy31pJyj~L(Ef(tv(8f`rUlF zWY8t7&RCT6+4^CWQOd0NzRk0U^;0_ga~~!o??*YK5>}-6)r2}!V?=WFj12@fvW{R! zT#pr;4kWd54y5$U)Vg-@Pr&=dzZ-+D%S8(d&e z*p_3&EhPGc8`a}~ZM zlJbotOyCNf)MKA&vs!v~Xw>>(U24^YRs~TuM4pbGcX#~O)yB>lOeIM3-V|r#$f9XD zi97E5kTU`NUX2YpDpDU+0@M`i`^r0OmPOG+giG`w2G(O?mMn(G2M=zR2ql7=W(lqc z<7?#JXb#dV)y4VMhA{se#}hB#hqURem;EthD2rk46r$HPQw))nlIQD3xQ*hT%?WMp zAn0Q^kZpT!49FFzE*4`?H10IYd0>2dQ~aQufqNSUE+>6Il0uR+sk=wILa#O(N5QAG zyNR2s$@t2Uc@n>V2(nDscPkDke5ecgH7vw%EO6Fe4Xc4x!MKr!JIF9`A{(@e| z#RPP~=J!$T7;o}TWOnDV&bgYAI(+7F5+dZ}y@ZHu#judgS5+)`pF>uj?cr9+XuaBRXR zy7v)N@asIK&Hi=35l$2njPpY(P&97C@sZ!tf+n+_bOOu}n}!N@#TIOTSb(z^Qmx!H z!Zjy^&6Ys9VB@f+%drQ2gp1$;kZd>lyVvkVM^k=W-mB5LMbJyGI+q0Vd?j zvXi$-r;9f~SdNmy6G6$by?{mqZ(Qd$0s=J!DO20mCCF{7vAkhZzOTVd5?{Xj8^9@FemQm7}o5W*PcV+A-CHT9946A2y>wI`pWv9~@FG$oKc8 zqwP2A3fBexPQW)GdWMa(*n5vzZK6`e=uC}m;p=W9|Hi}_x@^WQDo(GxP*^^3@ELYE zpo^c}Skl*@v1?O_fShCl_nwUOz&fv*7_T(LbwT}8LT;wzmVL8@4VK-h9WNBe*e<6D z3HH6(4IlHA;KrdMSvPa|#~1>?9Jt3cgp`BK;7gzDV7afB?TDO2Z58#@kxmiZurmI! z2WwgYOo}cAS&W~Fxx;H2^+)XuG451b z`knFnSr=44+BuN-&b-D;g+FMzu2$g0-gD-A$s-b? zk0sq{*lCoy1(FzhM%#bPl5pe+j^=i?qt?x+pg3})YW;MJAJ85z_nFjFi}iS}$dOyU zp&egpY<4WDK-HRDuD&!_F_&Fa* zjBTrF*b;?sK`5-g#WegN1ad?5&uh{>=cGE-{Axin|3u`a6=x6OCe`p%lb-hP*VVK| zgdreoKQ}w|)Pg}%y>&wSvR+5sT^1wbCD!ww3_q6DR~aHquGPa|8Y;>iyl*5NpJSDu zm$E^rv6y|}+-S7KKzJNGb7k&=CHo(>+vnv%8)!4pb=C2kXJ-sij_f-oBXdkf*@cvM zW!K1@L-0-r_;swQm)5l_mWk2P;9~=!VY-dFbxK$gMgIb)L33{*WCGFOps%{bx}^v_ zmf%}HTIk6y;^OfJ10Om0D51F2?BE7TcmW3P&mS#*{mL7XKb(($@+^WG(dQ6!J&;uWmyZ@agkQ>a$nZ28R({ew zg7#oSNsykiUUWlbUw6Reu^6B}9RMx5GpaY#rwn|f4_N|hR(pl7v9(KFB+Pi?=d_S0 zXm%Sb>!u3@csLfZ^H8nSg4-%_GOF|9IcH?Y&GGou2Fd4wVlbj(T|`bL(=atHx|~G4 z!X8sUixu?FGvvj(dGxSuh>(yElo{8I;f(hX z8p^g`jaHsfN}+l`XwOkT!IyihdJ`#ur0h=lQYh|jwde#FJ0eeLjBS8+cgKcL(c-~4 zNW(dDvvnC4isz4nXis>F`;Rgk<@`lBg*yPc4ZV3xvsJ&q&h1_Oqj$&CP4p9I*k^L^ zO82pOEytG@Go~rx`w?2J{qv-U@@nbvTgfy+bMTkm$fJ}2ZSg$0(FP&B4{)SDVPq_A zFZhD2fk*nnziW!*R6XVMxRYX(yYH9khn0z%UF4R=2N(ybq3c6jKZNy$FE7Z{1~73pmxPu`3WsCw z+RV4uG*&%;g{evBx{u>z{pac&;8}u#JoU`7MXC|6^Q4R z>}sppr7-&xgOZLew119qHH7LmdZ?Bp>`4nvB>QC1u5zfBEl$q`O1z;zILa3}vxNnO0xWg_<> zNG9}{Fnd=tLCENR=i@z@N&OvWXA8$#aG1DsS+5p{+VVh+(3AahS?mYf{D1PHTi_ZB z=M$=aGszRxEZ^HE;e4Xg?;Brfo)1Hk5v5oUD~IZM>rhHWejBQIe0Dx)BKAYFjAh~E1HF8#YO{b|M)G6jp&w|-;0-iN`F@4 zii?#lq_!)a_gRr!!g*`<`D2zZi7n$UWvWjad-{;GYG?N6$#mp_x-2rV)!Tj2XDhpMs-Oqtqw0qXn6c0TMGRdeDWqXaG%3{HilQ<{jNNcHtcVd{fUNW z4*^^uKdh-!n$GGC25hZ59u+2(ZE_;@ap+lKyYEi;@~xg18;S@`42_U6!st3bmoX`` z@Tnaxx`E)qwy)GC4n)l?cKdVXpX~6)-TsE=VW5ep7ssfV6}$>2``}SCDU?Jh@3_JT zDPF$#2><9-pu37CxKl-_H^wDRX{-6tD8X z*!l{ns=BUgy1TnuI;BBCy8F`IAl)sYfOII*-6-8iN{4he(%tnR#OJN=AL9(h74P8g zv-jF-%{kZH=Z*~zMa#`!-X+OB`WdP)MxWZx7w5z`rQ6P$L|??cI+RcMXxO~_%(OhN zpQ%sey$Rk&W493dx=Q5X=!!NqgYAI$%o$bTQcrl+_QtfUGHKKG(6iXgGku;k!_7tb zPVV%xYe6%&Z>D|7!j4sZ9D zlyL!^Y}yB+WcTq}Zt(k!&ND|$xCd$Uqig5CaH>olsE;ciu_mC7b>q8n8Yc2v6yeX~ zJ~{&pSnjbbu5V6{)%GleeT=_%`Ea9{su`*jcBkX4G^VR@?iA+q>Xn`F&W;=#2&B#oFQC8uNZ_?OHN8?4#RU({@{( z?`a5XwJ>s>U{dMD1^v;JeMXYVL#d69zK-qEMl9yMetEu!|L)_}(e(FEH_q`}MOt-_ zwVm6vx~PMo=aDGi#e3*7how_Uc#jdcL~7AB9)lRUj>V+D^wg8!8r=W0~-@`<|pQeG? z!MxGcMs{~DP@AE^lTJyx@e2^7oPldu3G?@sGH27IU$Kl1AS7u_maRM=W|-pQYrlR& z?0qtD8dpPYzrU=ttElo_@9ev4<=VV1)0AhPwdlVpcoMuBcPQ{Ncwg)8%S(Uw)!yON z6xCC^Ro{iGAg;-6o>C)+63eaQ#!8x4ZVbS=uq#^CV#8 z!2hc*=MK4b&Xz2RfKks%y~n%Xp=xOOHXsc#&C+!n=s#N|3KQEAE9&02 zIz&6{TxO+GFV8e??)~X7_UU}%zII<9E!A9I^P~Y zN%GTrR|uOJJiT-OJ~;~{^>vGQCQbXBN5nSikFdcwIw!IL1&Y$43XSXDyFev=YWrlV zz3dZTG*vGAZhfQrAfM>MKJd18MB&lnD#3T;M(z9bo%!Lty|;@i^2J&*Soh5Hef<`L z=w95}+n!s9mu^#Ivf2kwO!{D$jI~}B@W0Q5Ne@6vu4xT%cP*;+Llqo5!!2<(^7fCd zwn>070Dwc8ZV=tUQW3Cm3QLck9^a>O!x(VgsadW!lVAgJ=F|76g&)r&#RRT;Oh?WN zn*Dk%Z~XVupj{HCfAwTQA!95=h`pn&SEW;;g8GO>2ZcDgrc%w6VBAgLy@{Hqv_Nl< zOo9OAj))c1bmr^K^XkOCvo%%zbdcAZd-iJSb3>cEw@i9k+K)OM-|jqvy7L2WP+fmJ zRm5r*#TM;v^ogS;X>#x2FzC7!xK1$n9J_s_iD8Fpc~sFw6{KXmwh0a-Tx9#GZLn7m zukKZ8*u%GaP|+V7pwy}@TQGb^3&u2$@6CRfAo<&I5^8xaR5FxvtniF3)CmZPwhX>r zSy6Y+H$vvF*@`04Rhn*e4=Ttq5RQV93V<@k2j9tIewetZg^((qYa0cA_4jI*3JBs` zMihn9?Q*W}WZVDY+Y~n&a#|Rv<`&gwNF@S6Wyk@M*8>q&fxoaRV`52aY{m2h%gAT! zA>kDeLAQ@ldJ%?%B`-X>0F!5JFY+FggRGBw|9$qp$qc%onL+)u=q|NF)+RQ2y@r&n zUaGkZ(Gs*!X@DxK=amvYYd&1zk8EiAka;8I18#~3)r_(q{|b9wrO%!dfBegZxz?p2n!dW{6!&C7)*2&beJO>))8tbN$w>(a%h+wR=d#Q}4J zNj*xGbv^`mjFH|xzd4rb-Q_3I1g^PEmVi~)V7~ZEvT>R&%LovpK{674<;5GrALN~T zj$Z@k+rX?KV6&x>K2U4WQNA-48GRVH5%5EGCUtAL^`anywT+^vRKfa#6>HK`rxn_IWAY8}J{Q)6a1^O~JQ#eJ3F zI+7VLn&#$Qy+|8U=e*idK`ywTq%;0{sG=v)k^w=D>x-C8<{J@`cp(v5pLE=!Ui~O0 z<8q@&0C#a4c@GW*h!j~Il#tXwENMV$bg47h;`~uc1ea0=S_V zt>Ffa;R;`;&G_Ek);lu2@fbEib8s7l6oaR4+{dbE;m&t=oJ!tbJk!n@+W5y8{1>N! z8lNadpiGO3dFHxF1HTpxwPmy+Zrt#$Ed*D@ke9MYPL6kAPMGN(KVFy+LMVWFRj_-1 z!EXRcmu-gu(_y}GUG=!9uNx~*vP6m!a7RU;R)T4bLbmq1W z#OoMt77|{a4h)j`zd}0^imp(S`hhO;0fm$eV>>bBv13?$$7w$|Jc4$V>{OhbGL+`| z@4&%_zXq+>!6k<@8b-p7)_MJu6}E>8wPSB)_MIY)gt1nDzSL)LzBB_DnTvaGUUdad zjFVasZux2w=qD4C|1=l%O|Kq4mv#|61~IkzmjlT5g@2 z^)@G@Z`Xo$x$&@Ro__m?vk5Yca?k+bTn1ka0=svd*;k*dS3{jzpZ8FQu{9?^YDTs# zQ)h)-;bAp>%TC9!t>nydzIhN}el|F{Ffa!m6%p!(fxkqLeOO15S`ksnsD9X^zn{dv z><`we10(m;dtV&h5~rD7y)|u1Ul_fNUVW;Qt%V|zxGb@P6L{mb@>F2jzFW2`GX6d* z!@E;jq{}+TR}((vRDI?K7I(rd?_4~2>G#`#Sb}<=k^82+Oy&wdUg8;#ejmN!Jsy9; z>i#A6`4us(cq*`R6fVtTRi(NM|Fm;S2r4v0c&s1HUquWNS@^#igeDG)peKkT@Qa(k zVLZpl^Cd|xBD$!2_@4N*J~X+Q!55}{mK^k(+%!BI=`1T2*yJMBv}7%Hzfhsl;br7Y z{_z5|u@Ol?+2B(!9O!m@=lc~PUofPZ$DmVO6|A!<-JTv1s)=X{mP-L*l%Nocgj!YW zEaQjgOu=_~U9`Waf?l{~{_||dX62a6FjR3=G#A5UCb>NZB+Bt!Ln&Eki)nF4D7_it z(;Z}$57-W-gH=y0cTxrP5%rNal-8J#ZTUE)&?4B%m~1D(jw>@nv(IZX9OVJrob9c% zKeUG>i{I%&h!yg7BOJyQCo8PYARtu`7(mR0dIK(;~8u-{A0z8~?}DkpWYO zei%gTloDD}%T%c7Y>q+8gF zC199@Aq(iu1$B-gNqFDg#+fsxWklv0v`m&Z1Fhu2X|2fYjiwNGK_*GVFt&%rmfwu6 zI;6Dl4_H_-rB9AqydI3uhNEhWAy<@Vj#D*6A9}>ZmM@bX#Ci~z3kMK(1X&t6Xt~8Xp*p3P7ELOSlU^lHCd6gub;5jjY|t%jb5?fel&?o& z@%Z$*LPEX{>P{t2UJfTL4DIvHr(zUx^IFzi93G0~!NDX*b2-m}2UMG*%cf!-liK5P zT3h`nS&o`UxdfNdK8Ha)5=kAwn``(?PW0? zK@3kJfm&DWDH8cy!jvAT7(Po7;I=`!NWNf5-o{=WBn589(0GSGhZ;^cggu;;QU)d=* zQ1Us;b+(ZwnDCr5j~Nb{cLF$qDNjkx8_%T-)-5bKs-6&zmoZmPWXb$=$yC`hwahzX ze$jM;?WmF@`4(p~Lo`;W^(B*B3!siRa>h_c`c)yKf-f_2T8x)MRo2UQZTnq;|73-$ zzZ$IM_9I%kgd;PfIKbZhe$-7UmUufPDQXf*T}Y^T& z8YyycFM{Y!=82aWfi*$d+WRth8feEoj)Rfe8p)F}FupO6H9us8UfJU($AQ6%i$PH2 zMw9SjxF0P=h0gB9pZ2!5p{E7;?`dYdQ{I}Koy8ye!Xp`-F1Wh8OJL?Hu5O61t1O{k zP(N})a^^_v{Eqmk!^v-ht|{`ZBUDny2faIIJ;PmL|Xv)9R)Ms^_BYKc*-bg{TWrN+46^LzgQ2iSS|3SpYq=6Ny5#7hp--8Rp zASQKMc%GO)e)n!~2S!y(eZ2Am(#3L_q(C7ZY3;Suc&>~ZlWr~?yZK(HS zkq=jv-Vf|ehfXCD^SOw0%OnyBnAq(|3*XPzIjr|5zIyGk0#>e%JbUQW@6eX@cIe9- zQBQz6){`f>Iz%TKP9+b2Y^D>WfZUndO8aUt-cOvB6GP>io7ISl?jnRY5@v z2DS&;N3k&kYh9UtpvDW9&ZG@QuMZG?onrwf-)h#HAka^lmw%!A2atRc&$LVBo~d)l zpwCk)QZbtP%KI}Tqs$Ll#uj~IvsC4Su*WD_sZP_>xt~-DD|r&5-p6LoGrsY8jbvTA z!o47M;Q}4B%(+JK&1sxYK0Wk$W15fISaEx>0qM^O?msUw45<7ygw|jKDz`a5S>Ieq zS)b5~n6b;@o!I9$x{$G2Z%7Sh@QiHmS`2?pX)^>L&y~&*BU6NSi?OGG#&m(CXd!1*hM)la}&F2f#_A>`{-s^5gu7vF1Z7ZcRD zRVOvUtQ)FROyEm-C~ik#Bz_c7iWlf36?KjBnKYi_IWhdl75KRx#(~Hk4~;rj7k-cF z82>5BDW$1H92jH}X8pTIf!)b68!v4b<#L@ilA;_XxvPtd?n}G*O7CfA-A0!WJVT*S z>}LJ%5wKrnTTd1js?=D&Prvhj64a;wnSrKrtyGcjZnojBB(|ZkCWx;O1v_*YQL)B- zkK4&Pu)+1-yP!{4{qJsD`3<$T#y7W`B9`|V9bUe}%c!1D&0g+LweY(59SA($=ZnaF zjSKxpEG7bKL$`y44?qO1f#`zSa;UQKNUGnhc3j^i8^q8mroU6%-B}I%RiKzUb-lk_ zQM_nUtgPf-$$tk<`VGaslEl3dnMhn@U^_Q3XbA+JQ^ zIYIu!XWH2F@d6~Z7jwf#4}jJgiItsS1$3&#SWB?A%CTAT>^|d5ZVz)@_kh`dW_#V_ zXfzTw)1pHE_;7+=4rg4)z-yn-uDw0b((c4tE?7!*QS|V)!U7`J*wG3^Iof(&gLTRm8kD~oOPCI(j7>l;%=Yz}-$*OE6@~g! zJ#!@453~1)|V%&-f^AcbIB`RJ-t|7XY*W{G`@*@v!8`+ zZNm0T%^!d#6Rym(J%wsrO==nxSzlC^ek-6=NEaw#PJX3{;=DalH|zV3QxeE2$Dgj( zVx`5CGjf8Zxf<2-WL^1Q@WFp0sXR@!qp3UGvCrw#q`&cZ}a9wv8!IYBG9o^j$N0bsD{1JBDdYC7-dy<$>qw9W~5(yBb9pX4s|L2YZ z#~6LH!X-qf{Gh2j@m-*QT57XVS=U|ilx`&K58ShbxY(QG`p~~zZ66gF3^RMs?tQf{ z8g_XQ-1SN&7tRl#4MOE}c~}{!0mH=q0sHD`dAhTu^IGl;C%xDC{)a6Ce`E`bZPqhT ztu26{nzmcKuHH&I9HDuezTQu+u}RgB?$^Kb3eL|g=P?qw5KZ>`9oqWaoy>PUC*JYc z(xp*nF!6uliXCcdMVPwuZdKZ}REr<;x} zWFltV_sIsM*CiGEae39+RvSC;ML0Zj$p(HO95HErV;FdKU+vCfQmloUs|+#OndxFs zk5jkmD=atrMWsGI*88)ZXD=CdN37Q^`yp0gM{c-Y9~-&s&Y+KE2=nCeI$zqV6|2#U z&)uAD0a^;_#9o_XYN+*O$)0O9-G!{E9_&5KF-h1lTG)w}po16~3Hd&WEMKl6M>3Is zHAjNWzo_R+Jy=60W`g+!Z+)de|| z@Hsd7n1mdz@}i}eMz2A$2RiXwP3OUUT`k4 zh%|opwdfGU;I6pVT?#+h3x6$~`*{eU8vj^Qg6T?fa@TCx>V6wZ1aE|g85Pusd|0fO zN!me4ojzb9OtMCgBnFpVk|!?UBH@NY5>?I<;|a(nf78yN7vf*q-z>DFz78w#K(``Q zZcx50m*r21lR|ON6~U+KwFv+0Ynv0tVG=K5OJ+!4sQ8r=zJ?Lx_1pDvRrrZW{Jcy# z2PR)Gtys1mn9FRVV3_NpwkNqq4j^T-ne+ms1f#Jl(z>8PG2`v>QVTf~D01ryBfdsC zDDQS7%uMyEEzY-pqc4AeJyQ)P5d@kY&m))X4!yso1XWw2Pxeky3qfB<8MXv$2X@>* z?stmaN5rUxQm#%J)rQ9`A@jyWblMYbrL&^{N6C5KEO!|7k=wfFD{q$$|Ap5mUX#qL#5BA3>9z;aZ8K(?ODG3 z>h`w9DUraT;A@EjRGZL~k#wC*_y|fQo^z z6K`*YHDPkv)YD%@+(Wq^EGlsI!}oeUF_9#@_Y~(^PCYOA?Z@A-tX0pXDlkQ1Wkx>FUJuH7?(o7Yod;9ui_dn4}p z-ktwwtg(?tn<_Uz<%y`}sLkbYA0~>#w|n%KWf;e0(zhKzLpj=OV%Dp)o99+dx0|mK zYddN~y3a`Qj!2OeJ(-o1$9TU;Zza-6>H~t*hp$pWL{hmV z_=b1Iqj-q1u#|y#QtjzMjpqvPKusbQ_EV$Un<@$Ww%)VzMm;n}qeKPzlriZU27#(z z=vBJPDSl~I=&zRaL^-bBdv=qH20_iVn!u_QNMka%TScjM8{_R1vYD)`t{Q=We3D#e zGr{j09W4swEDNp|`k{v=UdE+JD!Jc<;LlDBfW#P;ReEybt2{|qZHHfjQ2EB3M9=%q z7jI=Bi#t*gy|{a?@V5Pm>&@-c9^LT}#7b1+6N|zjgzX+e!cU@!?Sc(y(M9kl6GNG2 zptFJpRZ9t``VQL0@UUhN@AFQw1Vxu93Kci}KJVnn*7AC%cH7Fi91#DTQ2X?S75Xg% z4|f-;7N0O_QEF}HVRkIa!{qUVNjUNqc^c9Ish>d`uG_22MJ>Z(Bt1m(;Wqy~m!O#3|_4vuL;O_;x<@5Wm2Ma zm{AHsoE%p$ml+l1v_5OGX#b$o{=2OGrpes@!y4pM6j&S$Yn$6Ofs&)~=$X{8oeX5n zDfnkqyweshQY}X!EziNPZ61B;2*-qQRG%C!@dZY1LjsEAs~2r=V#wt&L{J~+*jE@{ zatJJKB~jfmVYwmCA-_ldZ9y_VbD(jPs44Cb!B-gM$ZI8%PFnZ;;!iGkfdH}Yd7eb~ zy*X?hZU+roI)f~Tt-&;#^;ql6l3@$zat(&0nlOXu%lkx9h`|6q{5y6Po!_8j8+dM)hN$Zs(=FrEztl9L4 zfZozfAzB`oMh)(YTJDkXdgwM1?Z>H}Rj-$63Zr2qoMwYgc7%XY4#kNR5qM3`gz*K+ z4SlxrE)7CpS%PXs>v?W)U#UQ`7!Yg;T)`+g;Y=wgg9BX`sB1eOKyAzV zxF~2ds=*c8_v=fYgz1eAX0Xi*9m|Fe)V$6VceR3chWr8JCmDhHS|ctA!Uv&C4B~Z3 zSalNHJrV55D%J*9gL$+4{p|66u0D^xY*4)i_5i4bZ)(wudn~q{rwl~?xY-m=c#QQ- zO_>nM=aRPJnVl3ng?IVdYRv*v z>jHx)2P+0L6|L$pzDT?+Ea%0Z@#1!Q>f{C&CTL|Y9L!;@Ebc5=Zuq%jB|q`=xUNTd z`dPsMgcN=V6(XAK#_Ax?kL@>9V~1F5{6`x)UUSQ%HJQ&6|r!SdlFB zc8&-Q+wr4jLzv*FTaEx%+M#dxJdn);{(MD0FO`x5OY!3+h=keiDKGo6U;a2-K)aQI zdiJf4dWHRF7ia{AiFD^=tH=bX6lM%jCe zUKl9LNJ!ca^;;WIy2J>k(&+4}Wn$8#0u<U zc)LrPd1=vCTA2DRLP|pbx%5#7R-H7)UmBkHy|a zf1pLV`OhtHvbfBV9vDuuyqpckVG0$2)C&k}y*um?<70xhV8&cQa+3Phw^ zij4+}S85RjY99h0T7pps6L&A-0~1faZ;3c$y41!1PgZ~!+727J+0k-7y85{V6yV1r zv$ucnoR-K+g@}WkrDSgAp{4u#8*y9+H}r`*ThZyGRt|Dr*Da*AuCao> zH*LVv;M|4?uuEhni&KP5-X<&{6v;VER2tPAH?n=3tFbZZ$dzu~x>-jRUa6p#Rf`-q z>tFH5dDCEKs8Lw;MsJ!YJAF8+WsH!lCEe(E>I<|}hSz#k$dd-kC}{mUN>*THSc=T5 z@<$GJFIX!NlFh<6#CGU=0bkRQT>?+!PAO-YyE*d^_<(2$uAU?ZaBac`xole@dSWK~7m+ayNq zcWc*5_b6xP#4Ig0FHbcHsO10=h1+7dT1DELvQI_)pRb%fKREEM*G z&n1Ow_Oj7?RFT)G(W>z-HNd$YN|fQCE~}R zv74%qAjg6eu@g|&1wOM@srD0K=)Z^0!JCl{7OVRCG@<+)FkB*%vT_L(z+IW<2B_S@ z6;PnqsZsI$2Dw+fJExfv)kh$0Is7L%7JPIbQMFvUngQWfy)HT8rK%7Gx4S{56i;QW zrI}D+i&bT2l88AlM(6PZ1Fn_y+1-%lJU!>+)vtU zPZ@BH^F%sMQ5fOBB19>QAl-pADzk zz(v81x1$bRtVRVlx2J9*IoVswH3+-z84x$2kf{18SHpJT9*OYyOUG>+AwRpW+n2%R<`oYISdqWRF2k>!;2t_a9#7gz!;i0=guYp)@%(jj{vkk{_EI6_Hw z-^#{;!QsJEMOt`Jd)V^!P8c58ba;p5%Gly95hPh{l2$E;2oV37$pB)wpVerxjt_7o zv*gx;NTQ;G=1ZFCGX4-)6Luq7UIntKt~oWflL*0KNbu-|>H|ryeSXJy3Hk>@Xf;?T z9>l|+|4d?;8&gr59`2`kRYFlCEzW}C+nQ|@FTV5sC7iy&TcW!N`$0LOK$kD@eC?iv zujeKDxkB(b>vV6rMA=dM^o~p(qm#r2%2oU6#-aVvdCQ~b6f%`BEV6A1)sh?4!)kLy z?PMbfM{5%NXU5V#4|}I7Qx#|m#nM*!GpT?H(>?JWao7G!?aHPP%<;gYtAs7wzN*9< zC6*sCt*E9ioR8pK@8SgR>Y^b>u*tnQUw&(i*1^HSWp^B!nVGrX^NfZjk}wRJkUJ&l z>h96I+HP7Q!&EEF9$OP(S7Y_NpCbvCC_I&<6_uvo*cpXVOyv@``(L#r;Bx?usQZXS z<|)-#dT~P_@ghb3YeObh>k`k!+#Zp-_F^|1XjdyBbiVWJ`1}}dRlxNNXFV<&+Q!9KUT5Qj+lz2a$u{1IQl)9X4EjPF3+z=H z+%8e=ToGxiFtv<`m~_MslncGkFL6j^$OX<6Lrc&CeuRUpf_tNdr>D zH0t^8WXV{Y!OAko=)H8h0I&IQdQ?XU;$AY`tBEpWS1emUD(CP;POtt1^?%A(B8-&BFr@F`qTj)xt`gE!W_173di%pi7h(6?<@k~pPwJO##Es)r0?ye#LVId!9QMrDcjj|`5<6B`vB9~wTVQl?hEuI z1tJ2{p_vKXo$>$ACj+=vFc7R+8KMd90QLkd>;w)U#;PK&`^`^{bo6}~03Y$%m{kKv_pYz|!U(e4vfnGu^pR08O zoiap&({^o7H*Fd5UpnNI@XCP1d3y+Pa=9`~>|{GzVi)w8-Hg@$2gI+&?|HK8tDRxH zSLDKv;W$hn9~Fg9jh}&G3j~v< zuTi9n`L%}Q?#_}{7>~07+2ZY@0!hy&sD1K6Qh|41Wo-+Astw?(fDR=0(ErRd{d(Za@kYu&q`qVc?MhO2LW z@geN~h~YJ|bMYn>PjOJ7(#UQ=LP@khA3Gys8>bL`@7?ep!u`uu0e%{@2PS(&BYKp- zzf2*kRaJ`aJJLv(SA@7kn_$te4`?*-v*PQyMJ9A98BXW$=Jq4zc-!5dLXYXTzfeTm zYPsIDqiL`Td|d#80U+V~2pftNHmEAW8vBHJVRWfeG<;iIp!*ULK!Q3vwk1C#{!)_v z_2JJi+LhtnQ`atc5-xPw{5<3LaY=AdCjoj-yKbzXEybS~I~W#Ksay^p6WfZC;z0bo zvc>x{Q|#`tza~B&GnYU};v<&V`;Xj0%dNhMR~XdCyNRo*(v*@>Z^RT85q6ChepoUU zHj#ZQrcn&O7ERBq1IBdEK^4jEpilEZ&B#A1#}?8~*{t4i>w95~HamoRb`-h?L$0p~ zpC05T=V@_5bV*|f_z#EGvV1%j5aE=1?^^x+J! z3uBqTWk>u1n#`R|Vz8=>LU&h`>cwhV`Olq8M%4Wp{UR0W!LNez)t{IQg2<~R2a>Pf zp{SFgGN%ywDTY&pW9ls>561r~3IDTrWDpQnOyXC#9??A40n^u+>B}pW`mo+i)i&Rm ze+vbp(*JA$pSU;Dx^7*B3L z=q-6F{x^aCvr+#2Pc&rs4OeFlv$DF(R`UyMpXG{-kF;f4Q)LDfI;5^el}R!-Ir162 zn7|x<2zCGcOI67Gl2KrHnum9HvWbV!%R6jmrpid{tB|XV-qGkcO0TOO6JTr)zm8x9 z|JI%V%ya*|7FUJ1#F{u-Zi_xO8~7qMS)>ZPPOC5x^0nH#=;UU*e)Fi}-r{Erc*%6R z1OT&KK5Q2%0R4tQnkd5cweARp?p*13W55W~-rY?-k&q$m|7ra2(BtYbtx?GS-or<` zuG|VhkCH9F1|$A|OZl?0BJR(F*koOH+X*_DuPt)s<>xo~wd_x6Q)}D!)p_>28J@9n z-r?clCvE2~GNXe2b?#P~RUbD=IKnquxFXqzq{<8o{$nkQ9LQd$z#_ z_ww#~1*j4A?nfktODz#VBY_-9H*{+CtO!_i0hc(PrWAw`cmK6BpEu`H&~4%?&118J zx$EQA;2?uSC2~ekGv3L1Z{5vM3|^T|O$U%9MNXncdfb zu^n5Eg4H=Jvfqrvuu*zl?1p#&mTFgc5($M(La^s1-RWw`m~K3E=a(8A^}W?qu#li|n6(0=F=^KT*qTKl9YY3wy3q%uCX$t{ zp;Qf{fkb|uVvVwo*%A@ix7!&yHUIFBe@&?|EI1%vi`${sUDVP>ljb<)ysh_pXrxz* zNMd5!2qSfY_dV%=uC`w!xH?)yTr+qyx1OkH6A%!Hp^!k(GoBwPVoiKghW$!oWuh-$ zw1Y-E4ytN1WC)ySpa>QgjjI{X!1r_KTO+fs`-ynyemTFc`=IQmBe zInDyWso)p+0e1cKKhxfbaeQ_r2DFmYb#P^0={MICT*q-}GMf%0Ap@;)9zDN@TP|k3 z=5Rz@=E6XB_M(UT2IqR`?N8=Nj%!__4X2yR<+{Aj>CclC_g_KxvemleAk-PuJN%y> z3Q(r~+rg?&PQMR`vKX{RzC|Yd0;LOIyd5(R7+Z3D=WFX-c2o+t<8fGl^82QPHPm$u zT81j9+3y13vCcl^y0ZN@gI=Rc3Woy;P~oxjuR6m}vYZPPL=jp{wMrLIW#dIFpiehB zS~z`skkpDmTo~H?k2rsv$|>Y8?1zzp%%E*=vWixmjOUBb?Q(&Gfsb-Y(j--G<04(T zYz061tb_}X2C}7N3ZFayU^jsVnuqGHF#pr?CUZlx+}N=ywmkfOP!_5&H*k448;o)= z4+~E#IO%}e|9I0d}_8%oqbH(Rmb-{|A!FLP$YP# zS)fZ9iO0*{g>y4?zCBs|S>K@5i8`0oSB?{5m+hqdRPH6<$Ku*2mi;;%RP)=fH`z2b zHC+zJq03rtU>w(bYIZ*7LUhtq5@zHfYyiE_FY7-?zsMvqWNCdfF4WEYxaF%W_1}&g zz`c${#0vIGvs9_CUpF5b5qFO3Bp4QDrOBZUSs9J0LF(xc0h@tL`@1Rk5IxXs_h-}% z2aG5iGuebit-#f@B=N4Bt!bl+XKf4XQPyg3eoVFCQj5Rskun$9Pd?yUK1m^9t_+xlntpDo|_4>88+83f=|GO%;7?oJkX}$y1 z%BACJ@VI?EQi@!57V!BY?uwg|8A3w*@6l(giTy|cRjy6quPKBKc;rT%1L>Tn=V$Rf zz{zDYzR`#BD?<@xM5-iZ<;`7=WHje8!Oj(PA{w=9QuP2C<6Hq#e*DJrUJT3VOSJn`-=a#RtDS04>uzSxX2_x#)4j#;swKL2N{KF6e>z} zn3kdBFUE(!QMiRxSHz3GNerenG^T7Au`NZi_M;{!cmlS zrO?$%)!=)!!>7*p{u{3c_`y%&zQhzJma&a&8d7Ae@VOLT4X<3g+dK#teG-uJg1g(Ef%dp zv|`PQPfnWyB^qq#vk86iLp}P0UsE=FLtp}NCd*u=Iho03Rdi}1OP&HzFFrDB{3VSHX>dp5wGU$ zfn-JJ;?roI6RT27p4ylO|D$ws(&y|qS*)(yY$`obq$+tP#Qeu6{L&$M{&~#_k<=;O ztqL4-WHp&$l(LbOWV^ZRe%g|6MlKj>NN;enTwbEub^kpo>Wj(Ks1=th9V_hbSMrNk z*q+FIIK^l#d9)k4$?fPZP`t`6vD3H#eMZ4OqTwZXchNxrT>zE%_3rHA-mhv=q%&=# zuYh`7Tc$&v-KY@{o(sT`V4ZYB~fx4m*zpgIfZ8(otWSdO# z0VKEf%($=_G{jdsLe#OL|7XXx*Fu?+S)7>_FzmqSG3!{gGW%_l%;u zBXAk+&?zN5s+4mqz2d@uB{@H`n!-(0=-`^3Of36LUW^Dw&xmpw0EFtxvPk~lMG=G# zf2UXd&M2|@oP43modu}!ReMH&6Co&lv1xsOwu(FIl{$Qb^QMaWzCBL#1i>96AUdJ5 zPxPo5CT9TcTWbO*Oy!O^F~ESJ)F_9~X*I{0z1ghrKS>lk&>I|FMy<_p{cTL5!9;Q1 zt?hPy8ovfdBy!O0+4jgc+Z`1yvP%FPi5^}(cdyZ}k@r&`-va96uOrqGz=01yn3WhP z;LFv5k_`OIoJus?g#3v4r^-Et0iicXG714*b*?cyh4_nlsS-G~Y@$jFrWxE$LzM-2 zcC$wOqqpbTrmAsMv9-Ii*iy5ndJ`cNjlp8G$4NHE9MgR7PeY0_8tjYlj20l{72b5? zg6bS!)T@7`6R-dPyoi8Ozw&vqL!ny1(@*w|7qjWzo`)0CDwG=Ir0KN2chA{KA6V7} z2>wi^pKqaT!Tlwn^+YMY%^?qPV#2w^Q|To(B`H{+RqHRjs(GA_<5UyHdh^UXALthA z6iM$}tm5g@tL0;_7aQFHTU*|^;mvn5t?wRe_YV(Z8`O!kLv4>Bb<(Z~TvS{ZT_uR7 z-3XFv)=T|qr$Qur4vOg1)S_&?_m{d2PUQ9r^`P2y0Du+uFMStof;&{q5Spwu08Q67 zHRbq(AOLW-k|0#(rBCuVqX0g;w18@h{mH6=B429WZheSTrVV=4{7kKrwQmRzz-_oT zd20Q=4RWP?HF^QBb1C@oFkfHwdE6HHHCM}N1$CV84>8Q@P!zcl0mNVI=4+AtnY4od zBKp3b(N0}JP*Ax}Ur_zT&T5?S0ob{s;+L|xEMG#;-@9wtBkM*_dh5$}sDwu}7c zE4MZHnd{1;&36xH82ZwjN2A)H)kpg*CL5p;*`OM0I`u|Q0xtW~tAi~6e{X%@cEUBF z0BXkOx3Be+V@O0~PLtqi>SLeWv+Mqnm_OU|Y|HINXKGAKMajLIzr*Jx6B-Ky0&RoL zcPlID-^~V$m!2LA?mnAY%Ek9YsSjYWp?A{Cr$+)6$>yW)z%pqB4pYa+&4Ec+@E`K6 zQ#WRdjg~8`fq*;~x~mH6mLher!ln$CjIuMaUu-nH4Wl(pv04#+Bj$Ws^f239KoH>d z*lbOh!!SRR5%yKFq%RCLu|!R|Q>jF~qTH46pVI#lf+CSrWD>9Lt`35uqob{%owtY6 z@H~fSeCX)G2I6T^7i1IPbbrL2EG?d~1?)d(i`%m=U_ASMfSQ74nTkaB<>_h16(r2> zFJWrZQo?Qimxt<(ch-4Z<7rfNMC06oXNzp@HcvMB-PRz!x*kj7C8!J- z51nQ?(MRl8ID4(9g^B3@bwgb~5aV&mb8q^WQL29{ihx}Dc|xqr0rm98{-03f#{^ua z!L|DO47)#-b4EvhsZJx&D5M1J{K_xF8}Bg%_%`IfetiVYX`UlNEU;8nRfJ)Dp}P@dek7-9IK7n<4X|D?}RvGM@G*klB+vWMBD zr4}24AnVdnVc*;8{Ocl>0*z%b%lTTS+#`Yi$;JTFBfG@}a?`^Rx#9~gM;n5B?vBcR zd97^LV!SDX1!wz|-ODB(S#D5Q?sTxfAIW>RB|0}aGoG6maTH6bRcBAk{q*2ouf7OK z!^H+oaC<5e%&6$8fc{pYLI5cI)~_hJ|GEXGih;qYmVp?8}F+%QT*OE>nev8a&HCVZUb+nRsKf%{*aJzc zr-`q=ypi5)hTEGi*Y5_X-9)-NfIkc#@4s9M$C4KoD8k|gF&J?8KHS#iKYW+Eg&^pD zd=r9@W!vB+<1uZGA?x*>RM-tkGMYr4lpPB9HkI2ZG^;bz%C*n+zo_e<8Af>voHGnw zM9UX@K@(^28_4^5=}bD@_bp}-_OLicbyo2-{r*65|K@c7S~L#Xs#iQ((rU9$Yn-^> zs{pK>U_f4e_6KrquYO_tTtwTbyq`p}Q(j*F#YZXv&uY?`NQ6Onx!F_om%erapE^T* zGIP|hUZaRtr;bgN+d)Uy$$H|bJ?9CB$(EcHKf#NC>fiMNa8jRBh=>Y$EwY&ZIYUQ< zHuUG*3-w2A)q?A64JNrS0@`($HI_?6t*x#7Pcx3|6PZfhpkS{HH5(kZjEB2e26cvu zDkOS7*VEianm1=5XWPIhM&&8Q!`L@Cmmr)H@j4Tb@H&wJ>~6IY{ju);VNyiBD7Vey zgyP;|NiA_>65+_p>4OmTJC;!PRJvesB_72A5metf?FnM32^Ee}jg@nzQs%o0gN3IH>Q zc#H&qu6ltgNVZq{4KRFU%N8iiwE4Hq(cDd!8AM~zt7xr<{&nU2=Y(d5KTjpZNaf$D zjBjV@3^Q2`g5Es_RKX~fzyVy3%H_>- zwcS?_ck>-(ePPu$4PF-v<+`n<>8Sh54&~|OS_S*wT^7mj@z}pdVx8;+4o`$UF8h;qU5sxIDA&I; zD(R4xO%FvTSOEZ_^>V_ppIFovuCmh~-TyZaT+#w(1s@0T{~R=tB1^*XczP5>*cd2K z_#?LIe0#%#;kmewaJ11EzuulD*4Pa{;0Sc#o{6`f{x>IT1T4lv8fd(*{-SFjcBt# zwFeHIWckP60+Re%zNYE;bAzD!sZpqag&5_&z#1; z4t#gYZVkZNja-Ef@i8{qB9>e5b3c;EMu@P#i!W*E7xuYZpm?PALD(uUa%ef z3j`l1%mze_2rAxUW4}5_EY(TH*zMq*^p;PQD+63sCoza{njGUUkBp3S{@BIDOW||e zRE=Wt2SW)`Pk$kemd7PBGSVkqzn&rXdZb#bO=)-sXwz+`{Bi zxP4xO&wQ}lLnhS1n>s>Hcb?f$z5KlKSC{0kZ%0BzKfiOI!ZfqSNiGah6Jh*{c z$-&FQTyf37FX1xEHWME0i_-Y#b z2KjUM1W@rfX~;c-rEtNSz$A>|mfRcRM>|5S^*LH>;o-3CK)%xCw_)&kN{77(`-ZmM z)l4kJd-7)HNt_B=zI7pV1xMGJZz;#AlC9@nD(W#z%fU8O6>vnNF|Ft(vQ{bK5$NP9 zFC-?_3g0jR*rR2<9iN<(G`ESEe&m2>bc*}ptKKSLbb_Do45M-XbzY1?)Wc2bN3F)& zUZ14rcckB;ddGr^3m?o=&%U~-mivIJqq7rWltGOz&*|J<$~DDIN0qvM#)KMM_;sb| zD;az(P_DQ&-Ku_4B{?{C>Yce-jICuyt|AX?;$^ir)y%Z2AujJge2il zkFMBRXWAv`@WyCd#ZnjNvh}1~+~d?K{pMuvB&9Uep`sO>FK9HQv>XCMhTvP?wufF; zI(xFi`|3+B-H#Q7s9K7U!yH>!csS4GfXIKRg{6v$G7@TeOn{2{?no%Y?I9wfe|hEd zCHX_`&XUFkBTrJ0JcbRVRV3S-8F($Wzkhb3l~q2$5rJu~0=vGMhoCfe_7>YN?iKUh zcLSH9_1@)7d-liyX^tt5YxVp&a?U`VnBEX#9Lk z6EbH?waMLu7d=AezYvXJ$7=&>-@#X8>&^tZAr4va#ium*l|(s{q-!ji4XilrIuMol z@r)81h1o<0A9sS%^+Neq8e$(J&Pn8$`)H2r=RovTT(ll>nLyYAqcIQh=r@(j>bJ^I zTIjY%XLEtC6{~ zTnoE}yj2=*wQ6BD*VZZ}3zv$xTln2xg$W1)kDGFRFWad~;?Z}<&4Fs6f)@0UAHkd< za_RKPScd{<{wS-ork~P3Bid?NRlxCKHNl9{gDSA)SVQ#X4`pQ}G0Bv7Qp7k-N{Ev0 zq>C6*-%}!0v%58mQs|kSOcM#`eYh9mpsi;NgoTMfHl!_$b|TeknFi}aJ#QS9K)rUr z&Wh&Gjb|Ci>HF+I`G!=EfiaH4sr@trxr}m9Rk*$(j z^W-1jCycO1kg@AUd3=gJrfIqE(W`~u^T6jaNC?!ahUOA-*-7PO*QF2s(OChQhQ8f zURoN53b%1;Z!=1j4srt;1`NdGBX3frN@(~Y5O}3|z!swTjD~HQA@2+zKmeim=$4wC z1N~)N{%adQ>e~z0*W7uJmxN4-v&7pd=!HjxsZ>!-IYwRnkgkd`ld9cmL}Qlsa8&V_ z)N@JXtzL_%NGFZq>q4hiz#S@qG%jvF6U58FZNjL?rk<(+SP;4w+=_0aFXW$yxPSjS ztA9*7Xg9z+Tj+J#CW|$1c6Wbi)^BA7c@{En_E&renEKK3MnO|S8cVB;dRhTog2I>< zelU}K05MxmyN~ppD#g3$F79(;SBdrK(#FU`izd-D%~QqdJbI);LPE1MA3O7(Fo}|> z_PGx&wKXR#MC-_8l^4pNVq5B?sLT6-`AkB0!AO3T;xHdEge2?i^8U(xhBGR`;ZdKF zd`Ag#Sc4c6y(%E*HAxMlaa7#j?S70nnlcakptQC&-Jr(RIE|h+JbSlWSXCoS?=!I{ z32Vj$g6g%mYB=*j&pR6kuHY**EN`R0(6TZQ-ChNN%hjr68hA4aEm3|x&}jLP15(|u zEIST%@bU8T>3*wq-=OyVGQ9sbyQmLcuwv7x3)780YmEb7n9{X_ryE+aqdIlp2kYnt zinWszrQ`#sPxvcLF$mZ^g1Z(UStnPJ2|M|uhtE{wn1$&Lk}KM06McPm;Si1;r@LC% zi_8Xg>N!ohw<)45blGm@eo{GjUUjAY`Kdt9FK;59#Gl2<@L=ml2jf}>3AaE&z^-+~ z!Mfoc?EzMILeIwpfb zLd&)({l3;O6~Xz|RbjW$%7}W+ltD)6+S(SGea2HCz^`#Lu;hFk|>}Q zv&1g`_*J`Q!;GSig5C}*m?EFxA z3ok63>T+6fAGz%|;kJVsRb$q7^hWe$6EiDCJ3+^VD3yG#M{E?DPFDKQ>Yg6=g-o_| zgsfIQk|UDk!p(4Y1&oF-lI>D@Zw1eIqvmIzY6a=ToK)pvhg$WD{b^kJGVUi0+|D+1 zJ^P=+1yEn@JWST#!6|svd=X}2WK^iRnPQ*|&0>!iv}K8wx@`1yuL5>L0#w?8?*2(jn+%8Ue@_5uT%7=-_zR_=efU6>l?9&&bF{TY_Nix*i9<=#v#)t{~>maqf71al?g#B~Nhs4PBv z`h;Nu*tc{{Iiq`M=wKWN%^khuV+Wm85kQS;e1JuhcwUX2pLF#aWq#uuyfR$s>XjXm zD$V+$x56iJOKd}AN0Oz!r3|kD_)Sy4z9c_b6WDV4#pz2Q55Z+Lwm5VIZ>5>LN$o$~ z4fdaETRpiUz&U(Rt66gN^Plc`>@t1ktVv(7CpaN3M#KTPx*yP0=} zI7i;hw>kpiDUu3$SZMlJKhgQ6*!ak`Fy2>-{t&*DRS1+eXr}9|!=q%KV5=`!u`_U=Q2;M$Jk1#t1V50aAhtBA& zjtf%~b*Yg8j>%+YJ_>+GX}tfjsQ|f|eDKH12hI9w0^L)d-jZmqmSM}In0o8gWt|ij zm+bBB_;8`ad%u+1nG;Swf1HXvvGB4n9-nX<#&5lcd0L+b+$8Uc%8@N+Zq_k`d=i?? z>1x`xO+$$Mu#Zk%Xi}uu)nbz#7azNc4>WSMhemjgl!t{8`BKn7JudA5=oXX}t8Qal zbI8Pr6n+QHJ^{M(+>2k*%};RY)Wm)r>JjzC>)Tn5_*xpBaejk^f1^@BCR1ACJ)wu~ z#PQj3_53Sg*+K-fM1V(6!=_|~`DP=+VZtAiO8$!~XHh(ye4QTeh{3X4c_ zdbC=^KpAnO*Fl1(geo;jUnxxkV4>jJ6xzeU`v{amESPJD{Eeis`IqD0S(Df+GaTWOxWy>0ao74E(VnMkBk z(oxN*SHjN3A=nJ*6>D$SUbNSkgo6XP8ImZOAe5ZuHjAFcB;p3MGp!8U-wj1NJ+I}~ zZMX};BFtA>I)dtuJvKX)Zd=Tgp1Z2g|EViM0u0>4{>Kq((3>)Rr75g~eRp49jE9aM zC!|4YeSErA+*DN|yOy#cS(&MonQH{=xZIY-$P8iD3q~E=b50bz?jqf>H{si`Q3Dcj zo#FUGtvT9aM1-6}<0sTHxd%~QUbB8lFCGZ4UIt9tX8=w#*x}@^s`UOC@1%o(!%d^! zs(^svpfjQX0!+5L4WM2DoA1J=2+P68gG_0P+j_|eLi!J@AQaRrBe^h()r4oL03m%B zT$u~=T~1T=-wJslwl#Q}8lB6SvzxIlwDs(E9+(+(K8tkRdrz-#Toz4VxWpq~*DQf? z88TPPJW|ijsZE5sp+)g6Qq|3lss$fOfNCUUQ{xy6>U4|PEhNTXe;g{LL_>aduES`M z?r5;Olh`sDd9vkemEoooIf?OSE!+*$?rRhJO%-c}LA{j;P`F1%q%FzHu17s7H0M)Q zncRlIyGVsnCo+JLW2p3*1|O_m&Fsf;evd7&l{g6Gp_q~za#WMHPS&%#I00rsUOIR{ z8mTebl5*+Jaq#`fgz~sr$6v!&xpuqP@9O!U`a}q-LEAMmkcQJN78A}uLx&wr3r6S% zwOzFMa`pwGpxd9cz-UVeW*=gL`d76CJe%cH-}+v>(o^D0@&(e1z%WfZRkWL|4q#qa z?q2X2r{U6R%2aP_1eNNPS2a665mrUUtQu}UTDK6$Yzjlz9RNFsyy0hMMa5S2oCnTU zC32{uC`u=Zs)#g|St8vbn`froU-xXAH3_lFEJmUE=>V?Kj;RAMfCtFP z86IcqHmXoFSGUnL#^YlPn5;HS%-wh8-cRN#{Qf(yjmjf{=;@uoEKYnC)o^}rZoECD z9(hWRq)h`=6*2vlpH>}{6t+VzQ%W}Z)XezMc?=zlFA`L!7QpW(ZWJ(znVh#9vYr+Rd|H3m2d{dh}?W;oBL<`Q`a3 z+$Y(W?JA+GO@Ux__zzNhDHD*S`pUnC7LMW}76Mz3nwpvuV%-H025XJ}T6HalVmEi! z19kgQME))WmKP(n{5GenSitO<(VgO=%mJmcvZ=47uB?`%*bTcU>yW_9_P)NNLI=bv(@Q)$%45_7F0H^r_Zdy)3LFi2S@M)3_ z;MUSDM_Y8NarJK;$~?&PFb9u>gofVU*$|1a%a#xAe2J?YX#`UJrkyf$Z*><|E8J5K z3qTizp}KPKUsbw^oDb}J9LC>Ta9#(pnrvnUWm20n80}3=&XQS=``~amoiE>t9qeXe zqM=TVKbS(5t|KFZD@{%EGb?FMs#j)uiX5h96XgVjL!>)If6>$0_t@jVr@nf}YIhaq zy`)ePi)KDUUlTLCu-uXoH1S3oB2kQsrkDw2%HJbXh+0Ju7qV1!`)`Sx*BNdmB z=(`p}RqP*71^CS%OEki6uKZP*XI~6Nq;4j%CAIv~=?2#JX%TkuW8@QRLZ_a?j8OT^ zJs9mIq@$yw;piy%^XJcK_Zb5ID z&-(D6Z6EBbGAOHEsEVN-+wNJCw zy4d~o(vRn`C-IeuG#iMDz;@dyPeMN=wV-6nKU(UnKZBC*@vtWdo@;d*7;1gx!pg9$ zw^}LEe|;z6ZN%|Fe%Y0grN!W7^Es!`BR}sZ#LII3V-+d;;b1{T>5oUV7N|ha07&8T ze(&wQUoc{P!)C32SJXjLL7^XFVTTwdFp8uYRfM4DA03a@Uwb5M4ZT+KHLqR!-Qe^0 zLs*O90m_7&heX+%{xP&+p`=W(t_ll#y1wiUAKKU$WsPTu44`AnA7`>o2A$A@VbY(E z@Azg9Nw;T0o4#*@TfRhW`p2YbQFwgV+)Qfo!+VecXIn?|2C@0z7M}2!f3W}g`fN6Q z_@o0=7rO1P-R6T2?{SVLp54~iI5j;`I}!X??jKwwu|qzo`OBRo%chq>cEL68;K$5Y z;2+yTdK3CY#h*7_{>NZUFeRq*VjJeU&P9PCkAx9f-lPBE(4D{syV6fFufPB22j?cB zFtE7}j$ACeo zNJuvdN~bWyQ16{#KzDWb7ytJk@B81~{jAU2=f=6GzUQ2KA8*3cmG)B|r`oY&$9@%M z`O7smho7MC1_np-NEIU}ri)#PoRkx;kIKCT{47Mp#n5C|)Kup(hj7q}^SBr=X~v&9VIY;NJa z*#t=8=MYff;FSSg3I7Smkys0UIGO^oi6c1_1UN(mIK*T~53+K^2YwD&QPQL~B*r@^ zUxe{FsA`zO9TYT_&{q5kW{Q7YV{0V`cO_?2Cu=Ce+`=9#XYRhan4o|NY1if+B*J-x z1%x(g#a@>?s69P1a@!nk+cp_#eaS5 zHaDENjp;u!9ne>z8JOC;Z7JTS4!e46=`dgiQOj){h!T(mCgW-Y_^xJZW?>IQxY)RE z8ju;n)fM3Ytk|CLLe>;+XXT7=b2OJj*dqwKZ*E~}>ShnvwLOE3y^R&Y^jr~6pw-mH zX;UvOZQKb?MV7dr%vLKfl+6~xRHm+`z{PA*#INXrwBq2Gb$0+fmV+s)^Xq%a3YzJ- zyTQ>;f@VtgZl-8n8&l=Wyl{C0Qcb{Iz}!Pf0O}!xggd~IP%S$l4NbAlejX}T7D{|B zW{yxX6$fixb7dJ}H4iZ`0`6vxhPs&vTy#`JtDvCrGDx_9zN3nbEWfFaw!kF^F+rH7 z3Q9#@#tN#XAf#q{iC;zj5(>O`(wFD8(NabSdT zI0zxl9Ikw8w?Vn-@w=ndwA4l50+&6^_+9PQbj_Xgl`kVSY-Ldv@~&cP4(cv&4_>qd zzrK^15=vMFt%8Q?=y^cFJD8jp+FaS*MPEx$6wKoUS0vJ6WvX)t@I>9kR964>)1P*Dueg7#61g`>RjeE1^WiP;8U|za0h%K@W)MEQ^g9*X$==3 z@Rvw~hl-6TffI6K#9dw?>{4D(RE>X|M@sO`we2q=^>i+yf4;7Qjf(Q-9>F?jHQOuT zw;iB|APd5?m6(c+ARnLutfGj91AW-!5!6Nv4fa9gt*jkP^P($MONLj?*3JcLE90iF zW96#uA?N|s)pLdFSP7`vs<@lmDw>*U^17?b3GzZUQ7BV6-pzI!UUyS@xEs_~ksqq< zGS8#zU{r9f(r+oQAzW)TDfxMwM zg6_~CWsN4u8c6gHTHsEUs*;$Cg^oGW%tjVv#&7Rtt_-xq7FZOJoQ9?hur8>Zx|WI+ zR8tTIwUHr6*+WHM!3`=8+B}GT+@V@lfTMap{zmH&I1R?ipw(>%l9O=<^YH@-SwZDC z+lbbShHv)Uwqhud?j_Jy!CgaBkXPMC#sjP?MC?nX>j#bA+NGSBBg__s)Cc;dCIEaA zT9AM!0`}PkB>`~vKlTT1ogqzfC{T*@&@sj2;B_X!e_IiXB{uxvQeMq4A z*Lxxaqkq6oQk;VP{}izP0;p_dP*8$%c7OwirthS$Yc6Ld02~{^MC4?6HRNPG2u4SA z)OPOH7CPD<0k@}zRwKGS0Brv}O<Bf$pnk;zJb$A{i{OU; zlpYsT9U*%F$Q}Tk-NC#>zCvvYGA07GJE2`eP7tjQ^ua=20qBFuPr!OpwuFFAUsG0y zFdl&L&*lRBRp2Mc4hr;zxW>=<^gUfbR>VMoK%)m#PLO|74+yj<0J#v~5$N20_XC7& z1~N*(LL9CDO;!1RBwVXuK?{K2M9K(&pdoL~ z55RyQ>Hr0ORNO!Y;rhEiT7*7e9D#ZTD*_;))%ihYX(Pz50kRb}kZ}NqPWTPv%L|+y z$ZCjf=KN}4thy}#2032fK=p(+=LeaI91)Pd?`sOU@P|z5N8sJ!;3mKm>H0mu6F>t5 zDBopnB=<<fWFU51PTPY35r5*amDHW!Aj1VfMFc(KY)a|`EfXTFPTUtU;Q2#PVM7Qi z{)c1@VxoMYatg}2{Cs>O!h#~CTG2PBF9NEiq$1ky@&*BJL4N+9WDddt+yWw`_WzdT zfwcBt`FjgTa~VQ45+rMm2uDy8leKmQg(U%bLVcQ8&mtDQ32^J;>Wr|n*eY*v@C)$r zDk{nn`fa}1Dno*tNI(`;>zqAw!93eP^awvdf<<~KPsr7_U&<4>O!&2lm=@+g6hFV! z|NhmKSZq7)e!V}c`U$%|kS-_v03z%0C90!p! z-UYDE^$#}qzs3p#Kp_1WRv;w8`?ENE%NqX^tl&RpmjAXDZ21YG2d0EV*47T42wua5 zpbmen?cW>s)?7dO96^D9z-_*tar+-vxcUU+8>D=W>5L zAJR$X7To^#L9nRkKQIU3pC`1cRT{;p?kRpb7yXZ~H!{C2eUzp9=oDkdt%O}M5?s%Mh!S!~xcg?ah7!R3bS ze@G>!@5*F+g8ySno8SQOk0FhWwg$MTqAsTZ@@Fj>1tkTo%`PtA?)HH@Cxi=m-<3E` zNq6$#pkPV3qw>RLJqH_ebHdd?S(LSntA(bMDV$IlM1gCipzZes(m!5xu>@CNNEb)> zML}=kZxS(t`V!&ycTtq0A}_D79C6m|bIxxiQNlIE|GXPBV!V9(+#*8!{9IxC_eP$uh?Sl(dBySO z%q7fk1}_a}l<5y2(wI5*nC;hBXUCr=Ox(JAo%`kCy|=iJY9q0b7ga_lM@q5=-ko|p z!zoi`@N3}JgFB1K@5|j;^-j@jmXwqf=oPrq+S?kBj+40eFby5rV1S96E?Y~t8E?xp zU^qZVzK50-a(&0nKRjGD#MqFzq4xZ-ozyc@7m^^A6DIKU!Pg;sT6)RNA1am2u$ z&cGr6N=-YiiNb+$4B@rLIPfm~oTtr1wd|Hg|K1S1*=7nVB-xIfKpDp0F2M0pjCo_d zc5D2sGiDu_%3{rhV;n!XeOEnTgkLBcC4c^UKHxe8E8X_?^xmJ^Q$j5n8IGIh`qZDi zmIlVQmZPqy@-xzQk{KPLO+|U^bp0viJIU5gvcjfA-S{v5oOvV90d2L^37&uQng)0# z-;8^g4*tv|UWY_b>^=*t_*iQa(w}K0e#@&aDnDobSL%{7`V!9Hvzw#~7~>;HQz70N z{<^uA(2SyiTgJwmaQ2^f<))s~Cxv%wqYv$apeISo}Mh&z=YMhnaz>;{*Vm&w6o8^?^Ko z@TeMwK8uCd*XM*s%O$_PSKGc9{fH(gE5vihm>vSr8DxX1Z26Ad4P;U%$~;LHk9rUr zT$b}58a^a-X*rHQmAX~DR3`@doi$+`srIy#rez}tR2)4G7UGsz=(uExE->&|nCRSP zK$SQfvCn3B;cXCu&QPE7csa5z>X91)m-SoT`fv=Y4;Jf2`8&9uF97A6!uFaG0y`39 z$#`N!5S6=>G_OY?Ia79cG=`p~91FIKeudNGsSwlESbW7%`(Qub;p+PDcI5$f)xZMn@bNPc0~Y zJ+J-M{P`BBcuJ{TVtMX0a}K8xp$F z)8gn)>(3s4PZcXKU`lWAX0?opURgYwfm@fiM@|IA8hWLo^u;KRYx88=o9QG^^8|+X zpT934HQoU1-2Y1oF@C_jr4p116qNLu|6CQs+1-+ueJD{QiaUZ@^I6>3mz2=VkfA0X ztoFgv4CKMz2OJ4(pj>zBe4-7Z5i-3u@$OlK)O_P7OcJl8|Cj}H9o%|CoT4yoYSG;8 zdZ;bdnSmkm9Gv;q{> zLeQS9^m0Zi&#PnZxDNt;)s&g1R%T^!L;7RA=l2VSd)DWF&&|{lz>=|Z_CAEhMj?!r zxTOEn(bJ{3mC|EJZT4}-J6}90gN}j^a*t;{ifEaYw=itt)n9WqE$bZ)rpcbHEhSA{; zdZnOZYgp{uk~BG?jlc!n$eHpNVR3%rB(0F8!@0Yj<9B)#22QO|o5j1+$_WNLZ3g{d z%`Laiv+!#NFR<0Vqt7!O6po%0)|hiR(9TI!5$*elw{2>ndL`+-$qU!ln(^Q7e?$l9 zctuvsHKNHkP`k3j5LwYumpa6+R91^67o0*b4QZ{6`;Qxh7d(7ZT&##re_@!=N1blB z@B3+vg8J~(fz4AkioJwMdSZ=Tdl!ayu_NnL`pGIn-DLt5u_nI=qVv0wxMA@vmx}_w zk4}<+>rnmDc8tKteRm<981&rKJijV--{r`--q)G3IMoMSjB`g2eMx;~Qe-$8e70Zl zcje^9Y@n1rMq+~mlf%R@oEC@ixS-H3u?zISq!_jPAq69R#XM#Ql)o5OUpU?yRa?2I zg>rI=&xEK-o9xA30&)vYw|q~O8v~ie?lFrgb;Ok2W7=Y#BX)QF?0r6t$cy6`r*96q zP>kI(B#)p2Ca|@O1bM*8n;j)=1PWdr9I;IB!3nj~-@rP({8jl88cE-&V|wpR&L?%B zhaZZb7$w9FvRU8S8cdjl1NaBkU)u<}RDG~WYUR@2J5ET-1a0LLRK3HrGO#OmpXS79mS3li@xUt@+|LmSNtKrNZ7)m!!RmukYSQ z0@y8JQuLOwz@E||3v%B0NQ&c~?T*$|2{qI^s;TABCq+kEs+QL{o(-O~IzX9N$c(#N zG?^MfFN~Qy;&rA#AHVi!VLE2xc9G4jjQ@Q8hpujTp$E$`$CVO`nyOs_ESHo`)>^Cw z^+Sg%TAR+nODQ(^B=WDc$6Q!lM0SsGGQc?+fz>@iQ+4My_|IU=Y^xPXQW_x~2dvm# zB_}`2)p+!F%FX2KrD8|3<25&olP;+_UL}9GuLTv2x@@1f5OT6R`bfpeshExTvN0kC zv*R7JjRKzBFyD@b_R3`GGAZFA+?2a@Ep)J)bNcAw`#vnKpLVcg>1P8z_}ju8<>7cE z?>=$;1uhtmgNmy>D+*H`J2g7p5PB?(Vis98T%RdJ(mhB6(0xy&&A!`^jXma=rLRQ} zqUSf%dybE~P-0|`oECufyM)4Tqy_D3siFR@G^Z^(qlAxnIVZd3H4hf8wYVsGO}hu* zw>GHJ(3?B+NND#M&HJ8HSq8{52-eAsiFSl(r>W<3hJVFc5zb-6P zG8*1ql~L$(D!G60MNx0>(g%@hqihfKBRShehW*G?hLU~9IUDbh!Tl#);EEa{?Frj4 zO*J^uDU|~;!pS@SpGV0KF6KH!@zx>G<3g9dJQesHxp+J@8Vj z$xngPN)3C#hXTnPqwDSyeYgOhKKHSg*V@zLgrBBCecYO1 zdXW=LlfKM{7pL;)%u8Zsj$`n@$*Z$MSSc|X%qs?FN)~3$Gu!7vSNXw0Z&QnJKxnAU zcb3eQQ8Lur*{ux@0^c_w+-r?;R$Qb6dzQxL`sfzlGq2IMjV`W=F_*Sq!_Ae?EEElQ zhH{z1$Z)c{LKm;UASdfQu%Q29>ST)J(Jj3{2Il9#kCRDY#hjPlkj)60M}hDU%fSlc zv6f`kXYiC-U!xmu+wbO7o0A>b-G2e4WkpjlKNg8AXgJ`zhR?=|O!d30$nNHV@%(n> z3HcsZR#wC59kppBWWt;Q2VE)GhcA;^P$xD@NJ0d?CHS<%d$H?#Xh&ec*`L&e_gziT;*yfk2VU{1bi-u6W{zxO$FI1Ob_evL{~t zK*JzsBA5;7<=A-l?!@4KX}nNm9)cwT<4SaD>DS1}sc4lyq0y0}k2`X&w+U?>pr>YmX-n+v zEWKH;a-vzz-#vLS^4IGSZz^{t!x9_=Pf%t<1)Fg3Q1z#D<{roNrPt#_l@8Nhm*g?x z&AA6C#+c4WYVM^SIkU60&C^zF-;GUTM|J^ZB}}HR@xpO_EHmvGoi#y87Rx(klEvYE z;_LJ@4&^Em&jt&UklZkya04syJ@miavCT*^8V9~dM$-Dhmho%=om)4N6BuE~DCC?i zr%h+47z6i`p7Ox76XJeZ>=}$SZQS_hGyMhnLZ|!7onlEd8)D zoUAM@fwxfF$k36#o%bGs%_tYv_w<|)o@Rf&n%>~8)FWWE=%X7VTT|5gD^HcSYK3%5 zjk{?P1lwrQ=pIkCw1JrBHq?(kWY(Z8-p;fgkO}R?l!#*>GGu2Wp)^M&#kCn){4D2= z%{XArDch)*ylsDE8)^i zQPV?8*i&&{EsWIBE4`}a2c-?1*I_FJLs&3c$o9wK#^t0WB(mxIDrU;?A-Gt|2_N-0 zsPkAsZsVC8)9DJa#XR?x7|z1^jn2Eip&Q0ui$A&HKR&0v(Xdh>ccdCzKnalQ_gwdx zZK|3+XTP7bdxmvw1*+(`*grhAv0?ofbt`yrZG5ngt`K=)@dnOf;rV!z*dZKWr!R}2 zlM!Ad=lsI4B40+oX9Yu~Q}R4;UXSR1_mI5$Fm2+nr=R&r#Up)*4UB#z)py`!*R9HU z%^QEc>!qV?H@SzH81HIg54~`o zsBjhBxT^prF1(|%coR~P?(NYdEI2S-nJJgOwp+}eA!G4von7Rnc0s0q0rjW|iJm4K z4M=@G`1Fm>v*Y(YLPZ+RpYZj0fAoTbqy4#GQ1E?ukcSxbuZ}%y5-vmUAN4jUOkPIx zg&WNuST)9m9pCj;uo^`4LFUqJvqh2%N7uFWlFG=N}ekCeviF-q)RLGc4g?K-D2qG0dtwwfsFxE_ zcjQq2?s}4U$Ae3beKkQ=BVYFHlfBcY`&7Z*xZXP{;w9~fVnW{u=aksNwDM(l3+3eJ z$LnZLLmdtqIa;0_jD45?R=BS4T7-vie_pp&*%J>GIz6D8swL(5g)EN73bMM=4$Y1@ z?@SY`qmLFFDu0pgMo+N_bCL9F|LjYvOT-%hmSw%DwbljhWZ;#LBoX zXd$L}T8Q%ur>4<+dAHmqczr$%?z_-wYPQnpG8a~Vntf8<&vaiqkx!y6D>cjZ} z2z)sl`D?p`RqI(Tp6AsbUD#e-P05Dhd0T_Y-}>rI(NU`Dy`!V!AfKMwrRv%GqG%88 zX(d+A8uPPMOsO^q1OER>>6eU&vo5x}q$&C=s^L)QjV4HKVi zj7vSQ9C!50NAiQHH7{3y?9L`Du!5&v-E-DKD^jiI0L zdwso?5>W~ZLu=+*BwH8;woqSZcqX0Af{OGb! zYSLbct^+MJKCfl?9J=!MGEVp(T3;QOu8D{+?x2=STRqz6+Q@j0uckY+kEeV&!vSy0 zt#>_6Dw$GREcw*T+h+Bk!#Wv}`s`V8u#Z6|7kpp2Jav_w+a=q5hK|2=Ia@FHREXq| zH+xj^*LUH34)}S#4e2~P zKIb`w?Vc*Fl8$w~Y;xP}eY{C~{_>&mm)X8@{S*A%bJskp+bfpq%8es^j(Sl!3`s3| ztns$+)hvC?P^z5P@YZZtZ~P$Plw^3Tw6}?7_qnX1$3+M7Bz|$4#8n&%;LVc z%Hp+J7S|ML&}ef?)%Osni>f?D2}>cn%L2aiuVg{6A3Z-^q8Av4eB>Eqe=Qw^ z+w}!GUu5>R)b=GwSti7B{dN_5KN=f*VZ0M^9F>xiZRA}ilyp0Xz6}QJi{I0>Q?t=p`7JKnwX0e_f3@YP5ennOsTyF)%5(sl6)0j$u7;kLqYK@jQ{1pV7Gi%dqmKte* z7nNM|)^90?t$)z{np7v!5H9`Z26J?OLDX0yP3x0*$%KMikNJ!(=#>S8h%Z zA=q6RXJWcCA=qngIVglot#(+uL0MCI~<#;H@utzh74?m@DsV$DD_y^oGA;TGS%{JMJ zpwpw}5{&Dmk73Ya^?oN(IX?|Cy&bjdbj0l%YG~k4JDeKf!lQ8trXhn@P>l%b2#*V1 zh;eC{Ox02o%boDy0b0}!vemL{*}KQEM>2-#e!u>a)ChPC8fYj2)M)y26O7BRS$IwW zk{MLXZWl5F8^HQd;^aNjkfC?)Kzp-qbcC^!j2Lwk zoToWiBQzrf{q#}!)T01rd&!ODCYq8_4RIy?IpF3CB=YYCL=-gZwAK@B;xR$PJtbj? zeQmzJW6?L5&AKw-Pl@&reu$(`fT9o}DuP9b)dyoc9vPQ=SfD3x5G*)^Q1_dkP|T47 z(%~mahhj`09S?zc zU$$p5`2{u|X@8kvPs_Od8Lb8+cM3mi$V)oq{JFWavzl%~z>LoktU?smsDVKrM-;Lc zM#hslM3sFt_DBy*snY~tX=M5KdZ z(Kew^)fBJw>-@yj!PJPkX|+uv^IhOY#6zTeP3@;V6E~#9Zyk;lveWKnN_@_pJN*9G z1!@1$kOh!*O&UNK)G&DSFBeL)`pIzi$X>4_ACh$p8O2ZJC9+#%&`O5)r1TP`Y)T4v z=u-=!LP>`x#xw`)R?INyZmoM#z%Xq}R7`-)2*y%-^1&+BM%D&Go-9t|2kfuCeCJ+i z(;t{uYWXw(;{Ej3Nh2N@qQT~=)!vqrv!b)OH9V~8rd6APmDTM#22 zX}+(15WGTMW+-Gyt@xDiDZn54H02;q$#nV3z^iOSEwfO+&MQHYHeA(Dfvi1A@yQ^93N=p=>jPsaQ{rKja$-rtyXvot5TZVj_ER-`Si++mrhhsEggHN+n<4(udN5s#_5#Yol_iZ z&vWmgPzQKh6I0^IaP1WfFFKrSxj1_j^%(kmH`a2R)y1ng)ul5txT!}|CL!26eL@#m zIWZpB^v;KNJKJW?St4)N4P+rt&x54cK99jj(dp8s4^--2>9WSwa|i1y5n{K- z6fzpgd6-(f6c(ZAI~@=T=UxpHqG0FJ;hYT8cXOt;){rbKsjGzxhnU$kL{jg#tb&Qju&2CWf2=csPE&B8;wT9FsQq1HbQDZup9E$un~&+ za%~)zSjtooZ;%LuU zJ0P~}lil6zg~*f7-nsZ<;&^|Yt-zphyl~n1Aa6E8$#k>k^$wKRBDk_DRQBGVeO2ah zbrhpC`cmop56QY1P7mgn2J=j22MCaAa-b1#Ssp@1MTs?d?`P=h7Xy{S_M|bPq_au9;<=wHHj2hj*n-ZHfCnp?amNFU>?v zzcx^M4f1L}B%+4m8&6KrE8|);Mf&vAGY$j)eKWKTBNupLM;xdm%IMcUm1usiGr7qU_Rg{;}h%hg}F z9w+gR|3)f~L9V`_xaAW(y)$W-kKaQn;+WImP|TREAgk-p>2yc@-W;p*_;Hr+59zC@ z>6h)_bt0qVX)P+(<^ zz@koJ?Yv6wblvRS=Rbm*D=ymd}$^~9aR)CCe7)xepp@kkWpLz1z2 zpd|c*$%g1RrqhlEcYEr?j+If4~9{5w#l5su&H8GACAO*`!uOhnhaEjG-ysiX->Os zG3hHk_^u}{Ewh09RtKi3BL{ucfy?jSH~QvpL+HM+I^>N${31k4lmqMxs7@w5$X(>r z1QIHRp*NU$Nrg*-0PDyU)?)4;Q&ZyUwmdqfj9^PDwkcc$q7rvz1nJ}p9pKz5w}HhP z#mUkpRMDK{UyHcfWjd4M&ZSh7xCai9O7~wp1RF~dv}O7>WJDa33&+7y;}#$NVh+l! zo7?mQ>cBFA<8fF}!1@bBzv$@@eo*CdF*-El+m2}8=p>{D+{5dg?00J--rAu(>IzEy z3H>`c>P*ri?k2dAYAJw63856X+;!~EuG~eYrG#!d#1~q?A88(TUHgq>1E(Yq&pF+x zht0njlC+pGwvhZ*S5h3aS`;&EY|AI9T>-VlD>Ch&=Mq|i7`I&lum^SWp(+bz^{%~< zE+hwg8LX1zOk-@NP1GG={Z=-YZZ`#&8xT1 zf7tr^Eb=xmCw|+kQQOEYz=&^Ooq=n|O$Ts!nv&D6OO57^v@#R@Qro;p5?C1+LSjZC@hw8jQ8$jSfgzcbV)Ksqt=3N ze{*1cKvQpj+L`2$eSgzbUwj0tqqNGTjj8f*I4V)UeZ_w6q z=&VkM(eZrUc>DHK@vR*gAKKGjKPB3%`}Bt2c3#6XiC!6vhN``I1w%9U-=A**Cld;qCn}j;&q(K8oUzDELQMEZk(+^ zT54bs)!wi?dW}w_%jdI@$%1~V6q(9QXadmReSMv10WW%xE27~%wQ7enJ z@gS4K*Cv8$m>W=8!I7TmwH2F)Wtu+eudAV6=LU9dFy%NJS zHoT^lqSwls9F&hp$N;=Q#C=1@&cwzQ8gH_O36x}!Tre~M^^J*Tjo_jghsZEF>#BmEC$h^-xwM4Mj7v%|KdM)K8>>>hvH+&}Nyph306D*1vj-A8iK2Ko7f#_iKyT-TNGxw8}aU4 zUTJeh=!VC!3&0oN;$FK8QVjuR{K%GrxDDc56e5ocW*Irf72&`WbO;>o9>&n0n0E52 z%=CR4JTl^uPrHVT&klWdMJysO$g5C+u3e<1p?tkEFqVZ6Z8_Q#yUu4;hiCP8vY*Xo z@e}^Qw3e)8`=K$oGFM_(mui1oi6Y*QruAL8SHUA@&l1Zod~^*x#eKdh7<89+EYh^_ zLKDxfK9^5#dgoM)8LoXUhi8AL(NU6EdxD$x{Sv63u%0&ER$eeDOeYf4QDO+i`wT9n zXr#CDReTA}x6|y!voJG;*8IxU>3JT;6LgmQLKh70sN+>}e|?-W2JZ zo7#tPNm#F?k(Y3cFWq1E$eWPo$-NR=XBQd)mE{7o0kZLoWdpPNs@ z;=fAE?5AbrJxXR1fiEkPXsUS}^4hFM^xOjXQ;$g!=6iDkCd^TsM=vR~pS5SM0M`T$ zw}Onre{Uk;7U^h*O>|&ht%T&qIk)(rqK``Ba?MKehK1IyPBF|UN>*;-jJg{-xduFa zrO~O=D;F!%B3dfqkhT^0Gq{Gu6)kzRvL(`M^?IPM`^!pA_4Y)&T=*Q6%~6_zZSuN? zQXd8%yQuhn^~IZjoOO4ZNe0?Fr7ned6btZ!OJsbuFjutIt+Hy4=_Scrs*i{lxry;2ceK$8tF(ThnWp0TUVS=2{Gh zC@?s(+QGI*Fzg$-RO7^~f=$2gONgL7*Ql7hKL}ApQ%+BY`*WvMgR3Q%KNd*0%Jxfd zB(>G@@!VeOu(S2mFhx_f=CZd|`>ewiLx+}Alnl`hljCOsP3AP7)CMFru9XBgQ6qRFG*jVuy(LF9V;(QC=biEfVYLA(^cr z@$InEbx9X?bx()2r(pj&>jss+8yP-RRx}~*?01wG!`~-! zPK)JP^gGv021J8Wg7Bl=lX?^qDq)Fh?z@nXriqH$q(`7cAqoMPV z50fG35i$=KI|AujENdv&#Rn3D#^Xh%ST#(brJt?Nr}|2VA1PiuGzk|8s5H4CF|c1F z-N-~fA2!7PTZhf|EDwbTzv8zOuwYLvVNWAn#rs9WM!!vf=lR=<9_1x%wwNm@|vy|z+jRrbKL0khA5KllJ+iJ-IdFqA(Q=NN2j)8^ z-OhXqs3KaYGKi%;Zcdj_(B0bU`#Oj$4pUa8w)uBv3}Qctxj%-t7i z*t4upXEud6bbX0KmWnVBf+#0;XXqNN5{hcg>KMF4CoRrBaDO9s>0|qNW{ku0<{?f*3RKF64=?;Zrmv7J0 zw$1alRm005lCkZE73(d#*pd}0J$arMHXTikN2^q>lwaQHI~PYkn_s9Q(PoFZxwP;! zuziv#XY#dD91kqMqv06AX~`u_)X4}_6dxvftQS{-%cgW+tM&QRsm!Iu@{zHjWv`YB ztN#-oDY&x$ek7f}Z}IVm_BaAY;}s{z)9Ue)De`5XP1wp;#=F{qR}Iv9kk~rgS<4|$La zYS)C2-RdRFiWy~^D^Oe)Lq*9t_YMr2^W20Xh-7acJiTJY_^2d$GsE2nZti*SXfJ=S z@0aQBKf24k`5`~%Db)$IdZmX>n^nZSqB5u3g_smd`}$Q#zBM*$@Ho|_b(uq6a89C zw}Hpvbu>Fxn*HfKrApTGC3fL7R{P(?_NPTuQzj%gXugOg8|u&U?XX6_7@L+lkyG_r zzhPxuI!M{n4SAv%QF*sLSaN*`i20%I zy*P#nyU*M!)gOeVe{%ytK$dh)xu#KqaqGs#NKm}y*y}oIb;7MxRo}38v!1{VYU+y} zztT&_Y{Jvw-nz(1>gH0#Y*63$dPF(Dun-uNhHqAW4B7ZR?FX%Ti;O`Fka!F-;HHy} zI&DzMx!Kibc5ZCJLMx{uOBhl<1s+{z>ut|p@26O?kQ=Dui~bBM4{p<5#+B3ysljto zE9_ZiCkOhu8JAg`T51A}nP*?FDTbsrLnK@Iq(48z2~U;q4Aj`MOS$ODKRwj%Zf@al zyrRue)n{Fko!hIsBP(t9>XXo*rPtVe7fT6=0Tib~qRD|o_~W}gdbJ1%@c~t7>s}3) zgz~YWuB-*Y!U^T+(*Ug57d&MrU#6n^8D?vv?JAxveHsg!^clm^O}iVf+0|k2Ul(sP z)r*Ak*5zK=n~+oG6#)E0IQ@vCSS|h2l-{v`wfusu(&f>8gi1)p94vUAJ`oghN`&F2 z==Kpewd)W%vbvKFR7#r47y4%X57Pz2>PQa~BZ$e7b5V9^E33R_r3;JmU+6ZT39^N| zjDB`sabc_XlB>+qf|Pw45riQM8^lWG4Oi>+Z-!U1ALB@$SPFg3ZoH8w8&5iC%>g2i76}wovkSX~lZ`S%iOSi+h z*a)A|yBAl8g{Fj-fcqg!COQ+M^cgAF2_IKsWEgZyk(0D9yM*j^$38wd7cXX~4KBLm z9&~wYcaRKM_KRm;EPZ19(R8*+wdtWSqp^N%%U?4F-Q{B~^Ci#8+ zN>?|#@oeG;9iizapPnb|KFgS!`Yg+9TI_4-(wX58mwhX47L8^Ficbf3xW5j3XrM5G zg-@PL$?g|tYdym<9%-8pM>em89GdM`D6?(|EPQ_xqzi4>*i!z1y5Y78RAV!Hy|n#+ zhx8Jxa-l|{2cOba%!r`9HmJnLoTIlQ-qP&0xLRDG>Rrd8xF81Z{l?;A?breE1Wp?< zgdt1%*HgOGH|ACErA*M~Y#d_in|~je8I2sYYNu}DG=^IdN~pUq&si>aiRRH~Y?jSF zybO%J2()JXkg^OOd};}5@F6b`D(_s`IX7HGxcQ}f$VA!zgRXjjjret5KDuwgIzX|? zk-z!d-%Qv@N!ELyby9oUFS?R;FKuKVgsQ2TrRFMi;?=d7xq8N;yS!vLs@}z3ua_OS z_`=<1o#Lo^uO@$2=5HV`SrfR+&+CnReUy7A*&!-$sf;>QvcSS7!oJ-ZFB&LR*zYy+ z=(P{{26Lh_mlNEJJM=tiDJ@1L9mT$Hz|jqZmhLG&bej*WyegZ)jNYMX`Wsf*0wthn;sM|W$<&wk*zG<;CKC2n>bHLVo&6}~Nm#>Blw@E*&O`%ixG!Dm zVyEv6dbH}QfDu)*?;)NsflIHy`+V*yEqRI2deR5oXHt7mF=7W(A3)CHa=;f_pHz~Z zPo*J|*-Uk%$+ag;y0Gy~omp%AEAbai?s=nRT)5U+>cQ8gP>a*v*T4-So(E@cyekH$ zOal|Tz4zGFdG=`5xqg2xMvlJ1x+dY~ZrCdDdhS4foE{Y@|6V1-RQI-H4@M<7v8QFB zE*#%*{7EQsFzPkZ0t)pYj6s|X8LM8$>_Wd#*6pwc0U1yQ`5=!1pTm|;+?+>ihOu-@B**kAaxdE;%_RBLpPNnb9#9Tn*DlXBIi+X%gi}#WsL*COhT{Ed+Mx3jX zx*t-DS|Z=Fe@0Q9rw3WdQd>TH`3~k4d({K`d`a0$RzNR#YxGK>%UNhv4#IwvG9aPb zpmBHC*e%Gn;@!EGpr~q>b+FzX5!ZC?pgrB z8VYyL4`UUVrj1N1CV5bt+a0&026#>0HgNl#n@LhWkYM)yPoF_Ek-)hfj|R<(UtsV* zTpF@lg5dmE?qUT_a^iGaVha2}N zhMA1V8HAG^MU*=$Y>f~u}7wM7s|o>|rSl4W!&03fO?dDd7V z%z78EkmPrg?Ntrr{oBpZ;us@Vg9Be5X%|S0+C|A4|AV z*j(e(zV)A3u%^?q@A6v)fV}p;_~EdJ25%YfgzMj*}LNmbbUf2uEE5 z^QB{j6D&X_=gfV$97pqDhJ-5YTZTdrqyXxf8g(jA1D zf0gA=)H$zANL0r*`&?Y4;@*vEx24ax#=Tk1o!y5UaAj!eEw7~aJ7BKmLBa8dQWg02 zgUJ`uHYH*a&ku=4fbEffF?J~&+T=Lq^{BAL2*hu=@z$c@UkdWyYoyS)hI?)_M2*UL z9)9@;;^jWQv=}a`ipS!CJs>4>>P}aNUx}Hb%%egbR)XVidi|%l@ zE59U=LQa=ip~VL=+U3-5 z5}7uYWy=>0J=TX@3@p+HWnrpvu=XlzyK+);z(Hqs_M&BIu3`ue!yEo4yu}UET zaW$hU#IRz8Kcj8J818cq0gew*7&NuH&R8^VpGs0ujm1Yx0e^O@VqE%`rKuG^Sk^J6 zyKS%i5X;6G8=a0*eSL1(Lc_IbN3PAk5!|uBXM#H46UoP$-64q`QsAq>8lWaJxz&nh zreaCGH=p~Z$s$Y4ZnMlOyqAZSi~Wk59l4-E1JxgGQC+oVvomfuPt&hmhZ{|Br#I0b zZQXluOF@ftlQuOe8MGkC8Y+$l^+)Lw<*`%UgOlKBR%xg8He~dX#;ml8$XS4nSfD#i zl$Lz3RgF;jj=4Ijz~vFf{+bTYSt1-eTT6(R;kwoy-E{7mVrncsLWr6zk*HvFjlZD;+VVQ~iX~lCW6z znaX&XHV9vCGH&(0@|5_oH{r;s6)Qq^K(L>Co!+#ai4w~WHHvfi6c`g)2CC1`Wqno= z?4%s`!edOC1%eZi!-~=HDUO~kt-Rqdn6_zA-iOVh3ivXyzb!x4(SKB>nDp*Xlp{v& zOQhr-8#~*!|7ikTSrC*-`+52@Pn|@mIsZ_2FawGUSVxhlec=u<-ZjFa*4`q0xRTcR z`M(jDPI_G_FHTVPnj>c8RZw$&8X-avB6zsU%P5Z@WqyU@DRVBBBS*;D6Z1Zrxq{5&%B&0=cw8WivE2RIH3ihl1t)Di%RPA`Agydxe}pi#U*c)Q z`NgCV?X8@D=zObteCVJ+8bJkAs8#8fMm`vS7o1VnF?bi^b6ttxu|1-uI54+8XyQ+h zt)IkOc(nHVM{X zzPH){kS5JphP5$is>44(kIU}k69JAiNpk+0L-x$#Bkp0Vv4f}`t@z@>*HJefjieWz zTA8ncRpyW!jTxJ+RY?pq^ZcnB5}xDOQ?R$itJGIm(|+EIPs!q2tyq;$ z;r=W#_3=xON8B1!EED`BdJzH@b#6r0bmqX@E=qvuUZ=8^G&T9ogTuD_7IJv;xeHI2 z0qzs3^ahfLh@FzPUea4Io%aQ!{etSnS(#hvf#Y9Vy5$(xnGYJMKF$*ox}ePGuej@=?Qsq8>79v}|Iv6st%yF4s{J=_5cAb^26qU;Ha0 zdDf#VJIWQGtN3~o-SvR!@(Vxwp{p>@?^sokq-RisyCHoSAgJ8zj}0K}r(`>oY^etQ zmerQcLD#+*sR8s7$G^XKep#udN^y|z zjmwE44m%)#Dsp=J*`BBx1Axafmrlky6*krAwzIruw66JS9AmL$*VIQ1yXRM|OdRE< zZ&o3PpD&IM@Tt8qV=j4Og{R*1T+)H!;me5-wKq<-gyjmnzx-@P>|!A}EslixjIat=w5yTy zrW?J5=u8M-NnxgJ@tzk6rA1SD z{ZW2u!U(K66~u787(ua==ZKgU95Yy++J|1OBK+C+9uYhaYB}mv;`XslHplcuxJCfj zV*dP+>rgCfQv+EhKvW#mdpK$8l@1o2H+36Id*#&liMvW$X>1Q{VJf6QwE+ulPrY$w zX&DP$p6S3crN7=Cl)8vRFZyxNXVVJ2t#bsHKXf<^;bPe*wEgBd?M?Im?18`4U*5ax zK(H+j5?57ri2WNeK-X~{y%x!fyzH-I=k0GCvpB#z!z79B4D{ZT5T zY2B1c3Y59PC)ndftDEvA5>7c5P~+d?VW?hA|C#7z2Wg)tJb?HtHu0|U8K+EQiP9_$ zK*Y4bm%n9-)-%shXbV5XJAV@g_!IF(hi}#=(Q|UU&fXk*EGk64ge)DLJ_|~(i0%A< zAdyBF9EjS$%>3G%TvM?&?nE`K4J<;BgNid|@O(uBR*1$cZ=U!4pX$sr$+1~JDr2{F zs(b|;_rn$|Ak)INjJ;gLV=Y@+Nx3J+YWKvjaBq~7@$+VTJVV>@Y?M|^2&dxa)`2{gCa(?`R!J z$S1!2HUOlyQp4=gfCPz>XLG*$Vi~mPs!IYggfsF-P8E)3xQ~2)%p2`i@%80Ldb=?N zCZg1;beccWt=yoyy7Lr>tu+K4sBn4DMk6Hp!o_h6%8FSzX@vltcm#Pe-&j-SdbzL? zo97+Y4cxnSFZm-cwW@=G`D`Vt74thS5r>fpD^O;<--X*DD#b9e@Ki1(q}vJg7%eky zpUFzy;|_29ULb(mfHMUFe@e+g*!(BnJ}p!#3_mQe&+Jekkac2ksHwZfq1-#)CyCgl zmgq{c2#04(&>lhX)s|MJzOQq)4x@{sjKFaf^h&t5D-p(=@zcPk(Uxvmls|XdA2AZ! z8!SJY0&?&-y~}$6T8DfnF?uQ4??O~3l)1xLRWsU9i3viiFEI-XL85ra^%r zC+iPloP3DhLsLCwY9Jj4eAo7dXj#cVrHLo*?Z-3kUq>i z^}=@gtYjp+QeAKF&UBquy5J@SO#p9&s+R5zOX#8|`J!D9-5q*6h2!nQV6D(Y%=*sLv372|=s@!SD}Wr=(&0owp%%=c->fFtc`DX&z# z3jt&XR@}QiS8cR;=Vh3Sb$Q6%R=n+wRwmYSPT2Csjls=Jk9;fkdOqEDE2u~Pg6|)n zxZXIXRGoC<;*99IVl5S{ctNhyL@hG!S?%}^SZmoSR({Sx z);ipJ_tgUUHmL`)+aI__oP@Q*?*Ad`FaZsNR*=GsT^bbTqMRqvXbM;2BGR4f7mK6k z_9ijN2~m13a#8b|>f%L%11Yo6znhitI>#&1(5VVyaRRwN^A`fh2FtQYvQ<%M# zs<0WOho{&*bk1>Dv2p?!b>_eTs<}CuIr3s9^ZB{N5g*>b}*#%C}e@qO=SeEWG}dNJenY#g%Uk)0bC$EZm& zCC$$XveHwmwiBF{EQn_Akj9+nHyn3!A$HEq%!#&JTUlCVp?vq_<;CL(Z=Mw|q@m&r z)CAjVZ)JHU{WzhEFPB;R@s2~KzLgh~7skG!Bqko-31605QI2~Y?d9=Q7^585va&FF zj#-udVx^yG2AzOKM>k`YX7(_|IOsRu3o|Fe(6MUvVJaaBGuR#P_wYi3{AY*yi>X1! zO+Flsv)Sytl){a_5CiqXMzT?g64zo9%^~MqH!k{jTL&CzWVNtTm_~W^3sAp?U>rI( z_8opN=S9_^re@aLIUeDltLK3K|9Tw#1`)lrLGAv%d z*8sjn`(W=NoP&Ne%OE;;;q=+P>*l1X9%I8#vq3w46!u&qB;JW`Eeh1QUwV%xi!V`) zN5I0tsdl2{??G9VBj-29NV>)pUsYGOeG9VCRpxYkYR_5TucAC5aIeP0x)bvkuFx8l zO+}h=2I8=K9#DI;nL*(Etod9&{}yJhzoA1Attm@1*s2jEHFbo)`X*2HaKb5mz1vliIBKW z0sLdhqy)PZP2bWlEG9}?+myJRZIYH_d_M8V*DDyxzNaFM79e`oQId zSG>^75<>0WwvO0f83`iAU{RVfK)!W7T_#Xy7^CEUm+`oAF@etggD-fWnyGF2(VA2* zh1cS1SOUI!OuSLJl!D;5So+R%{q{jX?d4L;1<3r}mHH!6m(4Ba&NJvE#gV3j$vgeL zuWCIb8tUre79y1dNH3I&h-xZv-In1Pq1SUIQ$Plu)hmTFJ{91ukH&hRiKUDc+Ph~( z%*M>3k4(8dmiMr#%|CN^T^v@V`>jGEg&#`P3#z%F&*oxoq*qkSx69VeCE9)Lwm%;O zty4le{`*DNP-jmxTE_^bU4M5?aV0Re`s>t64n*2ezufI(7+UDT1e>|GtpxgG?(tZX8 z1^N9>_|Ll(^);9uOP13%DuE)q^H}BE$0G|YE*OE!JQNv2u}UYbI@b^zcp(NXS!8kKls6hSk>mSlsJWOC)gn(y4x1>aHeTa>8c=F08w@;~?K?!#ee zYkhlsd2C6KR_aGh7jI?+uMfI=Yb&BpqVhFc5T)BT&tN~Fwi%uZ(zzOEYGu36%*zQ~ zNVR}=EM_0m{AY;`T+_)keaffGv9Rs0@jA30zp@JA5hVJ%;3 zRaNSoVTeqn0RL1IlV+JJDfCq_*Ms&faGCd%$*@-Nl_Jwior?uTA*ac2pL|>(u7W>x zLdqLw(c4%dr#$sH_OqUsUKX~uILxT*|JrEyN*3ZXdsEj1oi~7E zT%)8ugz(}R>K&@~Y)6V;w2@hlJ?YSDrcmpdPTbrjr%DQUBS=JI>J_>wQ^OIjAN@AN zJNKV@$~~-=V|w81b1`q(gE@VtOO7g!3S~|%WWX$UOkW=k3R+n%KoZkm;YZEvKuvAt zLZD{p%GDb1^KJ1yHccUpE!8t1%sdxQ1HBWo3rmcx#ZMphSzW?HEM z!Zd&WWWs4oP8H$lxwaO(J3JMFiC2>65V;UU z6S;SBMa^^e?8k>mc?odLiJVV=vPO*=;aIjnzcM4(mz^xOI2ebl70^*kBFYZFvk`Fa zvbC*yEkm_ITE6Z$F}He`N@E_J*>L>1P5(!IjoKsELtwFj)=S%7GD-4x&@f>^22a31 zu(DTF=&V$Qa#@0nprXz8g@a+}-4-3FV?TKR6m%VzpS6BA2jUIadOO%UD-w5B(t_~; zwIcu}GNPY_>dvzLh^(y^kA4%ZGTV`5*LGrY&0RjFd$!Iz?tFf7=}ENOJFe=xDxVU< z?^-7q#wQb)x4YcG*zPV-k&*`Lub6N>?}t62}9%t|?33}KvBWBO=>p>1qmdDeYZ;Gna&Vb;#VfBY#T zLFb*Y1`sT{^a?= zU49AiRdOOun$vG3W0$&aU9H$@;Tai&IfS%4Obpi3rq zHFXE-4woolJHy*`G1m&8@6$+|5$dz(W}^MD5xz%0%Fdd_kbN_xf0~~SxFvyflIxh= zGD1wWHrT8|;{39cISgU%8@IS?ik6dtJ5(aWeMp?_;xr4p8syh1xQnfl79y@Z67$1X%bFxyyGlxOU(73HFvDkj?8Gfj>P9~-kY|J^Vi}?EUAO@9Lj6oj^h%aogz#8r%h%LDmi-6s z>X<{4KZ$w?x9*LH`8Dj5wyO!vL#%vjQRE+stv~#L4h%1~Np_IvtwjnqG)?;BcSby% z3nylLxxS21s9e=|`_sHfMgXYJ4=8l3W36_nt2nT&NJlQj%h3lLtqa3yavV)kHSr94 zkI%`vU%fBL*nLsi4wj}zjd61Yi_1{Tn|oiY#S<*eXa|v&Vhnz()hgR7TlT;tPL7f> z9jG$xyV{jPC2(@HxOec_G;lwr$BmU(8;a(|Z{QfFgM!U<8*ZXsEt@%%1lZ?KFG6ZM zX*U(e*$C?me!A#E3XdCCa)^z8i>y_G6iG#5R~Bsh!Ej4oEfR$dD`Rhb zsq(nEsOqe~yc&s-Uf48FMPg3O`OXec4mq;XfIH})rWB%@S zj*=!Q|AR`SH?i8w!4X`86iQ11$am&0frT^ts9sBu?~>UavPVF!Fe01`>z$|9M>rPP zn&at9-RC5Y+tZD6ZJs`6Y7jc50+5!;IUTmc^l!y%GyKaDl6nm=WoKas))zM5zH%6Y zzN0-Dq6uN-wYP{ZdDtqS`>CO6`L2CGcuxmCC5+-d_evU1%bqqMJA47ew~Z3MVVEn; z8Y3tHy=;j2t9BWuhK|Q#y%&!Y%-57evgo%0Q5CDx``BuVYvR=I{qWY!hsQwltmCjB zd@%z_+KcMF=iXZqT-4>|=$Jl7J%=HN88hD-=ahFJ;e?>e5S=M;Mt$Y42i?Z^BqKiE z1MrE}xx`-ttU4-Sagg<=#_c#tG!`1^+lap|%EQtP$i*DM`dyU{#U*6ZWRIW#+( zQ;x$EC;tz{2#cufkQ;W$g?TIC2M6a)CD)|9=KsW?6HRj6lXMBm?`W%f05n<<9J;6- z+&_ab!93+YG7x#@64@@o@zXW^va0JyL_$@#K^3H{qCDG0_`Fe3;B@E-gRbIjo(F;t zrmAg?x(Q_@^R~=-tf8GpGa5*NFpIxP^koeLRSH|A|FFpX zE+D(QQ{WX#ofVHwQgtvV>aYV6gqH}9A!~!=E4iMwij57VoQGOjdessowB(s0qva1J zx5q4|xu5Moo7;3lD!=&93y{WrrYtwML#LQ($}lifs{dVA%GRJbP|j!ivz#zS6{q1% zaclPBg?0#htd>2gL5HC1laSnu1$V9DtACeV-5DDDaM&Xb-7<#l>T>Ji96mOF8?=p54cNI4$;1L>rn zglKbSM?roKCkC2?MF$pMWm{Vxj*|HbNHa+mHJ;}6qPXw#(2>cY`}tI-&uq0W#%3ayUd+QZViZ<)S7J-o_#&FPF&#J1cJi9np{g|l>2G_j2X*a{u0}T^{q=ykD)IdOO|KJ3tCY5%(0b$Sq$Ud+8U8s9`cbURY(Pdd4Bw1u;9|w{R7h)A!|RTiV|5nR4N=G zBe!(xYp}yw)ZKaZ7Kf3ff^4~uV#03}wlC)e*p0|`h5ZmB1^r|p%#Ma`hM zJ_ZNZk5vZ2MP-;d6SuhjV5Ri01OI9!9?Geon9GS|_hcQ)DQ(w)Xu0*eAb8(ahYEQ} zDY2A`RFrQpudIv8*i~{}znCo6n|RFU`b==h3e{i}z3BWh_Z&IG5N~Q?eVOu`d#ndI z>-NpiPutnxiJm=Qgj+ieW1vs&=a0clB#Ec-UCMj#b}+4xW0{8QUW`cr@1>6yxv+Pp z6b@ChDaE!L12IMQL}RNrarJdR-;>|ojhxy_%*z2<@wFED!p;MSK47tK6!U48RhqyZ zV3WelDaMzm^KL)`tiu(N#w*aLS?&wL)7F>1=XlTtXI=^_DNgcRJXs_Eo#9$QY7XNO zH&|qp25!y*;E?IVkqbTwB%VB)_n0tYX?lNz+hpEV=FK5FEH=BAn&ckw z>M(6v@DfTyAYpoWg3h(lRPy2k{!Eem>KX$S#2f`Xw??Bc+l6-AI)eyS8v;jrXVGKJ zmOVN42+{tT-mElkd}Us&{zEyOv^s3AY;1V~i)G-W=P&MVan@P8(su5D4mLZ@r;a}h z<$X8*K$^WyKh)rvgGdV($_YLf-5@bZau=Z<;9~Ub%;E z@FbscI2OHr-`NcMbBp_-Y*=3!3WZ0!?Dx!qx}NdBu3yGu#_S`)-+8XL!r{QMTRylaz@EPDB@te;{v|Qe$C;3}TLbRE z&h_|Dp7zwIzq!iDr#SM0oHx}^G&oVQXr0Fak5L8e59sjy8HzgmbnaS+>q#wW%voMf z%hCP#;S1`b;gH}sv=8OeotL5FE~b1y48#Md4w(gSLyXURcgt@?9r?pOQ#}(q1ir5E zYJq6Y%fJfUjJp4wy*YYv@bQ>sV?2$nUmuc$o*%a1-^Kq!>yXDc<3KqO%IVWxoE!68 zn0Q=9Q@&{CsI6LR`bL;3IN}GRNmu5lUp-M)r4Z6*>Ol%U!TV=j?|yK%ZW)QPMZ-ASjuDuyZFhXsk&2dI)s9pQlSLiAR`JmLbrFggq~j zzB5LFhON}0n6Ce~PQ?P93JiBtW!vFoo{Nb>Z|ykCE1GU?4c`wD(l?4{D5J(sC)R0r zhn$|PG4Wqi2O7&d$umhaZ)d?_ikp?Cj$6$zz-$1abg?3nOcr@A(* ztBz0SegC^Y=m*C-L{K=#Np%f_O;$6zXxaK+)oSl{iGe_0a?mNk(pWnWPN7vc0* zr?1#e6dazDYTGY<;=N_}Kyb$4xodOB+ILIdes|mJ;kfF=yoK{gXfNt%Zn`aFV`5F6 z^aM_bVnB@+qUf{;Y_ggw^H^&ghFD375&VV`)>6VH@m)_xD@Xs3Uwl>-&gZK3!Blo= z9M!qY8N{kHSU&%8g5A8!h#l9M6H<9YcGBbM9iA2!7vGef^o|ud(VB8db%I`3LN}&L z&}asyT-G_~Jerq*cYfIYGkbmD;y9x)vz;@gyx8#K$w!d)O2xFuYq~y+XNc{u1MaB& zk*cR1+Q%^K3Uq4lNz|%Yy-^T<)0$D zW>*SrC0UdF(8sw$NI5*pb3A{Bw!GNV;60mpk0w|0YGozVSRJ3~@P*L2ojcp%IQo59 z zjuJ+jj(U{+h7H@^UAcHpAK!eYLHW5*SEhImX0C_o3-Oj#VJ^|)d?P@dVBtZiXQ>@u zs@fg1oT|mU*Ox6AOZAc2;}Ni@Gmm+p;f85O26iED*84HfL4#JE_TC}3(!@C7Yy@aa z&JA&x$H`w&#S4S?Mgnt#swGCZmiE0(Z_} zpb{Dj@npq3Zte)cbP?0X9(7MOHh`1van-yiVV4K=rNhY;gkfK*6NU_1-W|Pk3q7$& zMuc{+({>T5bqmV8i*qljQh7$VU@^V0dAnS9W6B+fb0CPR9b4|CDU|n${uKh9SpJ0O zoS2eoI+tedZ#T!&vWQ=-y$v%?IZeoGpbE&IBu{&SbXk80taw|R^V&(l&9?yKulHed zJliAWj5mp~5y)gxU^=XXYi|+YUQKSX0lF)I|Hnu>UFf`GqE*dZISHe@J>T8=^5$|~ zkE^`BAikHD_v4wy-V1Z*BrW@9hCT~fFpjC2jtT8(^7-d>p0@3(t69%~p^wclf6W`5#oSLL>d%!YN25c~|-4y^y`dC3;V zJ)>{H%fGAxTfWyNfV3PhR_d9ofW%X*Q<0kb@6|NIodiKns^B^oEZA<&sjdd|iE5bbYk@1o<9it~kuGXsWW=?a*yf`2MpeDg#2L12Du` z!MXyMO^eB4QA784)1*|O7*e{4rLg6Th5TO);(v1VE4YfKMnU19X8AUkMIOxFj`9!# zL1atnisyuulI!T@5asF1)TU|gQ5QyLm{8*26NHI}m4ESQ#oIOwt;_4KhWVGgc#5t8 zfzcW-@Wy!-GnY+C;hVU3ym)7nD&Je=F?BdmOFxP?LKACMAcYAJU&loA0$>qZ2r%n^ z0LiyFuGXzA(HauOqrFb6EKPp4odZ)ZUK)Ue$sPn|p%b^)bwWD~NpkI=PMNn1MgDF< z_S5<61dFg?ocv0GZDB<2TxQYLQYEA@NA^T9hU+5qi0}xeXSInAYa}tyza~1hr0E|mInL)7v)p+*S}O#~uqj{` zFE-bMW#fj5>r}ljbPj#B$CP?ge4Wacwt_%Gf_H%CKV5*r-8N0zJkLr=dk2C zf#03e)^G>>BWo7VNsG5<|9kL87C7Um&H4lKZ}yftfQjAqWY$Lg{?ob#BLMvQbt+sn zroSi;M*^ejFcICkj#A+}`S#zot-|1E<25QOrS9bHm&Ow!)5> zZY)RQ_+NtsZFT7QaCkWYpeVfFh;bhiOk}Qj_J)lcUAMV=YW(+oN59ze^D7ei-*{m& zpY9DruTVAd+A+`;((UR0lu`J078^&O-&p6^|DH|hL)Pw3-thUqxm@Z1x(D61jIMq5 z`;B!EV&M9}=*d6!{|^aUgVu~tfyG;)|4G`v_OsvY|MeinYGcsZA)dLK&0EU_+-9I& z;zb*M|A%IGf{;%`CG^$NHEOYj4o%PsANqZ}l=6T7TMXT0>{ehfVhWa@}R!UX|+Sj?vv(i0dM|?@^BW2fvzN7!N!pP{%|W;6~vp)eEs{y(&2Gptk_pgnh;Ub#o z+Kv8c=>AP!Oeh$8Z$!XO7UuM~uSe7To?|u`JG Date: Fri, 6 Sep 2024 14:23:45 +0900 Subject: [PATCH 141/217] perf(autoware_map_based_prediction): replace pow (#8751) --- .../src/path_generator.cpp | 40 +++++++++++-------- 1 file changed, 24 insertions(+), 16 deletions(-) diff --git a/perception/autoware_map_based_prediction/src/path_generator.cpp b/perception/autoware_map_based_prediction/src/path_generator.cpp index 0d8b7c6f6cd20..4b759e22cdb4f 100644 --- a/perception/autoware_map_based_prediction/src/path_generator.cpp +++ b/perception/autoware_map_based_prediction/src/path_generator.cpp @@ -260,16 +260,18 @@ FrenetPath PathGenerator::generateFrenetPath( path.reserve(static_cast(duration / sampling_time_interval_)); for (double t = 0.0; t <= duration; t += sampling_time_interval_) { + const auto t2 = t * t; + const auto t3 = t2 * t; + const auto t4 = t3 * t; + const auto t5 = t4 * t; const double current_acc = 0.0; // Currently we assume the object is traveling at a constant speed - const double d_next_ = current_point.d + current_point.d_vel * t + - current_acc * 2.0 * std::pow(t, 2) + lat_coeff(0) * std::pow(t, 3) + - lat_coeff(1) * std::pow(t, 4) + lat_coeff(2) * std::pow(t, 5); + const double d_next_ = current_point.d + current_point.d_vel * t + current_acc * 2.0 * t2 + + lat_coeff(0) * t3 + lat_coeff(1) * t4 + lat_coeff(2) * t5; // t > lateral_duration: 0.0, else d_next_ const double d_next = t > lateral_duration ? 0.0 : d_next_; - const double s_next = current_point.s + current_point.s_vel * t + - 2.0 * current_acc * std::pow(t, 2) + lon_coeff(0) * std::pow(t, 3) + - lon_coeff(1) * std::pow(t, 4); + const double s_next = current_point.s + current_point.s_vel * t + 2.0 * current_acc * t2 + + lon_coeff(0) * t3 + lon_coeff(1) * t4; if (s_next > max_length) { break; } @@ -302,10 +304,14 @@ Eigen::Vector3d PathGenerator::calcLatCoefficients( // b = np.matrix([[xe - self.a0 - self.a1 * T - self.a2 * T**2], // [vxe - self.a1 - 2 * self.a2 * T], // [axe - 2 * self.a2]]) + const auto T2 = T * T; + const auto T3 = T2 * T; + const auto T4 = T3 * T; + const auto T5 = T4 * T; + Eigen::Matrix3d A_lat_inv; - A_lat_inv << 10 / std::pow(T, 3), -4 / std::pow(T, 2), 1 / (2 * T), -15 / std::pow(T, 4), - 7 / std::pow(T, 3), -1 / std::pow(T, 2), 6 / std::pow(T, 5), -3 / std::pow(T, 4), - 1 / (2 * std::pow(T, 3)); + A_lat_inv << 10 / T3, -4 / T2, 1 / (2 * T), -15 / T4, 7 / T3, -1 / T2, 6 / T5, -3 / T4, + 1 / (2 * T3); Eigen::Vector3d b_lat; b_lat[0] = target_point.d - current_point.d - current_point.d_vel * T; b_lat[1] = target_point.d_vel - current_point.d_vel; @@ -323,9 +329,11 @@ Eigen::Vector2d PathGenerator::calcLonCoefficients( // [-1/(2*T**3), 1/(4*T**2)]]) // b = np.matrix([[vxe - self.a1 - 2 * self.a2 * T], // [axe - 2 * self.a2]]) + const auto T2 = T * T; + const auto T3 = T2 * T; + Eigen::Matrix2d A_lon_inv; - A_lon_inv << 1 / std::pow(T, 2), -1 / (3 * T), -1 / (2 * std::pow(T, 3)), - 1 / (4 * std::pow(T, 2)); + A_lon_inv << 1 / T2, -1 / (3 * T), -1 / (2 * T3), 1 / (4 * T2); Eigen::Vector2d b_lon; b_lon[0] = target_point.s_vel - current_point.s_vel; b_lon[1] = 0.0; @@ -474,6 +482,8 @@ FrenetPoint PathGenerator::getFrenetPoint( // Get velocity after time horizon const auto terminal_velocity = v + a * (1.0 / lambda) * (1 - std::exp(-lambda * t_h)); + const auto lambda_2 = lambda * lambda; + // If vehicle is decelerating, make sure its speed does not change signs (we assume it will, at // most stop, not reverse its direction) if (!have_same_sign(terminal_velocity, v)) { @@ -489,8 +499,7 @@ FrenetPoint PathGenerator::getFrenetPoint( // Calculate the distance traveled until stopping auto distance_to_reach_zero_speed = - v * t_stop + a * t_stop * (1.0 / lambda) + - a * (1.0 / std::pow(lambda, 2)) * std::expm1(-lambda * t_h); + v * t_stop + a * t_stop * (1.0 / lambda) + a * (1.0 / lambda_2) * std::expm1(-lambda * t_h); // Output an equivalent constant speed return distance_to_reach_zero_speed / t_h; } @@ -500,7 +509,7 @@ FrenetPoint PathGenerator::getFrenetPoint( // assume it will continue accelerating (reckless driving) const bool object_has_surpassed_limit_already = v > speed_limit; if (terminal_velocity < speed_limit || object_has_surpassed_limit_already) - return v + a * (1.0 / lambda) + (a / (t_h * std::pow(lambda, 2))) * std::expm1(-lambda * t_h); + return v + a * (1.0 / lambda) + (a / (t_h * lambda_2)) * std::expm1(-lambda * t_h); // It is assumed the vehicle accelerates until final_speed is reached and // then continues at constant speed for the rest of the time horizon @@ -510,8 +519,7 @@ FrenetPoint PathGenerator::getFrenetPoint( const double t_f = (-1.0 / lambda) * std::log(1 - ((speed_limit - v) * lambda) / a); const double distance_covered = // Distance covered while accelerating - a * (1.0 / lambda) * t_f + a * (1.0 / std::pow(lambda, 2)) * std::expm1(-lambda * t_f) + - v * t_f + + a * (1.0 / lambda) * t_f + a * (1.0 / lambda_2) * std::expm1(-lambda * t_f) + v * t_f + // Distance covered at constant speed for the rest of the horizon time speed_limit * (t_h - t_f); return distance_covered / t_h; From 5b71a33d622fcff2f94b393e656743f1c7186990 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 6 Sep 2024 14:41:34 +0900 Subject: [PATCH 142/217] fix(autoware_compare_map_segmentation): fix unusedFunction (#8725) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/voxel_grid_map_loader/voxel_grid_map_loader.hpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp index 1bcdff228f40b..4a044596b3dee 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp @@ -35,15 +35,6 @@ namespace autoware::compare_map_segmentation { -template -double distance3D(const T p1, const U p2) -{ - double dx = p1.x - p2.x; - double dy = p1.y - p2.y; - double dz = p1.z - p2.z; - return dx * dx + dy * dy + dz * dz; -} - template double distance2D(const T p1, const U p2) { From 67d9b8e91984fce16872d8f9af63c6134668b81f Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 6 Sep 2024 15:45:52 +0900 Subject: [PATCH 143/217] feat(autoware_mpc_lateral_controller): add predicted trajectory acconts for input delay (#8436) * feat: enable delayed initial state for predicted trajectory Signed-off-by: kyoichi-sugahara * feat: enable debug publishing of predicted and resampled reference trajectories Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../autoware_mpc_lateral_controller/README.md | 7 +++ .../autoware/mpc_lateral_controller/mpc.hpp | 12 ++++- .../lateral_controller_defaults.param.yaml | 3 +- .../src/mpc.cpp | 51 ++++++++++++------- .../src/mpc_lateral_controller.cpp | 4 +- .../param/lateral/mpc.param.yaml | 3 +- 6 files changed, 58 insertions(+), 22 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/README.md b/control/autoware_mpc_lateral_controller/README.md index 6c5064a4aafe8..1b3af44343208 100644 --- a/control/autoware_mpc_lateral_controller/README.md +++ b/control/autoware_mpc_lateral_controller/README.md @@ -95,6 +95,7 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving. | 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 | #### Path Smoothing @@ -202,6 +203,12 @@ Defined in the `steering_offset` namespace. This logic is designed as simple as | cf | double | front cornering power [N/rad] | 155494.663 | | cr | double | rear cornering power [N/rad] | 155494.663 | +#### Debug + +| Name | Type | Description | Default value | +| :------------------------- | :------ | :-------------------------------------------------------------------------------- | :------------ | +| publish_debug_trajectories | boolean | publish predicted trajectory and resampled reference trajectory for debug purpose | true | + ### How to tune MPC parameters #### Set kinematics information 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 058eb45bfaaff..36a79cc95728e 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 @@ -222,6 +222,7 @@ class MPC double m_min_prediction_length = 5.0; // Minimum prediction distance. rclcpp::Publisher::SharedPtr m_debug_frenet_predicted_trajectory_pub; + rclcpp::Publisher::SharedPtr m_debug_resampled_reference_trajectory_pub; /** * @brief Get variables for MPC calculation. * @param trajectory The reference trajectory. @@ -341,11 +342,14 @@ class MPC * @param Uex optimized input. * @param mpc_resampled_ref_traj reference trajectory resampled in the mpc time-step * @param dt delta time used in the mpc problem. + * @param coordinate String specifying the coordinate system ("world" or "frenet", default is + * "world") * @return predicted path */ Trajectory calculatePredictedTrajectory( const MPCMatrix & mpc_matrix, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, - const MPCTrajectory & mpc_resampled_ref_traj, const double dt) const; + const MPCTrajectory & reference_trajectory, const double dt, + const std::string & coordinate = "world") const; /** * @brief Check if the MPC matrix has any invalid values. @@ -426,7 +430,11 @@ class MPC double ego_nearest_dist_threshold = 3.0; // Threshold for nearest index search based on distance. double ego_nearest_yaw_threshold = M_PI_2; // Threshold for nearest index search based on yaw. - bool m_debug_publish_predicted_trajectory = false; // Flag to publish debug predicted trajectory + bool m_use_delayed_initial_state = + true; // Flag to use x0_delayed as initial state for predicted trajectory + + bool m_publish_debug_trajectories = false; // Flag to publish predicted trajectory and + // resampled reference trajectory for debug purpose //!< Constructor. explicit MPC(rclcpp::Node & node); 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 c0382ca2ccb6b..de194a8902a7d 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 @@ -5,6 +5,7 @@ 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 -- enable_path_smoothing: false # flag for path smoothing @@ -84,4 +85,4 @@ cf: 155494.663 cr: 155494.663 - debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate + publish_debug_trajectories: true # flag to publish predicted trajectory and resampled reference trajectory for debug purpose diff --git a/control/autoware_mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp index 1682f4ddc56c7..b5cd0e7ba3e2a 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -33,6 +33,8 @@ MPC::MPC(rclcpp::Node & node) { m_debug_frenet_predicted_trajectory_pub = node.create_publisher( "~/debug/predicted_trajectory_in_frenet_coordinate", rclcpp::QoS(1)); + m_debug_resampled_reference_trajectory_pub = + node.create_publisher("~/debug/resampled_reference_trajectory", rclcpp::QoS(1)); } bool MPC::calculateMPC( @@ -104,8 +106,19 @@ bool MPC::calculateMPC( m_raw_steer_cmd_prev = Uex(0); /* calculate predicted trajectory */ - predicted_trajectory = - calculatePredictedTrajectory(mpc_matrix, x0, Uex, mpc_resampled_ref_trajectory, prediction_dt); + Eigen::VectorXd initial_state = m_use_delayed_initial_state ? x0_delayed : x0; + predicted_trajectory = calculatePredictedTrajectory( + mpc_matrix, initial_state, Uex, mpc_resampled_ref_trajectory, prediction_dt, "world"); + + // Publish predicted trajectories in different coordinates for debugging purposes + if (m_publish_debug_trajectories) { + // Calculate and publish predicted trajectory in Frenet coordinate + auto predicted_trajectory_frenet = calculatePredictedTrajectory( + mpc_matrix, initial_state, Uex, mpc_resampled_ref_trajectory, prediction_dt, "frenet"); + predicted_trajectory_frenet.header.stamp = m_clock->now(); + predicted_trajectory_frenet.header.frame_id = "map"; + m_debug_frenet_predicted_trajectory_pub->publish(predicted_trajectory_frenet); + } // prepare diagnostic message diagnostic = @@ -310,6 +323,13 @@ std::pair MPC::resampleMPCTrajectoryByTime( warn_throttle("calculateMPC: mpc resample error. stop mpc calculation. check code!"); return {false, {}}; } + // Publish resampled reference trajectory for debug purpose. + if (m_publish_debug_trajectories) { + auto converted_output = MPCUtils::convertToAutowareTrajectory(output); + converted_output.header.stamp = m_clock->now(); + converted_output.header.frame_id = "map"; + m_debug_resampled_reference_trajectory_pub->publish(converted_output); + } return {true, output}; } @@ -785,12 +805,21 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory( Trajectory MPC::calculatePredictedTrajectory( const MPCMatrix & mpc_matrix, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, - const MPCTrajectory & reference_trajectory, const double dt) const + const MPCTrajectory & reference_trajectory, const double dt, const std::string & coordinate) const { - const auto predicted_mpc_trajectory = - m_vehicle_model_ptr->calculatePredictedTrajectoryInWorldCoordinate( + MPCTrajectory predicted_mpc_trajectory; + + if (coordinate == "world") { + predicted_mpc_trajectory = m_vehicle_model_ptr->calculatePredictedTrajectoryInWorldCoordinate( + mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory, + dt); + } else if (coordinate == "frenet") { + predicted_mpc_trajectory = m_vehicle_model_ptr->calculatePredictedTrajectoryInFrenetCoordinate( mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory, dt); + } else { + throw std::invalid_argument("Invalid coordinate system specified. Use 'world' or 'frenet'."); + } // do not over the reference trajectory const auto predicted_length = MPCUtils::calcMPCTrajectoryArcLength(reference_trajectory); @@ -799,18 +828,6 @@ Trajectory MPC::calculatePredictedTrajectory( const auto predicted_trajectory = MPCUtils::convertToAutowareTrajectory(clipped_trajectory); - // Publish trajectory in relative coordinate for debug purpose. - if (m_debug_publish_predicted_trajectory) { - const auto frenet = m_vehicle_model_ptr->calculatePredictedTrajectoryInFrenetCoordinate( - mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory, - dt); - auto frenet_clipped = MPCUtils::convertToAutowareTrajectory( - MPCUtils::clipTrajectoryByLength(frenet, predicted_length)); - frenet_clipped.header.stamp = m_clock->now(); - frenet_clipped.header.frame_id = "map"; - m_debug_frenet_predicted_trajectory_pub->publish(frenet_clipped); - } - return predicted_trajectory; } 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 0eef731bacd18..4ff7f329e5498 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -137,7 +137,9 @@ MpcLateralController::MpcLateralController( m_mpc->ego_nearest_dist_threshold = m_ego_nearest_dist_threshold; m_mpc->ego_nearest_yaw_threshold = m_ego_nearest_yaw_threshold; - m_mpc->m_debug_publish_predicted_trajectory = dp_bool("debug_publish_predicted_trajectory"); + m_mpc->m_use_delayed_initial_state = dp_bool("use_delayed_initial_state"); + + m_mpc->m_publish_debug_trajectories = dp_bool("publish_debug_trajectories"); m_pub_predicted_traj = node.create_publisher("~/output/predicted_trajectory", 1); m_pub_debug_values = 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 9998b6aadf656..166bd9f1e8ad8 100644 --- a/control/autoware_trajectory_follower_node/param/lateral/mpc.param.yaml +++ b/control/autoware_trajectory_follower_node/param/lateral/mpc.param.yaml @@ -5,6 +5,7 @@ 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 -- enable_path_smoothing: false # flag for path smoothing @@ -75,4 +76,4 @@ average_num: 1000 steering_offset_limit: 0.02 - debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate + publish_debug_trajectories: true # flag to publish predicted trajectory and resampled reference trajectory for debug purpose From 1a8fbc432614a35d41cff0c969a6e69e0586eafc Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Fri, 6 Sep 2024 16:01:31 +0900 Subject: [PATCH 144/217] feat(autoware_motion_utils): set zero velocity after stop in resample trajectory (#8768) * feat(autoware_motion_utils): set zero velocity after stop in resample trajectory Signed-off-by: Y.Hisaki * fix unit test Signed-off-by: Y.Hisaki * simplify implementation Signed-off-by: Y.Hisaki * update comment and add test Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki --- .../src/resample/resample.cpp | 17 ++ .../test/src/resample/test_resample.cpp | 163 ++++++++++++------ 2 files changed, 124 insertions(+), 56 deletions(-) diff --git a/common/autoware_motion_utils/src/resample/resample.cpp b/common/autoware_motion_utils/src/resample/resample.cpp index baf1c534a8a00..1f29a4577e428 100644 --- a/common/autoware_motion_utils/src/resample/resample.cpp +++ b/common/autoware_motion_utils/src/resample/resample.cpp @@ -21,6 +21,8 @@ #include "interpolation/spline_interpolation.hpp" #include "interpolation/zero_order_hold.hpp" +#include + namespace autoware::motion_utils { std::vector resamplePointVector( @@ -601,11 +603,13 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory( rear_wheel_angle.push_back(input_trajectory.points.front().rear_wheel_angle_rad); time_from_start.push_back( rclcpp::Duration(input_trajectory.points.front().time_from_start).seconds()); + for (size_t i = 1; i < input_trajectory.points.size(); ++i) { const auto & prev_pt = input_trajectory.points.at(i - 1); const auto & curr_pt = input_trajectory.points.at(i); const double ds = autoware::universe_utils::calcDistance2d(prev_pt.pose.position, curr_pt.pose.position); + input_arclength.push_back(ds + input_arclength.back()); input_pose.push_back(curr_pt.pose); v_lon.push_back(curr_pt.longitudinal_velocity_mps); @@ -617,6 +621,19 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory( time_from_start.push_back(rclcpp::Duration(curr_pt.time_from_start).seconds()); } + // Set Zero Velocity After Stop Point + // If the longitudinal velocity is zero, set the velocity to zero after that point. + bool stop_point_found_in_v_lon = false; + constexpr double epsilon = 1e-4; + for (size_t i = 0; i < v_lon.size(); ++i) { + if (std::abs(v_lon.at(i)) < epsilon) { + stop_point_found_in_v_lon = true; + } + if (stop_point_found_in_v_lon) { + v_lon.at(i) = 0.0; + } + } + // Interpolate const auto lerp = [&](const auto & input) { return interpolation::lerp(input_arclength, input, resampled_arclength); diff --git a/common/autoware_motion_utils/test/src/resample/test_resample.cpp b/common/autoware_motion_utils/test/src/resample/test_resample.cpp index 62db1b665d07a..68ead4b8c1520 100644 --- a/common/autoware_motion_utils/test/src/resample/test_resample.cpp +++ b/common/autoware_motion_utils/test/src/resample/test_resample.cpp @@ -173,6 +173,24 @@ std::vector generateArclength(const size_t num_points, const double inte return resampled_arclength; } + +template +std::vector setZeroVelocityAfterStop(const std::vector & traj_points) +{ + std::vector resampled_traj_points; + bool stop_point_found = false; + for (auto p : traj_points) { + if (!stop_point_found && p.longitudinal_velocity_mps < std::numeric_limits::epsilon()) { + stop_point_found = true; + } + if (stop_point_found) { + p.longitudinal_velocity_mps = 0.0; + } + resampled_traj_points.push_back(p); + } + return resampled_traj_points; +} + } // namespace TEST(resample_vector_pose, resample_by_same_interval) @@ -2643,7 +2661,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) const auto resampled_traj = resampleTrajectory(traj, resampled_arclength); for (size_t i = 0; i < resampled_traj.points.size(); ++i) { const auto p = resampled_traj.points.at(i); - const auto ans_p = traj.points.at(i); + const auto ans_p = setZeroVelocityAfterStop(traj.points).at(i); EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); @@ -2665,7 +2683,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) const auto resampled_path = resampleTrajectory(traj, resampled_arclength); for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { const auto p = resampled_path.points.at(i); - const auto ans_p = traj.points.at(i); + const auto ans_p = setZeroVelocityAfterStop(traj.points).at(i); EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); @@ -2680,7 +2698,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) } const auto p = resampled_path.points.back(); - const auto ans_p = traj.points.back(); + const auto ans_p = setZeroVelocityAfterStop(traj.points).back(); const auto ans_quat = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); @@ -2724,7 +2742,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) EXPECT_NEAR(p.pose.position.x, 1.2, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 1.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 0.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.12, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.05, epsilon); @@ -2735,7 +2753,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) EXPECT_NEAR(p.pose.position.x, 1.5, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 1.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 0.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.15, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.05, epsilon); @@ -2746,7 +2764,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) EXPECT_NEAR(p.pose.position.x, 5.3, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 5.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 2.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.53, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.25, epsilon); @@ -2757,7 +2775,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) EXPECT_NEAR(p.pose.position.x, 7.5, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 7.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 3.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.75, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.35, epsilon); @@ -2768,7 +2786,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) EXPECT_NEAR(p.pose.position.x, 9.0, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 9.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 4.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.9, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.45, epsilon); @@ -2920,7 +2938,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) EXPECT_NEAR(p.pose.position.x, 1.2, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 1.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 0.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.12, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.05, epsilon); @@ -2931,7 +2949,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) EXPECT_NEAR(p.pose.position.x, 5.3, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 5.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 2.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.53, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.25, epsilon); @@ -2942,7 +2960,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) EXPECT_NEAR(p.pose.position.x, 9.0, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 9.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 4.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.9, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.45, epsilon); @@ -2984,7 +3002,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) EXPECT_NEAR(p.pose.position.x, 1.2, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 1.2, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 1.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 0.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.12, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.05, epsilon); @@ -2995,7 +3013,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) EXPECT_NEAR(p.pose.position.x, 5.3, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 5.3, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 5.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 2.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.53, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.25, epsilon); @@ -3006,7 +3024,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) EXPECT_NEAR(p.pose.position.x, 9.0, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 9.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 9.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 4.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.9, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.45, epsilon); @@ -3050,7 +3068,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) EXPECT_NEAR(p.pose.position.x, 1.2, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 1.2, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 0.6, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.12, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.06, epsilon); @@ -3061,7 +3079,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) EXPECT_NEAR(p.pose.position.x, 5.3, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 5.3, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 2.65, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.53, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.265, epsilon); @@ -3072,7 +3090,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) EXPECT_NEAR(p.pose.position.x, 9.0, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); - EXPECT_NEAR(p.longitudinal_velocity_mps, 9.0, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); EXPECT_NEAR(p.lateral_velocity_mps, 4.5, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.9, epsilon); EXPECT_NEAR(p.acceleration_mps2, 0.45, epsilon); @@ -3105,7 +3123,7 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) const auto resampled_traj = resampleTrajectory(traj, 1.0); for (size_t i = 0; i < resampled_traj.points.size(); ++i) { const auto p = resampled_traj.points.at(i); - const auto ans_p = traj.points.at(i); + const auto ans_p = setZeroVelocityAfterStop(traj.points).at(i); EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); @@ -3127,7 +3145,7 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) const auto resampled_path = resampleTrajectory(traj, 1.0); for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { const auto p = resampled_path.points.at(i); - const auto ans_p = traj.points.at(i); + const auto ans_p = setZeroVelocityAfterStop(traj.points).at(i); EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); @@ -3142,7 +3160,7 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) } const auto p = resampled_path.points.back(); - const auto ans_p = traj.points.back(); + const auto ans_p = setZeroVelocityAfterStop(traj.points).back(); const auto ans_quat = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); @@ -3180,11 +3198,11 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); const size_t idx = i / 10; - EXPECT_NEAR( - p.longitudinal_velocity_mps, traj.points.at(idx).longitudinal_velocity_mps, epsilon); - EXPECT_NEAR(p.lateral_velocity_mps, traj.points.at(idx).lateral_velocity_mps, epsilon); + auto ans_p = setZeroVelocityAfterStop(traj.points).at(idx); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.01 * i, epsilon); - EXPECT_NEAR(p.acceleration_mps2, traj.points.at(idx).acceleration_mps2, epsilon); + EXPECT_NEAR(p.acceleration_mps2, ans_p.acceleration_mps2, epsilon); } } @@ -3210,11 +3228,11 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); const size_t idx = i / 2.5; - EXPECT_NEAR( - p.longitudinal_velocity_mps, traj.points.at(idx).longitudinal_velocity_mps, epsilon); - EXPECT_NEAR(p.lateral_velocity_mps, traj.points.at(idx).lateral_velocity_mps, epsilon); + auto ans_p = setZeroVelocityAfterStop(traj.points).at(idx); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.04 * i, epsilon); - EXPECT_NEAR(p.acceleration_mps2, traj.points.at(idx).acceleration_mps2, epsilon); + EXPECT_NEAR(p.acceleration_mps2, ans_p.acceleration_mps2, epsilon); } { @@ -3228,11 +3246,11 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); const size_t idx = 9; - EXPECT_NEAR( - p.longitudinal_velocity_mps, traj.points.at(idx).longitudinal_velocity_mps, epsilon); - EXPECT_NEAR(p.lateral_velocity_mps, traj.points.at(idx).lateral_velocity_mps, epsilon); + auto ans_p = setZeroVelocityAfterStop(traj.points).at(idx); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.9, epsilon); - EXPECT_NEAR(p.acceleration_mps2, traj.points.at(idx).acceleration_mps2, epsilon); + EXPECT_NEAR(p.acceleration_mps2, ans_p.acceleration_mps2, epsilon); } } @@ -3259,11 +3277,11 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); const size_t idx = i == 0 ? 0 : i - 1; - EXPECT_NEAR( - p.longitudinal_velocity_mps, traj.points.at(idx).longitudinal_velocity_mps, epsilon); - EXPECT_NEAR(p.lateral_velocity_mps, traj.points.at(idx).lateral_velocity_mps, epsilon); + auto ans_p = setZeroVelocityAfterStop(traj.points).at(idx); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); EXPECT_NEAR(p.heading_rate_rps, ds / 10.0 * i, epsilon); - EXPECT_NEAR(p.acceleration_mps2, traj.points.at(idx).acceleration_mps2, epsilon); + EXPECT_NEAR(p.acceleration_mps2, ans_p.acceleration_mps2, epsilon); } { @@ -3277,11 +3295,11 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); const size_t idx = 9; - EXPECT_NEAR( - p.longitudinal_velocity_mps, traj.points.at(idx).longitudinal_velocity_mps, epsilon); - EXPECT_NEAR(p.lateral_velocity_mps, traj.points.at(idx).lateral_velocity_mps, epsilon); + auto ans_p = setZeroVelocityAfterStop(traj.points).at(idx); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.9, epsilon); - EXPECT_NEAR(p.acceleration_mps2, traj.points.at(idx).acceleration_mps2, epsilon); + EXPECT_NEAR(p.acceleration_mps2, ans_p.acceleration_mps2, epsilon); } } @@ -3309,11 +3327,11 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); const size_t idx = i / 10; - EXPECT_NEAR( - p.longitudinal_velocity_mps, traj.points.at(idx).longitudinal_velocity_mps, epsilon); - EXPECT_NEAR(p.lateral_velocity_mps, traj.points.at(idx).lateral_velocity_mps, epsilon); + auto ans_p = setZeroVelocityAfterStop(traj.points).at(idx); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.01 * i, epsilon); - EXPECT_NEAR(p.acceleration_mps2, traj.points.at(idx).acceleration_mps2, epsilon); + EXPECT_NEAR(p.acceleration_mps2, ans_p.acceleration_mps2, epsilon); } } @@ -3416,6 +3434,7 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) { const auto p = resampled_traj.points.at(5); + auto ans_p = setZeroVelocityAfterStop(traj.points).at(6); EXPECT_NEAR(p.pose.position.x, 6.0, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); @@ -3424,15 +3443,15 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); - EXPECT_NEAR( - p.longitudinal_velocity_mps, traj.points.at(6).longitudinal_velocity_mps, epsilon); - EXPECT_NEAR(p.lateral_velocity_mps, traj.points.at(6).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.60, epsilon); - EXPECT_NEAR(p.acceleration_mps2, traj.points.at(6).acceleration_mps2, epsilon); + EXPECT_NEAR(p.acceleration_mps2, ans_p.acceleration_mps2, epsilon); } { const auto p = resampled_traj.points.at(6); + auto ans_p = setZeroVelocityAfterStop(traj.points).at(7); EXPECT_NEAR(p.pose.position.x, 7.5, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); @@ -3441,15 +3460,15 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); - EXPECT_NEAR( - p.longitudinal_velocity_mps, traj.points.at(7).longitudinal_velocity_mps, epsilon); - EXPECT_NEAR(p.lateral_velocity_mps, traj.points.at(7).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.75, epsilon); - EXPECT_NEAR(p.acceleration_mps2, traj.points.at(7).acceleration_mps2, epsilon); + EXPECT_NEAR(p.acceleration_mps2, ans_p.acceleration_mps2, epsilon); } { const auto p = resampled_traj.points.at(7); + const auto ans_p = setZeroVelocityAfterStop(traj.points).at(9); EXPECT_NEAR(p.pose.position.x, 9.0, epsilon); EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); @@ -3458,11 +3477,10 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); - EXPECT_NEAR( - p.longitudinal_velocity_mps, traj.points.at(9).longitudinal_velocity_mps, epsilon); - EXPECT_NEAR(p.lateral_velocity_mps, traj.points.at(9).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); EXPECT_NEAR(p.heading_rate_rps, 0.90, epsilon); - EXPECT_NEAR(p.acceleration_mps2, traj.points.at(9).acceleration_mps2, epsilon); + EXPECT_NEAR(p.acceleration_mps2, ans_p.acceleration_mps2, epsilon); } } @@ -3568,3 +3586,36 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) } } } + +TEST(resample_trajectory, resample_with_middle_stop_point) +{ + // This test is to check the behavior when the stop point is unstably resampled by zero-order hold + // interpolation. + + using autoware::motion_utils::resampleTrajectory; + + autoware_planning_msgs::msg::Trajectory traj; + traj.points.reserve(10); + + traj.points.push_back(generateTestTrajectoryPoint(0.0, 0.0, 0.0, 0.0, 10.0, 0.0, 0.0, 0.0)); + traj.points.push_back(generateTestTrajectoryPoint(1.0, 0.0, 0.0, 0.0, 10.0, 0.0, 0.0, 0.0)); + traj.points.push_back(generateTestTrajectoryPoint(2.0, 0.0, 0.0, 0.0, 10.0, 0.0, 0.0, 0.0)); + traj.points.push_back(generateTestTrajectoryPoint(3.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0)); + traj.points.push_back(generateTestTrajectoryPoint(3.1, 0.0, 0.0, 0.0, 10.0, 0.0, 0.0, 0.0)); + traj.points.push_back(generateTestTrajectoryPoint(4.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0)); + traj.points.push_back(generateTestTrajectoryPoint(5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0)); + traj.points.push_back(generateTestTrajectoryPoint(6.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0)); + traj.points.push_back(generateTestTrajectoryPoint(7.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0)); + + std::vector interpolated_axis = {0.0, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0}; + + const auto resampled_traj = resampleTrajectory(traj, interpolated_axis); + + EXPECT_NEAR(resampled_traj.points.at(0).longitudinal_velocity_mps, 10.0, epsilon); + EXPECT_NEAR(resampled_traj.points.at(1).longitudinal_velocity_mps, 10.0, epsilon); + EXPECT_NEAR(resampled_traj.points.at(2).longitudinal_velocity_mps, 10.0, epsilon); + EXPECT_NEAR(resampled_traj.points.at(3).longitudinal_velocity_mps, 0.0, epsilon); + EXPECT_NEAR(resampled_traj.points.at(4).longitudinal_velocity_mps, 0.0, epsilon); + EXPECT_NEAR(resampled_traj.points.at(5).longitudinal_velocity_mps, 0.0, epsilon); + EXPECT_NEAR(resampled_traj.points.at(6).longitudinal_velocity_mps, 0.0, epsilon); +} From 56aefc30eae1ab55a8ab2f1e1ccb3829b950c7f3 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Fri, 6 Sep 2024 16:51:01 +0900 Subject: [PATCH 145/217] feat(ndt_scan_matcher, ekf_localizer): fix some code for deterministic test (#8766) * Added namespace autoware::ndt_scan_matcher Signed-off-by: Shintaro Sakoda * Added namespace autoware::ekf_localizer Signed-off-by: Shintaro Sakoda * Added time_until_trigger Signed-off-by: Shintaro Sakoda * Added ekf_callback diag Signed-off-by: Shintaro Sakoda * Fixed seed Signed-off-by: Shintaro Sakoda * Add publish_callback_return_diagnostics Signed-off-by: Shintaro Sakoda * Added figure Signed-off-by: Shintaro Sakoda * Added comments Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda --- localization/ekf_localizer/README.md | 7 ++++++ .../include/ekf_localizer/ekf_localizer.hpp | 12 +++++++++ .../media/ekf_diagnostics_callback_pose.png | Bin 0 -> 17825 bytes .../media/ekf_diagnostics_callback_twist.png | Bin 0 -> 17945 bytes .../ekf_localizer/src/ekf_localizer.cpp | 23 ++++++++++++++++++ .../src/tree_structured_parzen_estimator.cpp | 2 +- .../ndt_scan_matcher_core.hpp | 6 +++++ 7 files changed, 49 insertions(+), 1 deletion(-) create mode 100644 localization/ekf_localizer/media/ekf_diagnostics_callback_pose.png create mode 100644 localization/ekf_localizer/media/ekf_diagnostics_callback_twist.png diff --git a/localization/ekf_localizer/README.md b/localization/ekf_localizer/README.md index 3b417b12bc6e9..7c1bc5257105b 100644 --- a/localization/ekf_localizer/README.md +++ b/localization/ekf_localizer/README.md @@ -180,6 +180,13 @@ 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. diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index d6feb17367b10..2dc06e50f8eb8 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -101,6 +101,12 @@ 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_; @@ -218,6 +224,12 @@ class EKFLocalizer : public rclcpp::Node 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 update simple 1d filter */ diff --git a/localization/ekf_localizer/media/ekf_diagnostics_callback_pose.png b/localization/ekf_localizer/media/ekf_diagnostics_callback_pose.png new file mode 100644 index 0000000000000000000000000000000000000000..9349a225c887b28731388326312abc744c4358ba GIT binary patch literal 17825 zcmdSBV{~Rg+a-L*wmMG7wr$(CZQHiZj%_>X*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/ekf_localizer/media/ekf_diagnostics_callback_twist.png b/localization/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/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 3362ce3a0c01e..7879ddbc55caa 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -319,6 +319,8 @@ void EKFLocalizer::callback_pose_with_covariance( } pose_queue_.push(msg); + + publish_callback_return_diagnostics("pose", msg->header.stamp); } /* @@ -333,6 +335,8 @@ void EKFLocalizer::callback_twist_with_covariance( msg->twist.covariance[0 * 6 + 0] = 10000.0; } twist_queue_.push(msg); + + publish_callback_return_diagnostics("twist", msg->header.stamp); } /* @@ -446,6 +450,25 @@ void EKFLocalizer::publish_diagnostics( 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); +} + void EKFLocalizer::update_simple_1d_filters( const geometry_msgs::msg::PoseWithCovarianceStamped & pose, const size_t smoothing_step) { diff --git a/localization/localization_util/src/tree_structured_parzen_estimator.cpp b/localization/localization_util/src/tree_structured_parzen_estimator.cpp index aab78f0aaec71..8d594310d79bc 100644 --- a/localization/localization_util/src/tree_structured_parzen_estimator.cpp +++ b/localization/localization_util/src/tree_structured_parzen_estimator.cpp @@ -20,7 +20,7 @@ #include // random number generator -std::mt19937_64 TreeStructuredParzenEstimator::engine(std::random_device{}()); +std::mt19937_64 TreeStructuredParzenEstimator::engine(0); TreeStructuredParzenEstimator::TreeStructuredParzenEstimator( const Direction direction, const int64_t n_startup_trials, std::vector sample_mean, diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index eb49711fe9270..08e623b69eb20 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -82,6 +82,12 @@ class NDTScanMatcher : public rclcpp::Node public: explicit NDTScanMatcher(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); + // This function is only used in static tools to know when timer callbacks are triggered. + std::chrono::nanoseconds time_until_trigger() const + { + return map_update_timer_->time_until_trigger(); + } + private: void callback_timer(); From 3064734fb399142d58364c8b233b29105f41453d Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 6 Sep 2024 16:56:07 +0900 Subject: [PATCH 146/217] fix(static_obstacle_avoidance): improve turn signal output timing when the ego returns original lane (#8726) fix(static_obstacle_avoidance): fix unexpected turn signal output Signed-off-by: satoshi-ota --- .../debug.hpp | 3 +- .../scene.hpp | 6 +- .../src/debug.cpp | 65 ++++++- .../src/scene.cpp | 162 +++++++++++++----- 4 files changed, 186 insertions(+), 50 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp index 29014105dab6e..efae5c6bbb441 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp @@ -48,7 +48,8 @@ MarkerArray createAmbiguousObjectsMarkerArray( MarkerArray createStopTargetObjectMarkerArray(const AvoidancePlanningData & data); MarkerArray createDebugMarkerArray( - const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug, + const BehaviorModuleOutput & output, const AvoidancePlanningData & data, + const PathShifter & shifter, const DebugData & debug, const std::shared_ptr & parameters); } // namespace autoware::behavior_path_planner::utils::static_obstacle_avoidance 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 a2dbdcc1dadb9..558ac557b66eb 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 @@ -346,7 +346,8 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface * @brief fill debug markers. */ void updateDebugMarker( - const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug) const; + const BehaviorModuleOutput & output, const AvoidancePlanningData & data, + const PathShifter & shifter, const DebugData & debug) const; /** * @brief fill information markers that are shown in Rviz by default. @@ -368,6 +369,9 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface */ bool isSafePath(ShiftedPath & shifted_path, DebugData & debug) const; + auto getTurnSignal(const ShiftedPath & spline_shift_path, const ShiftedPath & linear_shift_path) + -> TurnSignalInfo; + // post process /** diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index 5c1dbd364da90..997fb7353b14c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -229,6 +229,67 @@ MarkerArray unAvoidableObjectsMarkerArray(const ObjectDataArray & objects, std:: return msg; } +MarkerArray createTurnSignalMarkerArray(const TurnSignalInfo & turn_signal_info, std::string && ns) +{ + MarkerArray msg; + + if (turn_signal_info.turn_signal.command == TurnIndicatorsCommand::NO_COMMAND) { + return msg; + } + + const auto yaw_offset = [&turn_signal_info]() { + if (turn_signal_info.turn_signal.command == TurnIndicatorsCommand::ENABLE_RIGHT) { + return -1.0 * M_PI_2; + } + + if (turn_signal_info.turn_signal.command == TurnIndicatorsCommand::ENABLE_LEFT) { + return M_PI_2; + } + + return 0.0; + }(); + + size_t i = 0; + { + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, i++, Marker::ARROW, + createMarkerScale(0.6, 0.3, 0.3), createMarkerColor(0.0, 0.0, 1.0, 0.999)); + marker.pose = turn_signal_info.desired_start_point; + marker.pose = calcOffsetPose(marker.pose, 0.0, 0.0, 0.0, yaw_offset); + + msg.markers.push_back(marker); + } + { + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, i++, Marker::ARROW, + createMarkerScale(0.6, 0.3, 0.3), createMarkerColor(0.0, 0.0, 1.0, 0.999)); + marker.pose = turn_signal_info.desired_end_point; + marker.pose = calcOffsetPose(marker.pose, 0.0, 0.0, 0.0, yaw_offset); + + msg.markers.push_back(marker); + } + { + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, i++, Marker::ARROW, + createMarkerScale(0.8, 0.4, 0.4), createMarkerColor(1.0, 0.0, 0.0, 0.999)); + marker.pose = turn_signal_info.required_start_point; + marker.pose = calcOffsetPose(marker.pose, 0.0, 0.0, 0.0, yaw_offset); + + msg.markers.push_back(marker); + } + { + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, i++, Marker::ARROW, + createMarkerScale(0.8, 0.4, 0.4), createMarkerColor(1.0, 0.0, 0.0, 0.999)); + marker.pose = turn_signal_info.required_end_point; + marker.pose = calcOffsetPose(marker.pose, 0.0, 0.0, 0.0, yaw_offset); + + msg.markers.push_back(marker); + } + + return msg; +} + } // namespace MarkerArray createAvoidLineMarkerArray( @@ -494,7 +555,8 @@ MarkerArray createDrivableBounds( } MarkerArray createDebugMarkerArray( - const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug, + const BehaviorModuleOutput & output, const AvoidancePlanningData & data, + const PathShifter & shifter, const DebugData & debug, const std::shared_ptr & parameters) { using autoware::behavior_path_planner::utils::transformToLanelets; @@ -630,6 +692,7 @@ MarkerArray createDebugMarkerArray( // misc if (parameters->enable_misc_marker) { add(createPathMarkerArray(path, "centerline_resampled", 0, 0.0, 0.9, 0.5)); + add(createTurnSignalMarkerArray(output.turn_signal_info, "turn_signal_info")); } return msg; 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 bc8e406a170c9..e3ecdff3759c0 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 @@ -91,7 +91,7 @@ bool StaticObstacleAvoidanceModule::isExecutionRequested() const // Check ego is in preferred lane updateInfoMarker(avoid_data_); - updateDebugMarker(avoid_data_, path_shifter_, debug_data_); + updateDebugMarker(BehaviorModuleOutput{}, avoid_data_, path_shifter_, debug_data_); // there is object that should be avoid. return true. if (!!avoid_data_.stop_target_object) { @@ -945,6 +945,112 @@ PathWithLaneId StaticObstacleAvoidanceModule::extendBackwardLength( return extended_path; } +auto StaticObstacleAvoidanceModule::getTurnSignal( + const ShiftedPath & spline_shift_path, const ShiftedPath & linear_shift_path) -> TurnSignalInfo +{ + using autoware::motion_utils::calcSignedArcLength; + + const auto is_ignore_signal = [this](const UUID & uuid) { + if (!ignore_signal_.has_value()) { + return false; + } + + return ignore_signal_.value() == uuid; + }; + + const auto update_ignore_signal = [this](const UUID & uuid, const bool is_ignore) { + ignore_signal_ = is_ignore ? std::make_optional(uuid) : std::nullopt; + }; + + const auto is_large_deviation = [this](const auto & path) { + constexpr double threshold = 1.0; + const auto current_seg_idx = planner_data_->findEgoSegmentIndex(path.points); + const auto lateral_deviation = + autoware::motion_utils::calcLateralOffset(path.points, getEgoPosition(), current_seg_idx); + return std::abs(lateral_deviation) > threshold; + }; + + auto shift_lines = path_shifter_.getShiftLines(); + if (shift_lines.empty()) { + return getPreviousModuleOutput().turn_signal_info; + } + + if (is_large_deviation(spline_shift_path.path)) { + return getPreviousModuleOutput().turn_signal_info; + } + + const auto itr = + std::remove_if(shift_lines.begin(), shift_lines.end(), [&, this](const auto & s) { + const auto threshold = planner_data_->parameters.turn_signal_shift_length_threshold; + return std::abs(s.start_shift_length - s.end_shift_length) < threshold || + is_ignore_signal(s.id); + }); + shift_lines.erase(itr, shift_lines.end()); + + if (shift_lines.empty()) { + return getPreviousModuleOutput().turn_signal_info; + } + + const auto target_shift_line = [&]() { + const auto & s1 = shift_lines.front(); + + for (size_t i = 1; i < shift_lines.size(); i++) { + const auto & s2 = shift_lines.at(i); + + const auto s1_relative_length = s1.start_shift_length - s1.end_shift_length; + const auto s2_relative_length = s2.start_shift_length - s2.end_shift_length; + + // same side shift + if (s1_relative_length > 0.0 && s2_relative_length > 0.0) { + continue; + } + + // same side shift + if (s1_relative_length < 0.0 && s2_relative_length < 0.0) { + continue; + } + + // different side shift + const auto & points = path_shifter_.getReferencePath().points; + const size_t idx = planner_data_->findEgoIndex(points); + + // output turn signal for near shift line. + if (calcSignedArcLength(points, idx, s1.start_idx) > 0.0) { + return s1; + } + + // output turn signal for far shift line. + if ( + calcSignedArcLength(points, idx, s2.start_idx) < + getEgoSpeed() * parameters_->max_prepare_time) { + return s2; + } + + // output turn signal for near shift line. + return s1; + } + + return s1; + }(); + + const auto original_signal = getPreviousModuleOutput().turn_signal_info; + + constexpr bool is_driving_forward = true; + constexpr bool egos_lane_is_shifted = true; + + const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo( + linear_shift_path, target_shift_line, avoid_data_.current_lanelets, helper_->getEgoShift(), + is_driving_forward, egos_lane_is_shifted); + + update_ignore_signal(target_shift_line.id, is_ignore); + + const auto current_seg_idx = planner_data_->findEgoSegmentIndex(spline_shift_path.path.points); + return planner_data_->turn_signal_decider.overwrite_turn_signal( + spline_shift_path.path, getEgoPose(), current_seg_idx, original_signal, new_signal, + planner_data_->parameters.ego_nearest_dist_threshold, + planner_data_->parameters.ego_nearest_yaw_threshold); +} + BehaviorModuleOutput StaticObstacleAvoidanceModule::plan() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -990,48 +1096,9 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::plan() BehaviorModuleOutput output; - const auto is_ignore_signal = [this](const UUID & uuid) { - if (!ignore_signal_.has_value()) { - return false; - } - - return ignore_signal_.value() == uuid; - }; - - const auto update_ignore_signal = [this](const UUID & uuid, const bool is_ignore) { - ignore_signal_ = is_ignore ? std::make_optional(uuid) : std::nullopt; - }; - - const auto is_large_deviation = [this](const auto & path) { - constexpr double threshold = 1.0; - const auto current_seg_idx = planner_data_->findEgoSegmentIndex(path.points); - const auto lateral_deviation = - autoware::motion_utils::calcLateralOffset(path.points, getEgoPosition(), current_seg_idx); - return std::abs(lateral_deviation) > threshold; - }; - - // turn signal info - if (path_shifter_.getShiftLines().empty()) { - output.turn_signal_info = getPreviousModuleOutput().turn_signal_info; - } else if (is_ignore_signal(path_shifter_.getShiftLines().front().id)) { - output.turn_signal_info = getPreviousModuleOutput().turn_signal_info; - } else if (is_large_deviation(spline_shift_path.path)) { - output.turn_signal_info = getPreviousModuleOutput().turn_signal_info; - } else { - const auto original_signal = getPreviousModuleOutput().turn_signal_info; - - constexpr bool is_driving_forward = true; - constexpr bool egos_lane_is_shifted = true; - const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo( - linear_shift_path, path_shifter_.getShiftLines().front(), avoid_data_.current_lanelets, - helper_->getEgoShift(), is_driving_forward, egos_lane_is_shifted); - - const auto current_seg_idx = planner_data_->findEgoSegmentIndex(spline_shift_path.path.points); - output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal( - spline_shift_path.path, getEgoPose(), current_seg_idx, original_signal, new_signal, - planner_data_->parameters.ego_nearest_dist_threshold, - planner_data_->parameters.ego_nearest_yaw_threshold); - update_ignore_signal(path_shifter_.getShiftLines().front().id, is_ignore); + // turn signal + { + output.turn_signal_info = getTurnSignal(spline_shift_path, linear_shift_path); } // sparse resampling for computational cost @@ -1044,7 +1111,7 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::plan() { updateEgoBehavior(data, spline_shift_path); updateInfoMarker(avoid_data_); - updateDebugMarker(avoid_data_, path_shifter_, debug_data_); + updateDebugMarker(output, avoid_data_, path_shifter_, debug_data_); } if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) { @@ -1490,12 +1557,13 @@ void StaticObstacleAvoidanceModule::updateInfoMarker(const AvoidancePlanningData } void StaticObstacleAvoidanceModule::updateDebugMarker( - const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug) const + const BehaviorModuleOutput & output, const AvoidancePlanningData & data, + const PathShifter & shifter, const DebugData & debug) const { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); debug_marker_.markers.clear(); - debug_marker_ = - utils::static_obstacle_avoidance::createDebugMarkerArray(data, shifter, debug, parameters_); + debug_marker_ = utils::static_obstacle_avoidance::createDebugMarkerArray( + output, data, shifter, debug, parameters_); } void StaticObstacleAvoidanceModule::updateAvoidanceDebugData( From 78e4a92bd5500fc3c56ade16ea50fb3cd34cdcf3 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 6 Sep 2024 17:00:32 +0900 Subject: [PATCH 147/217] test(autoware_behavior_path_planner_common): add tests for calcInterpolatedPoseWithVelocity (#8270) * test: add interpolated pose calculation function's test Signed-off-by: kyoichi-sugahara * disabled SpecialCases test Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../path_safety_checker/safety_check.hpp | 8 ++ .../test/test_safety_check.cpp | 93 +++++++++++++++++++ 2 files changed, 101 insertions(+) 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 0e6256c3b4d7c..a357d51cc4afb 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 @@ -76,6 +76,14 @@ double calcMinimumLongitudinalLength( const double front_object_velocity, const double rear_object_velocity, const RSSparams & rss_params); +/** + * @brief Calculates an interpolated pose with velocity for a given relative time along a path. + * @param path A vector of PoseWithVelocityStamped objects representing the path. + * @param relative_time The relative time at which to calculate the interpolated pose and velocity. + * @return An optional PoseWithVelocityStamped object. If the interpolation is successful, + * it contains the interpolated pose, velocity, and time. If the interpolation fails + * (e.g., empty path, negative time, or time beyond the path), it returns std::nullopt. + */ std::optional calcInterpolatedPoseWithVelocity( const std::vector & path, const double relative_time); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp index 2708b1e608779..d4ca629e8804e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp @@ -27,7 +27,11 @@ constexpr double epsilon = 1e-6; +using autoware::behavior_path_planner::utils::path_safety_checker::calcInterpolatedPoseWithVelocity; using autoware::behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; +using autoware::behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::createQuaternionFromRPY; using autoware::universe_utils::Point2d; using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::Shape; @@ -35,6 +39,24 @@ using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; +geometry_msgs::msg::Pose createPose( + double x, double y, double z, double roll, double pitch, double yaw) +{ + geometry_msgs::msg::Pose p; + p.position = createPoint(x, y, z); + p.orientation = createQuaternionFromRPY(roll, pitch, yaw); + return p; +} + +std::vector createTestPath() +{ + std::vector path; + path.emplace_back(0.0, createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0), 1.0); + path.emplace_back(1.0, createPose(1.0, 0.0, 0.0, 0.0, 0.0, 0.0), 2.0); + path.emplace_back(2.0, createPose(2.0, 0.0, 0.0, 0.0, 0.0, 0.0), 3.0); + return path; +} + TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) { using autoware::behavior_path_planner::utils::path_safety_checker::createExtendedPolygon; @@ -207,3 +229,74 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, calcRssDistance) EXPECT_NEAR(calcRssDistance(front_vel, rear_vel, params), 63.75, epsilon); } } + +// Basic interpolation test +TEST(CalcInterpolatedPoseWithVelocityTest, BasicInterpolation) +{ + auto path = createTestPath(); + auto result = calcInterpolatedPoseWithVelocity(path, 0.5); + + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result->time, 0.5, 1e-6); + EXPECT_NEAR(result->pose.position.x, 0.5, 1e-6); + EXPECT_NEAR(result->velocity, 1.5, 1e-6); +} + +// Boundary conditions test +TEST(CalcInterpolatedPoseWithVelocityTest, BoundaryConditions) +{ + auto path = createTestPath(); + + // First point of the path + auto start_result = calcInterpolatedPoseWithVelocity(path, 0.0); + ASSERT_TRUE(start_result.has_value()); + EXPECT_NEAR(start_result->time, 0.0, 1e-6); + EXPECT_NEAR(start_result->pose.position.x, 0.0, 1e-6); + EXPECT_NEAR(start_result->velocity, 1.0, 1e-6); + + // Last point of the path + auto end_result = calcInterpolatedPoseWithVelocity(path, 2.0); + ASSERT_TRUE(end_result.has_value()); + EXPECT_NEAR(end_result->time, 2.0, 1e-6); + EXPECT_NEAR(end_result->pose.position.x, 2.0, 1e-6); + EXPECT_NEAR(end_result->velocity, 3.0, 1e-6); +} + +// Invalid input test +TEST(CalcInterpolatedPoseWithVelocityTest, InvalidInput) +{ + auto path = createTestPath(); + + // Empty path + EXPECT_FALSE(calcInterpolatedPoseWithVelocity({}, 1.0).has_value()); + + // Negative relative time + EXPECT_FALSE(calcInterpolatedPoseWithVelocity(path, -1.0).has_value()); + + // Relative time greater than the last time in the path + EXPECT_FALSE(calcInterpolatedPoseWithVelocity(path, 3.0).has_value()); +} + +// Special cases test +TEST(CalcInterpolatedPoseWithVelocityTest, DISABLED_SpecialCases) +{ + // Case with consecutive points at the same time + std::vector same_time_path; + same_time_path.emplace_back(0.0, createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0), 1.0); + same_time_path.emplace_back(0.0, createPose(1.0, 0.0, 0.0, 0.0, 0.0, 0.0), 2.0); + same_time_path.emplace_back(1.0, createPose(2.0, 0.0, 0.0, 0.0, 0.0, 0.0), 3.0); + + auto same_time_result = calcInterpolatedPoseWithVelocity(same_time_path, 0.0); + ASSERT_TRUE(same_time_result.has_value()); + EXPECT_NEAR(same_time_result->pose.position.x, 0.0, 1e-6); + EXPECT_NEAR(same_time_result->velocity, 1.0, 1e-6); + + // Case with reversed time order + std::vector reverse_time_path; + reverse_time_path.emplace_back(2.0, createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0), 1.0); + reverse_time_path.emplace_back(1.0, createPose(1.0, 0.0, 0.0, 0.0, 0.0, 0.0), 2.0); + reverse_time_path.emplace_back(0.0, createPose(2.0, 0.0, 0.0, 0.0, 0.0, 0.0), 3.0); + + auto reverse_time_result = calcInterpolatedPoseWithVelocity(reverse_time_path, 1.5); + ASSERT_FALSE(reverse_time_result.has_value()); +} From 7f1997d5057c201093f9097a3279284b31d0fb2d Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 6 Sep 2024 18:09:27 +0900 Subject: [PATCH 148/217] chore(ci): update lanelet2_extension version for build (#8800) Signed-off-by: Mamoru Sobue --- build_depends.repos | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build_depends.repos b/build_depends.repos index 67e06dba923f0..0c1deb7194cfb 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -16,7 +16,7 @@ repositories: core/autoware_lanelet2_extension: type: git url: https://github.com/autowarefoundation/autoware_lanelet2_extension.git - version: 0.5.0 + version: 0.6.1 core/autoware.core: type: git url: https://github.com/autowarefoundation/autoware.core.git From e228eeb49e253e7c7faa26571ca5bc97c0a4ea3e Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 6 Sep 2024 18:55:35 +0900 Subject: [PATCH 149/217] fix(motion_velocity_planner): relax test precision to prevent random failures (#8799) Signed-off-by: Maxime CLEMENT --- .../test/test_collision_checker.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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/test/test_collision_checker.cpp index df813db336a9d..fd9a7d6e6649b 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/test/test_collision_checker.cpp @@ -60,7 +60,7 @@ Polygon2d random_polygon() bool all_within(const MultiPoint2d & pts1, const MultiPoint2d & pts2) { // results from the collision checker and the direct checks can have some small precision errors - constexpr auto eps = 1e-3; + constexpr auto eps = 1e-2; for (const auto & p1 : pts1) { bool found = false; for (const auto & p2 : pts2) { From 49773d92d48a9dc8d35362b32e34502ecdc31256 Mon Sep 17 00:00:00 2001 From: Hayate TOBA <105347690+bathteayo@users.noreply.github.com> Date: Fri, 6 Sep 2024 19:13:14 +0900 Subject: [PATCH 150/217] fix(autoware_frenet_planner): fix unusedFunction (#8788) fix: unusedFunction Signed-off-by: bathteayo <105347690+bathteayo@users.noreply.github.com> --- .../frenet_planner.hpp | 16 ----- .../src/frenet_planner/frenet_planner.cpp | 63 ------------------- 2 files changed, 79 deletions(-) diff --git a/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp index 0dd4c74ddbb06..e2b63f6591463 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp @@ -25,16 +25,6 @@ namespace autoware::frenet_planner { -/// @brief generate trajectories relative to the reference for the given initial state and sampling -/// parameters -std::vector generateTrajectories( - const autoware::sampler_common::transform::Spline2D & reference_spline, - const FrenetState & initial_state, const SamplingParameters & sampling_parameters); -/// @brief generate trajectories relative to the reference for the given initial state and sampling -/// parameters -std::vector generateLowVelocityTrajectories( - const autoware::sampler_common::transform::Spline2D & reference_spline, - const FrenetState & initial_state, const SamplingParameters & sampling_parameters); /// @brief generate paths relative to the reference for the given initial state and sampling /// parameters std::vector generatePaths( @@ -51,12 +41,6 @@ Path generateCandidate( Trajectory generateCandidate( const FrenetState & initial_state, const FrenetState & target_state, const double duration, const double time_resolution); -/// @brief generate a low velocity candidate trajectory -/// @details the polynomial for lateral motion (d) is calculated over the longitudinal displacement -/// (s) rather than over time: d(s) and s(t). -Trajectory generateLowVelocityCandidate( - const FrenetState & initial_state, const FrenetState & target_state, const double duration, - const double time_resolution); /// @brief calculate the cartesian frame of the given path void calculateCartesian( const autoware::sampler_common::transform::Spline2D & reference, Path & path); 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 1e04db2a17eee..d53fc1cb1726f 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 @@ -33,45 +33,6 @@ namespace autoware::frenet_planner { -std::vector generateTrajectories( - const autoware::sampler_common::transform::Spline2D & reference_spline, - const FrenetState & initial_state, const SamplingParameters & sampling_parameters) -{ - std::vector trajectories; - trajectories.reserve(sampling_parameters.parameters.size()); - for (const auto & parameter : sampling_parameters.parameters) { - auto trajectory = generateCandidate( - initial_state, parameter.target_state, parameter.target_duration, - sampling_parameters.resolution); - trajectory.sampling_parameter = parameter; - calculateCartesian(reference_spline, trajectory); - std::stringstream ss; - ss << parameter; - trajectory.tag = ss.str(); - trajectories.push_back(trajectory); - } - return trajectories; -} - -std::vector generateLowVelocityTrajectories( - const autoware::sampler_common::transform::Spline2D & reference_spline, - const FrenetState & initial_state, const SamplingParameters & sampling_parameters) -{ - std::vector trajectories; - trajectories.reserve(sampling_parameters.parameters.size()); - for (const auto & parameter : sampling_parameters.parameters) { - auto trajectory = generateLowVelocityCandidate( - initial_state, parameter.target_state, parameter.target_duration, - sampling_parameters.resolution); - calculateCartesian(reference_spline, trajectory); - std::stringstream ss; - ss << parameter; - trajectory.tag = ss.str(); - trajectories.push_back(trajectory); - } - return trajectories; -} - std::vector generatePaths( const autoware::sampler_common::transform::Spline2D & reference_spline, const FrenetState & initial_state, const SamplingParameters & sampling_parameters) @@ -108,30 +69,6 @@ Trajectory generateCandidate( return trajectory; } -Trajectory generateLowVelocityCandidate( - const FrenetState & initial_state, const FrenetState & target_state, const double duration, - const double time_resolution) -{ - Trajectory trajectory; - trajectory.longitudinal_polynomial = Polynomial( - initial_state.position.s, initial_state.longitudinal_velocity, - initial_state.longitudinal_acceleration, target_state.position.s, - target_state.longitudinal_velocity, target_state.longitudinal_acceleration, duration); - const auto delta_s = target_state.position.s - initial_state.position.s; - trajectory.lateral_polynomial = Polynomial( - initial_state.position.d, initial_state.lateral_velocity, initial_state.lateral_acceleration, - target_state.position.d, target_state.lateral_velocity, target_state.lateral_acceleration, - delta_s); - for (double t = 0.0; t <= duration; t += time_resolution) { - trajectory.times.push_back(t); - const auto s = trajectory.longitudinal_polynomial->position(t); - const auto ds = s - initial_state.position.s; - const auto d = trajectory.lateral_polynomial->position(ds); - trajectory.frenet_points.emplace_back(s, d); - } - return trajectory; -} - Path generateCandidate( const FrenetState & initial_state, const FrenetState & target_state, const double s_resolution) { From 55d0905818affd6e921f4632178a9389a54f7913 Mon Sep 17 00:00:00 2001 From: SHtokuda <165623782+shtokuda@users.noreply.github.com> Date: Mon, 9 Sep 2024 10:03:14 +0900 Subject: [PATCH 151/217] refactor(autoware_external_cmd_converter): add explanation about external control commands (#8224) * refactor(autoware_external_cmd_converter): add explanation about external control commands Signed-off-by: shtokuda * style(pre-commit): autofix --------- Signed-off-by: shtokuda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Tomoya Kimura --- .../autoware_external_cmd_converter/README.md | 41 +++++++++++++++++++ 1 file changed, 41 insertions(+) diff --git a/vehicle/autoware_external_cmd_converter/README.md b/vehicle/autoware_external_cmd_converter/README.md index ef5865debd4d4..40003d330757a 100644 --- a/vehicle/autoware_external_cmd_converter/README.md +++ b/vehicle/autoware_external_cmd_converter/README.md @@ -2,6 +2,46 @@ `external_cmd_converter` is a node that converts desired mechanical input to acceleration and velocity by using accel/brake map. +## Algorithm + +### How to calculate reference acceleration and velocity + +A reference acceleration and velocity are derived from the throttle and brake values of external control commands. + +#### Reference Acceleration + +A reference acceleration is calculated from accel_brake_map based on values of a desired_pedal and a current velocity; + +$$ + pedal_d = throttle_d - brake_d, +$$ + +$$ + acc_{ref} = Acc(pedal_d, v_{x,current}). +$$ + +| Parameter | Description | +| --------------- | ----------------------------------------------------------------------------------------- | +| $throttle_d$ | throttle value of external control command (`~/in/external_control_cmd.control.throttle`) | +| $brake_d$ | brake value of external control command (`~/in/external_control_cmd.control.brake`) | +| $v_{x,current}$ | current longitudinal velocity (`~/in/odometry.twist.twist.linear.x`) | +| Acc | accel_brake_map | + +#### Reference Velocity + +A reference velocity is calculated based on a current velocity and a reference acceleration: + +$$ +v_{ref} = + v_{x,current} + k_{v_{ref}} \cdot \text{sign}_{gear} \cdot acc_{ref}. +$$ + +| Parameter | Description | +| -------------------- | --------------------------------------------------------------------- | +| $acc_{ref}$ | reference acceleration | +| $k_{v_{ref}}$ | reference velocity gain | +| $\text{sign}_{gear}$ | gear command (`~/in/shift_cmd`) (Drive/Low: 1, Reverse: -1, Other: 0) | + ## Input topics | Name | Type | Description | @@ -22,6 +62,7 @@ | Parameter | Type | Description | | ------------------------- | ------ | ----------------------------------------------------- | +| `ref_vel_gain_` | double | reference velocity gain | | `timer_rate` | double | timer's update rate | | `wait_for_first_topic` | double | if time out check is done after receiving first topic | | `control_command_timeout` | double | time out check for control command | From 67265bbd60c85282c1c3cf65e603098e0c30c477 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 9 Sep 2024 10:11:44 +0900 Subject: [PATCH 152/217] feat(autoware_map_based_prediction): improve frenet path generation (#8602) * feat: calculate terminal d position based on playable width in path_generator.cpp Signed-off-by: Taekjin LEE * feat: Add width parameter path generations refactor(path_generator): improve backlash width calculation Signed-off-by: Taekjin LEE refactor(path_generator): improve backlash width calculation Signed-off-by: Taekjin LEE * fix: set initial point of Frenet Path to Cartesian Path conversion Signed-off-by: Taekjin LEE refactor: limit the d value to the radius for curved reference paths refactor: limit d value to curve limit for curved reference paths refactor: extend base_path_s with extrapolated base_path_x, base_path_y, base_path_z if min_s is negative refactor: linear path when object is moving backward feat: Update getFrenetPoint function to include target_path parameter The getFrenetPoint function in path_generator.hpp and path_generator.cpp has been updated to include a new parameter called target_path. This parameter is used to trim the reference path based on the starting segment index, allowing for more accurate calculations. * feat: Add interpolationLerp function for linear interpolation Signed-off-by: Taekjin LEE * Update starting_segment_idx type in getFrenetPoint function Signed-off-by: Taekjin LEE refactor: Update starting_segment_idx type in getFrenetPoint function refactor: Update getFrenetPoint function to include target_path parameter refactor: exclude target path determination logic from getFrenetPoint refactor: Add interpolationLerp function for quaternion linear interpolation refactor: remove redundant yaw height update refactor: Update path_generator.cpp to include object height in predicted_pose fix: comment out optimum target searcher * feat: implement a new optimization of target ref path search Signed-off-by: Taekjin LEE refactor: Update path_generator.cpp to include object height in predicted_pose refactor: measure performance refactor: remove comment-outs, measure times style(pre-commit): autofix refactor: move starting point search function to getPredictedReferencePath refactor: target segment index search parameter adjust * fix: replace nearest search to custom one for efficiency Signed-off-by: Taekjin LEE feat: Update CLOSE_LANELET_THRESHOLD and CLOSE_PATH_THRESHOLD values Signed-off-by: Taekjin LEE * refactor: getFrenetPoint blocks Signed-off-by: Taekjin LEE * chore: add comments Signed-off-by: Taekjin LEE * feat: Trim reference paths if optimum position is not found Signed-off-by: Taekjin LEE style(pre-commit): autofix chore: remove comment Signed-off-by: Taekjin LEE * fix: shadowVariable of time keeper pointers Signed-off-by: Taekjin LEE * refactor: improve backlash width calculation, parameter adjustment Signed-off-by: Taekjin LEE * fix: cylinder type object do not have y dimension, use x dimension Signed-off-by: Taekjin LEE * chore: add comment to explain an internal parameter 'margin' Signed-off-by: Taekjin LEE * chore: add comment of backlash calculation shortcut Signed-off-by: Taekjin LEE * chore: Improve readability of backlash to target shift model Signed-off-by: Taekjin LEE * feat: set the return width by the path width Signed-off-by: Taekjin LEE * refactor: separate a logic to searchProperStartingRefPathIndex function Signed-off-by: Taekjin LEE * refactor: search starting ref path using optional for return type Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../map_based_prediction_node.hpp | 9 +- .../map_based_prediction/path_generator.hpp | 21 +- .../src/map_based_prediction_node.cpp | 160 +++++++++- .../src/path_generator.cpp | 278 ++++++++++++++---- 4 files changed, 384 insertions(+), 84 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 3078fe89444b8..d1d8bb172d247 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 @@ -127,6 +127,7 @@ struct PredictedRefPath { float probability; double speed_limit; + double width; PosePath path; Maneuver maneuver; }; @@ -291,6 +292,8 @@ class MapBasedPredictionNode : public rclcpp::Node const std::string & object_id); std::string tryMatchNewObjectToDisappeared( const std::string & object_id, std::unordered_map & current_users); + std::optional searchProperStartingRefPathIndex( + const TrackedObject & object, const PosePath & pose_path) const; std::vector getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, const double object_detected_time, const double time_horizon); @@ -315,9 +318,11 @@ class MapBasedPredictionNode : public rclcpp::Node const Maneuver & maneuver, std::vector & reference_paths, const double speed_limit = 0.0); - mutable universe_utils::LRUCache> + mutable universe_utils::LRUCache< + lanelet::routing::LaneletPaths, std::vector>> lru_cache_of_convert_path_type_{1000}; - std::vector convertPathType(const lanelet::routing::LaneletPaths & paths) const; + std::vector> convertPathType( + const lanelet::routing::LaneletPaths & paths) const; void updateFuturePossibleLanelets( const TrackedObject & object, const lanelet::routing::LaneletPaths & paths); diff --git a/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp index 8861598ae7fb2..416efd2aa5616 100644 --- a/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp +++ b/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp @@ -23,7 +23,11 @@ #include #include #include +#include #include +#include + +#include #include #include @@ -95,8 +99,9 @@ class PathGenerator const TrackedObject & object, const double duration) const; PredictedPath generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_paths, const double duration, - const double lateral_duration, const double speed_limit = 0.0) const; + const TrackedObject & object, const PosePath & ref_path, const double duration, + const double lateral_duration, const double path_width = 0.0, + const double speed_limit = 0.0) const; PredictedPath generatePathForCrosswalkUser( const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk, @@ -129,7 +134,8 @@ class PathGenerator PredictedPath generatePolynomialPath( const TrackedObject & object, const PosePath & ref_path, const double duration, - const double lateral_duration, const double speed_limit = 0.0) const; + const double lateral_duration, const double path_width, const double backlash_width, + const double speed_limit = 0.0) const; FrenetPath generateFrenetPath( const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length, @@ -139,6 +145,13 @@ class PathGenerator Eigen::Vector2d calcLonCoefficients( const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) const; + std::vector interpolationLerp( + const std::vector & base_keys, const std::vector & base_values, + const std::vector & query_keys) const; + std::vector interpolationLerp( + const std::vector & base_keys, const std::vector & base_values, + const std::vector & query_keys) const; + PosePath interpolateReferencePath( const PosePath & base_path, const FrenetPath & frenet_predicted_path) const; @@ -147,7 +160,7 @@ class PathGenerator const PosePath & ref_path) const; FrenetPoint getFrenetPoint( - const TrackedObject & object, const PosePath & ref_path, const double duration, + const TrackedObject & object, const geometry_msgs::msg::Pose & ref_pose, const double duration, const double speed_limit = 0.0) const; }; } // namespace autoware::map_based_prediction 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 bd8b6557bc3b6..7e08fc180a90d 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 @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -1114,7 +1115,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // If predicted reference path is empty, assume this object is out of the lane if (ref_paths.empty()) { - PredictedPath predicted_path = path_generator_->generatePathForLowSpeedVehicle( + PredictedPath predicted_path = path_generator_->generatePathForOffLaneVehicle( transformed_object, prediction_time_horizon_.vehicle); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) break; @@ -1153,7 +1154,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt for (const auto & ref_path : ref_paths) { PredictedPath predicted_path = path_generator_->generatePathForOnLaneVehicle( yaw_fixed_transformed_object, ref_path.path, prediction_time_horizon_.vehicle, - lateral_control_time_horizon_, ref_path.speed_limit); + lateral_control_time_horizon_, ref_path.width, ref_path.speed_limit); if (predicted_path.path.empty()) continue; if (!check_lateral_acceleration_constraints_) { @@ -1844,6 +1845,100 @@ void MapBasedPredictionNode::updateRoadUsersHistory( } } +std::optional MapBasedPredictionNode::searchProperStartingRefPathIndex( + const TrackedObject & object, const PosePath & pose_path) const +{ + std::unique_ptr st1_ptr; + if (time_keeper_) st1_ptr = std::make_unique(__func__, *time_keeper_); + + bool is_position_found = false; + std::optional opt_index{std::nullopt}; + auto & index = opt_index.emplace(); + + // starting segment index is a segment close enough to the object + const auto obj_point = object.kinematics.pose_with_covariance.pose.position; + { + std::unique_ptr st2_ptr; + if (time_keeper_) + st2_ptr = std::make_unique("find_close_segment_index", *time_keeper_); + double min_dist_sq = std::numeric_limits::max(); + constexpr double acceptable_dist_sq = 1.0; // [m2] + for (size_t i = 0; i < pose_path.size(); i++) { + const double dx = pose_path.at(i).position.x - obj_point.x; + const double dy = pose_path.at(i).position.y - obj_point.y; + const double dist_sq = dx * dx + dy * dy; + if (dist_sq < min_dist_sq) { + min_dist_sq = dist_sq; + index = i; + } + if (dist_sq < acceptable_dist_sq) { + break; + } + } + } + + // calculate score that object can reach the target path smoothly, and search the + // starting segment index that have the best score + size_t idx = 0; + { // find target segmentation index + std::unique_ptr st3_ptr; + if (time_keeper_) + st3_ptr = std::make_unique("find_target_seg_index", *time_keeper_); + + constexpr double search_distance = 22.0; // [m] + constexpr double yaw_diff_limit = M_PI / 3.0; // 60 degrees + + const double obj_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + const size_t search_segment_count = + static_cast(std::floor(search_distance / reference_path_resolution_)); + const size_t search_segment_num = + std::min(search_segment_count, static_cast(pose_path.size() - index)); + + // search for the best score, which is the smallest + double best_score = 1e9; // initial value is large enough + for (size_t i = 0; i < search_segment_num; ++i) { + const auto & path_pose = pose_path.at(index + i); + // yaw difference + const double path_yaw = tf2::getYaw(path_pose.orientation); + const double relative_path_yaw = autoware_utils::normalize_radian(path_yaw - obj_yaw); + if (std::abs(relative_path_yaw) > yaw_diff_limit) { + continue; + } + + const double dx = path_pose.position.x - obj_point.x; + const double dy = path_pose.position.y - obj_point.y; + const double dx_cp = std::cos(obj_yaw) * dx + std::sin(obj_yaw) * dy; + const double dy_cp = -std::sin(obj_yaw) * dx + std::cos(obj_yaw) * dy; + const double neutral_yaw = std::atan2(dy_cp, dx_cp) * 2.0; + const double delta_yaw = autoware_utils::normalize_radian(path_yaw - obj_yaw - neutral_yaw); + if (std::abs(delta_yaw) > yaw_diff_limit) { + continue; + } + + // objective function score + constexpr double weight_ratio = 0.01; + double score = delta_yaw * delta_yaw + weight_ratio * neutral_yaw * neutral_yaw; + constexpr double acceptable_score = 1e-3; + + if (score < best_score) { + best_score = score; + idx = i; + is_position_found = true; + if (score < acceptable_score) { + // if the score is small enough, we can break the loop + break; + } + } + } + } + + // update starting segment index + index += idx; + index = std::clamp(index, 0ul, pose_path.size() - 1); + + return is_position_found ? opt_index : std::nullopt; +} + std::vector MapBasedPredictionNode::getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, const double object_detected_time, const double time_horizon) @@ -1851,6 +1946,7 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + // Step 1. Set conditions for the prediction const double obj_vel = std::hypot( object.kinematics.twist_with_covariance.twist.linear.x, object.kinematics.twist_with_covariance.twist.linear.y); @@ -1891,9 +1987,10 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( return search_dist; }; + // Step 2. Get possible paths for each lanelet std::vector all_ref_paths; - for (const auto & current_lanelet_data : current_lanelets_data) { + // Set condition on each lanelet const lanelet::traffic_rules::SpeedLimitInformation limit = traffic_rules_ptr_->speedLimit(current_lanelet_data.lanelet); const double legal_speed_limit = static_cast(limit.speedLimit.value()); @@ -1959,22 +2056,21 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( return std::nullopt; }; - // Step1. Get the path - // Step1.1 Get the left lanelet + // a-1. Get the left lanelet lanelet::routing::LaneletPaths left_paths; const auto left_lanelet = getLeftOrRightLanelets(current_lanelet_data.lanelet, true); if (!!left_lanelet) { left_paths = getPathsForNormalOrIsolatedLanelet(left_lanelet.value()); } - // Step1.2 Get the right lanelet + // a-2. Get the right lanelet lanelet::routing::LaneletPaths right_paths; const auto right_lanelet = getLeftOrRightLanelets(current_lanelet_data.lanelet, false); if (!!right_lanelet) { right_paths = getPathsForNormalOrIsolatedLanelet(right_lanelet.value()); } - // Step1.3 Get the centerline + // a-3. Get the center lanelet lanelet::routing::LaneletPaths center_paths = getPathsForNormalOrIsolatedLanelet(current_lanelet_data.lanelet); @@ -1983,15 +2079,15 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( continue; } - // Step2. Predict Object Maneuver + // b. Predict Object Maneuver const Maneuver predicted_maneuver = predictObjectManeuver(object, current_lanelet_data, object_detected_time); - // Step3. Allocate probability for each predicted maneuver + // c. Allocate probability for each predicted maneuver const auto maneuver_prob = calculateManeuverProbability(predicted_maneuver, left_paths, right_paths, center_paths); - // Step4. add candidate reference paths to the all_ref_paths + // d. add candidate reference paths to the all_ref_paths const float path_prob = current_lanelet_data.probability; const auto addReferencePathsLocal = [&](const auto & paths, const auto & maneuver) { addReferencePaths( @@ -2002,6 +2098,31 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( addReferencePathsLocal(center_paths, Maneuver::LANE_FOLLOW); } + // Step 3. Search starting point for each reference path + for (auto it = all_ref_paths.begin(); it != all_ref_paths.end();) { + std::unique_ptr st1_ptr; + if (time_keeper_) + st1_ptr = + std::make_unique("searching_refpath_starting_point", *time_keeper_); + + auto & pose_path = it->path; + if (pose_path.empty()) { + continue; + } + + const std::optional opt_starting_idx = + searchProperStartingRefPathIndex(object, pose_path); + + if (opt_starting_idx.has_value()) { + // Trim the reference path + pose_path.erase(pose_path.begin(), pose_path.begin() + opt_starting_idx.value()); + ++it; + } else { + // Proper starting point is not found, remove the reference path + it = all_ref_paths.erase(it); + } + } + return all_ref_paths; } @@ -2341,7 +2462,8 @@ void MapBasedPredictionNode::addReferencePaths( for (const auto & converted_path : converted_paths) { PredictedRefPath predicted_path; predicted_path.probability = maneuver_probability.at(maneuver) * path_probability; - predicted_path.path = converted_path; + predicted_path.path = converted_path.first; + predicted_path.width = converted_path.second; predicted_path.maneuver = maneuver; predicted_path.speed_limit = speed_limit; reference_paths.push_back(predicted_path); @@ -2416,7 +2538,7 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability( return maneuver_prob; } -std::vector MapBasedPredictionNode::convertPathType( +std::vector> MapBasedPredictionNode::convertPathType( const lanelet::routing::LaneletPaths & paths) const { std::unique_ptr st_ptr; @@ -2426,9 +2548,10 @@ std::vector MapBasedPredictionNode::convertPathType( return *lru_cache_of_convert_path_type_.get(paths); } - std::vector converted_paths; + std::vector> converted_paths; for (const auto & path : paths) { PosePath converted_path; + double width = 10.0; // Initialize with a large value // Insert Positions. Note that we start inserting points from previous lanelet if (!path.empty()) { @@ -2446,6 +2569,7 @@ std::vector MapBasedPredictionNode::convertPathType( continue; } + // only considers yaw of the lanelet const double lane_yaw = std::atan2( current_p.position.y - prev_p.position.y, current_p.position.x - prev_p.position.x); const double sin_yaw_half = std::sin(lane_yaw / 2.0); @@ -2495,6 +2619,14 @@ std::vector MapBasedPredictionNode::convertPathType( converted_path.push_back(current_p); prev_p = current_p; } + + // Update minimum width + const auto left_bound = lanelet.leftBound2d(); + const auto right_bound = lanelet.rightBound2d(); + const double lanelet_width_front = std::hypot( + left_bound.front().x() - right_bound.front().x(), + left_bound.front().y() - right_bound.front().y()); + width = std::min(width, lanelet_width_front); } // Resample Path @@ -2506,7 +2638,7 @@ std::vector MapBasedPredictionNode::convertPathType( // interpolation for xy const auto resampled_converted_path = autoware::motion_utils::resamplePoseVector( converted_path, reference_path_resolution_, use_akima_spline_for_xy, use_lerp_for_z); - converted_paths.push_back(resampled_converted_path); + converted_paths.push_back(std::make_pair(resampled_converted_path, width)); } lru_cache_of_convert_path_type_.put(paths, converted_paths); diff --git a/perception/autoware_map_based_prediction/src/path_generator.cpp b/perception/autoware_map_based_prediction/src/path_generator.cpp index 4b759e22cdb4f..4f9f7a7586ce6 100644 --- a/perception/autoware_map_based_prediction/src/path_generator.cpp +++ b/perception/autoware_map_based_prediction/src/path_generator.cpp @@ -175,17 +175,37 @@ PredictedPath PathGenerator::generatePathForOffLaneVehicle( } PredictedPath PathGenerator::generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_paths, const double duration, - const double lateral_duration, const double speed_limit) const + const TrackedObject & object, const PosePath & ref_path, const double duration, + const double lateral_duration, const double path_width, const double speed_limit) const { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - if (ref_paths.size() < 2) { + if (ref_path.size() < 2) { + return generateStraightPath(object, duration); + } + + // if the object is moving backward, we generate a straight path + if (object.kinematics.twist_with_covariance.twist.linear.x < 0.0) { return generateStraightPath(object, duration); } - return generatePolynomialPath(object, ref_paths, duration, lateral_duration, speed_limit); + // get object width + double object_width = 5.0; // a large number + if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { + object_width = object.shape.dimensions.y; + } else if (object.shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { + object_width = object.shape.dimensions.x; + } + // Calculate the backlash width, which represents the maximum distance the object can be biased + // from the reference path + constexpr double margin = + 0.5; // Set a safety margin of 0.5m for the object to stay away from the edge of the lane + double backlash_width = (path_width - object_width) / 2.0 - margin; + backlash_width = std::max(backlash_width, 0.0); // minimum is 0.0 + + return generatePolynomialPath( + object, ref_path, duration, lateral_duration, path_width, backlash_width, speed_limit); } PredictedPath PathGenerator::generateStraightPath( @@ -210,37 +230,68 @@ PredictedPath PathGenerator::generateStraightPath( PredictedPath PathGenerator::generatePolynomialPath( const TrackedObject & object, const PosePath & ref_path, const double duration, - const double lateral_duration, const double speed_limit) const + const double lateral_duration, const double path_width, const double backlash_width, + const double speed_limit) const { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); // Get current Frenet Point const double ref_path_len = autoware::motion_utils::calcArcLength(ref_path); - const auto current_point = getFrenetPoint(object, ref_path, duration, speed_limit); + const auto current_point = getFrenetPoint(object, ref_path.at(0), duration, speed_limit); - // Step1. Set Target Frenet Point + // Step 1. Set Target Frenet Point // Note that we do not set position s, // since we don't know the target longitudinal position FrenetPoint terminal_point; - terminal_point.s_vel = current_point.s_vel; + terminal_point.s_vel = std::hypot(current_point.s_vel, current_point.d_vel); terminal_point.s_acc = 0.0; - terminal_point.d = 0.0; terminal_point.d_vel = 0.0; terminal_point.d_acc = 0.0; - // Step2. Generate Predicted Path on a Frenet coordinate + // calculate terminal d position, based on backlash width + { + if (backlash_width < 0.01 /*m*/) { + // If the backlash width is less than 0.01m, do not consider the backlash width and reduce + // calculation cost + terminal_point.d = 0.0; + } else { + const double return_width = path_width / 2.0; // [m] + const double current_momentum_d = + current_point.d + 0.5 * current_point.d_vel * lateral_duration; + const double momentum_d_abs = std::abs(current_momentum_d); + + if (momentum_d_abs < backlash_width) { + // If the object momentum is within the backlash width, we set the target d position to the + // current momentum + terminal_point.d = current_momentum_d; + } else if ( + momentum_d_abs >= backlash_width && momentum_d_abs < backlash_width + return_width) { + // If the object momentum is within the return zone, we set the target d position close to + // the zero gradually + terminal_point.d = + (backlash_width + return_width - momentum_d_abs) * backlash_width / return_width; + terminal_point.d *= (current_momentum_d > 0) ? 1 : -1; + } else { + // If the object momentum is outside the backlash width + return zone, we set the target d + // position to 0 + terminal_point.d = 0.0; + } + } + } + + // Step 2. Generate Predicted Path on a Frenet coordinate const auto frenet_predicted_path = generateFrenetPath(current_point, terminal_point, ref_path_len, duration, lateral_duration); - // Step3. Interpolate Reference Path for converting predicted path coordinate + // Step 3. Interpolate Reference Path for converting predicted path coordinate const auto interpolated_ref_path = interpolateReferencePath(ref_path, frenet_predicted_path); if (frenet_predicted_path.size() < 2 || interpolated_ref_path.size() < 2) { return generateStraightPath(object, duration); } - // Step4. Convert predicted trajectory from Frenet to Cartesian coordinate + // Step 4. Convert predicted trajectory from Frenet to Cartesian coordinate return convertToPredictedPath(object, frenet_predicted_path, interpolated_ref_path); } @@ -258,6 +309,7 @@ FrenetPath PathGenerator::generateFrenetPath( calcLatCoefficients(current_point, target_point, lateral_duration); const Eigen::Vector2d lon_coeff = calcLonCoefficients(current_point, target_point, duration); + // Generate the trajectory path.reserve(static_cast(duration / sampling_time_interval_)); for (double t = 0.0; t <= duration; t += sampling_time_interval_) { const auto t2 = t * t; @@ -268,22 +320,19 @@ FrenetPath PathGenerator::generateFrenetPath( 0.0; // Currently we assume the object is traveling at a constant speed const double d_next_ = current_point.d + current_point.d_vel * t + current_acc * 2.0 * t2 + lat_coeff(0) * t3 + lat_coeff(1) * t4 + lat_coeff(2) * t5; - // t > lateral_duration: 0.0, else d_next_ - const double d_next = t > lateral_duration ? 0.0 : d_next_; + // t > lateral_duration: target_point.d, else d_next_ + const double d_next = t > lateral_duration ? target_point.d : d_next_; const double s_next = current_point.s + current_point.s_vel * t + 2.0 * current_acc * t2 + lon_coeff(0) * t3 + lon_coeff(1) * t4; + if (s_next > max_length) { break; } - // We assume the object is traveling at a constant speed along s direction + // Fill the FrenetPoint, velocity and acceleration are not used in the path generator FrenetPoint point; - point.s = std::max(s_next, 0.0); - point.s_vel = current_point.s_vel; - point.s_acc = current_point.s_acc; + point.s = s_next; point.d = d_next; - point.d_vel = current_point.d_vel; - point.d_acc = current_point.d_acc; path.push_back(point); } @@ -340,6 +389,107 @@ Eigen::Vector2d PathGenerator::calcLonCoefficients( return A_lon_inv * b_lon; } +std::vector PathGenerator::interpolationLerp( + const std::vector & base_keys, const std::vector & base_values, + const std::vector & query_keys) const +{ + std::unique_ptr st_ptr; + if (time_keeper_) + st_ptr = std::make_unique("interpolationLerp_double", *time_keeper_); + + // calculate linear interpolation + // extrapolate the value if the query key is out of the base key range + std::vector query_values; + size_t key_index = 0; + double last_query_key = query_keys.at(0); + for (const auto query_key : query_keys) { + // search for the closest key index + // if current query key is larger than the last query key, search base_keys increasing order + if (query_key >= last_query_key) { + while (base_keys.at(key_index + 1) < query_key) { + if (key_index == base_keys.size() - 2) { + break; + } + ++key_index; + } + } else { + // if current query key is smaller than the last query key, search base_keys decreasing order + while (base_keys.at(key_index) > query_key) { + if (key_index == 0) { + break; + } + --key_index; + } + } + last_query_key = query_key; + + const double & src_val = base_values.at(key_index); + const double & dst_val = base_values.at(key_index + 1); + const double ratio = (query_key - base_keys.at(key_index)) / + (base_keys.at(key_index + 1) - base_keys.at(key_index)); + + const double interpolated_val = src_val + (dst_val - src_val) * ratio; + query_values.push_back(interpolated_val); + } + + return query_values; +} + +std::vector PathGenerator::interpolationLerp( + const std::vector & base_keys, const std::vector & base_values, + const std::vector & query_keys) const +{ + std::unique_ptr st_ptr; + if (time_keeper_) + st_ptr = std::make_unique("interpolationLerp_quaternion", *time_keeper_); + + // calculate linear interpolation + // extrapolate the value if the query key is out of the base key range + std::vector query_values; + size_t key_index = 0; + double last_query_key = query_keys.at(0); + for (const auto query_key : query_keys) { + // search for the closest key index + // if current query key is larger than the last query key, search base_keys increasing order + if (query_key >= last_query_key) { + while (base_keys.at(key_index + 1) < query_key) { + if (key_index == base_keys.size() - 2) { + break; + } + ++key_index; + } + } else { + // if current query key is smaller than the last query key, search base_keys decreasing order + while (base_keys.at(key_index) > query_key) { + if (key_index == 0) { + break; + } + --key_index; + } + } + last_query_key = query_key; + + const tf2::Quaternion & src_val = base_values.at(key_index); + const tf2::Quaternion & dst_val = base_values.at(key_index + 1); + const double ratio = (query_key - base_keys.at(key_index)) / + (base_keys.at(key_index + 1) - base_keys.at(key_index)); + + // in case of extrapolation, export the nearest quaternion + if (ratio < 0.0) { + query_values.push_back(src_val); + continue; + } + if (ratio > 1.0) { + query_values.push_back(dst_val); + continue; + } + const auto interpolated_quat = tf2::slerp(src_val, dst_val, ratio); + query_values.push_back(interpolated_quat); + } + + return query_values; +} + PosePath PathGenerator::interpolateReferencePath( const PosePath & base_path, const FrenetPath & frenet_predicted_path) const { @@ -353,49 +503,47 @@ PosePath PathGenerator::interpolateReferencePath( return interpolated_path; } + // Prepare base path vectors std::vector base_path_x(base_path.size()); std::vector base_path_y(base_path.size()); std::vector base_path_z(base_path.size()); + std::vector base_path_orientation(base_path.size()); std::vector base_path_s(base_path.size(), 0.0); for (size_t i = 0; i < base_path.size(); ++i) { base_path_x.at(i) = base_path.at(i).position.x; base_path_y.at(i) = base_path.at(i).position.y; base_path_z.at(i) = base_path.at(i).position.z; + tf2::Quaternion src_tf; + tf2::fromMsg(base_path.at(i).orientation, src_tf); + base_path_orientation.at(i) = src_tf; if (i > 0) { base_path_s.at(i) = base_path_s.at(i - 1) + autoware::universe_utils::calcDistance2d( base_path.at(i - 1), base_path.at(i)); } } + // Prepare resampled s vector std::vector resampled_s(frenet_predicted_path.size()); for (size_t i = 0; i < frenet_predicted_path.size(); ++i) { resampled_s.at(i) = frenet_predicted_path.at(i).s; } - if (resampled_s.front() > resampled_s.back()) { - std::reverse(resampled_s.begin(), resampled_s.end()); - } - // Lerp Interpolation - std::vector lerp_ref_path_x = interpolation::lerp(base_path_s, base_path_x, resampled_s); - std::vector lerp_ref_path_y = interpolation::lerp(base_path_s, base_path_y, resampled_s); - std::vector lerp_ref_path_z = interpolation::lerp(base_path_s, base_path_z, resampled_s); + // Linear Interpolation for x, y, z, and orientation + std::vector lerp_ref_path_x = interpolationLerp(base_path_s, base_path_x, resampled_s); + std::vector lerp_ref_path_y = interpolationLerp(base_path_s, base_path_y, resampled_s); + std::vector lerp_ref_path_z = interpolationLerp(base_path_s, base_path_z, resampled_s); + std::vector lerp_ref_path_orientation = + interpolationLerp(base_path_s, base_path_orientation, resampled_s); + // Set the interpolated PosePath interpolated_path.resize(interpolate_num); - for (size_t i = 0; i < interpolate_num - 1; ++i) { + for (size_t i = 0; i < interpolate_num; ++i) { geometry_msgs::msg::Pose interpolated_pose; - const auto current_point = - autoware::universe_utils::createPoint(lerp_ref_path_x.at(i), lerp_ref_path_y.at(i), 0.0); - const auto next_point = autoware::universe_utils::createPoint( - lerp_ref_path_x.at(i + 1), lerp_ref_path_y.at(i + 1), 0.0); - const double yaw = autoware::universe_utils::calcAzimuthAngle(current_point, next_point); interpolated_pose.position = autoware::universe_utils::createPoint( lerp_ref_path_x.at(i), lerp_ref_path_y.at(i), lerp_ref_path_z.at(i)); - interpolated_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); + interpolated_pose.orientation = tf2::toMsg(lerp_ref_path_orientation.at(i)); interpolated_path.at(i) = interpolated_pose; } - interpolated_path.back().position = autoware::universe_utils::createPoint( - lerp_ref_path_x.back(), lerp_ref_path_y.back(), lerp_ref_path_z.back()); - interpolated_path.back().orientation = interpolated_path.at(interpolate_num - 2).orientation; return interpolated_path; } @@ -407,27 +555,30 @@ PredictedPath PathGenerator::convertToPredictedPath( std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + // Object position + const auto & object_pose = object.kinematics.pose_with_covariance.pose; + const double object_height = object.shape.dimensions.z / 2.0; + + // Convert Frenet Path to Cartesian Path PredictedPath predicted_path; predicted_path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); predicted_path.path.resize(ref_path.size()); - for (size_t i = 0; i < predicted_path.path.size(); ++i) { + + // Set the first point as the object's current position + predicted_path.path.at(0) = object_pose; + + // Convert the rest of the points + for (size_t i = 1; i < predicted_path.path.size(); ++i) { // Reference Point from interpolated reference path const auto & ref_pose = ref_path.at(i); // Frenet Point from frenet predicted path const auto & frenet_point = frenet_predicted_path.at(i); + double d_offset = frenet_point.d; // Converted Pose - auto predicted_pose = - autoware::universe_utils::calcOffsetPose(ref_pose, 0.0, frenet_point.d, 0.0); - predicted_pose.position.z = object.kinematics.pose_with_covariance.pose.position.z; - if (i == 0) { - predicted_pose.orientation = object.kinematics.pose_with_covariance.pose.orientation; - } else { - const double yaw = autoware::universe_utils::calcAzimuthAngle( - predicted_path.path.at(i - 1).position, predicted_pose.position); - predicted_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); - } + auto predicted_pose = autoware::universe_utils::calcOffsetPose(ref_pose, 0.0, d_offset, 0.0); + predicted_pose.position.z += object_height; predicted_path.path.at(i) = predicted_pose; } @@ -435,27 +586,27 @@ PredictedPath PathGenerator::convertToPredictedPath( } FrenetPoint PathGenerator::getFrenetPoint( - const TrackedObject & object, const PosePath & ref_path, const double duration, + const TrackedObject & object, const geometry_msgs::msg::Pose & ref_pose, const double duration, const double speed_limit) const { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); FrenetPoint frenet_point; - const auto obj_point = object.kinematics.pose_with_covariance.pose.position; - const size_t nearest_segment_idx = - autoware::motion_utils::findNearestSegmentIndex(ref_path, obj_point); - const double l = autoware::motion_utils::calcLongitudinalOffsetToSegment( - ref_path, nearest_segment_idx, obj_point); - const float vx = static_cast(object.kinematics.twist_with_covariance.twist.linear.x); - const float vy = static_cast(object.kinematics.twist_with_covariance.twist.linear.y); + // 1. Position + const auto obj_point = object.kinematics.pose_with_covariance.pose.position; const float obj_yaw = static_cast(tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)); - const float lane_yaw = - static_cast(tf2::getYaw(ref_path.at(nearest_segment_idx).orientation)); - const float delta_yaw = obj_yaw - lane_yaw; + const float lane_yaw = static_cast(tf2::getYaw(ref_pose.orientation)); + frenet_point.s = (obj_point.x - ref_pose.position.x) * cos(lane_yaw) + + (obj_point.y - ref_pose.position.y) * sin(lane_yaw); + frenet_point.d = -(obj_point.x - ref_pose.position.x) * sin(lane_yaw) + + (obj_point.y - ref_pose.position.y) * cos(lane_yaw); + // 2. Velocity (adjusted by acceleration) + const float vx = static_cast(object.kinematics.twist_with_covariance.twist.linear.x); + const float vy = static_cast(object.kinematics.twist_with_covariance.twist.linear.y); const float ax = (use_vehicle_acceleration_) ? static_cast(object.kinematics.acceleration_with_covariance.accel.linear.x) @@ -464,8 +615,9 @@ FrenetPoint PathGenerator::getFrenetPoint( (use_vehicle_acceleration_) ? static_cast(object.kinematics.acceleration_with_covariance.accel.linear.y) : 0.0; + const float delta_yaw = obj_yaw - lane_yaw; - // Using a decaying acceleration model. Consult the README for more information about the model. + // using a decaying acceleration model. Consult the README for more information about the model. const double t_h = duration; const float lambda = std::log(2) / acceleration_exponential_half_life_; @@ -527,14 +679,12 @@ FrenetPoint PathGenerator::getFrenetPoint( const float acceleration_adjusted_velocity_x = get_acceleration_adjusted_velocity(vx, ax); const float acceleration_adjusted_velocity_y = get_acceleration_adjusted_velocity(vy, ay); - - frenet_point.s = - autoware::motion_utils::calcSignedArcLength(ref_path, 0, nearest_segment_idx) + l; - frenet_point.d = autoware::motion_utils::calcLateralOffset(ref_path, obj_point); frenet_point.s_vel = acceleration_adjusted_velocity_x * std::cos(delta_yaw) - acceleration_adjusted_velocity_y * std::sin(delta_yaw); frenet_point.d_vel = acceleration_adjusted_velocity_x * std::sin(delta_yaw) + acceleration_adjusted_velocity_y * std::cos(delta_yaw); + + // 3. Acceleration, assuming constant acceleration frenet_point.s_acc = 0.0; frenet_point.d_acc = 0.0; From d5f733904e53f61447fead469ec78ac8b3c17a56 Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Mon, 9 Sep 2024 11:22:06 +0900 Subject: [PATCH 153/217] fix(autoware_pointcloud_preprocessor): static TF listener as Filter option (#8678) Signed-off-by: amadeuszsz --- ...uffer.hpp => managed_transform_buffer.hpp} | 139 +++++++++++++----- ....cpp => test_managed_transform_buffer.cpp} | 96 +++++------- .../autoware_ground_segmentation/README.md | 17 ++- .../docs/ransac-ground-filter.md | 1 + .../docs/ray-ground-filter.md | 1 + .../docs/scan-ground-filter.md | 1 + .../src/ransac_ground_filter/node.cpp | 6 +- .../src/ransac_ground_filter/node.hpp | 4 +- .../config/concatenate_pointclouds.param.yaml | 1 + .../distortion_corrector_node.param.yaml | 1 + .../config/time_synchronizer_node.param.yaml | 1 + .../docs/concatenate-data.md | 13 +- .../concatenate_and_time_sync_nodelet.hpp | 7 +- .../concatenate_pointclouds.hpp | 7 +- .../distortion_corrector.hpp | 19 ++- .../pointcloud_preprocessor/filter.hpp | 12 +- .../time_synchronizer_node.hpp | 7 +- .../concatenate_pointclouds.schema.json | 14 +- .../distortion_corrector_node.schema.json | 7 +- .../schema/time_synchronizer_node.schema.json | 6 + .../concatenate_and_time_sync_nodelet.cpp | 11 +- .../concatenate_pointclouds.cpp | 8 +- .../distortion_corrector.cpp | 6 +- .../distortion_corrector_node.cpp | 6 +- .../src/filter.cpp | 26 +++- .../time_synchronizer_node.cpp | 12 +- .../test/test_distortion_corrector_node.cpp | 4 +- 27 files changed, 269 insertions(+), 164 deletions(-) rename common/autoware_universe_utils/include/autoware/universe_utils/ros/{static_transform_buffer.hpp => managed_transform_buffer.hpp} (54%) rename common/autoware_universe_utils/test/src/ros/{test_static_transform_buffer.cpp => test_managed_transform_buffer.cpp} (59%) diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/static_transform_buffer.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/managed_transform_buffer.hpp similarity index 54% rename from common/autoware_universe_utils/include/autoware/universe_utils/ros/static_transform_buffer.hpp rename to common/autoware_universe_utils/include/autoware/universe_utils/ros/managed_transform_buffer.hpp index 175d1934e973d..9d96dc9e6b133 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/static_transform_buffer.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/managed_transform_buffer.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__UNIVERSE_UTILS__ROS__STATIC_TRANSFORM_BUFFER_HPP_ -#define AUTOWARE__UNIVERSE_UTILS__ROS__STATIC_TRANSFORM_BUFFER_HPP_ +#ifndef AUTOWARE__UNIVERSE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ +#define AUTOWARE__UNIVERSE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ #include "autoware/universe_utils/ros/transform_listener.hpp" @@ -29,6 +29,7 @@ #include #include #include +#include #include #include @@ -58,12 +59,69 @@ struct PairEqual } }; using TFMap = std::unordered_map, PairEqual>; +constexpr std::array warn_frames = {"map", "odom", "world"}; -class StaticTransformBuffer +class ManagedTransformBuffer { public: - StaticTransformBuffer() = default; + explicit ManagedTransformBuffer(rclcpp::Node * node, const bool & has_static_tf_only) + : node_(node) + { + if (has_static_tf_only) { + get_transform_ = [this]( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) { + return getStaticTransform(target_frame, source_frame, eigen_transform); + }; + } else { + tf_listener_ = std::make_unique(node); + get_transform_ = [this]( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) { + return getDynamicTransform(target_frame, source_frame, eigen_transform); + }; + } + } + + bool getTransform( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) + { + return get_transform_(target_frame, source_frame, eigen_transform); + } + + /** + * Transforms a point cloud from one frame to another. + * + * @param target_frame The target frame to transform the point cloud to. + * @param cloud_in The input point cloud to be transformed. + * @param cloud_out The transformed point cloud. + * @return True if the transformation is successful, false otherwise. + */ + bool transformPointcloud( + const std::string & target_frame, const sensor_msgs::msg::PointCloud2 & cloud_in, + sensor_msgs::msg::PointCloud2 & cloud_out) + { + if ( + pcl::getFieldIndex(cloud_in, "x") == -1 || pcl::getFieldIndex(cloud_in, "y") == -1 || + pcl::getFieldIndex(cloud_in, "z") == -1) { + RCLCPP_ERROR(node_->get_logger(), "Input pointcloud does not have xyz fields"); + return false; + } + if (target_frame == cloud_in.header.frame_id) { + cloud_out = cloud_in; + return true; + } + Eigen::Matrix4f eigen_transform; + if (!getTransform(target_frame, cloud_in.header.frame_id, eigen_transform)) { + return false; + } + pcl_ros::transformPointCloud(eigen_transform, cloud_in, cloud_out); + cloud_out.header.frame_id = target_frame; + return true; + } +private: /** * @brief Retrieves a transform between two static frames. * @@ -72,17 +130,24 @@ class StaticTransformBuffer * Otherwise, transform matrix is set to identity and the function returns false. Transform * Listener is destroyed after function call. * - * @param node A pointer to the ROS node. * @param target_frame The target frame. * @param source_frame The source frame. - * @param eigen_transform The output Eigen transform matrix. Is set to identity if the transform - * is not found. + * @param eigen_transform The output Eigen transform matrix. It is set to the identity if the + * transform is not found. * @return True if the transform was successfully retrieved, false otherwise. */ - bool getTransform( - rclcpp::Node * node, const std::string & target_frame, const std::string & source_frame, + bool getStaticTransform( + const std::string & target_frame, const std::string & source_frame, Eigen::Matrix4f & eigen_transform) { + if ( + std::find(warn_frames.begin(), warn_frames.end(), target_frame) != warn_frames.end() || + std::find(warn_frames.begin(), warn_frames.end(), source_frame) != warn_frames.end()) { + RCLCPP_WARN( + node_->get_logger(), "Using %s -> %s transform. This may not be a static transform.", + target_frame.c_str(), source_frame.c_str()); + } + auto key = std::make_pair(target_frame, source_frame); auto key_inv = std::make_pair(source_frame, target_frame); @@ -109,11 +174,12 @@ class StaticTransformBuffer } // Get the transform from the TF tree - auto tf_listener = std::make_unique(node); - auto tf = tf_listener->getTransform( + tf_listener_ = std::make_unique(node_); + auto tf = tf_listener_->getTransform( target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms)); + tf_listener_.reset(); RCLCPP_DEBUG( - node->get_logger(), "Trying to enqueue %s -> %s transform to static TFs buffer...", + node_->get_logger(), "Trying to enqueue %s -> %s transform to static TFs buffer...", target_frame.c_str(), source_frame.c_str()); if (tf == nullptr) { eigen_transform = Eigen::Matrix4f::Identity(); @@ -124,42 +190,39 @@ class StaticTransformBuffer return true; } - /** - * Transforms a point cloud from one frame to another. + /** @brief Retrieves a transform between two dynamic frames. * - * @param node A pointer to the ROS node. - * @param target_frame The target frame to transform the point cloud to. - * @param cloud_in The input point cloud to be transformed. - * @param cloud_out The transformed point cloud. - * @return True if the transformation is successful, false otherwise. + * This function attempts to retrieve a transform between the target frame and the source frame. + * If successful, the transformation matrix is assigned to the output parameter, and the function + * returns true. Otherwise, the transformation matrix is set to the identity and the function + * returns false. + * + * @param target_frame The target frame. + * @param source_frame The source frame. + * @param eigen_transform The output Eigen transformation matrix. It is set to the identity if the + * transform is not found. + * @return True if the transform was successfully retrieved, false otherwise. */ - bool transformPointcloud( - rclcpp::Node * node, const std::string & target_frame, - const sensor_msgs::msg::PointCloud2 & cloud_in, sensor_msgs::msg::PointCloud2 & cloud_out) + bool getDynamicTransform( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) { - if ( - pcl::getFieldIndex(cloud_in, "x") == -1 || pcl::getFieldIndex(cloud_in, "y") == -1 || - pcl::getFieldIndex(cloud_in, "z") == -1) { - RCLCPP_ERROR(node->get_logger(), "Input pointcloud does not have xyz fields"); - return false; - } - if (target_frame == cloud_in.header.frame_id) { - cloud_out = cloud_in; - return true; - } - Eigen::Matrix4f eigen_transform; - if (!getTransform(node, target_frame, cloud_in.header.frame_id, eigen_transform)) { + auto tf = tf_listener_->getTransform( + target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms)); + if (tf == nullptr) { + eigen_transform = Eigen::Matrix4f::Identity(); return false; } - pcl_ros::transformPointCloud(eigen_transform, cloud_in, cloud_out); - cloud_out.header.frame_id = target_frame; + pcl_ros::transformAsMatrix(*tf, eigen_transform); return true; } -private: TFMap buffer_; + rclcpp::Node * const node_; + std::unique_ptr tf_listener_; + std::function get_transform_; }; } // namespace autoware::universe_utils -#endif // AUTOWARE__UNIVERSE_UTILS__ROS__STATIC_TRANSFORM_BUFFER_HPP_ +#endif // AUTOWARE__UNIVERSE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ diff --git a/common/autoware_universe_utils/test/src/ros/test_static_transform_buffer.cpp b/common/autoware_universe_utils/test/src/ros/test_managed_transform_buffer.cpp similarity index 59% rename from common/autoware_universe_utils/test/src/ros/test_static_transform_buffer.cpp rename to common/autoware_universe_utils/test/src/ros/test_managed_transform_buffer.cpp index 5200378e3bf52..9df6f9bb2ffef 100644 --- a/common/autoware_universe_utils/test/src/ros/test_static_transform_buffer.cpp +++ b/common/autoware_universe_utils/test/src/ros/test_managed_transform_buffer.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/universe_utils/ros/static_transform_buffer.hpp" +#include "autoware/universe_utils/ros/managed_transform_buffer.hpp" #include #include @@ -22,11 +22,11 @@ #include -class TestStaticTransformBuffer : public ::testing::Test +class TestManagedTransformBuffer : public ::testing::Test { protected: std::shared_ptr node_{nullptr}; - std::shared_ptr static_tf_buffer_{nullptr}; + std::shared_ptr managed_tf_buffer_{nullptr}; std::shared_ptr tf_broadcaster_; geometry_msgs::msg::TransformStamped tf_base_to_lidar_; Eigen::Matrix4f eigen_base_to_lidar_; @@ -54,8 +54,9 @@ class TestStaticTransformBuffer : public ::testing::Test void SetUp() override { - node_ = std::make_shared("test_static_transform_buffer"); - static_tf_buffer_ = std::make_shared(); + node_ = std::make_shared("test_managed_transform_buffer"); + managed_tf_buffer_ = + std::make_shared(node_.get(), true); tf_broadcaster_ = std::make_shared(node_); tf_base_to_lidar_ = generateTransformMsg( @@ -91,109 +92,91 @@ class TestStaticTransformBuffer : public ::testing::Test ASSERT_TRUE(rclcpp::ok()); } - void TearDown() override { static_tf_buffer_.reset(); } + void TearDown() override { managed_tf_buffer_.reset(); } }; -TEST_F(TestStaticTransformBuffer, TestTransformNoExist) +TEST_F(TestManagedTransformBuffer, TestTransformNoExist) { Eigen::Matrix4f transform; - auto success = static_tf_buffer_->getTransform(node_.get(), "base_link", "fake_link", transform); + auto success = managed_tf_buffer_->getTransform("base_link", "fake_link", transform); EXPECT_TRUE(transform.isIdentity()); EXPECT_FALSE(success); } -TEST_F(TestStaticTransformBuffer, TestTransformBase) +TEST_F(TestManagedTransformBuffer, TestTransformBase) { Eigen::Matrix4f eigen_base_to_lidar; - auto success = - static_tf_buffer_->getTransform(node_.get(), "base_link", "lidar_top", eigen_base_to_lidar); + auto success = managed_tf_buffer_->getTransform("base_link", "lidar_top", eigen_base_to_lidar); EXPECT_TRUE(eigen_base_to_lidar.isApprox(eigen_base_to_lidar_, 0.001)); EXPECT_TRUE(success); } -TEST_F(TestStaticTransformBuffer, TestTransformSameFrame) +TEST_F(TestManagedTransformBuffer, TestTransformSameFrame) { Eigen::Matrix4f eigen_base_to_base; - auto success = - static_tf_buffer_->getTransform(node_.get(), "base_link", "base_link", eigen_base_to_base); + auto success = managed_tf_buffer_->getTransform("base_link", "base_link", eigen_base_to_base); EXPECT_TRUE(eigen_base_to_base.isApprox(Eigen::Matrix4f::Identity(), 0.001)); EXPECT_TRUE(success); } -TEST_F(TestStaticTransformBuffer, TestTransformInverse) +TEST_F(TestManagedTransformBuffer, TestTransformInverse) { Eigen::Matrix4f eigen_lidar_to_base; - auto success = - static_tf_buffer_->getTransform(node_.get(), "lidar_top", "base_link", eigen_lidar_to_base); + auto success = managed_tf_buffer_->getTransform("lidar_top", "base_link", eigen_lidar_to_base); EXPECT_TRUE(eigen_lidar_to_base.isApprox(eigen_base_to_lidar_.inverse(), 0.001)); EXPECT_TRUE(success); } -TEST_F(TestStaticTransformBuffer, TestTransformMultipleCall) +TEST_F(TestManagedTransformBuffer, TestTransformMultipleCall) { Eigen::Matrix4f eigen_transform; - EXPECT_FALSE( - static_tf_buffer_->getTransform(node_.get(), "base_link", "fake_link", eigen_transform)); + EXPECT_FALSE(managed_tf_buffer_->getTransform("base_link", "fake_link", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(Eigen::Matrix4f::Identity(), 0.001)); - EXPECT_TRUE( - static_tf_buffer_->getTransform(node_.get(), "lidar_top", "base_link", eigen_transform)); + EXPECT_TRUE(managed_tf_buffer_->getTransform("lidar_top", "base_link", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(eigen_base_to_lidar_.inverse(), 0.001)); - EXPECT_TRUE( - static_tf_buffer_->getTransform(node_.get(), "fake_link", "fake_link", eigen_transform)); + EXPECT_TRUE(managed_tf_buffer_->getTransform("fake_link", "fake_link", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(Eigen::Matrix4f::Identity(), 0.001)); - EXPECT_TRUE( - static_tf_buffer_->getTransform(node_.get(), "base_link", "lidar_top", eigen_transform)); + EXPECT_TRUE(managed_tf_buffer_->getTransform("base_link", "lidar_top", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(eigen_base_to_lidar_, 0.001)); - EXPECT_FALSE( - static_tf_buffer_->getTransform(node_.get(), "fake_link", "lidar_top", eigen_transform)); + EXPECT_FALSE(managed_tf_buffer_->getTransform("fake_link", "lidar_top", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(Eigen::Matrix4f::Identity(), 0.001)); - EXPECT_TRUE( - static_tf_buffer_->getTransform(node_.get(), "base_link", "lidar_top", eigen_transform)); + EXPECT_TRUE(managed_tf_buffer_->getTransform("base_link", "lidar_top", eigen_transform)); EXPECT_TRUE(eigen_transform.isApprox(eigen_base_to_lidar_, 0.001)); } -TEST_F(TestStaticTransformBuffer, TestTransformEmptyPointCloud) +TEST_F(TestManagedTransformBuffer, TestTransformEmptyPointCloud) { auto cloud_in = std::make_unique(); cloud_in->header.frame_id = "lidar_top"; cloud_in->header.stamp = rclcpp::Time(10, 100'000'000); auto cloud_out = std::make_unique(); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("lidar_top", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("base_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("fake_link", *cloud_in, *cloud_out)); } -TEST_F(TestStaticTransformBuffer, TestTransformEmptyPointCloudNoHeader) +TEST_F(TestManagedTransformBuffer, TestTransformEmptyPointCloudNoHeader) { auto cloud_in = std::make_unique(); auto cloud_out = std::make_unique(); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("lidar_top", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("base_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("fake_link", *cloud_in, *cloud_out)); } -TEST_F(TestStaticTransformBuffer, TestTransformPointCloud) +TEST_F(TestManagedTransformBuffer, TestTransformPointCloud) { auto cloud_out = std::make_unique(); // Transform cloud with header - EXPECT_TRUE( - static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in_, *cloud_out)); - EXPECT_TRUE( - static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in_, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in_, *cloud_out)); + EXPECT_TRUE(managed_tf_buffer_->transformPointcloud("lidar_top", *cloud_in_, *cloud_out)); + EXPECT_TRUE(managed_tf_buffer_->transformPointcloud("base_link", *cloud_in_, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("fake_link", *cloud_in_, *cloud_out)); } -TEST_F(TestStaticTransformBuffer, TestTransformPointCloudNoHeader) +TEST_F(TestManagedTransformBuffer, TestTransformPointCloudNoHeader) { auto cloud_out = std::make_unique(); @@ -201,10 +184,7 @@ TEST_F(TestStaticTransformBuffer, TestTransformPointCloudNoHeader) auto cloud_in = std::make_unique(*cloud_in_); cloud_in->header.frame_id = ""; cloud_in->header.stamp = rclcpp::Time(0, 0); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in, *cloud_out)); - EXPECT_FALSE( - static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("lidar_top", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("base_link", *cloud_in, *cloud_out)); + EXPECT_FALSE(managed_tf_buffer_->transformPointcloud("fake_link", *cloud_in, *cloud_out)); } diff --git a/perception/autoware_ground_segmentation/README.md b/perception/autoware_ground_segmentation/README.md index b981b02e0a844..08b8a4f373bcc 100644 --- a/perception/autoware_ground_segmentation/README.md +++ b/perception/autoware_ground_segmentation/README.md @@ -33,14 +33,15 @@ Detail description of each ground segmentation algorithm is in the following lin ### Node Parameters -| Name | Type | Default Value | Description | -| ------------------ | ------ | ------------- | ------------------------------------- | -| `input_frame` | string | " " | input frame id | -| `output_frame` | string | " " | output frame id | -| `max_queue_size` | int | 5 | max queue size of input/output topics | -| `use_indices` | bool | false | flag to use pointcloud indices | -| `latched_indices` | bool | false | flag to latch pointcloud indices | -| `approximate_sync` | bool | false | flag to use approximate sync option | +| Name | Type | Default Value | Description | +| -------------------- | ------ | ------------- | ------------------------------------- | +| `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 | +| `use_indices` | bool | false | flag to use pointcloud indices | +| `latched_indices` | bool | false | flag to latch pointcloud indices | +| `approximate_sync` | bool | false | flag to use approximate sync option | ## Assumptions / Known limits diff --git a/perception/autoware_ground_segmentation/docs/ransac-ground-filter.md b/perception/autoware_ground_segmentation/docs/ransac-ground-filter.md index a11a35521d173..37388e665eb2c 100644 --- a/perception/autoware_ground_segmentation/docs/ransac-ground-filter.md +++ b/perception/autoware_ground_segmentation/docs/ransac-ground-filter.md @@ -23,6 +23,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, | Name | Type | Description | | ----------------------- | ------ | --------------------------------------------------------------- | | `base_frame` | string | base_link frame | +| `has_static_tf_only` | bool | Flag to listen TF only once | | `unit_axis` | string | The axis which we need to search ground plane | | `max_iterations` | int | The maximum number of iterations | | `outlier_threshold` | double | The distance threshold to the model [m] | diff --git a/perception/autoware_ground_segmentation/docs/ray-ground-filter.md b/perception/autoware_ground_segmentation/docs/ray-ground-filter.md index 9b80b0588f851..ed4f5833b3b3a 100644 --- a/perception/autoware_ground_segmentation/docs/ray-ground-filter.md +++ b/perception/autoware_ground_segmentation/docs/ray-ground-filter.md @@ -28,6 +28,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, | ----------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | | `input_frame` | string | frame id of input pointcloud | | `output_frame` | string | frame id of output pointcloud | +| `has_static_tf_only` | bool | Flag to listen TF only once | | `general_max_slope` | double | The triangle created by `general_max_slope` is called the global cone. If the point is outside the global cone, it is judged to be a point that is no on the ground | | `initial_max_slope` | double | Generally, the point where the object first hits is far from ego-vehicle because of sensor blind spot, so resolution is different from that point and thereafter, so this parameter exists to set a separate `local_max_slope` | | `local_max_slope` | double | The triangle created by `local_max_slope` is called the local cone. This parameter for classification based on the continuity of points | diff --git a/perception/autoware_ground_segmentation/docs/scan-ground-filter.md b/perception/autoware_ground_segmentation/docs/scan-ground-filter.md index bdd46cffb7df4..392bed89ac902 100644 --- a/perception/autoware_ground_segmentation/docs/scan-ground-filter.md +++ b/perception/autoware_ground_segmentation/docs/scan-ground-filter.md @@ -35,6 +35,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, | --------------------------------- | ------ | ------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | `input_frame` | string | "base_link" | frame id of input pointcloud | | `output_frame` | string | "base_link" | frame id of output pointcloud | +| `has_static_tf_only` | bool | false | Flag to listen TF only once | | `global_slope_max_angle_deg` | double | 8.0 | The global angle to classify as the ground or object [deg].
A large threshold may reduce false positive of high slope road classification but it may lead to increase false negative of non-ground classification, particularly for small objects. | | `local_slope_max_angle_deg` | double | 10.0 | The local angle to classify as the ground or object [deg] when comparing with adjacent point.
A small value enhance accuracy classification of object with inclined surface. This should be considered together with `split_points_distance_tolerance` value. | | `radial_divider_angle_deg` | double | 1.0 | The angle which divide the whole pointcloud to sliced group [deg] | diff --git a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp index 4d45f5df07027..e2f96d862e1a6 100644 --- a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp +++ b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp @@ -116,7 +116,8 @@ RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptio pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS); - static_tf_buffer_ = std::make_unique(); + managed_tf_buffer_ = + std::make_unique(this, has_static_tf_only_); } void RANSACGroundFilterComponent::setDebugPublisher() @@ -163,8 +164,7 @@ bool RANSACGroundFilterComponent::transformPointCloud( return true; } - return static_tf_buffer_->transformPointcloud( - this, in_target_frame, *in_cloud_ptr, *out_cloud_ptr); + return managed_tf_buffer_->transformPointcloud(in_target_frame, *in_cloud_ptr, *out_cloud_ptr); } void RANSACGroundFilterComponent::extractPointsIndices( diff --git a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp index bdc217e80650c..b36a7f5e55fc4 100644 --- a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp +++ b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp @@ -17,7 +17,7 @@ #include "autoware/pointcloud_preprocessor/filter.hpp" -#include +#include #include #include @@ -83,7 +83,7 @@ class RANSACGroundFilterComponent : public autoware::pointcloud_preprocessor::Fi bool debug_ = false; bool is_initialized_debug_message_ = false; Eigen::Vector3d unit_vec_ = Eigen::Vector3d::UnitZ(); - std::unique_ptr static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; /*! * Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml index 5d38186840057..449795c328402 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml @@ -1,6 +1,7 @@ /**: ros__parameters: output_frame: base_link + has_static_tf_only: true input_topics: [ "/sensing/lidar/left/pointcloud_before_sync", "/sensing/lidar/right/pointcloud_before_sync", diff --git a/sensing/autoware_pointcloud_preprocessor/config/distortion_corrector_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/distortion_corrector_node.param.yaml index 3afa4816271cb..eca08c37b6458 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/distortion_corrector_node.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/distortion_corrector_node.param.yaml @@ -3,3 +3,4 @@ base_frame: base_link use_imu: true use_3d_distortion_correction: false + has_static_tf_only: true diff --git a/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml index 9add0be3f8809..7e5bd0fd96bcf 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml @@ -3,6 +3,7 @@ input_twist_topic_type: twist output_frame: base_link keep_input_frame_in_synchronized_pointcloud: false + has_static_tf_only: true input_topics: [ "/sensing/lidar/left/pointcloud_before_sync", "/sensing/lidar/right/pointcloud_before_sync", diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index 74b4f3df17615..08f7b92f88975 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -28,12 +28,13 @@ The figure below represents the reception time of each sensor data and how it is ## Parameters -| 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 | -| `max_queue_size` | int | 5 | max queue size of input/output topics | +| 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 | ### Core Parameters 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 549a60e49d748..977adc59cd7e5 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 @@ -64,7 +64,7 @@ #include "autoware_point_types/types.hpp" #include -#include +#include #include #include #include @@ -146,11 +146,14 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node /** \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 static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; std::deque twist_ptr_queue_; 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 9711025b713df..b7e0e86ca1d3a 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 @@ -62,7 +62,7 @@ // ROS includes #include -#include +#include #include #include #include @@ -135,11 +135,14 @@ class PointCloudConcatenationComponent : public rclcpp::Node /** \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 static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; std::deque twist_ptr_queue_; diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index 7ba419770af17..e786bff04b3cd 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -16,7 +16,7 @@ #define AUTOWARE__POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_HPP_ #include -#include +#include #include #include @@ -74,7 +74,7 @@ class DistortionCorrector : public DistortionCorrectorBase bool pointcloud_transform_exists_{false}; bool imu_transform_exists_{false}; rclcpp::Node * node_; - std::unique_ptr static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; std::deque twist_queue_; std::deque angular_velocity_queue_; @@ -99,9 +99,10 @@ class DistortionCorrector : public DistortionCorrectorBase void convertMatrixToTransform(const Eigen::Matrix4f & matrix, tf2::Transform & transform); public: - explicit DistortionCorrector(rclcpp::Node * node) : node_(node) + explicit DistortionCorrector(rclcpp::Node * node, const bool & has_static_tf_only) : node_(node) { - static_tf_buffer_ = std::make_unique(); + managed_tf_buffer_ = + std::make_unique(node, has_static_tf_only); } bool pointcloud_transform_exists(); bool pointcloud_transform_needed(); @@ -133,7 +134,10 @@ class DistortionCorrector2D : public DistortionCorrector tf2::Transform tf2_base_link_to_lidar_; public: - explicit DistortionCorrector2D(rclcpp::Node * node) : DistortionCorrector(node) {} + explicit DistortionCorrector2D(rclcpp::Node * node, const bool & has_static_tf_only) + : DistortionCorrector(node, has_static_tf_only) + { + } void initialize() override; void undistortPointImplementation( sensor_msgs::PointCloud2Iterator & it_x, sensor_msgs::PointCloud2Iterator & it_y, @@ -160,7 +164,10 @@ class DistortionCorrector3D : public DistortionCorrector Eigen::Matrix4f eigen_base_link_to_lidar_; public: - explicit DistortionCorrector3D(rclcpp::Node * node) : DistortionCorrector(node) {} + explicit DistortionCorrector3D(rclcpp::Node * node, const bool & has_static_tf_only) + : DistortionCorrector(node, has_static_tf_only) + { + } void initialize() override; void undistortPointImplementation( sensor_msgs::PointCloud2Iterator & it_x, sensor_msgs::PointCloud2Iterator & it_y, diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp index 789f377e7ec95..b39be3cfaf9e5 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp @@ -74,15 +74,10 @@ #include #include -// Include TF -#include -#include -#include - // Include tier4 autoware utils #include +#include #include -#include #include namespace autoware::pointcloud_preprocessor @@ -174,6 +169,9 @@ class Filter : public rclcpp::Node * if input.header.frame_id is different. */ std::string tf_output_frame_; + /** \brief The flag to indicate if only static TF are used. */ + bool has_static_tf_only_; + /** \brief Internal mutex. */ std::mutex mutex_; @@ -240,7 +238,7 @@ class Filter : public rclcpp::Node * versus an exact one (false by default). */ bool approximate_sync_ = false; - std::unique_ptr static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; inline bool isValid( const PointCloud2ConstPtr & cloud, const std::string & /*topic_name*/ = "input") 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 ad5cde3056ef0..b02860a6f112e 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 @@ -62,7 +62,7 @@ // ROS includes #include -#include +#include #include #include #include @@ -140,11 +140,14 @@ class PointCloudDataSynchronizerComponent : public rclcpp::Node std::string output_frame_; bool keep_input_frame_in_synchronized_pointcloud_; + /** \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 static_tf_buffer_{nullptr}; + std::unique_ptr managed_tf_buffer_{nullptr}; std::deque twist_ptr_queue_; diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_pointclouds.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_pointclouds.schema.json index 916650c69a68b..19044f851bda6 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_pointclouds.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_pointclouds.schema.json @@ -25,6 +25,11 @@ "default": "base_link", "description": "Output frame id." }, + "has_static_tf_only": { + "type": "boolean", + "default": false, + "description": "Flag to indicate if only static TF is used." + }, "input_topics": { "type": "array", "items": { @@ -40,7 +45,14 @@ "description": "Max queue size of input/output topics." } }, - "required": ["timeout_sec", "input_offset", "output_frame", "input_topics", "max_queue_size"] + "required": [ + "timeout_sec", + "input_offset", + "output_frame", + "has_static_tf_only", + "input_topics", + "max_queue_size" + ] } }, "properties": { 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 acf67fd2746c4..75579227981ac 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json @@ -20,9 +20,14 @@ "type": "boolean", "description": "Use 3d distortion correction algorithm, otherwise, use 2d distortion correction algorithm.", "default": "false" + }, + "has_static_tf_only": { + "type": "boolean", + "description": "Flag to indicate if only static TF is used.", + "default": false } }, - "required": ["base_frame", "use_imu", "use_3d_distortion_correction"] + "required": ["base_frame", "use_imu", "use_3d_distortion_correction", "has_static_tf_only"] } }, "properties": { diff --git a/sensing/autoware_pointcloud_preprocessor/schema/time_synchronizer_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/time_synchronizer_node.schema.json index 8954fcaf6d814..90c14b50508db 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/time_synchronizer_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/time_synchronizer_node.schema.json @@ -31,6 +31,11 @@ "default": "base_link", "description": "Output frame." }, + "has_static_tf_only": { + "type": "boolean", + "default": false, + "description": "Flag to indicate if only static TF is used." + }, "keep_input_frame_in_synchronized_pointcloud": { "type": "boolean", "default": true, @@ -61,6 +66,7 @@ "input_offset", "input_twist_topic_type", "output_frame", + "has_static_tf_only", "keep_input_frame_in_synchronized_pointcloud", "input_topics", "synchronized_pointcloud_postfix", 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 0a051d780f5f7..d0911f769d3bd 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 @@ -92,6 +92,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro 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()) { @@ -137,7 +138,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // tf2 listener { - static_tf_buffer_ = std::make_unique(); + managed_tf_buffer_ = + std::make_unique(this, has_static_tf_only_); } // Output Publishers @@ -361,8 +363,7 @@ PointCloudConcatenateDataSynchronizerComponent::combineClouds( } sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr( new sensor_msgs::msg::PointCloud2()); - static_tf_buffer_->transformPointcloud( - this, output_frame_, *e.second, *transformed_cloud_ptr); + 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(); @@ -392,8 +393,8 @@ PointCloudConcatenateDataSynchronizerComponent::combineClouds( 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()); - static_tf_buffer_->transformPointcloud( - this, e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr, + 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; 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 e9078cbe717cb..5e1911c93409d 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp @@ -54,6 +54,8 @@ PointCloudConcatenationComponent::PointCloudConcatenationComponent( 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); // TODO(amadeuszsz): remove default value declare_parameter>("input_topics"); input_topics_ = get_parameter("input_topics").as_string_array(); if (input_topics_.empty()) { @@ -93,7 +95,8 @@ PointCloudConcatenationComponent::PointCloudConcatenationComponent( // tf2 listener { - static_tf_buffer_ = std::make_unique(); + managed_tf_buffer_ = + std::make_unique(this, has_static_tf_only_); } // Output Publishers @@ -237,8 +240,7 @@ void PointCloudConcatenationComponent::combineClouds( // transform to output frame sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr( new sensor_msgs::msg::PointCloud2()); - static_tf_buffer_->transformPointcloud( - this, output_frame_, *e.second, *transformed_cloud_ptr); + managed_tf_buffer_->transformPointcloud(output_frame_, *e.second, *transformed_cloud_ptr); // concatenate if (concat_cloud_ptr == nullptr) { diff --git a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index affa6d901be2d..d0119fbc44f24 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -90,7 +90,7 @@ void DistortionCorrector::getIMUTransformation( tf2::Transform tf2_imu_to_base_link; Eigen::Matrix4f eigen_imu_to_base_link; imu_transform_exists_ = - static_tf_buffer_->getTransform(node_, base_frame, imu_frame, eigen_imu_to_base_link); + managed_tf_buffer_->getTransform(base_frame, imu_frame, eigen_imu_to_base_link); convertMatrixToTransform(eigen_imu_to_base_link, tf2_imu_to_base_link); geometry_imu_to_base_link_ptr_ = std::make_shared(); @@ -311,7 +311,7 @@ void DistortionCorrector2D::setPointCloudTransform( Eigen::Matrix4f eigen_lidar_to_base_link; pointcloud_transform_exists_ = - static_tf_buffer_->getTransform(node_, base_frame, lidar_frame, eigen_lidar_to_base_link); + managed_tf_buffer_->getTransform(base_frame, lidar_frame, eigen_lidar_to_base_link); convertMatrixToTransform(eigen_lidar_to_base_link, tf2_lidar_to_base_link_); tf2_base_link_to_lidar_ = tf2_lidar_to_base_link_.inverse(); pointcloud_transform_needed_ = base_frame != lidar_frame && pointcloud_transform_exists_; @@ -325,7 +325,7 @@ void DistortionCorrector3D::setPointCloudTransform( } pointcloud_transform_exists_ = - static_tf_buffer_->getTransform(node_, base_frame, lidar_frame, eigen_lidar_to_base_link_); + managed_tf_buffer_->getTransform(base_frame, lidar_frame, eigen_lidar_to_base_link_); eigen_base_link_to_lidar_ = eigen_lidar_to_base_link_.inverse(); pointcloud_transform_needed_ = base_frame != lidar_frame && pointcloud_transform_exists_; } 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 822bb2ba5add5..8e4eaa6ec8f11 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 @@ -35,6 +35,8 @@ DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOpt base_frame_ = declare_parameter("base_frame"); use_imu_ = declare_parameter("use_imu"); use_3d_distortion_correction_ = declare_parameter("use_3d_distortion_correction"); + auto has_static_tf_only = + declare_parameter("has_static_tf_only", false); // TODO(amadeuszsz): remove default value // Publisher { @@ -59,9 +61,9 @@ DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOpt // Setup the distortion corrector if (use_3d_distortion_correction_) { - distortion_corrector_ = std::make_unique(this); + distortion_corrector_ = std::make_unique(this, has_static_tf_only); } else { - distortion_corrector_ = std::make_unique(this); + distortion_corrector_ = std::make_unique(this, has_static_tf_only); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/filter.cpp index de6549463e7ff..62495fc8b70cb 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/filter.cpp @@ -72,6 +72,7 @@ autoware::pointcloud_preprocessor::Filter::Filter( { tf_input_frame_ = static_cast(declare_parameter("input_frame", "")); tf_output_frame_ = static_cast(declare_parameter("output_frame", "")); + has_static_tf_only_ = static_cast(declare_parameter("has_static_tf_only", false)); max_queue_size_ = static_cast(declare_parameter("max_queue_size", 5)); // ---[ Optional parameters @@ -114,7 +115,17 @@ autoware::pointcloud_preprocessor::Filter::Filter( ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// void autoware::pointcloud_preprocessor::Filter::setupTF() { - static_tf_buffer_ = std::make_unique(); + // Always consider static TF if in & out frames are same + if (tf_input_frame_ == tf_output_frame_) { + if (!has_static_tf_only_) { + RCLCPP_INFO( + this->get_logger(), + "Input and output frames are the same. Overriding has_static_tf_only to true."); + } + has_static_tf_only_ = true; + } + managed_tf_buffer_ = + std::make_unique(this, has_static_tf_only_); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -269,7 +280,7 @@ void autoware::pointcloud_preprocessor::Filter::input_indices_callback( // Convert the cloud into the different frame PointCloud2 cloud_transformed; - if (!static_tf_buffer_->transformPointcloud(this, tf_input_frame_, *cloud, cloud_transformed)) { + if (!managed_tf_buffer_->transformPointcloud(tf_input_frame_, *cloud, cloud_transformed)) { return; } cloud_tf = std::make_shared(cloud_transformed); @@ -298,8 +309,8 @@ bool autoware::pointcloud_preprocessor::Filter::calculate_transform_matrix( this->get_logger(), "[get_transform_matrix] Transforming input dataset from %s to %s.", from.header.frame_id.c_str(), target_frame.c_str()); - if (!static_tf_buffer_->getTransform( - this, target_frame, from.header.frame_id, transform_info.eigen_transform)) { + if (!managed_tf_buffer_->getTransform( + target_frame, from.header.frame_id, transform_info.eigen_transform)) { return false; } @@ -321,8 +332,7 @@ bool autoware::pointcloud_preprocessor::Filter::convert_output_costly( // Convert the cloud into the different frame auto cloud_transformed = std::make_unique(); - if (!static_tf_buffer_->transformPointcloud( - this, tf_output_frame_, *output, *cloud_transformed)) { + if (!managed_tf_buffer_->transformPointcloud(tf_output_frame_, *output, *cloud_transformed)) { RCLCPP_ERROR( this->get_logger(), "[convert_output_costly] Error converting output dataset from %s to %s.", @@ -342,8 +352,8 @@ bool autoware::pointcloud_preprocessor::Filter::convert_output_costly( auto cloud_transformed = std::make_unique(); - if (!static_tf_buffer_->transformPointcloud( - this, tf_input_orig_frame_, *output, *cloud_transformed)) { + if (!managed_tf_buffer_->transformPointcloud( + tf_input_orig_frame_, *output, *cloud_transformed)) { return false; } 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 3f6f37fd31720..e34c165383867 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 @@ -58,6 +58,8 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent( std::string synchronized_pointcloud_postfix; { output_frame_ = declare_parameter("output_frame"); + has_static_tf_only_ = declare_parameter( + "has_static_tf_only", false); // TODO(amadeuszsz): remove default value keep_input_frame_in_synchronized_pointcloud_ = declare_parameter("keep_input_frame_in_synchronized_pointcloud"); if (output_frame_.empty() && !keep_input_frame_in_synchronized_pointcloud_) { @@ -109,7 +111,8 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent( // tf2 listener { - static_tf_buffer_ = std::make_unique(); + managed_tf_buffer_ = + std::make_unique(this, has_static_tf_only_); } // Subscribers @@ -320,8 +323,7 @@ PointCloudDataSynchronizerComponent::synchronizeClouds() continue; } // transform pointcloud to output frame - static_tf_buffer_->transformPointcloud( - this, output_frame_, *e.second, *transformed_cloud_ptr); + managed_tf_buffer_->transformPointcloud(output_frame_, *e.second, *transformed_cloud_ptr); // calculate transforms to oldest stamp and transform pointcloud to oldest stamp Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity(); @@ -341,8 +343,8 @@ PointCloudDataSynchronizerComponent::synchronizeClouds() sensor_msgs::msg::PointCloud2::SharedPtr transformed_delay_compensated_cloud_ptr_in_input_frame( new sensor_msgs::msg::PointCloud2()); - static_tf_buffer_->transformPointcloud( - this, e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr, + managed_tf_buffer_->transformPointcloud( + e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr, *transformed_delay_compensated_cloud_ptr_in_input_frame); transformed_delay_compensated_cloud_ptr = transformed_delay_compensated_cloud_ptr_in_input_frame; diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp index f90314a001105..047d021a4c6da 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp @@ -48,9 +48,9 @@ class DistortionCorrectorTest : public ::testing::Test { node_ = std::make_shared("test_node"); distortion_corrector_2d_ = - std::make_shared(node_.get()); + std::make_shared(node_.get(), true); distortion_corrector_3d_ = - std::make_shared(node_.get()); + std::make_shared(node_.get(), true); // Setup TF tf_broadcaster_ = std::make_shared(node_); From c99ea5d71ff9b905a0b9d5da1df24fdb2d8cad72 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 9 Sep 2024 11:36:44 +0900 Subject: [PATCH 154/217] fix(autoware_frenet_planner): fix build error (#8807) fix:build error Signed-off-by: kobayu858 --- .../frenet_planner.hpp | 5 +++++ .../src/frenet_planner/frenet_planner.cpp | 21 +++++++++++++++++++ 2 files changed, 26 insertions(+) diff --git a/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp index e2b63f6591463..e9625beacc158 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp @@ -25,6 +25,11 @@ namespace autoware::frenet_planner { +/// @brief generate trajectories relative to the reference for the given initial state and sampling +/// parameters +std::vector generateTrajectories( + const autoware::sampler_common::transform::Spline2D & reference_spline, + const FrenetState & initial_state, const SamplingParameters & sampling_parameters); /// @brief generate paths relative to the reference for the given initial state and sampling /// parameters std::vector generatePaths( 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 d53fc1cb1726f..faabd0bcfdbe5 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 @@ -33,6 +33,27 @@ namespace autoware::frenet_planner { +// cppcheck-suppress unusedFunction +std::vector generateTrajectories( + const autoware::sampler_common::transform::Spline2D & reference_spline, + const FrenetState & initial_state, const SamplingParameters & sampling_parameters) +{ + std::vector trajectories; + trajectories.reserve(sampling_parameters.parameters.size()); + for (const auto & parameter : sampling_parameters.parameters) { + auto trajectory = generateCandidate( + initial_state, parameter.target_state, parameter.target_duration, + sampling_parameters.resolution); + trajectory.sampling_parameter = parameter; + calculateCartesian(reference_spline, trajectory); + std::stringstream ss; + ss << parameter; + trajectory.tag = ss.str(); + trajectories.push_back(trajectory); + } + return trajectories; +} + std::vector generatePaths( const autoware::sampler_common::transform::Spline2D & reference_spline, const FrenetState & initial_state, const SamplingParameters & sampling_parameters) From 60f9829795fcf6c4f07b2972a15a3c331c7eb37a Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Mon, 9 Sep 2024 12:01:27 +0900 Subject: [PATCH 155/217] refactor(autoware_pointcloud_preprocessor): rework ring passthrough filter parameters (#8472) * feat: rework ring passthrough parameters Signed-off-by: vividf * chore: fix cmake Signed-off-by: vividf * feat: add schema Signed-off-by: vividf * chore: fix readme Signed-off-by: vividf * chore: fix parameter file name Signed-off-by: vividf * chore: add boundary Signed-off-by: vividf * chore: fix default parameter Signed-off-by: vividf * chore: fix default parameter in schema Signed-off-by: vividf --------- Signed-off-by: vividf --- .../CMakeLists.txt | 4 +- .../passthrough_filter_uint16_node.param.yaml | 7 +++ .../docs/passthrough-filter.md | 9 +-- ...odelet.hpp => passthrough_filter_node.hpp} | 8 +-- ...hpp => passthrough_filter_uint16_node.hpp} | 8 +-- .../launch/ring_passthrough_filter.launch.xml | 18 ++---- ...passthrough_filter_uint16_node.schema.json | 61 +++++++++++++++++++ ...odelet.cpp => passthrough_filter_node.cpp} | 4 +- ...cpp => passthrough_filter_uint16_node.cpp} | 16 +++-- 9 files changed, 94 insertions(+), 41 deletions(-) create mode 100644 sensing/autoware_pointcloud_preprocessor/config/passthrough_filter_uint16_node.param.yaml rename sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/{passthrough_filter_nodelet.hpp => passthrough_filter_node.hpp} (96%) rename sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/{passthrough_filter_uint16_nodelet.hpp => passthrough_filter_uint16_node.hpp} (90%) create mode 100644 sensing/autoware_pointcloud_preprocessor/schema/passthrough_filter_uint16_node.schema.json rename sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/{passthrough_filter_nodelet.cpp => passthrough_filter_node.cpp} (98%) rename sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/{passthrough_filter_uint16_nodelet.cpp => passthrough_filter_uint16_node.cpp} (88%) diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt index 5d7aba4d0567b..2474b483cb2fe 100644 --- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt @@ -74,8 +74,8 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED src/outlier_filter/voxel_grid_outlier_filter_node.cpp src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp src/outlier_filter/dual_return_outlier_filter_nodelet.cpp - src/passthrough_filter/passthrough_filter_nodelet.cpp - src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp + src/passthrough_filter/passthrough_filter_node.cpp + src/passthrough_filter/passthrough_filter_uint16_node.cpp src/passthrough_filter/passthrough_uint16.cpp src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp src/vector_map_filter/lanelet2_map_filter_node.cpp diff --git a/sensing/autoware_pointcloud_preprocessor/config/passthrough_filter_uint16_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/passthrough_filter_uint16_node.param.yaml new file mode 100644 index 0000000000000..ff1d31f0db33d --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/config/passthrough_filter_uint16_node.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + filter_limit_min: 0 + filter_limit_max: 127 + filter_field_name: "channel" + keep_organized: false + filter_limit_negative: false diff --git a/sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md index 4d28f08da28cc..58da60c8fe90e 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md @@ -25,13 +25,8 @@ The `passthrough_filter` is a node that removes points on the outside of a range ### Core Parameters -| Name | Type | Default Value | Description | -| ----------------------- | ------ | ------------- | ------------------------------------------------------ | -| `filter_limit_min` | int | 0 | minimum allowed field value | -| `filter_limit_max` | int | 127 | maximum allowed field value | -| `filter_field_name` | string | "ring" | filtering field name | -| `keep_organized` | bool | false | flag to keep indices structure | -| `filter_limit_negative` | bool | false | flag to return whether the data is inside limit or not | +{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/passthrough_filter_uint16_node.schema.json +") }} ## Assumptions / Known limits diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_node.hpp similarity index 96% rename from sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_node.hpp index bbb2c0b113658..4e9e6f9ab727e 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_node.hpp @@ -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. @@ -48,8 +48,8 @@ * */ -#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_ -#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODE_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODE_HPP_ #include "autoware/pointcloud_preprocessor/filter.hpp" @@ -77,4 +77,4 @@ class PassThroughFilterComponent : public autoware::pointcloud_preprocessor::Fil }; } // namespace autoware::pointcloud_preprocessor -#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODE_HPP_ diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_node.hpp similarity index 90% rename from sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_node.hpp index 0ffb50dc65092..53ef8eb0cfa7a 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_node.hpp @@ -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. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT -#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODE_HPP_ // NOLINT +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODE_HPP_ // NOLINT #include "autoware/pointcloud_preprocessor/filter.hpp" #include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp" @@ -46,5 +46,5 @@ class PassThroughFilterUInt16Component : public autoware::pointcloud_preprocesso } // namespace autoware::pointcloud_preprocessor // clang-format off -#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODE_HPP_ // NOLINT // clang-format on diff --git a/sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml index a9ed23e9faa3a..800fa5f3ec3ee 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml @@ -1,24 +1,16 @@ - - - - - - + + - + + + - - - - - - diff --git a/sensing/autoware_pointcloud_preprocessor/schema/passthrough_filter_uint16_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/passthrough_filter_uint16_node.schema.json new file mode 100644 index 0000000000000..ead8137142da0 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/schema/passthrough_filter_uint16_node.schema.json @@ -0,0 +1,61 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Passthrough Filter UInt16 Node", + "type": "object", + "definitions": { + "passthrough_filter_uint16": { + "type": "object", + "properties": { + "filter_limit_min": { + "type": "integer", + "description": "minimum allowed field value", + "default": "0", + "minimum": 0 + }, + "filter_limit_max": { + "type": "integer", + "description": "maximum allowed field value", + "default": "127", + "minimum": 0 + }, + "filter_field_name": { + "type": "string", + "description": "filtering field name", + "default": "channel" + }, + "keep_organized": { + "type": "boolean", + "description": "flag to keep indices structure", + "default": "false" + }, + "filter_limit_negative": { + "type": "boolean", + "description": "flag to return whether the data is inside limit or not", + "default": "false" + } + }, + "required": [ + "filter_limit_min", + "filter_limit_max", + "filter_field_name", + "keep_organized", + "filter_limit_negative" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/passthrough_filter_uint16" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_node.cpp similarity index 98% rename from sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_node.cpp index 53bb6ad619333..04c1a4cdbcfb2 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_node.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. @@ -48,7 +48,7 @@ * */ -#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_node.hpp" #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_node.cpp similarity index 88% rename from sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_node.cpp index cc9f3276033a1..ef4e67696001d 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_node.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. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_node.hpp" #include #include @@ -29,15 +29,13 @@ PassThroughFilterUInt16Component::PassThroughFilterUInt16Component( { // set initial parameters { - int filter_min = static_cast(declare_parameter("filter_limit_min", 0)); - int filter_max = static_cast(declare_parameter("filter_limit_max", 127)); + int filter_min = declare_parameter("filter_limit_min"); + int filter_max = declare_parameter("filter_limit_max"); impl_.setFilterLimits(filter_min, filter_max); - impl_.setFilterFieldName( - static_cast(declare_parameter("filter_field_name", "ring"))); - impl_.setKeepOrganized(static_cast(declare_parameter("keep_organized", false))); - impl_.setFilterLimitsNegative( - static_cast(declare_parameter("filter_limit_negative", false))); + impl_.setFilterFieldName(declare_parameter("filter_field_name")); + impl_.setKeepOrganized(declare_parameter("keep_organized")); + impl_.setFilterLimitsNegative(declare_parameter("filter_limit_negative")); } using std::placeholders::_1; From 225e18bb6e6fb76c56010992bddff06fdc423d2b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 9 Sep 2024 12:30:16 +0900 Subject: [PATCH 156/217] feat(map loader): visualize bus stop area and bicycle_lane (#8777) Signed-off-by: Mamoru Sobue --- map/map_loader/package.xml | 1 + .../lanelet2_map_visualization_node.cpp | 26 +++++++++++++++++++ 2 files changed, 27 insertions(+) diff --git a/map/map_loader/package.xml b/map/map_loader/package.xml index b8f92504a8b99..d86767861c5ce 100644 --- a/map/map_loader/package.xml +++ b/map/map_loader/package.xml @@ -11,6 +11,7 @@ NGUYEN Viet Anh Taiki Yamada Shintaro Sakoda + Mamoru Sobue Apache License 2.0 Ryohsuke Mitsudome diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp index 4bff12c640c30..4a9aae78e8eb3 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp @@ -95,6 +95,8 @@ void Lanelet2MapVisualizationNode::on_map_bin( lanelet::ConstLanelets shoulder_lanelets = lanelet::utils::query::shoulderLanelets(all_lanelets); lanelet::ConstLanelets crosswalk_lanelets = lanelet::utils::query::crosswalkLanelets(all_lanelets); + lanelet::ConstLanelets bicycle_lane_lanelets = + lanelet::utils::query::bicycleLaneLanelets(all_lanelets); lanelet::ConstLineStrings3d partitions = lanelet::utils::query::getAllPartitions(viz_lanelet_map); lanelet::ConstLineStrings3d pedestrian_polygon_markings = lanelet::utils::query::getAllPedestrianPolygonMarkings(viz_lanelet_map); @@ -130,6 +132,8 @@ void Lanelet2MapVisualizationNode::on_map_bin( std::vector no_parking_reg_elems = lanelet::utils::query::noParkingAreas(all_lanelets); lanelet::ConstLineStrings3d curbstones = lanelet::utils::query::curbstones(viz_lanelet_map); + std::vector bus_stop_reg_elems = + lanelet::utils::query::busStopAreas(all_lanelets); std_msgs::msg::ColorRGBA cl_road; std_msgs::msg::ColorRGBA cl_shoulder; @@ -155,6 +159,8 @@ void Lanelet2MapVisualizationNode::on_map_bin( std_msgs::msg::ColorRGBA cl_no_parking_areas; std_msgs::msg::ColorRGBA cl_curbstones; std_msgs::msg::ColorRGBA cl_intersection_area; + std_msgs::msg::ColorRGBA cl_bus_stop_area; + std_msgs::msg::ColorRGBA cl_bicycle_lane; set_color(&cl_road, 0.27, 0.27, 0.27, 0.999); set_color(&cl_shoulder, 0.15, 0.15, 0.15, 0.999); set_color(&cl_cross, 0.27, 0.3, 0.27, 0.5); @@ -179,6 +185,8 @@ void Lanelet2MapVisualizationNode::on_map_bin( set_color(&cl_no_parking_areas, 0.42, 0.42, 0.42, 0.5); set_color(&cl_curbstones, 0.1, 0.1, 0.2, 0.999); set_color(&cl_intersection_area, 0.16, 1.0, 0.69, 0.5); + set_color(&cl_bus_stop_area, 0.863, 0.863, 0.863, 0.5); + set_color(&cl_bicycle_lane, 0.0, 0.3843, 0.6274, 0.5); visualization_msgs::msg::MarkerArray map_marker_array; @@ -286,6 +294,24 @@ void Lanelet2MapVisualizationNode::on_map_bin( &map_marker_array, lanelet::visualization::intersectionAreaAsMarkerArray( intersection_areas, cl_intersection_area)); + insert_marker_array( + &map_marker_array, + lanelet::visualization::busStopAreasAsMarkerArray(bus_stop_reg_elems, cl_bus_stop_area)); + + insert_marker_array( + &map_marker_array, + lanelet::visualization::laneletDirectionAsMarkerArray(bicycle_lane_lanelets, "bicycle_lane_")); + insert_marker_array( + &map_marker_array, lanelet::visualization::laneletsBoundaryAsMarkerArray( + bicycle_lane_lanelets, cl_ll_borders /* use ll_border color */, + viz_lanelets_centerline_, "bicycle_lane_")); + insert_marker_array( + &map_marker_array, lanelet::visualization::generateLaneletIdMarker( + bicycle_lane_lanelets, cl_lanelet_id /* use lanelet_id color */)); + insert_marker_array( + &map_marker_array, lanelet::visualization::laneletsAsTriangleMarkerArray( + "bicycle_lane_lanelets", bicycle_lane_lanelets, cl_bicycle_lane)); + pub_marker_->publish(map_marker_array); } From a967adbad7a585aa7a211422ff6a6f635e57196c Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Mon, 9 Sep 2024 13:33:52 +0900 Subject: [PATCH 157/217] feat(occupancy_grid_map_outlier_filter): add time_keeper (#8597) * add time_keeper Signed-off-by: a-maumau * add option for time keeper Signed-off-by: a-maumau * add scope and timekeeper Signed-off-by: a-maumau * remove and add scope and timekeeper Signed-off-by: a-maumau * remove duplicated Signed-off-by: a-maumau * add timekeeper option Signed-off-by: a-maumau * fix comment Signed-off-by: a-maumau --------- Signed-off-by: a-maumau --- ...cupancy_grid_map_outlier_filter.param.yaml | 3 + ...occupancy_grid_map_outlier_filter_node.cpp | 74 +++++++++++++++++-- ...occupancy_grid_map_outlier_filter_node.hpp | 6 ++ 3 files changed, 75 insertions(+), 8 deletions(-) diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/config/occupancy_grid_map_outlier_filter.param.yaml b/perception/autoware_occupancy_grid_map_outlier_filter/config/occupancy_grid_map_outlier_filter.param.yaml index 61cd3a2dc19e2..20289d02f9ca6 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/config/occupancy_grid_map_outlier_filter.param.yaml +++ b/perception/autoware_occupancy_grid_map_outlier_filter/config/occupancy_grid_map_outlier_filter.param.yaml @@ -10,3 +10,6 @@ cost_threshold: 45 use_radius_search_2d_filter: true enable_debugger: false + + # debug parameters + publish_processing_time_detail: False 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 046598e445ba8..cf8e36833b339 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 @@ -39,6 +39,8 @@ namespace { +using autoware::universe_utils::ScopedTimeTrack; + bool transformPointcloud( const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2, const std::string & target_frame, sensor_msgs::msg::PointCloud2 & output) @@ -263,11 +265,24 @@ OccupancyGridMapOutlierFilterComponent::OccupancyGridMapOutlierFilterComponent( if (enable_debugger) { debugger_ptr_ = std::make_shared(*this); } + + // 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); + } } void OccupancyGridMapOutlierFilterComponent::splitPointCloudFrontBack( const PointCloud2::ConstSharedPtr & input_pc, PointCloud2 & front_pc, PointCloud2 & behind_pc) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + int x_offset = input_pc->fields[pcl::getFieldIndex(*input_pc, "x")].offset; int point_step = input_pc->point_step; size_t front_count = 0; @@ -295,6 +310,9 @@ void OccupancyGridMapOutlierFilterComponent::splitPointCloudFrontBack( void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( const OccupancyGrid::ConstSharedPtr & input_ogm, const PointCloud2::ConstSharedPtr & input_pc) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + stop_watch_ptr_->toc("processing_time", true); // Transform to occupancy grid map frame @@ -309,12 +327,19 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( PointCloud2 ogm_frame_pc{}; PointCloud2 ogm_frame_input_behind_pc{}; - if ( - !transformPointcloud(input_front_pc, *tf2_, input_ogm->header.frame_id, ogm_frame_pc) || - !transformPointcloud( - input_behind_pc, *tf2_, input_ogm->header.frame_id, ogm_frame_input_behind_pc)) { - return; + { // transform pointclouds + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("transformPointcloud", *time_keeper_); + + if ( + !transformPointcloud(input_front_pc, *tf2_, input_ogm->header.frame_id, ogm_frame_pc) || + !transformPointcloud( + input_behind_pc, *tf2_, input_ogm->header.frame_id, ogm_frame_input_behind_pc)) { + return; + } } + // Occupancy grid map based filter PointCloud2 high_confidence_pc{}; PointCloud2 low_confidence_pc{}; @@ -330,18 +355,26 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( PointCloud2 outlier_pc{}; initializerPointCloud2(low_confidence_pc, outlier_pc); initializerPointCloud2(low_confidence_pc, filtered_low_confidence_pc); - initializerPointCloud2(low_confidence_pc, outlier_pc); if (radius_search_2d_filter_ptr_) { + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("radius_search_2d_filter", *time_keeper_); + auto pc_frame_pose_stamped = getPoseStamped( *tf2_, input_ogm->header.frame_id, input_pc->header.frame_id, input_ogm->header.stamp); radius_search_2d_filter_ptr_->filter( high_confidence_pc, low_confidence_pc, pc_frame_pose_stamped.pose, filtered_low_confidence_pc, outlier_pc); } else { + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("low_confidence_pc_filter", *time_keeper_); + std::memcpy(&outlier_pc.data[0], &low_confidence_pc.data[0], low_confidence_pc.data.size()); outlier_pc.data.resize(low_confidence_pc.data.size()); } + // Concatenate high confidence pointcloud from occupancy grid map and non-outlier pointcloud PointCloud2 ogm_frame_filtered_pc{}; concatPointCloud2(ogm_frame_filtered_pc, high_confidence_pc); @@ -349,15 +382,28 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( concatPointCloud2(ogm_frame_filtered_pc, out_ogm_pc); concatPointCloud2(ogm_frame_filtered_pc, ogm_frame_input_behind_pc); finalizePointCloud2(ogm_frame_pc, ogm_frame_filtered_pc); - { - auto base_link_frame_filtered_pc_ptr = std::make_unique(); + + auto base_link_frame_filtered_pc_ptr = std::make_unique(); + { // scope for the timekeeper to track the time spent on transformPointcloud + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("transformPointcloud", *time_keeper_); + ogm_frame_filtered_pc.header = ogm_frame_pc.header; if (!transformPointcloud( ogm_frame_filtered_pc, *tf2_, base_link_frame_, *base_link_frame_filtered_pc_ptr)) { return; } + } + + { // scope for the timekeeper to track the time spent on publishing pointcloud + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("publish_pointcloud", *time_keeper_); + pointcloud_pub_->publish(std::move(base_link_frame_filtered_pc_ptr)); } + if (debugger_ptr_) { finalizePointCloud2(ogm_frame_pc, high_confidence_pc); finalizePointCloud2(ogm_frame_pc, filtered_low_confidence_pc); @@ -381,6 +427,9 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( void OccupancyGridMapOutlierFilterComponent::initializerPointCloud2( const PointCloud2 & input, PointCloud2 & output) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + output.point_step = input.point_step; output.data.resize(input.data.size()); } @@ -388,6 +437,9 @@ void OccupancyGridMapOutlierFilterComponent::initializerPointCloud2( void OccupancyGridMapOutlierFilterComponent::finalizePointCloud2( const PointCloud2 & input, PointCloud2 & output) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + output.header = input.header; output.point_step = input.point_step; output.fields = input.fields; @@ -401,6 +453,9 @@ void OccupancyGridMapOutlierFilterComponent::finalizePointCloud2( void OccupancyGridMapOutlierFilterComponent::concatPointCloud2( PointCloud2 & output, const PointCloud2 & input) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + size_t output_size = output.data.size(); output.data.resize(output.data.size() + input.data.size()); std::memcpy(&output.data[output_size], &input.data[0], input.data.size()); @@ -409,6 +464,9 @@ void OccupancyGridMapOutlierFilterComponent::filterByOccupancyGridMap( const OccupancyGrid & occupancy_grid_map, const PointCloud2 & pointcloud, PointCloud2 & high_confidence, PointCloud2 & low_confidence, PointCloud2 & out_ogm) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + int x_offset = pointcloud.fields[pcl::getFieldIndex(pointcloud, "x")].offset; int y_offset = pointcloud.fields[pcl::getFieldIndex(pointcloud, "y")].offset; size_t high_confidence_size = 0; diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.hpp b/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.hpp index b7ec3ffeac6df..bf2604a6fccae 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.hpp +++ b/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.hpp @@ -17,6 +17,7 @@ #include "autoware/pointcloud_preprocessor/filter.hpp" #include "autoware/universe_utils/ros/published_time_publisher.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include #include @@ -128,6 +129,11 @@ class OccupancyGridMapOutlierFilterComponent : public rclcpp::Node std::string map_frame_; std::string base_link_frame_; int cost_threshold_; + + // time keeper + rclcpp::Publisher::SharedPtr + detailed_processing_time_publisher_; + std::shared_ptr time_keeper_; }; } // namespace autoware::occupancy_grid_map_outlier_filter From a848be12ab366e12e9ef6bb596fd56b3e0787c34 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 9 Sep 2024 15:39:28 +0900 Subject: [PATCH 158/217] revert(autoware_map_based_prediction): revert improve frenet path gen (#8808) Revert "feat(autoware_map_based_prediction): improve frenet path generation (#8602)" This reverts commit 67265bbd60c85282c1c3cf65e603098e0c30c477. Signed-off-by: Taekjin LEE --- .../map_based_prediction_node.hpp | 9 +- .../map_based_prediction/path_generator.hpp | 21 +- .../src/map_based_prediction_node.cpp | 160 +--------- .../src/path_generator.cpp | 278 ++++-------------- 4 files changed, 84 insertions(+), 384 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 d1d8bb172d247..3078fe89444b8 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 @@ -127,7 +127,6 @@ struct PredictedRefPath { float probability; double speed_limit; - double width; PosePath path; Maneuver maneuver; }; @@ -292,8 +291,6 @@ class MapBasedPredictionNode : public rclcpp::Node const std::string & object_id); std::string tryMatchNewObjectToDisappeared( const std::string & object_id, std::unordered_map & current_users); - std::optional searchProperStartingRefPathIndex( - const TrackedObject & object, const PosePath & pose_path) const; std::vector getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, const double object_detected_time, const double time_horizon); @@ -318,11 +315,9 @@ class MapBasedPredictionNode : public rclcpp::Node const Maneuver & maneuver, std::vector & reference_paths, const double speed_limit = 0.0); - mutable universe_utils::LRUCache< - lanelet::routing::LaneletPaths, std::vector>> + mutable universe_utils::LRUCache> lru_cache_of_convert_path_type_{1000}; - std::vector> convertPathType( - const lanelet::routing::LaneletPaths & paths) const; + std::vector convertPathType(const lanelet::routing::LaneletPaths & paths) const; void updateFuturePossibleLanelets( const TrackedObject & object, const lanelet::routing::LaneletPaths & paths); diff --git a/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp index 416efd2aa5616..8861598ae7fb2 100644 --- a/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp +++ b/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp @@ -23,11 +23,7 @@ #include #include #include -#include #include -#include - -#include #include #include @@ -99,9 +95,8 @@ class PathGenerator const TrackedObject & object, const double duration) const; PredictedPath generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_path, const double duration, - const double lateral_duration, const double path_width = 0.0, - const double speed_limit = 0.0) const; + const TrackedObject & object, const PosePath & ref_paths, const double duration, + const double lateral_duration, const double speed_limit = 0.0) const; PredictedPath generatePathForCrosswalkUser( const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk, @@ -134,8 +129,7 @@ class PathGenerator PredictedPath generatePolynomialPath( const TrackedObject & object, const PosePath & ref_path, const double duration, - const double lateral_duration, const double path_width, const double backlash_width, - const double speed_limit = 0.0) const; + const double lateral_duration, const double speed_limit = 0.0) const; FrenetPath generateFrenetPath( const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length, @@ -145,13 +139,6 @@ class PathGenerator Eigen::Vector2d calcLonCoefficients( const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) const; - std::vector interpolationLerp( - const std::vector & base_keys, const std::vector & base_values, - const std::vector & query_keys) const; - std::vector interpolationLerp( - const std::vector & base_keys, const std::vector & base_values, - const std::vector & query_keys) const; - PosePath interpolateReferencePath( const PosePath & base_path, const FrenetPath & frenet_predicted_path) const; @@ -160,7 +147,7 @@ class PathGenerator const PosePath & ref_path) const; FrenetPoint getFrenetPoint( - const TrackedObject & object, const geometry_msgs::msg::Pose & ref_pose, const double duration, + const TrackedObject & object, const PosePath & ref_path, const double duration, const double speed_limit = 0.0) const; }; } // namespace autoware::map_based_prediction 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 7e08fc180a90d..bd8b6557bc3b6 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 @@ -23,7 +23,6 @@ #include #include #include -#include #include #include @@ -1115,7 +1114,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // If predicted reference path is empty, assume this object is out of the lane if (ref_paths.empty()) { - PredictedPath predicted_path = path_generator_->generatePathForOffLaneVehicle( + PredictedPath predicted_path = path_generator_->generatePathForLowSpeedVehicle( transformed_object, prediction_time_horizon_.vehicle); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) break; @@ -1154,7 +1153,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt for (const auto & ref_path : ref_paths) { PredictedPath predicted_path = path_generator_->generatePathForOnLaneVehicle( yaw_fixed_transformed_object, ref_path.path, prediction_time_horizon_.vehicle, - lateral_control_time_horizon_, ref_path.width, ref_path.speed_limit); + lateral_control_time_horizon_, ref_path.speed_limit); if (predicted_path.path.empty()) continue; if (!check_lateral_acceleration_constraints_) { @@ -1845,100 +1844,6 @@ void MapBasedPredictionNode::updateRoadUsersHistory( } } -std::optional MapBasedPredictionNode::searchProperStartingRefPathIndex( - const TrackedObject & object, const PosePath & pose_path) const -{ - std::unique_ptr st1_ptr; - if (time_keeper_) st1_ptr = std::make_unique(__func__, *time_keeper_); - - bool is_position_found = false; - std::optional opt_index{std::nullopt}; - auto & index = opt_index.emplace(); - - // starting segment index is a segment close enough to the object - const auto obj_point = object.kinematics.pose_with_covariance.pose.position; - { - std::unique_ptr st2_ptr; - if (time_keeper_) - st2_ptr = std::make_unique("find_close_segment_index", *time_keeper_); - double min_dist_sq = std::numeric_limits::max(); - constexpr double acceptable_dist_sq = 1.0; // [m2] - for (size_t i = 0; i < pose_path.size(); i++) { - const double dx = pose_path.at(i).position.x - obj_point.x; - const double dy = pose_path.at(i).position.y - obj_point.y; - const double dist_sq = dx * dx + dy * dy; - if (dist_sq < min_dist_sq) { - min_dist_sq = dist_sq; - index = i; - } - if (dist_sq < acceptable_dist_sq) { - break; - } - } - } - - // calculate score that object can reach the target path smoothly, and search the - // starting segment index that have the best score - size_t idx = 0; - { // find target segmentation index - std::unique_ptr st3_ptr; - if (time_keeper_) - st3_ptr = std::make_unique("find_target_seg_index", *time_keeper_); - - constexpr double search_distance = 22.0; // [m] - constexpr double yaw_diff_limit = M_PI / 3.0; // 60 degrees - - const double obj_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); - const size_t search_segment_count = - static_cast(std::floor(search_distance / reference_path_resolution_)); - const size_t search_segment_num = - std::min(search_segment_count, static_cast(pose_path.size() - index)); - - // search for the best score, which is the smallest - double best_score = 1e9; // initial value is large enough - for (size_t i = 0; i < search_segment_num; ++i) { - const auto & path_pose = pose_path.at(index + i); - // yaw difference - const double path_yaw = tf2::getYaw(path_pose.orientation); - const double relative_path_yaw = autoware_utils::normalize_radian(path_yaw - obj_yaw); - if (std::abs(relative_path_yaw) > yaw_diff_limit) { - continue; - } - - const double dx = path_pose.position.x - obj_point.x; - const double dy = path_pose.position.y - obj_point.y; - const double dx_cp = std::cos(obj_yaw) * dx + std::sin(obj_yaw) * dy; - const double dy_cp = -std::sin(obj_yaw) * dx + std::cos(obj_yaw) * dy; - const double neutral_yaw = std::atan2(dy_cp, dx_cp) * 2.0; - const double delta_yaw = autoware_utils::normalize_radian(path_yaw - obj_yaw - neutral_yaw); - if (std::abs(delta_yaw) > yaw_diff_limit) { - continue; - } - - // objective function score - constexpr double weight_ratio = 0.01; - double score = delta_yaw * delta_yaw + weight_ratio * neutral_yaw * neutral_yaw; - constexpr double acceptable_score = 1e-3; - - if (score < best_score) { - best_score = score; - idx = i; - is_position_found = true; - if (score < acceptable_score) { - // if the score is small enough, we can break the loop - break; - } - } - } - } - - // update starting segment index - index += idx; - index = std::clamp(index, 0ul, pose_path.size() - 1); - - return is_position_found ? opt_index : std::nullopt; -} - std::vector MapBasedPredictionNode::getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, const double object_detected_time, const double time_horizon) @@ -1946,7 +1851,6 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - // Step 1. Set conditions for the prediction const double obj_vel = std::hypot( object.kinematics.twist_with_covariance.twist.linear.x, object.kinematics.twist_with_covariance.twist.linear.y); @@ -1987,10 +1891,9 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( return search_dist; }; - // Step 2. Get possible paths for each lanelet std::vector all_ref_paths; + for (const auto & current_lanelet_data : current_lanelets_data) { - // Set condition on each lanelet const lanelet::traffic_rules::SpeedLimitInformation limit = traffic_rules_ptr_->speedLimit(current_lanelet_data.lanelet); const double legal_speed_limit = static_cast(limit.speedLimit.value()); @@ -2056,21 +1959,22 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( return std::nullopt; }; - // a-1. Get the left lanelet + // Step1. Get the path + // Step1.1 Get the left lanelet lanelet::routing::LaneletPaths left_paths; const auto left_lanelet = getLeftOrRightLanelets(current_lanelet_data.lanelet, true); if (!!left_lanelet) { left_paths = getPathsForNormalOrIsolatedLanelet(left_lanelet.value()); } - // a-2. Get the right lanelet + // Step1.2 Get the right lanelet lanelet::routing::LaneletPaths right_paths; const auto right_lanelet = getLeftOrRightLanelets(current_lanelet_data.lanelet, false); if (!!right_lanelet) { right_paths = getPathsForNormalOrIsolatedLanelet(right_lanelet.value()); } - // a-3. Get the center lanelet + // Step1.3 Get the centerline lanelet::routing::LaneletPaths center_paths = getPathsForNormalOrIsolatedLanelet(current_lanelet_data.lanelet); @@ -2079,15 +1983,15 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( continue; } - // b. Predict Object Maneuver + // Step2. Predict Object Maneuver const Maneuver predicted_maneuver = predictObjectManeuver(object, current_lanelet_data, object_detected_time); - // c. Allocate probability for each predicted maneuver + // Step3. Allocate probability for each predicted maneuver const auto maneuver_prob = calculateManeuverProbability(predicted_maneuver, left_paths, right_paths, center_paths); - // d. add candidate reference paths to the all_ref_paths + // Step4. add candidate reference paths to the all_ref_paths const float path_prob = current_lanelet_data.probability; const auto addReferencePathsLocal = [&](const auto & paths, const auto & maneuver) { addReferencePaths( @@ -2098,31 +2002,6 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( addReferencePathsLocal(center_paths, Maneuver::LANE_FOLLOW); } - // Step 3. Search starting point for each reference path - for (auto it = all_ref_paths.begin(); it != all_ref_paths.end();) { - std::unique_ptr st1_ptr; - if (time_keeper_) - st1_ptr = - std::make_unique("searching_refpath_starting_point", *time_keeper_); - - auto & pose_path = it->path; - if (pose_path.empty()) { - continue; - } - - const std::optional opt_starting_idx = - searchProperStartingRefPathIndex(object, pose_path); - - if (opt_starting_idx.has_value()) { - // Trim the reference path - pose_path.erase(pose_path.begin(), pose_path.begin() + opt_starting_idx.value()); - ++it; - } else { - // Proper starting point is not found, remove the reference path - it = all_ref_paths.erase(it); - } - } - return all_ref_paths; } @@ -2462,8 +2341,7 @@ void MapBasedPredictionNode::addReferencePaths( for (const auto & converted_path : converted_paths) { PredictedRefPath predicted_path; predicted_path.probability = maneuver_probability.at(maneuver) * path_probability; - predicted_path.path = converted_path.first; - predicted_path.width = converted_path.second; + predicted_path.path = converted_path; predicted_path.maneuver = maneuver; predicted_path.speed_limit = speed_limit; reference_paths.push_back(predicted_path); @@ -2538,7 +2416,7 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability( return maneuver_prob; } -std::vector> MapBasedPredictionNode::convertPathType( +std::vector MapBasedPredictionNode::convertPathType( const lanelet::routing::LaneletPaths & paths) const { std::unique_ptr st_ptr; @@ -2548,10 +2426,9 @@ std::vector> MapBasedPredictionNode::convertPathType return *lru_cache_of_convert_path_type_.get(paths); } - std::vector> converted_paths; + std::vector converted_paths; for (const auto & path : paths) { PosePath converted_path; - double width = 10.0; // Initialize with a large value // Insert Positions. Note that we start inserting points from previous lanelet if (!path.empty()) { @@ -2569,7 +2446,6 @@ std::vector> MapBasedPredictionNode::convertPathType continue; } - // only considers yaw of the lanelet const double lane_yaw = std::atan2( current_p.position.y - prev_p.position.y, current_p.position.x - prev_p.position.x); const double sin_yaw_half = std::sin(lane_yaw / 2.0); @@ -2619,14 +2495,6 @@ std::vector> MapBasedPredictionNode::convertPathType converted_path.push_back(current_p); prev_p = current_p; } - - // Update minimum width - const auto left_bound = lanelet.leftBound2d(); - const auto right_bound = lanelet.rightBound2d(); - const double lanelet_width_front = std::hypot( - left_bound.front().x() - right_bound.front().x(), - left_bound.front().y() - right_bound.front().y()); - width = std::min(width, lanelet_width_front); } // Resample Path @@ -2638,7 +2506,7 @@ std::vector> MapBasedPredictionNode::convertPathType // interpolation for xy const auto resampled_converted_path = autoware::motion_utils::resamplePoseVector( converted_path, reference_path_resolution_, use_akima_spline_for_xy, use_lerp_for_z); - converted_paths.push_back(std::make_pair(resampled_converted_path, width)); + converted_paths.push_back(resampled_converted_path); } lru_cache_of_convert_path_type_.put(paths, converted_paths); diff --git a/perception/autoware_map_based_prediction/src/path_generator.cpp b/perception/autoware_map_based_prediction/src/path_generator.cpp index 4f9f7a7586ce6..4b759e22cdb4f 100644 --- a/perception/autoware_map_based_prediction/src/path_generator.cpp +++ b/perception/autoware_map_based_prediction/src/path_generator.cpp @@ -175,37 +175,17 @@ PredictedPath PathGenerator::generatePathForOffLaneVehicle( } PredictedPath PathGenerator::generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_path, const double duration, - const double lateral_duration, const double path_width, const double speed_limit) const + const TrackedObject & object, const PosePath & ref_paths, const double duration, + const double lateral_duration, const double speed_limit) const { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - if (ref_path.size() < 2) { - return generateStraightPath(object, duration); - } - - // if the object is moving backward, we generate a straight path - if (object.kinematics.twist_with_covariance.twist.linear.x < 0.0) { + if (ref_paths.size() < 2) { return generateStraightPath(object, duration); } - // get object width - double object_width = 5.0; // a large number - if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { - object_width = object.shape.dimensions.y; - } else if (object.shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { - object_width = object.shape.dimensions.x; - } - // Calculate the backlash width, which represents the maximum distance the object can be biased - // from the reference path - constexpr double margin = - 0.5; // Set a safety margin of 0.5m for the object to stay away from the edge of the lane - double backlash_width = (path_width - object_width) / 2.0 - margin; - backlash_width = std::max(backlash_width, 0.0); // minimum is 0.0 - - return generatePolynomialPath( - object, ref_path, duration, lateral_duration, path_width, backlash_width, speed_limit); + return generatePolynomialPath(object, ref_paths, duration, lateral_duration, speed_limit); } PredictedPath PathGenerator::generateStraightPath( @@ -230,68 +210,37 @@ PredictedPath PathGenerator::generateStraightPath( PredictedPath PathGenerator::generatePolynomialPath( const TrackedObject & object, const PosePath & ref_path, const double duration, - const double lateral_duration, const double path_width, const double backlash_width, - const double speed_limit) const + const double lateral_duration, const double speed_limit) const { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); // Get current Frenet Point const double ref_path_len = autoware::motion_utils::calcArcLength(ref_path); - const auto current_point = getFrenetPoint(object, ref_path.at(0), duration, speed_limit); + const auto current_point = getFrenetPoint(object, ref_path, duration, speed_limit); - // Step 1. Set Target Frenet Point + // Step1. Set Target Frenet Point // Note that we do not set position s, // since we don't know the target longitudinal position FrenetPoint terminal_point; - terminal_point.s_vel = std::hypot(current_point.s_vel, current_point.d_vel); + terminal_point.s_vel = current_point.s_vel; terminal_point.s_acc = 0.0; + terminal_point.d = 0.0; terminal_point.d_vel = 0.0; terminal_point.d_acc = 0.0; - // calculate terminal d position, based on backlash width - { - if (backlash_width < 0.01 /*m*/) { - // If the backlash width is less than 0.01m, do not consider the backlash width and reduce - // calculation cost - terminal_point.d = 0.0; - } else { - const double return_width = path_width / 2.0; // [m] - const double current_momentum_d = - current_point.d + 0.5 * current_point.d_vel * lateral_duration; - const double momentum_d_abs = std::abs(current_momentum_d); - - if (momentum_d_abs < backlash_width) { - // If the object momentum is within the backlash width, we set the target d position to the - // current momentum - terminal_point.d = current_momentum_d; - } else if ( - momentum_d_abs >= backlash_width && momentum_d_abs < backlash_width + return_width) { - // If the object momentum is within the return zone, we set the target d position close to - // the zero gradually - terminal_point.d = - (backlash_width + return_width - momentum_d_abs) * backlash_width / return_width; - terminal_point.d *= (current_momentum_d > 0) ? 1 : -1; - } else { - // If the object momentum is outside the backlash width + return zone, we set the target d - // position to 0 - terminal_point.d = 0.0; - } - } - } - - // Step 2. Generate Predicted Path on a Frenet coordinate + // Step2. Generate Predicted Path on a Frenet coordinate const auto frenet_predicted_path = generateFrenetPath(current_point, terminal_point, ref_path_len, duration, lateral_duration); - // Step 3. Interpolate Reference Path for converting predicted path coordinate + // Step3. Interpolate Reference Path for converting predicted path coordinate const auto interpolated_ref_path = interpolateReferencePath(ref_path, frenet_predicted_path); if (frenet_predicted_path.size() < 2 || interpolated_ref_path.size() < 2) { return generateStraightPath(object, duration); } - // Step 4. Convert predicted trajectory from Frenet to Cartesian coordinate + // Step4. Convert predicted trajectory from Frenet to Cartesian coordinate return convertToPredictedPath(object, frenet_predicted_path, interpolated_ref_path); } @@ -309,7 +258,6 @@ FrenetPath PathGenerator::generateFrenetPath( calcLatCoefficients(current_point, target_point, lateral_duration); const Eigen::Vector2d lon_coeff = calcLonCoefficients(current_point, target_point, duration); - // Generate the trajectory path.reserve(static_cast(duration / sampling_time_interval_)); for (double t = 0.0; t <= duration; t += sampling_time_interval_) { const auto t2 = t * t; @@ -320,19 +268,22 @@ FrenetPath PathGenerator::generateFrenetPath( 0.0; // Currently we assume the object is traveling at a constant speed const double d_next_ = current_point.d + current_point.d_vel * t + current_acc * 2.0 * t2 + lat_coeff(0) * t3 + lat_coeff(1) * t4 + lat_coeff(2) * t5; - // t > lateral_duration: target_point.d, else d_next_ - const double d_next = t > lateral_duration ? target_point.d : d_next_; + // t > lateral_duration: 0.0, else d_next_ + const double d_next = t > lateral_duration ? 0.0 : d_next_; const double s_next = current_point.s + current_point.s_vel * t + 2.0 * current_acc * t2 + lon_coeff(0) * t3 + lon_coeff(1) * t4; - if (s_next > max_length) { break; } - // Fill the FrenetPoint, velocity and acceleration are not used in the path generator + // We assume the object is traveling at a constant speed along s direction FrenetPoint point; - point.s = s_next; + point.s = std::max(s_next, 0.0); + point.s_vel = current_point.s_vel; + point.s_acc = current_point.s_acc; point.d = d_next; + point.d_vel = current_point.d_vel; + point.d_acc = current_point.d_acc; path.push_back(point); } @@ -389,107 +340,6 @@ Eigen::Vector2d PathGenerator::calcLonCoefficients( return A_lon_inv * b_lon; } -std::vector PathGenerator::interpolationLerp( - const std::vector & base_keys, const std::vector & base_values, - const std::vector & query_keys) const -{ - std::unique_ptr st_ptr; - if (time_keeper_) - st_ptr = std::make_unique("interpolationLerp_double", *time_keeper_); - - // calculate linear interpolation - // extrapolate the value if the query key is out of the base key range - std::vector query_values; - size_t key_index = 0; - double last_query_key = query_keys.at(0); - for (const auto query_key : query_keys) { - // search for the closest key index - // if current query key is larger than the last query key, search base_keys increasing order - if (query_key >= last_query_key) { - while (base_keys.at(key_index + 1) < query_key) { - if (key_index == base_keys.size() - 2) { - break; - } - ++key_index; - } - } else { - // if current query key is smaller than the last query key, search base_keys decreasing order - while (base_keys.at(key_index) > query_key) { - if (key_index == 0) { - break; - } - --key_index; - } - } - last_query_key = query_key; - - const double & src_val = base_values.at(key_index); - const double & dst_val = base_values.at(key_index + 1); - const double ratio = (query_key - base_keys.at(key_index)) / - (base_keys.at(key_index + 1) - base_keys.at(key_index)); - - const double interpolated_val = src_val + (dst_val - src_val) * ratio; - query_values.push_back(interpolated_val); - } - - return query_values; -} - -std::vector PathGenerator::interpolationLerp( - const std::vector & base_keys, const std::vector & base_values, - const std::vector & query_keys) const -{ - std::unique_ptr st_ptr; - if (time_keeper_) - st_ptr = std::make_unique("interpolationLerp_quaternion", *time_keeper_); - - // calculate linear interpolation - // extrapolate the value if the query key is out of the base key range - std::vector query_values; - size_t key_index = 0; - double last_query_key = query_keys.at(0); - for (const auto query_key : query_keys) { - // search for the closest key index - // if current query key is larger than the last query key, search base_keys increasing order - if (query_key >= last_query_key) { - while (base_keys.at(key_index + 1) < query_key) { - if (key_index == base_keys.size() - 2) { - break; - } - ++key_index; - } - } else { - // if current query key is smaller than the last query key, search base_keys decreasing order - while (base_keys.at(key_index) > query_key) { - if (key_index == 0) { - break; - } - --key_index; - } - } - last_query_key = query_key; - - const tf2::Quaternion & src_val = base_values.at(key_index); - const tf2::Quaternion & dst_val = base_values.at(key_index + 1); - const double ratio = (query_key - base_keys.at(key_index)) / - (base_keys.at(key_index + 1) - base_keys.at(key_index)); - - // in case of extrapolation, export the nearest quaternion - if (ratio < 0.0) { - query_values.push_back(src_val); - continue; - } - if (ratio > 1.0) { - query_values.push_back(dst_val); - continue; - } - const auto interpolated_quat = tf2::slerp(src_val, dst_val, ratio); - query_values.push_back(interpolated_quat); - } - - return query_values; -} - PosePath PathGenerator::interpolateReferencePath( const PosePath & base_path, const FrenetPath & frenet_predicted_path) const { @@ -503,47 +353,49 @@ PosePath PathGenerator::interpolateReferencePath( return interpolated_path; } - // Prepare base path vectors std::vector base_path_x(base_path.size()); std::vector base_path_y(base_path.size()); std::vector base_path_z(base_path.size()); - std::vector base_path_orientation(base_path.size()); std::vector base_path_s(base_path.size(), 0.0); for (size_t i = 0; i < base_path.size(); ++i) { base_path_x.at(i) = base_path.at(i).position.x; base_path_y.at(i) = base_path.at(i).position.y; base_path_z.at(i) = base_path.at(i).position.z; - tf2::Quaternion src_tf; - tf2::fromMsg(base_path.at(i).orientation, src_tf); - base_path_orientation.at(i) = src_tf; if (i > 0) { base_path_s.at(i) = base_path_s.at(i - 1) + autoware::universe_utils::calcDistance2d( base_path.at(i - 1), base_path.at(i)); } } - // Prepare resampled s vector std::vector resampled_s(frenet_predicted_path.size()); for (size_t i = 0; i < frenet_predicted_path.size(); ++i) { resampled_s.at(i) = frenet_predicted_path.at(i).s; } + if (resampled_s.front() > resampled_s.back()) { + std::reverse(resampled_s.begin(), resampled_s.end()); + } - // Linear Interpolation for x, y, z, and orientation - std::vector lerp_ref_path_x = interpolationLerp(base_path_s, base_path_x, resampled_s); - std::vector lerp_ref_path_y = interpolationLerp(base_path_s, base_path_y, resampled_s); - std::vector lerp_ref_path_z = interpolationLerp(base_path_s, base_path_z, resampled_s); - std::vector lerp_ref_path_orientation = - interpolationLerp(base_path_s, base_path_orientation, resampled_s); + // Lerp Interpolation + std::vector lerp_ref_path_x = interpolation::lerp(base_path_s, base_path_x, resampled_s); + std::vector lerp_ref_path_y = interpolation::lerp(base_path_s, base_path_y, resampled_s); + std::vector lerp_ref_path_z = interpolation::lerp(base_path_s, base_path_z, resampled_s); - // Set the interpolated PosePath interpolated_path.resize(interpolate_num); - for (size_t i = 0; i < interpolate_num; ++i) { + for (size_t i = 0; i < interpolate_num - 1; ++i) { geometry_msgs::msg::Pose interpolated_pose; + const auto current_point = + autoware::universe_utils::createPoint(lerp_ref_path_x.at(i), lerp_ref_path_y.at(i), 0.0); + const auto next_point = autoware::universe_utils::createPoint( + lerp_ref_path_x.at(i + 1), lerp_ref_path_y.at(i + 1), 0.0); + const double yaw = autoware::universe_utils::calcAzimuthAngle(current_point, next_point); interpolated_pose.position = autoware::universe_utils::createPoint( lerp_ref_path_x.at(i), lerp_ref_path_y.at(i), lerp_ref_path_z.at(i)); - interpolated_pose.orientation = tf2::toMsg(lerp_ref_path_orientation.at(i)); + interpolated_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); interpolated_path.at(i) = interpolated_pose; } + interpolated_path.back().position = autoware::universe_utils::createPoint( + lerp_ref_path_x.back(), lerp_ref_path_y.back(), lerp_ref_path_z.back()); + interpolated_path.back().orientation = interpolated_path.at(interpolate_num - 2).orientation; return interpolated_path; } @@ -555,30 +407,27 @@ PredictedPath PathGenerator::convertToPredictedPath( std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - // Object position - const auto & object_pose = object.kinematics.pose_with_covariance.pose; - const double object_height = object.shape.dimensions.z / 2.0; - - // Convert Frenet Path to Cartesian Path PredictedPath predicted_path; predicted_path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); predicted_path.path.resize(ref_path.size()); - - // Set the first point as the object's current position - predicted_path.path.at(0) = object_pose; - - // Convert the rest of the points - for (size_t i = 1; i < predicted_path.path.size(); ++i) { + for (size_t i = 0; i < predicted_path.path.size(); ++i) { // Reference Point from interpolated reference path const auto & ref_pose = ref_path.at(i); // Frenet Point from frenet predicted path const auto & frenet_point = frenet_predicted_path.at(i); - double d_offset = frenet_point.d; // Converted Pose - auto predicted_pose = autoware::universe_utils::calcOffsetPose(ref_pose, 0.0, d_offset, 0.0); - predicted_pose.position.z += object_height; + auto predicted_pose = + autoware::universe_utils::calcOffsetPose(ref_pose, 0.0, frenet_point.d, 0.0); + predicted_pose.position.z = object.kinematics.pose_with_covariance.pose.position.z; + if (i == 0) { + predicted_pose.orientation = object.kinematics.pose_with_covariance.pose.orientation; + } else { + const double yaw = autoware::universe_utils::calcAzimuthAngle( + predicted_path.path.at(i - 1).position, predicted_pose.position); + predicted_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); + } predicted_path.path.at(i) = predicted_pose; } @@ -586,27 +435,27 @@ PredictedPath PathGenerator::convertToPredictedPath( } FrenetPoint PathGenerator::getFrenetPoint( - const TrackedObject & object, const geometry_msgs::msg::Pose & ref_pose, const double duration, + const TrackedObject & object, const PosePath & ref_path, const double duration, const double speed_limit) const { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); FrenetPoint frenet_point; - - // 1. Position const auto obj_point = object.kinematics.pose_with_covariance.pose.position; - const float obj_yaw = - static_cast(tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)); - const float lane_yaw = static_cast(tf2::getYaw(ref_pose.orientation)); - frenet_point.s = (obj_point.x - ref_pose.position.x) * cos(lane_yaw) + - (obj_point.y - ref_pose.position.y) * sin(lane_yaw); - frenet_point.d = -(obj_point.x - ref_pose.position.x) * sin(lane_yaw) + - (obj_point.y - ref_pose.position.y) * cos(lane_yaw); - // 2. Velocity (adjusted by acceleration) + const size_t nearest_segment_idx = + autoware::motion_utils::findNearestSegmentIndex(ref_path, obj_point); + const double l = autoware::motion_utils::calcLongitudinalOffsetToSegment( + ref_path, nearest_segment_idx, obj_point); const float vx = static_cast(object.kinematics.twist_with_covariance.twist.linear.x); const float vy = static_cast(object.kinematics.twist_with_covariance.twist.linear.y); + const float obj_yaw = + static_cast(tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)); + const float lane_yaw = + static_cast(tf2::getYaw(ref_path.at(nearest_segment_idx).orientation)); + const float delta_yaw = obj_yaw - lane_yaw; + const float ax = (use_vehicle_acceleration_) ? static_cast(object.kinematics.acceleration_with_covariance.accel.linear.x) @@ -615,9 +464,8 @@ FrenetPoint PathGenerator::getFrenetPoint( (use_vehicle_acceleration_) ? static_cast(object.kinematics.acceleration_with_covariance.accel.linear.y) : 0.0; - const float delta_yaw = obj_yaw - lane_yaw; - // using a decaying acceleration model. Consult the README for more information about the model. + // Using a decaying acceleration model. Consult the README for more information about the model. const double t_h = duration; const float lambda = std::log(2) / acceleration_exponential_half_life_; @@ -679,12 +527,14 @@ FrenetPoint PathGenerator::getFrenetPoint( const float acceleration_adjusted_velocity_x = get_acceleration_adjusted_velocity(vx, ax); const float acceleration_adjusted_velocity_y = get_acceleration_adjusted_velocity(vy, ay); + + frenet_point.s = + autoware::motion_utils::calcSignedArcLength(ref_path, 0, nearest_segment_idx) + l; + frenet_point.d = autoware::motion_utils::calcLateralOffset(ref_path, obj_point); frenet_point.s_vel = acceleration_adjusted_velocity_x * std::cos(delta_yaw) - acceleration_adjusted_velocity_y * std::sin(delta_yaw); frenet_point.d_vel = acceleration_adjusted_velocity_x * std::sin(delta_yaw) + acceleration_adjusted_velocity_y * std::cos(delta_yaw); - - // 3. Acceleration, assuming constant acceleration frenet_point.s_acc = 0.0; frenet_point.d_acc = 0.0; From 96b522a2ab7b05beb3fa73351134f2e110586992 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Mon, 9 Sep 2024 16:25:33 +0900 Subject: [PATCH 159/217] refactor(autoware_pointcloud_preprocessor): rework radius search 2d outlier filter parameters (#8474) * feat: rework radius search 2d outlier filter parameters Signed-off-by: vividf * chore: fix schema Signed-off-by: vividf * chore: explicit cast Signed-off-by: vividf * chore: add boundary in schema Signed-off-by: vividf --------- Signed-off-by: vividf --- .../CMakeLists.txt | 2 +- ...s_search_2d_outlier_filter_node.param.yaml | 4 ++ .../docs/radius-search-2d-outlier-filter.md | 5 +-- ... radius_search_2d_outlier_filter_node.hpp} | 6 +-- ...s_search_2d_outlier_filter_node.launch.xml | 16 ++++++++ ..._search_2d_outlier_filter_node.schema.json | 40 +++++++++++++++++++ ... radius_search_2d_outlier_filter_node.cpp} | 6 +-- 7 files changed, 68 insertions(+), 11 deletions(-) create mode 100644 sensing/autoware_pointcloud_preprocessor/config/radius_search_2d_outlier_filter_node.param.yaml rename sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/{radius_search_2d_outlier_filter_nodelet.hpp => radius_search_2d_outlier_filter_node.hpp} (92%) create mode 100644 sensing/autoware_pointcloud_preprocessor/launch/radius_search_2d_outlier_filter_node.launch.xml create mode 100644 sensing/autoware_pointcloud_preprocessor/schema/radius_search_2d_outlier_filter_node.schema.json rename sensing/autoware_pointcloud_preprocessor/src/outlier_filter/{radius_search_2d_outlier_filter_nodelet.cpp => radius_search_2d_outlier_filter_node.cpp} (94%) diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt index 2474b483cb2fe..15634187900f9 100644 --- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt @@ -71,8 +71,8 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED src/downsample_filter/approximate_downsample_filter_nodelet.cpp src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp src/outlier_filter/ring_outlier_filter_nodelet.cpp + src/outlier_filter/radius_search_2d_outlier_filter_node.cpp src/outlier_filter/voxel_grid_outlier_filter_node.cpp - src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp src/outlier_filter/dual_return_outlier_filter_nodelet.cpp src/passthrough_filter/passthrough_filter_node.cpp src/passthrough_filter/passthrough_filter_uint16_node.cpp diff --git a/sensing/autoware_pointcloud_preprocessor/config/radius_search_2d_outlier_filter_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/radius_search_2d_outlier_filter_node.param.yaml new file mode 100644 index 0000000000000..8d2d32584c86d --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/config/radius_search_2d_outlier_filter_node.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + min_neighbors: 5 + search_radius: 0.2 diff --git a/sensing/autoware_pointcloud_preprocessor/docs/radius-search-2d-outlier-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/radius-search-2d-outlier-filter.md index d0d621b586da6..1c44f13e3d016 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/radius-search-2d-outlier-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/radius-search-2d-outlier-filter.md @@ -24,10 +24,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, ### Core Parameters -| Name | Type | Description | -| --------------- | ------ | ------------------------------------------------------------------------------------------------------------------------ | -| `min_neighbors` | int | If points in the circle centered on reference point is less than `min_neighbors`, a reference point is judged as outlier | -| `search_radius` | double | Searching number of points included in `search_radius` | +{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/radius_search_2d_outlier_filter_node.schema.json") }} ## Assumptions / Known limits diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_node.hpp similarity index 92% rename from sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_node.hpp index ffb737b0b9b06..6dfefde981982 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ // NOLINT -#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ // NOLINT +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODE_HPP_ // NOLINT +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODE_HPP_ // NOLINT #include "autoware/pointcloud_preprocessor/filter.hpp" @@ -55,5 +55,5 @@ class RadiusSearch2DOutlierFilterComponent : public autoware::pointcloud_preproc } // namespace autoware::pointcloud_preprocessor // clang-format off -#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ // NOLINT +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODE_HPP_ // NOLINT // clang-format on diff --git a/sensing/autoware_pointcloud_preprocessor/launch/radius_search_2d_outlier_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/radius_search_2d_outlier_filter_node.launch.xml new file mode 100644 index 0000000000000..665c8d7c6e37c --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/launch/radius_search_2d_outlier_filter_node.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/sensing/autoware_pointcloud_preprocessor/schema/radius_search_2d_outlier_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/radius_search_2d_outlier_filter_node.schema.json new file mode 100644 index 0000000000000..0a471162a77b6 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/schema/radius_search_2d_outlier_filter_node.schema.json @@ -0,0 +1,40 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Radius Search 2D Outlier Filter Node", + "type": "object", + "definitions": { + "radius_search_2d_outlier_filter": { + "type": "object", + "properties": { + "min_neighbors": { + "type": "integer", + "description": "If points in the circle centered on reference point is less than min_neighbors, a reference point is judged as outlier", + "default": "5", + "minimum": 0 + }, + "search_radius": { + "type": "number", + "description": "Searching number of points included in search_radius", + "default": "0.2", + "minimum": 0 + } + }, + "required": ["min_neighbors", "search_radius"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/radius_search_2d_outlier_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_node.cpp similarity index 94% rename from sensing/autoware_pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_node.cpp index 05bf3898d0cf0..c76a687fe1192 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_node.hpp" #include #include @@ -28,8 +28,8 @@ RadiusSearch2DOutlierFilterComponent::RadiusSearch2DOutlierFilterComponent( { // set initial parameters { - min_neighbors_ = static_cast(declare_parameter("min_neighbors", 5)); - search_radius_ = static_cast(declare_parameter("search_radius", 0.2)); + min_neighbors_ = static_cast(declare_parameter("min_neighbors")); + search_radius_ = declare_parameter("search_radius"); } kd_tree_ = pcl::make_shared>(false); From 0b3aab95186160ac893f4b957ffe83112195eee3 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 9 Sep 2024 16:52:41 +0900 Subject: [PATCH 160/217] feat(autoware_map_based_prediction): improve frenet path generation (#8811) * feat: calculate terminal d position based on playable width in path_generator.cpp Signed-off-by: Taekjin LEE * feat: Add width parameter path generations refactor(path_generator): improve backlash width calculation Signed-off-by: Taekjin LEE refactor(path_generator): improve backlash width calculation Signed-off-by: Taekjin LEE * fix: set initial point of Frenet Path to Cartesian Path conversion Signed-off-by: Taekjin LEE refactor: limit the d value to the radius for curved reference paths refactor: limit d value to curve limit for curved reference paths refactor: extend base_path_s with extrapolated base_path_x, base_path_y, base_path_z if min_s is negative refactor: linear path when object is moving backward feat: Update getFrenetPoint function to include target_path parameter The getFrenetPoint function in path_generator.hpp and path_generator.cpp has been updated to include a new parameter called target_path. This parameter is used to trim the reference path based on the starting segment index, allowing for more accurate calculations. * feat: Add interpolationLerp function for linear interpolation Signed-off-by: Taekjin LEE * Update starting_segment_idx type in getFrenetPoint function Signed-off-by: Taekjin LEE refactor: Update starting_segment_idx type in getFrenetPoint function refactor: Update getFrenetPoint function to include target_path parameter refactor: exclude target path determination logic from getFrenetPoint refactor: Add interpolationLerp function for quaternion linear interpolation refactor: remove redundant yaw height update refactor: Update path_generator.cpp to include object height in predicted_pose fix: comment out optimum target searcher * feat: implement a new optimization of target ref path search Signed-off-by: Taekjin LEE refactor: Update path_generator.cpp to include object height in predicted_pose refactor: measure performance refactor: remove comment-outs, measure times style(pre-commit): autofix refactor: move starting point search function to getPredictedReferencePath refactor: target segment index search parameter adjust * fix: replace nearest search to custom one for efficiency Signed-off-by: Taekjin LEE feat: Update CLOSE_LANELET_THRESHOLD and CLOSE_PATH_THRESHOLD values Signed-off-by: Taekjin LEE * refactor: getFrenetPoint blocks Signed-off-by: Taekjin LEE * chore: add comments Signed-off-by: Taekjin LEE * feat: Trim reference paths if optimum position is not found Signed-off-by: Taekjin LEE style(pre-commit): autofix chore: remove comment Signed-off-by: Taekjin LEE * fix: shadowVariable of time keeper pointers Signed-off-by: Taekjin LEE * refactor: improve backlash width calculation, parameter adjustment Signed-off-by: Taekjin LEE * fix: cylinder type object do not have y dimension, use x dimension Signed-off-by: Taekjin LEE * chore: add comment to explain an internal parameter 'margin' Signed-off-by: Taekjin LEE * chore: add comment of backlash calculation shortcut Signed-off-by: Taekjin LEE * chore: Improve readability of backlash to target shift model Signed-off-by: Taekjin LEE * feat: set the return width by the path width Signed-off-by: Taekjin LEE * refactor: separate a logic to searchProperStartingRefPathIndex function Signed-off-by: Taekjin LEE * refactor: search starting ref path using optional for return type Signed-off-by: Taekjin LEE * fix: object orientation calculation is added to the predicted path generation Signed-off-by: Taekjin LEE * chore: fix spell-check Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../map_based_prediction_node.hpp | 9 +- .../map_based_prediction/path_generator.hpp | 21 +- .../src/map_based_prediction_node.cpp | 160 +++++++++- .../src/path_generator.cpp | 282 ++++++++++++++---- 4 files changed, 388 insertions(+), 84 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 3078fe89444b8..d1d8bb172d247 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 @@ -127,6 +127,7 @@ struct PredictedRefPath { float probability; double speed_limit; + double width; PosePath path; Maneuver maneuver; }; @@ -291,6 +292,8 @@ class MapBasedPredictionNode : public rclcpp::Node const std::string & object_id); std::string tryMatchNewObjectToDisappeared( const std::string & object_id, std::unordered_map & current_users); + std::optional searchProperStartingRefPathIndex( + const TrackedObject & object, const PosePath & pose_path) const; std::vector getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, const double object_detected_time, const double time_horizon); @@ -315,9 +318,11 @@ class MapBasedPredictionNode : public rclcpp::Node const Maneuver & maneuver, std::vector & reference_paths, const double speed_limit = 0.0); - mutable universe_utils::LRUCache> + mutable universe_utils::LRUCache< + lanelet::routing::LaneletPaths, std::vector>> lru_cache_of_convert_path_type_{1000}; - std::vector convertPathType(const lanelet::routing::LaneletPaths & paths) const; + std::vector> convertPathType( + const lanelet::routing::LaneletPaths & paths) const; void updateFuturePossibleLanelets( const TrackedObject & object, const lanelet::routing::LaneletPaths & paths); diff --git a/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp index 8861598ae7fb2..416efd2aa5616 100644 --- a/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp +++ b/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp @@ -23,7 +23,11 @@ #include #include #include +#include #include +#include + +#include #include #include @@ -95,8 +99,9 @@ class PathGenerator const TrackedObject & object, const double duration) const; PredictedPath generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_paths, const double duration, - const double lateral_duration, const double speed_limit = 0.0) const; + const TrackedObject & object, const PosePath & ref_path, const double duration, + const double lateral_duration, const double path_width = 0.0, + const double speed_limit = 0.0) const; PredictedPath generatePathForCrosswalkUser( const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk, @@ -129,7 +134,8 @@ class PathGenerator PredictedPath generatePolynomialPath( const TrackedObject & object, const PosePath & ref_path, const double duration, - const double lateral_duration, const double speed_limit = 0.0) const; + const double lateral_duration, const double path_width, const double backlash_width, + const double speed_limit = 0.0) const; FrenetPath generateFrenetPath( const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length, @@ -139,6 +145,13 @@ class PathGenerator Eigen::Vector2d calcLonCoefficients( const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) const; + std::vector interpolationLerp( + const std::vector & base_keys, const std::vector & base_values, + const std::vector & query_keys) const; + std::vector interpolationLerp( + const std::vector & base_keys, const std::vector & base_values, + const std::vector & query_keys) const; + PosePath interpolateReferencePath( const PosePath & base_path, const FrenetPath & frenet_predicted_path) const; @@ -147,7 +160,7 @@ class PathGenerator const PosePath & ref_path) const; FrenetPoint getFrenetPoint( - const TrackedObject & object, const PosePath & ref_path, const double duration, + const TrackedObject & object, const geometry_msgs::msg::Pose & ref_pose, const double duration, const double speed_limit = 0.0) const; }; } // namespace autoware::map_based_prediction 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 bd8b6557bc3b6..6427dd9c8914c 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 @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -1114,7 +1115,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // If predicted reference path is empty, assume this object is out of the lane if (ref_paths.empty()) { - PredictedPath predicted_path = path_generator_->generatePathForLowSpeedVehicle( + PredictedPath predicted_path = path_generator_->generatePathForOffLaneVehicle( transformed_object, prediction_time_horizon_.vehicle); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) break; @@ -1153,7 +1154,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt for (const auto & ref_path : ref_paths) { PredictedPath predicted_path = path_generator_->generatePathForOnLaneVehicle( yaw_fixed_transformed_object, ref_path.path, prediction_time_horizon_.vehicle, - lateral_control_time_horizon_, ref_path.speed_limit); + lateral_control_time_horizon_, ref_path.width, ref_path.speed_limit); if (predicted_path.path.empty()) continue; if (!check_lateral_acceleration_constraints_) { @@ -1844,6 +1845,100 @@ void MapBasedPredictionNode::updateRoadUsersHistory( } } +std::optional MapBasedPredictionNode::searchProperStartingRefPathIndex( + const TrackedObject & object, const PosePath & pose_path) const +{ + std::unique_ptr st1_ptr; + if (time_keeper_) st1_ptr = std::make_unique(__func__, *time_keeper_); + + bool is_position_found = false; + std::optional opt_index{std::nullopt}; + auto & index = opt_index.emplace(); + + // starting segment index is a segment close enough to the object + const auto obj_point = object.kinematics.pose_with_covariance.pose.position; + { + std::unique_ptr st2_ptr; + if (time_keeper_) + st2_ptr = std::make_unique("find_close_segment_index", *time_keeper_); + double min_dist_sq = std::numeric_limits::max(); + constexpr double acceptable_dist_sq = 1.0; // [m2] + for (size_t i = 0; i < pose_path.size(); i++) { + const double dx = pose_path.at(i).position.x - obj_point.x; + const double dy = pose_path.at(i).position.y - obj_point.y; + const double dist_sq = dx * dx + dy * dy; + if (dist_sq < min_dist_sq) { + min_dist_sq = dist_sq; + index = i; + } + if (dist_sq < acceptable_dist_sq) { + break; + } + } + } + + // calculate score that object can reach the target path smoothly, and search the + // starting segment index that have the best score + size_t idx = 0; + { // find target segmentation index + std::unique_ptr st3_ptr; + if (time_keeper_) + st3_ptr = std::make_unique("find_target_seg_index", *time_keeper_); + + constexpr double search_distance = 22.0; // [m] + constexpr double yaw_diff_limit = M_PI / 3.0; // 60 degrees + + const double obj_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + const size_t search_segment_count = + static_cast(std::floor(search_distance / reference_path_resolution_)); + const size_t search_segment_num = + std::min(search_segment_count, static_cast(pose_path.size() - index)); + + // search for the best score, which is the smallest + double best_score = 1e9; // initial value is large enough + for (size_t i = 0; i < search_segment_num; ++i) { + const auto & path_pose = pose_path.at(index + i); + // yaw difference + const double path_yaw = tf2::getYaw(path_pose.orientation); + const double relative_path_yaw = autoware_utils::normalize_radian(path_yaw - obj_yaw); + if (std::abs(relative_path_yaw) > yaw_diff_limit) { + continue; + } + + const double dx = path_pose.position.x - obj_point.x; + const double dy = path_pose.position.y - obj_point.y; + const double dx_cp = std::cos(obj_yaw) * dx + std::sin(obj_yaw) * dy; + const double dy_cp = -std::sin(obj_yaw) * dx + std::cos(obj_yaw) * dy; + const double neutral_yaw = std::atan2(dy_cp, dx_cp) * 2.0; + const double delta_yaw = autoware_utils::normalize_radian(path_yaw - obj_yaw - neutral_yaw); + if (std::abs(delta_yaw) > yaw_diff_limit) { + continue; + } + + // objective function score + constexpr double weight_ratio = 0.01; + double score = delta_yaw * delta_yaw + weight_ratio * neutral_yaw * neutral_yaw; + constexpr double acceptable_score = 1e-3; + + if (score < best_score) { + best_score = score; + idx = i; + is_position_found = true; + if (score < acceptable_score) { + // if the score is small enough, we can break the loop + break; + } + } + } + } + + // update starting segment index + index += idx; + index = std::clamp(index, 0ul, pose_path.size() - 1); + + return is_position_found ? opt_index : std::nullopt; +} + std::vector MapBasedPredictionNode::getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, const double object_detected_time, const double time_horizon) @@ -1851,6 +1946,7 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + // Step 1. Set conditions for the prediction const double obj_vel = std::hypot( object.kinematics.twist_with_covariance.twist.linear.x, object.kinematics.twist_with_covariance.twist.linear.y); @@ -1891,9 +1987,10 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( return search_dist; }; + // Step 2. Get possible paths for each lanelet std::vector all_ref_paths; - for (const auto & current_lanelet_data : current_lanelets_data) { + // Set condition on each lanelet const lanelet::traffic_rules::SpeedLimitInformation limit = traffic_rules_ptr_->speedLimit(current_lanelet_data.lanelet); const double legal_speed_limit = static_cast(limit.speedLimit.value()); @@ -1959,22 +2056,21 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( return std::nullopt; }; - // Step1. Get the path - // Step1.1 Get the left lanelet + // a-1. Get the left lanelet lanelet::routing::LaneletPaths left_paths; const auto left_lanelet = getLeftOrRightLanelets(current_lanelet_data.lanelet, true); if (!!left_lanelet) { left_paths = getPathsForNormalOrIsolatedLanelet(left_lanelet.value()); } - // Step1.2 Get the right lanelet + // a-2. Get the right lanelet lanelet::routing::LaneletPaths right_paths; const auto right_lanelet = getLeftOrRightLanelets(current_lanelet_data.lanelet, false); if (!!right_lanelet) { right_paths = getPathsForNormalOrIsolatedLanelet(right_lanelet.value()); } - // Step1.3 Get the centerline + // a-3. Get the center lanelet lanelet::routing::LaneletPaths center_paths = getPathsForNormalOrIsolatedLanelet(current_lanelet_data.lanelet); @@ -1983,15 +2079,15 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( continue; } - // Step2. Predict Object Maneuver + // b. Predict Object Maneuver const Maneuver predicted_maneuver = predictObjectManeuver(object, current_lanelet_data, object_detected_time); - // Step3. Allocate probability for each predicted maneuver + // c. Allocate probability for each predicted maneuver const auto maneuver_prob = calculateManeuverProbability(predicted_maneuver, left_paths, right_paths, center_paths); - // Step4. add candidate reference paths to the all_ref_paths + // d. add candidate reference paths to the all_ref_paths const float path_prob = current_lanelet_data.probability; const auto addReferencePathsLocal = [&](const auto & paths, const auto & maneuver) { addReferencePaths( @@ -2002,6 +2098,31 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( addReferencePathsLocal(center_paths, Maneuver::LANE_FOLLOW); } + // Step 3. Search starting point for each reference path + for (auto it = all_ref_paths.begin(); it != all_ref_paths.end();) { + std::unique_ptr st1_ptr; + if (time_keeper_) + st1_ptr = + std::make_unique("searching_ref_path_starting_point", *time_keeper_); + + auto & pose_path = it->path; + if (pose_path.empty()) { + continue; + } + + const std::optional opt_starting_idx = + searchProperStartingRefPathIndex(object, pose_path); + + if (opt_starting_idx.has_value()) { + // Trim the reference path + pose_path.erase(pose_path.begin(), pose_path.begin() + opt_starting_idx.value()); + ++it; + } else { + // Proper starting point is not found, remove the reference path + it = all_ref_paths.erase(it); + } + } + return all_ref_paths; } @@ -2341,7 +2462,8 @@ void MapBasedPredictionNode::addReferencePaths( for (const auto & converted_path : converted_paths) { PredictedRefPath predicted_path; predicted_path.probability = maneuver_probability.at(maneuver) * path_probability; - predicted_path.path = converted_path; + predicted_path.path = converted_path.first; + predicted_path.width = converted_path.second; predicted_path.maneuver = maneuver; predicted_path.speed_limit = speed_limit; reference_paths.push_back(predicted_path); @@ -2416,7 +2538,7 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability( return maneuver_prob; } -std::vector MapBasedPredictionNode::convertPathType( +std::vector> MapBasedPredictionNode::convertPathType( const lanelet::routing::LaneletPaths & paths) const { std::unique_ptr st_ptr; @@ -2426,9 +2548,10 @@ std::vector MapBasedPredictionNode::convertPathType( return *lru_cache_of_convert_path_type_.get(paths); } - std::vector converted_paths; + std::vector> converted_paths; for (const auto & path : paths) { PosePath converted_path; + double width = 10.0; // Initialize with a large value // Insert Positions. Note that we start inserting points from previous lanelet if (!path.empty()) { @@ -2446,6 +2569,7 @@ std::vector MapBasedPredictionNode::convertPathType( continue; } + // only considers yaw of the lanelet const double lane_yaw = std::atan2( current_p.position.y - prev_p.position.y, current_p.position.x - prev_p.position.x); const double sin_yaw_half = std::sin(lane_yaw / 2.0); @@ -2495,6 +2619,14 @@ std::vector MapBasedPredictionNode::convertPathType( converted_path.push_back(current_p); prev_p = current_p; } + + // Update minimum width + const auto left_bound = lanelet.leftBound2d(); + const auto right_bound = lanelet.rightBound2d(); + const double lanelet_width_front = std::hypot( + left_bound.front().x() - right_bound.front().x(), + left_bound.front().y() - right_bound.front().y()); + width = std::min(width, lanelet_width_front); } // Resample Path @@ -2506,7 +2638,7 @@ std::vector MapBasedPredictionNode::convertPathType( // interpolation for xy const auto resampled_converted_path = autoware::motion_utils::resamplePoseVector( converted_path, reference_path_resolution_, use_akima_spline_for_xy, use_lerp_for_z); - converted_paths.push_back(resampled_converted_path); + converted_paths.push_back(std::make_pair(resampled_converted_path, width)); } lru_cache_of_convert_path_type_.put(paths, converted_paths); diff --git a/perception/autoware_map_based_prediction/src/path_generator.cpp b/perception/autoware_map_based_prediction/src/path_generator.cpp index 4b759e22cdb4f..d8f6f85b239a7 100644 --- a/perception/autoware_map_based_prediction/src/path_generator.cpp +++ b/perception/autoware_map_based_prediction/src/path_generator.cpp @@ -175,17 +175,37 @@ PredictedPath PathGenerator::generatePathForOffLaneVehicle( } PredictedPath PathGenerator::generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_paths, const double duration, - const double lateral_duration, const double speed_limit) const + const TrackedObject & object, const PosePath & ref_path, const double duration, + const double lateral_duration, const double path_width, const double speed_limit) const { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - if (ref_paths.size() < 2) { + if (ref_path.size() < 2) { + return generateStraightPath(object, duration); + } + + // if the object is moving backward, we generate a straight path + if (object.kinematics.twist_with_covariance.twist.linear.x < 0.0) { return generateStraightPath(object, duration); } - return generatePolynomialPath(object, ref_paths, duration, lateral_duration, speed_limit); + // get object width + double object_width = 5.0; // a large number + if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { + object_width = object.shape.dimensions.y; + } else if (object.shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { + object_width = object.shape.dimensions.x; + } + // Calculate the backlash width, which represents the maximum distance the object can be biased + // from the reference path + constexpr double margin = + 0.5; // Set a safety margin of 0.5m for the object to stay away from the edge of the lane + double backlash_width = (path_width - object_width) / 2.0 - margin; + backlash_width = std::max(backlash_width, 0.0); // minimum is 0.0 + + return generatePolynomialPath( + object, ref_path, duration, lateral_duration, path_width, backlash_width, speed_limit); } PredictedPath PathGenerator::generateStraightPath( @@ -210,37 +230,68 @@ PredictedPath PathGenerator::generateStraightPath( PredictedPath PathGenerator::generatePolynomialPath( const TrackedObject & object, const PosePath & ref_path, const double duration, - const double lateral_duration, const double speed_limit) const + const double lateral_duration, const double path_width, const double backlash_width, + const double speed_limit) const { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); // Get current Frenet Point const double ref_path_len = autoware::motion_utils::calcArcLength(ref_path); - const auto current_point = getFrenetPoint(object, ref_path, duration, speed_limit); + const auto current_point = getFrenetPoint(object, ref_path.at(0), duration, speed_limit); - // Step1. Set Target Frenet Point + // Step 1. Set Target Frenet Point // Note that we do not set position s, // since we don't know the target longitudinal position FrenetPoint terminal_point; - terminal_point.s_vel = current_point.s_vel; + terminal_point.s_vel = std::hypot(current_point.s_vel, current_point.d_vel); terminal_point.s_acc = 0.0; - terminal_point.d = 0.0; terminal_point.d_vel = 0.0; terminal_point.d_acc = 0.0; - // Step2. Generate Predicted Path on a Frenet coordinate + // calculate terminal d position, based on backlash width + { + if (backlash_width < 0.01 /*m*/) { + // If the backlash width is less than 0.01m, do not consider the backlash width and reduce + // calculation cost + terminal_point.d = 0.0; + } else { + const double return_width = path_width / 2.0; // [m] + const double current_momentum_d = + current_point.d + 0.5 * current_point.d_vel * lateral_duration; + const double momentum_d_abs = std::abs(current_momentum_d); + + if (momentum_d_abs < backlash_width) { + // If the object momentum is within the backlash width, we set the target d position to the + // current momentum + terminal_point.d = current_momentum_d; + } else if ( + momentum_d_abs >= backlash_width && momentum_d_abs < backlash_width + return_width) { + // If the object momentum is within the return zone, we set the target d position close to + // the zero gradually + terminal_point.d = + (backlash_width + return_width - momentum_d_abs) * backlash_width / return_width; + terminal_point.d *= (current_momentum_d > 0) ? 1 : -1; + } else { + // If the object momentum is outside the backlash width + return zone, we set the target d + // position to 0 + terminal_point.d = 0.0; + } + } + } + + // Step 2. Generate Predicted Path on a Frenet coordinate const auto frenet_predicted_path = generateFrenetPath(current_point, terminal_point, ref_path_len, duration, lateral_duration); - // Step3. Interpolate Reference Path for converting predicted path coordinate + // Step 3. Interpolate Reference Path for converting predicted path coordinate const auto interpolated_ref_path = interpolateReferencePath(ref_path, frenet_predicted_path); if (frenet_predicted_path.size() < 2 || interpolated_ref_path.size() < 2) { return generateStraightPath(object, duration); } - // Step4. Convert predicted trajectory from Frenet to Cartesian coordinate + // Step 4. Convert predicted trajectory from Frenet to Cartesian coordinate return convertToPredictedPath(object, frenet_predicted_path, interpolated_ref_path); } @@ -258,6 +309,7 @@ FrenetPath PathGenerator::generateFrenetPath( calcLatCoefficients(current_point, target_point, lateral_duration); const Eigen::Vector2d lon_coeff = calcLonCoefficients(current_point, target_point, duration); + // Generate the trajectory path.reserve(static_cast(duration / sampling_time_interval_)); for (double t = 0.0; t <= duration; t += sampling_time_interval_) { const auto t2 = t * t; @@ -268,22 +320,19 @@ FrenetPath PathGenerator::generateFrenetPath( 0.0; // Currently we assume the object is traveling at a constant speed const double d_next_ = current_point.d + current_point.d_vel * t + current_acc * 2.0 * t2 + lat_coeff(0) * t3 + lat_coeff(1) * t4 + lat_coeff(2) * t5; - // t > lateral_duration: 0.0, else d_next_ - const double d_next = t > lateral_duration ? 0.0 : d_next_; + // t > lateral_duration: target_point.d, else d_next_ + const double d_next = t > lateral_duration ? target_point.d : d_next_; const double s_next = current_point.s + current_point.s_vel * t + 2.0 * current_acc * t2 + lon_coeff(0) * t3 + lon_coeff(1) * t4; + if (s_next > max_length) { break; } - // We assume the object is traveling at a constant speed along s direction + // Fill the FrenetPoint, velocity and acceleration are not used in the path generator FrenetPoint point; - point.s = std::max(s_next, 0.0); - point.s_vel = current_point.s_vel; - point.s_acc = current_point.s_acc; + point.s = s_next; point.d = d_next; - point.d_vel = current_point.d_vel; - point.d_acc = current_point.d_acc; path.push_back(point); } @@ -340,6 +389,107 @@ Eigen::Vector2d PathGenerator::calcLonCoefficients( return A_lon_inv * b_lon; } +std::vector PathGenerator::interpolationLerp( + const std::vector & base_keys, const std::vector & base_values, + const std::vector & query_keys) const +{ + std::unique_ptr st_ptr; + if (time_keeper_) + st_ptr = std::make_unique("interpolationLerp_double", *time_keeper_); + + // calculate linear interpolation + // extrapolate the value if the query key is out of the base key range + std::vector query_values; + size_t key_index = 0; + double last_query_key = query_keys.at(0); + for (const auto query_key : query_keys) { + // search for the closest key index + // if current query key is larger than the last query key, search base_keys increasing order + if (query_key >= last_query_key) { + while (base_keys.at(key_index + 1) < query_key) { + if (key_index == base_keys.size() - 2) { + break; + } + ++key_index; + } + } else { + // if current query key is smaller than the last query key, search base_keys decreasing order + while (base_keys.at(key_index) > query_key) { + if (key_index == 0) { + break; + } + --key_index; + } + } + last_query_key = query_key; + + const double & src_val = base_values.at(key_index); + const double & dst_val = base_values.at(key_index + 1); + const double ratio = (query_key - base_keys.at(key_index)) / + (base_keys.at(key_index + 1) - base_keys.at(key_index)); + + const double interpolated_val = src_val + (dst_val - src_val) * ratio; + query_values.push_back(interpolated_val); + } + + return query_values; +} + +std::vector PathGenerator::interpolationLerp( + const std::vector & base_keys, const std::vector & base_values, + const std::vector & query_keys) const +{ + std::unique_ptr st_ptr; + if (time_keeper_) + st_ptr = std::make_unique("interpolationLerp_quaternion", *time_keeper_); + + // calculate linear interpolation + // extrapolate the value if the query key is out of the base key range + std::vector query_values; + size_t key_index = 0; + double last_query_key = query_keys.at(0); + for (const auto query_key : query_keys) { + // search for the closest key index + // if current query key is larger than the last query key, search base_keys increasing order + if (query_key >= last_query_key) { + while (base_keys.at(key_index + 1) < query_key) { + if (key_index == base_keys.size() - 2) { + break; + } + ++key_index; + } + } else { + // if current query key is smaller than the last query key, search base_keys decreasing order + while (base_keys.at(key_index) > query_key) { + if (key_index == 0) { + break; + } + --key_index; + } + } + last_query_key = query_key; + + const tf2::Quaternion & src_val = base_values.at(key_index); + const tf2::Quaternion & dst_val = base_values.at(key_index + 1); + const double ratio = (query_key - base_keys.at(key_index)) / + (base_keys.at(key_index + 1) - base_keys.at(key_index)); + + // in case of extrapolation, export the nearest quaternion + if (ratio < 0.0) { + query_values.push_back(src_val); + continue; + } + if (ratio > 1.0) { + query_values.push_back(dst_val); + continue; + } + const auto interpolated_quat = tf2::slerp(src_val, dst_val, ratio); + query_values.push_back(interpolated_quat); + } + + return query_values; +} + PosePath PathGenerator::interpolateReferencePath( const PosePath & base_path, const FrenetPath & frenet_predicted_path) const { @@ -353,49 +503,47 @@ PosePath PathGenerator::interpolateReferencePath( return interpolated_path; } + // Prepare base path vectors std::vector base_path_x(base_path.size()); std::vector base_path_y(base_path.size()); std::vector base_path_z(base_path.size()); + std::vector base_path_orientation(base_path.size()); std::vector base_path_s(base_path.size(), 0.0); for (size_t i = 0; i < base_path.size(); ++i) { base_path_x.at(i) = base_path.at(i).position.x; base_path_y.at(i) = base_path.at(i).position.y; base_path_z.at(i) = base_path.at(i).position.z; + tf2::Quaternion src_tf; + tf2::fromMsg(base_path.at(i).orientation, src_tf); + base_path_orientation.at(i) = src_tf; if (i > 0) { base_path_s.at(i) = base_path_s.at(i - 1) + autoware::universe_utils::calcDistance2d( base_path.at(i - 1), base_path.at(i)); } } + // Prepare resampled s vector std::vector resampled_s(frenet_predicted_path.size()); for (size_t i = 0; i < frenet_predicted_path.size(); ++i) { resampled_s.at(i) = frenet_predicted_path.at(i).s; } - if (resampled_s.front() > resampled_s.back()) { - std::reverse(resampled_s.begin(), resampled_s.end()); - } - // Lerp Interpolation - std::vector lerp_ref_path_x = interpolation::lerp(base_path_s, base_path_x, resampled_s); - std::vector lerp_ref_path_y = interpolation::lerp(base_path_s, base_path_y, resampled_s); - std::vector lerp_ref_path_z = interpolation::lerp(base_path_s, base_path_z, resampled_s); + // Linear Interpolation for x, y, z, and orientation + std::vector lerp_ref_path_x = interpolationLerp(base_path_s, base_path_x, resampled_s); + std::vector lerp_ref_path_y = interpolationLerp(base_path_s, base_path_y, resampled_s); + std::vector lerp_ref_path_z = interpolationLerp(base_path_s, base_path_z, resampled_s); + std::vector lerp_ref_path_orientation = + interpolationLerp(base_path_s, base_path_orientation, resampled_s); + // Set the interpolated PosePath interpolated_path.resize(interpolate_num); - for (size_t i = 0; i < interpolate_num - 1; ++i) { + for (size_t i = 0; i < interpolate_num; ++i) { geometry_msgs::msg::Pose interpolated_pose; - const auto current_point = - autoware::universe_utils::createPoint(lerp_ref_path_x.at(i), lerp_ref_path_y.at(i), 0.0); - const auto next_point = autoware::universe_utils::createPoint( - lerp_ref_path_x.at(i + 1), lerp_ref_path_y.at(i + 1), 0.0); - const double yaw = autoware::universe_utils::calcAzimuthAngle(current_point, next_point); interpolated_pose.position = autoware::universe_utils::createPoint( lerp_ref_path_x.at(i), lerp_ref_path_y.at(i), lerp_ref_path_z.at(i)); - interpolated_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); + interpolated_pose.orientation = tf2::toMsg(lerp_ref_path_orientation.at(i)); interpolated_path.at(i) = interpolated_pose; } - interpolated_path.back().position = autoware::universe_utils::createPoint( - lerp_ref_path_x.back(), lerp_ref_path_y.back(), lerp_ref_path_z.back()); - interpolated_path.back().orientation = interpolated_path.at(interpolate_num - 2).orientation; return interpolated_path; } @@ -407,27 +555,34 @@ PredictedPath PathGenerator::convertToPredictedPath( std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + // Object position + const auto & object_pose = object.kinematics.pose_with_covariance.pose; + const double object_height = object.shape.dimensions.z / 2.0; + + // Convert Frenet Path to Cartesian Path PredictedPath predicted_path; predicted_path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); predicted_path.path.resize(ref_path.size()); - for (size_t i = 0; i < predicted_path.path.size(); ++i) { + + // Set the first point as the object's current position + predicted_path.path.at(0) = object_pose; + + // Convert the rest of the points + for (size_t i = 1; i < predicted_path.path.size(); ++i) { // Reference Point from interpolated reference path const auto & ref_pose = ref_path.at(i); // Frenet Point from frenet predicted path const auto & frenet_point = frenet_predicted_path.at(i); + double d_offset = frenet_point.d; // Converted Pose - auto predicted_pose = - autoware::universe_utils::calcOffsetPose(ref_pose, 0.0, frenet_point.d, 0.0); - predicted_pose.position.z = object.kinematics.pose_with_covariance.pose.position.z; - if (i == 0) { - predicted_pose.orientation = object.kinematics.pose_with_covariance.pose.orientation; - } else { - const double yaw = autoware::universe_utils::calcAzimuthAngle( - predicted_path.path.at(i - 1).position, predicted_pose.position); - predicted_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); - } + auto predicted_pose = autoware::universe_utils::calcOffsetPose(ref_pose, 0.0, d_offset, 0.0); + predicted_pose.position.z += object_height; + const double yaw = autoware::universe_utils::calcAzimuthAngle( + predicted_path.path.at(i - 1).position, predicted_pose.position); + predicted_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); + predicted_path.path.at(i) = predicted_pose; } @@ -435,27 +590,27 @@ PredictedPath PathGenerator::convertToPredictedPath( } FrenetPoint PathGenerator::getFrenetPoint( - const TrackedObject & object, const PosePath & ref_path, const double duration, + const TrackedObject & object, const geometry_msgs::msg::Pose & ref_pose, const double duration, const double speed_limit) const { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); FrenetPoint frenet_point; - const auto obj_point = object.kinematics.pose_with_covariance.pose.position; - const size_t nearest_segment_idx = - autoware::motion_utils::findNearestSegmentIndex(ref_path, obj_point); - const double l = autoware::motion_utils::calcLongitudinalOffsetToSegment( - ref_path, nearest_segment_idx, obj_point); - const float vx = static_cast(object.kinematics.twist_with_covariance.twist.linear.x); - const float vy = static_cast(object.kinematics.twist_with_covariance.twist.linear.y); + // 1. Position + const auto obj_point = object.kinematics.pose_with_covariance.pose.position; const float obj_yaw = static_cast(tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)); - const float lane_yaw = - static_cast(tf2::getYaw(ref_path.at(nearest_segment_idx).orientation)); - const float delta_yaw = obj_yaw - lane_yaw; + const float lane_yaw = static_cast(tf2::getYaw(ref_pose.orientation)); + frenet_point.s = (obj_point.x - ref_pose.position.x) * cos(lane_yaw) + + (obj_point.y - ref_pose.position.y) * sin(lane_yaw); + frenet_point.d = -(obj_point.x - ref_pose.position.x) * sin(lane_yaw) + + (obj_point.y - ref_pose.position.y) * cos(lane_yaw); + // 2. Velocity (adjusted by acceleration) + const float vx = static_cast(object.kinematics.twist_with_covariance.twist.linear.x); + const float vy = static_cast(object.kinematics.twist_with_covariance.twist.linear.y); const float ax = (use_vehicle_acceleration_) ? static_cast(object.kinematics.acceleration_with_covariance.accel.linear.x) @@ -464,8 +619,9 @@ FrenetPoint PathGenerator::getFrenetPoint( (use_vehicle_acceleration_) ? static_cast(object.kinematics.acceleration_with_covariance.accel.linear.y) : 0.0; + const float delta_yaw = obj_yaw - lane_yaw; - // Using a decaying acceleration model. Consult the README for more information about the model. + // using a decaying acceleration model. Consult the README for more information about the model. const double t_h = duration; const float lambda = std::log(2) / acceleration_exponential_half_life_; @@ -527,14 +683,12 @@ FrenetPoint PathGenerator::getFrenetPoint( const float acceleration_adjusted_velocity_x = get_acceleration_adjusted_velocity(vx, ax); const float acceleration_adjusted_velocity_y = get_acceleration_adjusted_velocity(vy, ay); - - frenet_point.s = - autoware::motion_utils::calcSignedArcLength(ref_path, 0, nearest_segment_idx) + l; - frenet_point.d = autoware::motion_utils::calcLateralOffset(ref_path, obj_point); frenet_point.s_vel = acceleration_adjusted_velocity_x * std::cos(delta_yaw) - acceleration_adjusted_velocity_y * std::sin(delta_yaw); frenet_point.d_vel = acceleration_adjusted_velocity_x * std::sin(delta_yaw) + acceleration_adjusted_velocity_y * std::cos(delta_yaw); + + // 3. Acceleration, assuming constant acceleration frenet_point.s_acc = 0.0; frenet_point.d_acc = 0.0; From fd5fc3f84cb60966350b7391c776f83a75b02db9 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 9 Sep 2024 17:11:20 +0900 Subject: [PATCH 161/217] feat(goal_planner): add getBusStopAreaPolygons (#8794) Signed-off-by: Mamoru Sobue --- .../goal_searcher.hpp | 1 + .../src/goal_searcher.cpp | 14 ++++++++++++++ 2 files changed, 15 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp index 6bdad3a3063ef..dd81650394740 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp @@ -65,6 +65,7 @@ class GoalSearcher : public GoalSearcherBase const std::shared_ptr & planner_data) const; BasicPolygons2d getNoParkingAreaPolygons(const lanelet::ConstLanelets & lanes) const; BasicPolygons2d getNoStoppingAreaPolygons(const lanelet::ConstLanelets & lanes) const; + BasicPolygons2d getBusStopAreaPolygons(const lanelet::ConstLanelets & lanes) const; bool isInAreas(const LinearRing2d & footprint, const BasicPolygons2d & areas) const; LinearRing2d vehicle_footprint_{}; 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 2d49f930c2692..54f0b6bfabf87 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 @@ -19,8 +19,10 @@ #include "autoware/behavior_path_planner_common/utils/path_utils.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" +#include "autoware_lanelet2_extension/regulatory_elements/bus_stop_area.hpp" #include "autoware_lanelet2_extension/regulatory_elements/no_parking_area.hpp" #include "autoware_lanelet2_extension/regulatory_elements/no_stopping_area.hpp" +#include "autoware_lanelet2_extension/utility/query.hpp" #include "autoware_lanelet2_extension/utility/utilities.hpp" #include @@ -490,6 +492,18 @@ BasicPolygons2d GoalSearcher::getNoStoppingAreaPolygons(const lanelet::ConstLane return area_polygons; } +BasicPolygons2d GoalSearcher::getBusStopAreaPolygons(const lanelet::ConstLanelets & lanes) const +{ + BasicPolygons2d area_polygons{}; + for (const auto & bus_stop_area_reg_elem : lanelet::utils::query::busStopAreas(lanes)) { + for (const auto & area : bus_stop_area_reg_elem->busStopAreas()) { + const auto & area_poly = lanelet::utils::to2D(area).basicPolygon(); + area_polygons.push_back(area_poly); + } + } + return area_polygons; +} + bool GoalSearcher::isInAreas(const LinearRing2d & footprint, const BasicPolygons2d & areas) const { for (const auto & area : areas) { From d669351948cbc2c1a74dd6b3c713a5ca37dcf406 Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Mon, 9 Sep 2024 17:45:09 +0900 Subject: [PATCH 162/217] fix(motion_planning): align the parameters with launcher (#8792) parameters in motion_planning aligned Signed-off-by: Zhe Shen --- .../config/obstacle_cruise_planner.param.yaml | 32 ++++++------------- .../config/path_optimizer.param.yaml | 10 +++--- .../config/elastic_band_smoother.param.yaml | 4 +-- .../config/out_of_lane.param.yaml | 6 ++-- 4 files changed, 20 insertions(+), 32 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml b/planning/autoware_obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml index e797faaff9aa9..2844ff6a54e3d 100644 --- a/planning/autoware_obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml +++ b/planning/autoware_obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -12,7 +12,7 @@ idling_time: 2.0 # idling time to detect front vehicle starting deceleration [s] min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] - safe_distance_margin : 6.0 # This is also used as a stop margin [m] + safe_distance_margin : 5.0 # This is also used as a stop margin [m] terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m] hold_stop_velocity_threshold: 0.01 # The maximum ego velocity to hold stopping [m/s] hold_stop_distance_threshold: 0.3 # The ego keeps stopping if the distance to stop changes within the threshold [m] @@ -23,10 +23,10 @@ nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index min_behavior_stop_margin: 3.0 # [m] stop_on_curve: - enable_approaching: true # false - additional_safe_distance_margin: 0.0 # [m] + enable_approaching: false # false + additional_safe_distance_margin: 3.0 # [m] min_safe_distance_margin: 3.0 # [m] - suppress_sudden_obstacle_stop: true + suppress_sudden_obstacle_stop: false stop_obstacle_type: unknown: true @@ -109,7 +109,7 @@ ego_obstacle_overlap_time_threshold : 2.0 # time threshold to decide cut-in obstacle for cruise or stop [s] max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego yield: - enable_yield: false + enable_yield: true lat_distance_threshold: 5.0 # lateral margin between obstacle in neighbor lanes and trajectory band with ego's width for yielding max_lat_dist_between_obstacles: 2.5 # lateral margin between moving obstacle in neighbor lanes and stopped obstacle in front of it max_obstacles_collision_time: 10.0 # how far the blocking obstacle @@ -125,7 +125,7 @@ # Both the lateral error and the yaw error are assumed to decrease to zero by the time duration "time_to_convergence" # The both errors decrease with constant rates against the time. consider_current_pose: - enable_to_consider_current_pose: false + enable_to_consider_current_pose: true time_to_convergence: 1.5 #[s] cruise: @@ -196,29 +196,17 @@ # parameters to calculate slow down velocity by linear interpolation labels: - "default" - - "pedestrian" default: moving: - min_lat_margin: 0.8 - max_lat_margin: 1.3 - min_ego_velocity: 0.5 - max_ego_velocity: 1.5 + min_lat_margin: 0.2 + max_lat_margin: 1.0 + min_ego_velocity: 2.0 + max_ego_velocity: 8.0 static: min_lat_margin: 0.2 max_lat_margin: 1.0 min_ego_velocity: 4.0 max_ego_velocity: 8.0 - pedestrian: - moving: - min_lat_margin: 0.8 - max_lat_margin: 1.3 - min_ego_velocity: 0.5 - max_ego_velocity: 0.8 - static: - min_lat_margin: 0.8 - max_lat_margin: 1.3 - min_ego_velocity: 1.0 - max_ego_velocity: 2.0 moving_object_speed_threshold: 0.5 # [m/s] how fast the object needs to move to be considered as "moving" moving_object_hysteresis_range: 0.1 # [m/s] hysteresis range used to prevent chattering when obstacle moves close to moving_object_speed_threshold diff --git a/planning/autoware_path_optimizer/config/path_optimizer.param.yaml b/planning/autoware_path_optimizer/config/path_optimizer.param.yaml index bb64006656216..5f97567ad1561 100644 --- a/planning/autoware_path_optimizer/config/path_optimizer.param.yaml +++ b/planning/autoware_path_optimizer/config/path_optimizer.param.yaml @@ -3,12 +3,12 @@ option: enable_skip_optimization: false # skip elastic band and model predictive trajectory enable_reset_prev_optimization: false # If true, optimization has no fix constraint to the previous result. - enable_outside_drivable_area_stop: true # stop if the ego's trajectory footprint is outside the drivable area + enable_outside_drivable_area_stop: false # stop if the ego's trajectory footprint is outside the drivable area use_footprint_polygon_for_outside_drivable_area_check: false # If false, only the footprint's corner points are considered. debug: # flag to publish - enable_pub_debug_marker: true # publish debug marker + enable_pub_debug_marker: false # publish debug marker enable_pub_extra_debug_marker: false # publish extra debug marker # flag to show @@ -31,7 +31,7 @@ max_ego_moving_dist: 5.0 # threshold of ego's moving distance for replan [m] # make max_goal_moving_dist long to keep start point fixed for pull over max_goal_moving_dist: 15.0 # threshold of goal's moving distance for replan [m] - max_delta_time_sec: 1.0 # threshold of delta time for replan [second] + max_delta_time_sec: 0.0 # threshold of delta time for replan [second] # mpt param mpt: @@ -40,7 +40,7 @@ steer_limit_constraint: false visualize_sampling_num: 1 enable_manual_warm_start: false - enable_warm_start: true + enable_warm_start: false enable_optimization_validation: false common: @@ -62,7 +62,7 @@ # weight parameter for optimization weight: # collision free - soft_collision_free_weight: 1000.0 # soft weight for lateral error around the middle point + soft_collision_free_weight: 1.0 # soft weight for lateral error around the middle point # tracking error lat_error_weight: 1.0 # weight for lateral error diff --git a/planning/autoware_path_smoother/config/elastic_band_smoother.param.yaml b/planning/autoware_path_smoother/config/elastic_band_smoother.param.yaml index 8e77420dd4ae9..a9e71368e332c 100644 --- a/planning/autoware_path_smoother/config/elastic_band_smoother.param.yaml +++ b/planning/autoware_path_smoother/config/elastic_band_smoother.param.yaml @@ -40,8 +40,8 @@ enable: true # if true, only perform smoothing when the input changes significantly max_path_shape_around_ego_lat_dist: 2.0 # threshold of path shape change around ego [m] max_path_shape_forward_lon_dist: 100.0 # forward point to check lateral distance difference [m] - max_path_shape_forward_lat_dist: 0.1 # threshold of path shape change around forward point [m] + max_path_shape_forward_lat_dist: 0.2 # threshold of path shape change around forward point [m] max_ego_moving_dist: 5.0 # threshold of ego's moving distance for replan [m] # make max_goal_moving_dist long to keep start point fixed for pull over max_goal_moving_dist: 15.0 # threshold of goal's moving distance for replan [m] - max_delta_time_sec: 1.0 # threshold of delta time for replan [second] + max_delta_time_sec: 0.0 # threshold of delta time for replan [second] diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml index 5d36aa8d3f018..a4ab065539bdb 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -2,19 +2,19 @@ ros__parameters: out_of_lane: # module to stop or slowdown before overlapping another lane with other objects mode: ttc # mode used to consider a conflict with an object. "threshold", or "ttc" - skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane + skip_if_already_overlapping: false # do not run this module when ego already overlaps another lane max_arc_length: 100.0 # [m] maximum trajectory arc length that is checked for out_of_lane collisions threshold: time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time ttc: - threshold: 3.0 # [s] consider objects with an estimated time to collision bellow this value while on the overlap + threshold: 1.0 # [s] consider objects with an estimated time to collision bellow this value while on the overlap objects: minimum_velocity: 0.5 # [m/s] objects lower than this velocity will be ignored predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights - ignore_behind_ego: true # if true, objects behind the ego vehicle are ignored + ignore_behind_ego: false # if true, objects behind the ego vehicle are ignored action: # action to insert in the trajectory if an object causes a conflict at an overlap precision: 0.1 # [m] precision when inserting a stop pose in the trajectory From c82309171abd34274612e47313511006664dd673 Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Mon, 9 Sep 2024 17:45:43 +0900 Subject: [PATCH 163/217] fix(behavior_velocity_planner): align the parameters with launcher (#8791) parameters in behavior_velocity_planner aligned Signed-off-by: Zhe Shen --- .../config/crosswalk.param.yaml | 6 +++--- .../config/intersection.param.yaml | 6 +++--- .../config/occlusion_spot.param.yaml | 8 ++++---- .../config/run_out.param.yaml | 4 ++-- 4 files changed, 12 insertions(+), 12 deletions(-) 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 e0d25c56b1610..7d6b7700b7bc8 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 @@ -38,7 +38,7 @@ # params for the pass judge logic against the crosswalk users such as pedestrians or bicycles pass_judge: ego_pass_first_margin_x: [0.0] # [[s]] time to collision margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) - ego_pass_first_margin_y: [3.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) + ego_pass_first_margin_y: [4.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) ego_pass_first_additional_margin: 0.5 # [s] additional time margin for ego pass first situation to suppress chattering ego_pass_later_margin_x: [0.0] # [[s]] time to vehicle margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_margin_y: [13.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) @@ -75,8 +75,8 @@ enable: true # if true, ego will slowdown around crosswalks that are occluded occluded_object_velocity: 1.0 # [m/s] assumed velocity of objects that may come out of the occluded space slow_down_velocity: 1.0 # [m/s] - time_buffer: 1.0 # [s] consecutive time with/without an occlusion to add/remove the slowdown - min_size: 0.5 # [m] minimum size of an occlusion (square side size) + time_buffer: 0.5 # [s] consecutive time with/without an occlusion to add/remove the slowdown + min_size: 1.0 # [m] minimum size of an occlusion (square side size) free_space_max: 43 # [-] maximum value of a free space cell in the occupancy grid occupied_min: 58 # [-] minimum value of an occupied cell in the occupancy grid ignore_with_traffic_light: true # [-] if true, occlusions at crosswalks with traffic lights are ignored diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/config/intersection.param.yaml index 5ff420edc1c4d..270eb4d7b902b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/config/intersection.param.yaml @@ -90,19 +90,19 @@ object_time_margin_to_collision_point: 4.0 occlusion: - enable: false + enable: true occlusion_attention_area_length: 70.0 free_space_max: 43 occupied_min: 58 denoise_kernel: 1.0 attention_lane_crop_curvature_threshold: 0.25 - attention_lane_curvature_calculation_ds: 0.5 + attention_lane_curvature_calculation_ds: 0.6 creep_during_peeking: enable: false creep_velocity: 0.8333 peeking_offset: -0.5 occlusion_required_clearance_distance: 55.0 - possible_object_bbox: [1.5, 2.5] + possible_object_bbox: [1.9, 2.5] ignore_parked_vehicle_speed_threshold: 0.8333 occlusion_detection_hold_time: 1.5 temporal_stop_time_before_peeking: 0.1 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/config/occlusion_spot.param.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/config/occlusion_spot.param.yaml index 1a9b61a0b51a9..b3c12f298b4f7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/config/occlusion_spot.param.yaml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/config/occlusion_spot.param.yaml @@ -21,8 +21,8 @@ search_angle: 0.63 # [rad] PI/5.0 motion: safety_ratio: 0.8 # [-] jerk/acceleration ratio for safety - max_slow_down_jerk: -0.5 # [m/s^3] minimum jerk deceleration for safe brake. - max_slow_down_accel: -1.8 # [m/s^2] minimum accel deceleration for safe brake. + max_slow_down_jerk: -0.3 # [m/s^3] minimum jerk deceleration for safe brake. + max_slow_down_accel: -1.5 # [m/s^2] minimum accel deceleration for safe brake. non_effective_jerk: -0.3 # [m/s^3] weak jerk for velocity planning. non_effective_acceleration: -1.0 # [m/s^2] weak deceleration for velocity planning. min_allowed_velocity: 1.0 # [m/s] minimum velocity allowed @@ -31,7 +31,7 @@ min_occlusion_spot_size: 1.0 # [m] occupancy grid must contain an UNKNOWN area of at least size NxN to be considered a hidden obstacle. slice_length: 10.0 # [m] size of slices in both length and distance relative to the ego path. min_longitudinal_offset: 1.0 # [m] detection area safety buffer from front bumper. - max_lateral_distance: 6.0 # [m] buffer around the ego path used to build the detection area. + max_lateral_distance: 5.0 # [m] buffer around the ego path used to build the detection area. grid: free_space_max: 43 # [-] maximum value of a free space cell in the occupancy grid - occupied_min: 58 # [-] minimum value of an occupied cell in the occupancy grid + occupied_min: 57 # [-] minimum value of an occupied cell in the occupancy grid diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/config/run_out.param.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/config/run_out.param.yaml index 6d0d9571bf43b..7ea438d25790d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/config/run_out.param.yaml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/config/run_out.param.yaml @@ -29,7 +29,7 @@ std_dev_multiplier: 1.96 # [-] min and max velocity of the obstacles are calculated from this value and covariance diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points - max_prediction_time: 10.0 # [sec] create predicted path until this time + max_prediction_time: 3.0 # [sec] create predicted path until this time time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method @@ -44,7 +44,7 @@ # Parameter to prevent abrupt stops caused by false positives in perception ignore_momentary_detection: enable: true - time_threshold: 0.15 # [sec] ignores detections that persist for less than this duration + time_threshold: 0.5 # [sec] ignores detections that persist for less than this duration # Typically used when the "detection_method" is set to ObjectWithoutPath or Points # Approach if the ego has stopped in front of the obstacle for a certain period From fe6b98f2c33b9ea75be069d5d9f8d881ff931922 Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Mon, 9 Sep 2024 17:46:21 +0900 Subject: [PATCH 164/217] fix(autoware_behavior_path_planner): align the parameters with launcher (#8790) parameters in behavior_path_planner aligned Signed-off-by: Zhe Shen --- .../dynamic_obstacle_avoidance.param.yaml | 2 +- .../config/goal_planner.param.yaml | 28 +++++++------- .../config/lane_change.param.yaml | 38 +++++++++---------- .../config/behavior_path_planner.param.yaml | 4 -- .../config/drivable_area_expansion.param.yaml | 7 ++-- .../config/scene_module_manager.param.yaml | 4 +- .../config/sampling_planner.param.yaml | 17 --------- .../config/start_planner.param.yaml | 12 +++--- .../static_obstacle_avoidance.param.yaml | 32 ++++++++-------- 9 files changed, 62 insertions(+), 82 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/config/dynamic_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/config/dynamic_obstacle_avoidance.param.yaml index 3236bf8d0ade7..aa1fdb304824a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/config/dynamic_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/config/dynamic_obstacle_avoidance.param.yaml @@ -59,7 +59,7 @@ lat_offset_from_obstacle: 1.0 # [m] margin_distance_around_pedestrian: 2.0 # [m] predicted_path: - end_time_to_consider: 3.0 # [s] + end_time_to_consider: 2.0 # [s] threshold_confidence: 0.0 # [] not probability max_lat_offset_to_avoid: 0.5 # [m] max_time_for_object_lat_shift: 0.0 # [s] 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 b40214bf2e89e..379dad254fbec 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 @@ -14,14 +14,14 @@ lateral_weight: 40.0 prioritize_goals_before_objects: true parking_policy: "left_side" # "left_side" or "right_side" - forward_goal_search_length: 20.0 + forward_goal_search_length: 40.0 backward_goal_search_length: 20.0 goal_search_interval: 2.0 longitudinal_margin: 3.0 - max_lateral_offset: 0.5 - lateral_offset_interval: 0.25 + max_lateral_offset: 1.0 + lateral_offset_interval: 0.5 ignore_distance_from_lane_start: 0.0 - margin_from_boundary: 0.5 + margin_from_boundary: 0.75 high_curvature_threshold: 0.1 # occupancy grid map @@ -35,7 +35,7 @@ # object recognition object_recognition: - use_object_recognition: false + use_object_recognition: true collision_check_soft_margins: [5.0, 4.5, 4.0, 3.5, 3.0, 2.5, 2.0, 1.5, 1.0] # the maximum margin when ego and objects are oriented. collision_check_hard_margins: [0.6] # this should be larger than `surround_check_distance` of surround_obstacle_checker. object_recognition_collision_check_max_extra_stopping_margin: 1.0 @@ -46,7 +46,7 @@ # pull over pull_over: - minimum_request_length: 100.0 + minimum_request_length: 0.0 pull_over_velocity: 3.0 pull_over_minimum_velocity: 1.38 decide_path_distance: 10.0 @@ -91,13 +91,13 @@ velocity: 1.0 vehicle_shape_margin: 1.0 time_limit: 3000.0 - max_turning_ratio: 0.7 + max_turning_ratio: 0.5 turning_steps: 1 # search configs search_configs: - theta_size: 144 + theta_size: 120 angle_goal_range: 6.0 - curve_weight: 1.2 + curve_weight: 0.5 reverse_weight: 1.0 lateral_goal_range: 0.5 longitudinal_goal_range: 2.0 @@ -108,8 +108,8 @@ astar: search_method: "forward" # options: forward, backward only_behind_solutions: false - use_back: false - distance_heuristic_weight: 1.0 + use_back: true + distance_heuristic_weight: 2.0 # -- RRT* search Configurations -- rrtstar: enable_update: true @@ -124,7 +124,7 @@ path_safety_check: # EgoPredictedPath ego_predicted_path: - min_velocity: 0.0 + min_velocity: 1.0 min_acceleration: 1.0 time_horizon_for_front_object: 10.0 time_horizon_for_rear_object: 10.0 @@ -135,7 +135,7 @@ safety_check_time_horizon: 10.0 safety_check_time_resolution: 1.0 # detection range - object_check_forward_distance: 10.0 + object_check_forward_distance: 100.0 object_check_backward_distance: 100.0 ignore_object_velocity_threshold: 1.0 # ObjectTypesToCheck @@ -184,7 +184,7 @@ hysteresis_factor_expand_rate: 1.0 collision_check_yaw_diff_threshold: 3.1416 # temporary - backward_path_length: 100.0 + backward_path_length: 30.0 forward_path_length: 100.0 # debug 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 9fe9dfd62eece..4c55beb89e813 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 @@ -28,8 +28,8 @@ skip_process: longitudinal_distance_diff_threshold: - prepare: 0.5 - lane_changing: 0.5 + prepare: 1.0 + lane_changing: 1.0 # safety check safety_check: @@ -42,7 +42,7 @@ rear_vehicle_safety_time_margin: 1.0 lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 - longitudinal_velocity_delta_time: 0.8 + longitudinal_velocity_delta_time: 0.0 parked: expected_front_deceleration: -1.0 expected_rear_deceleration: -2.0 @@ -58,7 +58,7 @@ rear_vehicle_safety_time_margin: 0.8 lateral_distance_max_threshold: 1.0 longitudinal_distance_min_threshold: 2.5 - longitudinal_velocity_delta_time: 0.6 + longitudinal_velocity_delta_time: 0.0 stuck: expected_front_deceleration: -1.0 expected_rear_deceleration: -1.0 @@ -66,18 +66,18 @@ rear_vehicle_safety_time_margin: 1.0 lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 - longitudinal_velocity_delta_time: 0.8 + longitudinal_velocity_delta_time: 0.0 # lane expansion for object filtering lane_expansion: - left_offset: 0.0 # [m] - right_offset: 0.0 # [m] + left_offset: 1.0 # [m] + right_offset: 1.0 # [m] # lateral acceleration map lateral_acceleration: velocity: [0.0, 4.0, 10.0] - min_values: [0.15, 0.15, 0.15] - max_values: [0.5, 0.5, 0.5] + min_values: [0.4,0.4,0.4] + max_values: [0.65,0.65,0.65] # target object target_object: @@ -85,20 +85,20 @@ truck: true bus: true trailer: true - unknown: true + unknown: false bicycle: true motorcycle: true pedestrian: true # lane change regulations regulation: - crosswalk: false - intersection: false + crosswalk: true + intersection: true traffic_light: true # ego vehicle stuck detection stuck_detection: - velocity: 0.1 # [m/s] + velocity: 0.5 # [m/s] stop_time: 3.0 # [s] # collision check @@ -107,9 +107,9 @@ intersection: true turns: true stopped_object_velocity_threshold: 1.0 # [m/s] - check_objects_on_current_lanes: true - check_objects_on_other_lanes: true - use_all_predicted_path: true + check_objects_on_current_lanes: false + check_objects_on_other_lanes: false + use_all_predicted_path: false # lane change cancel cancel: @@ -117,9 +117,9 @@ enable_on_lane_changing_phase: true delta_time: 1.0 # [s] duration: 5.0 # [s] - max_lateral_jerk: 1000.0 # [m/s3] + max_lateral_jerk: 100.0 # [m/s3] overhang_tolerance: 0.0 # [m] - unsafe_hysteresis_threshold: 10 # [/] + unsafe_hysteresis_threshold: 5 # [/] deceleration_sampling_num: 5 # [/] lane_change_finish_judge_buffer: 2.0 # [m] @@ -127,4 +127,4 @@ finish_judge_lateral_angle_deviation: 1.0 # [deg] # debug - publish_debug_marker: false + publish_debug_marker: true diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/config/behavior_path_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_planner/config/behavior_path_planner.param.yaml index 7d5249dea689f..d94d4e2e8a8a1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/config/behavior_path_planner.param.yaml @@ -23,7 +23,3 @@ enable_cog_on_centerline: false input_path_interval: 2.0 output_path_interval: 2.0 - - closest_lanelet: - distance_threshold: 5.0 # [m] - yaw_threshold: 0.79 # [rad] diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/config/drivable_area_expansion.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_planner/config/drivable_area_expansion.param.yaml index f4f9d131810fd..2e4984afe7cff 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/config/drivable_area_expansion.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/config/drivable_area_expansion.param.yaml @@ -10,7 +10,7 @@ enabled: true print_runtime: false max_expansion_distance: 0.0 # [m] maximum distance by which the drivable area can be expended (0.0 means no limit) - min_bound_interval: 0.1 # [m] minimum interval between two consecutive bound points (before expansion) + min_bound_interval: 1.0 # [m] minimum interval between two consecutive bound points (before expansion) smoothing: curvature_average_window: 3 # window size used for smoothing the curvatures using a moving window average max_bound_rate: 1.0 # [m/m] maximum rate of change of the bound lateral distance over its arc length @@ -20,17 +20,18 @@ extra_front_overhang: 0.5 # [m] extra length to add to the front overhang extra_width: 1.0 # [m] extra length to add to the width dynamic_objects: - avoid: true # if true, the drivable area is not expanded in the predicted path of dynamic objects + avoid: false # if true, the drivable area is not expanded in the predicted path of dynamic objects extra_footprint_offset: front: 0.5 # [m] extra length to add to the front of the dynamic object footprint rear: 0.5 # [m] extra length to add to the rear of the dynamic object footprint left: 0.5 # [m] extra length to add to the left of the dynamic object footprint right: 0.5 # [m] extra length to add to the rear of the dynamic object footprint path_preprocessing: - max_arc_length: 50.0 # [m] maximum arc length along the path where the ego footprint is projected (0.0 means no limit) + max_arc_length: 100.0 # [m] maximum arc length along the path where the ego footprint is projected (0.0 means no limit) resample_interval: 2.0 # [m] fixed interval between resampled path points (0.0 means path points are directly used) reuse_max_deviation: 0.5 # [m] if the path changes by more than this value, the curvatures are recalculated. Otherwise they are reused. avoid_linestring: types: # linestring types in the lanelet maps that will not be crossed when expanding the drivable area - road_border + - curbstone distance: 0.0 # [m] distance to keep between the drivable area and the linestrings to avoid diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml index f94657c1418e4..9f270b0637e16 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml @@ -47,7 +47,7 @@ start_planner: enable_rtc: false - enable_simultaneous_execution_as_approved_module: false + enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: false side_shift: @@ -57,7 +57,7 @@ goal_planner: enable_rtc: false - enable_simultaneous_execution_as_approved_module: false + enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: false static_obstacle_avoidance: diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/config/sampling_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/config/sampling_planner.param.yaml index 53c531c4b04a4..f485ac3ac08b6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/config/sampling_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/config/sampling_planner.param.yaml @@ -1,20 +1,3 @@ /**: ros__parameters: start_planner: - max_curvature: 0.1 - min_curvature: -0.1 - lateral_deviation_weight: 1.0 - length_weight: 1.0 - curvature_weight: 1.0 - enable_frenet: true - enable_bezier: false - resolution: 0.5 - previous_path_reuse_points_nb: 2 - nb_target_lateral_positions: {10.0, 20.0} - target_lengths: {-2.0, -1.0, 0.0, 1.0, 2.0} - target_lateral_positions: 2 - target_lateral_velocities: {-0.1, 0.0, 0.1} - target_lateral_accelerations: {0.0} - force_zero_deviation: true - force_zero_heading: true - smooth_reference: false diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml index 499f713a3d65b..443563a7626eb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml @@ -32,7 +32,7 @@ minimum_lateral_acc: 0.15 maximum_lateral_acc: 0.5 maximum_curvature: 0.07 - end_pose_curvature_threshold: 0.01 + end_pose_curvature_threshold: 0.1 # geometric pull out enable_geometric_pull_out: true geometric_collision_check_distance_from_end: 0.0 @@ -66,9 +66,9 @@ turning_steps: 1 # search configs search_configs: - theta_size: 144 + theta_size: 120 angle_goal_range: 6.0 - curve_weight: 1.2 + curve_weight: 0.5 reverse_weight: 1.0 lateral_goal_range: 0.5 longitudinal_goal_range: 2.0 @@ -79,8 +79,8 @@ astar: search_method: "forward" # options: forward, backward only_behind_solutions: false - use_back: false - distance_heuristic_weight: 1.0 + use_back: true + distance_heuristic_weight: 2.0 # -- RRT* search Configurations -- rrtstar: enable_update: true @@ -103,7 +103,7 @@ delay_until_departure: 1.0 # For target object filtering target_filtering: - safety_check_time_horizon: 5.0 + safety_check_time_horizon: 10.0 safety_check_time_resolution: 1.0 # detection range object_check_forward_distance: 10.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml index 4a88d2b9d514a..69e3ed5dff567 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml @@ -23,44 +23,44 @@ th_moving_time: 2.0 # [s] longitudinal_margin: 0.0 # [m] lateral_margin: - soft_margin: 0.3 # [m] + soft_margin: 0.7 # [m] hard_margin: 0.2 # [m] hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 # [-] FOR DEVELOPER - envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER + envelope_buffer_margin: 0.1 # [m] FOR DEVELOPER th_error_eclipse_long_radius : 0.6 # [m] truck: th_moving_speed: 1.0 th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.3 + soft_margin: 0.7 hard_margin: 0.2 hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 - envelope_buffer_margin: 0.5 + envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 bus: th_moving_speed: 1.0 th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.3 + soft_margin: 0.7 hard_margin: 0.2 hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 - envelope_buffer_margin: 0.5 + envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 trailer: th_moving_speed: 1.0 th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.3 + soft_margin: 0.7 hard_margin: 0.2 hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 - envelope_buffer_margin: 0.5 + envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 unknown: th_moving_speed: 0.28 @@ -150,16 +150,16 @@ # "auto" : generate candidate path. if RTC is running as AUTO mode, the ego avoids it automatically. # "manual" : generate candidate path and wait operator approval even if RTC is running as AUTO mode. # "ignore" : never avoid it. - policy: "auto" # [-] + policy: "manual" # [-] condition: th_stopped_time: 3.0 # [s] th_moving_distance: 1.0 # [m] ignore_area: traffic_light: - front_distance: 100.0 # [m] + front_distance: 20.0 # [m] crosswalk: - front_distance: 30.0 # [m] - behind_distance: 30.0 # [m] + front_distance: 20.0 # [m] + behind_distance: 0.0 # [m] wait_and_see: target_behaviors: ["MERGING", "DEVIATING"] # [-] th_closest_distance: 10.0 # [m] @@ -232,7 +232,7 @@ # avoidance distance parameters longitudinal: min_prepare_time: 1.0 # [s] - max_prepare_time: 2.0 # [s] + max_prepare_time: 3.0 # [s] min_prepare_distance: 1.0 # [m] min_slow_down_speed: 1.38 # [m/s] buf_slow_down_speed: 0.56 # [m/s] FOR DEVELOPER @@ -291,7 +291,7 @@ constraints: # lateral constraints lateral: - velocity: [1.0, 1.38, 11.1] # [m/s] + velocity: [1.39, 4.17, 11.1] # [m/s] max_accel_values: [0.5, 0.5, 0.5] # [m/ss] min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] @@ -327,8 +327,8 @@ # for debug debug: - enable_other_objects_marker: false - enable_other_objects_info: false + enable_other_objects_marker: true + enable_other_objects_info: true enable_detection_area_marker: false enable_drivable_bound_marker: false enable_safety_check_marker: false From cd30d18d9bdc7f91c5b04cc1a5c53262a978779b Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Mon, 9 Sep 2024 19:12:50 +0900 Subject: [PATCH 165/217] feat(probabilistic_occupancy_grid_map): add time_keeper (#8601) * add time_keeper Signed-off-by: a-maumau * add option for time keeper Signed-off-by: a-maumau * correct namespace Signed-off-by: a-maumau * set default to false Signed-off-by: a-maumau * add scope and timekeeper Signed-off-by: a-maumau * remove scope and add comment for scopes Signed-off-by: a-maumau * mod comment Signed-off-by: a-maumau * change comment Co-authored-by: Taekjin LEE Signed-off-by: a-maumau * fix variable shadowing Signed-off-by: a-maumau --------- Signed-off-by: a-maumau Co-authored-by: Taekjin LEE --- ...erscan_based_occupancy_grid_map.param.yaml | 3 + ...tcloud_based_occupancy_grid_map.param.yaml | 3 + ...tcloud_based_occupancy_grid_map.param.yaml | 3 + ...nchronized_grid_map_fusion_node.param.yaml | 3 + ...ntcloud_based_occupancy_grid_map.launch.py | 2 +- .../synchronized_grid_map_fusion_node.cpp | 102 ++++++++++----- .../synchronized_grid_map_fusion_node.hpp | 6 + ...aserscan_based_occupancy_grid_map_node.cpp | 119 ++++++++++++------ ...aserscan_based_occupancy_grid_map_node.hpp | 6 + ...intcloud_based_occupancy_grid_map_node.cpp | 49 ++++++-- ...intcloud_based_occupancy_grid_map_node.hpp | 6 + 11 files changed, 225 insertions(+), 77 deletions(-) diff --git a/perception/autoware_probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml b/perception/autoware_probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml index 9dcc722587e92..eaaeb026d0829 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml +++ b/perception/autoware_probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml @@ -16,3 +16,6 @@ map_length: 150.0 map_width: 150.0 map_resolution: 0.5 + + # debug parameters + publish_processing_time_detail: false diff --git a/perception/autoware_probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml b/perception/autoware_probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml index 878bea4cd8ced..8ed3fdddfa449 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml +++ b/perception/autoware_probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml @@ -12,6 +12,9 @@ map_length_x: 150.0 # [m] map_length_y: 150.0 # [m] + # debug parameters + publish_processing_time_detail: false + # downsample input pointcloud downsample_input_pointcloud: true downsample_voxel_size: 0.25 # [m] diff --git a/perception/autoware_probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml b/perception/autoware_probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml index 922d4be6d519f..27a16a02f9408 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml +++ b/perception/autoware_probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml @@ -32,3 +32,6 @@ projection_dz_threshold: 0.01 # [m] for avoiding null division obstacle_separation_threshold: 1.0 # [m] fill the interval between obstacles with unknown for this length pub_debug_grid: false + + # debug parameters + publish_processing_time_detail: false diff --git a/perception/autoware_probabilistic_occupancy_grid_map/config/synchronized_grid_map_fusion_node.param.yaml b/perception/autoware_probabilistic_occupancy_grid_map/config/synchronized_grid_map_fusion_node.param.yaml index f8a2dc2fbc7de..42966e01fa90b 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/config/synchronized_grid_map_fusion_node.param.yaml +++ b/perception/autoware_probabilistic_occupancy_grid_map/config/synchronized_grid_map_fusion_node.param.yaml @@ -18,3 +18,6 @@ fusion_map_length_x: 100.0 fusion_map_length_y: 100.0 fusion_map_resolution: 0.5 + + # debug parameters + publish_processing_time_detail: false diff --git a/perception/autoware_probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py b/perception/autoware_probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py index f8e050c7e8206..844c7cc0ee473 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/autoware_probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py @@ -219,7 +219,7 @@ def launch_setup(context, *args, **kwargs): gridmap_fusion_node = [ ComposableNode( package="autoware_probabilistic_occupancy_grid_map", - plugin="synchronized_grid_map_fusion::GridMapFusionNode", + plugin="autoware::occupancy_grid_map::GridMapFusionNode", name="occupancy_grid_map_fusion_node", remappings=[ ("~/output/occupancy_grid_map", LaunchConfiguration("output")), 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 28a5759eeb7b0..880dfda03c495 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 @@ -21,6 +21,7 @@ namespace autoware::occupancy_grid_map { +using autoware::universe_utils::ScopedTimeTrack; using costmap_2d::OccupancyGridMapFixedBlindSpot; using costmap_2d::OccupancyGridMapLOBFUpdater; using geometry_msgs::msg::Pose; @@ -142,6 +143,16 @@ GridMapFusionNode::GridMapFusionNode(const rclcpp::NodeOptions & node_options) debug_publisher_ptr_ = std::make_unique(this, "synchronized_grid_map_fusion"); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); + + // time keeper setup + 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); + } } } @@ -176,6 +187,9 @@ void GridMapFusionNode::onGridMap( const nav_msgs::msg::OccupancyGrid::ConstSharedPtr & occupancy_grid_msg, const std::string & topic_name) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + std::lock_guard lock(mutex_); const bool is_already_subscribed_this = (gridmap_dict_[topic_name] != nullptr); const bool is_already_subscribed_tmp = std::any_of( @@ -260,6 +274,9 @@ void GridMapFusionNode::timer_callback() */ void GridMapFusionNode::publish() { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + stop_watch_ptr_->toc("processing_time", true); builtin_interfaces::msg::Time latest_stamp = get_clock()->now(); double height = 0.0; @@ -267,12 +284,18 @@ void GridMapFusionNode::publish() // merge available gridmap std::vector subscribed_maps; std::vector weights; - for (const auto & e : gridmap_dict_) { - if (e.second != nullptr) { - subscribed_maps.push_back(GridMapFusionNode::OccupancyGridMsgToGridMap(*e.second)); - weights.push_back(input_topic_weights_map_[e.first]); - latest_stamp = e.second->header.stamp; - height = e.second->info.origin.position.z; + { // merging grid map + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("merge_grid_map", *time_keeper_); + + for (const auto & e : gridmap_dict_) { + if (e.second != nullptr) { + subscribed_maps.push_back(GridMapFusionNode::OccupancyGridMsgToGridMap(*e.second)); + weights.push_back(input_topic_weights_map_[e.first]); + latest_stamp = e.second->header.stamp; + height = e.second->info.origin.position.z; + } } } @@ -322,6 +345,9 @@ OccupancyGridMapFixedBlindSpot GridMapFusionNode::SingleFrameOccupancyFusion( std::vector & occupancy_grid_maps, const builtin_interfaces::msg::Time latest_stamp, const std::vector & weights) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + // if only single map if (occupancy_grid_maps.size() == 1) { return occupancy_grid_maps[0]; @@ -336,42 +362,51 @@ OccupancyGridMapFixedBlindSpot GridMapFusionNode::SingleFrameOccupancyFusion( return occupancy_grid_maps[0]; } - // 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); - - // fix origin of each map - for (auto & map : occupancy_grid_maps) { - map.updateOrigin(fused_map.getOriginX(), fused_map.getOriginY()); - } + { // create fused occupancy grid map + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("create_fused_map", *time_keeper_); + + // 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); + + // fix origin of each map + for (auto & map : occupancy_grid_maps) { + 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++) { - // get cost of each map - std::vector costs; - for (auto & map : occupancy_grid_maps) { - costs.push_back(map.getCost(x, y)); - } + // 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++) { + // get cost of each map + std::vector costs; + for (auto & map : occupancy_grid_maps) { + costs.push_back(map.getCost(x, y)); + } - // set fusion policy - auto fused_cost = fusion_policy::singleFrameOccupancyFusion(costs, fusion_method_, weights); + // set fusion policy + auto fused_cost = fusion_policy::singleFrameOccupancyFusion(costs, fusion_method_, weights); - // set max cost to fused map - fused_map.setCost(x, y, fused_cost); + // set max cost to fused map + fused_map.setCost(x, y, fused_cost); + } } - } - return fused_map; + return fused_map; + } // scope for time keeper ends } OccupancyGridMapFixedBlindSpot GridMapFusionNode::OccupancyGridMsgToGridMap( const nav_msgs::msg::OccupancyGrid & occupancy_grid_map) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + OccupancyGridMapFixedBlindSpot gridmap( occupancy_grid_map.info.width, occupancy_grid_map.info.height, occupancy_grid_map.info.resolution); @@ -392,6 +427,9 @@ nav_msgs::msg::OccupancyGrid::UniquePtr GridMapFusionNode::OccupancyGridMapToMsg const std::string & frame_id, const builtin_interfaces::msg::Time & stamp, const float & robot_pose_z, const nav2_costmap_2d::Costmap2D & occupancy_grid_map) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + auto msg_ptr = std::make_unique(); msg_ptr->header.frame_id = frame_id; 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 23aeb76826e5f..0f9475e476921 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 @@ -22,6 +22,7 @@ #include #include +#include #include #include @@ -118,6 +119,11 @@ class GridMapFusionNode : public rclcpp::Node float fusion_map_length_y_; float fusion_map_resolution_; fusion_policy::FusionMethod fusion_method_; + + // time keeper + rclcpp::Publisher::SharedPtr + detailed_processing_time_publisher_; + std::shared_ptr time_keeper_; }; } // namespace autoware::occupancy_grid_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 6c4ad8135b37d..cb1b22a519e2d 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 @@ -37,6 +37,7 @@ namespace autoware::occupancy_grid_map { +using autoware::universe_utils::ScopedTimeTrack; using costmap_2d::OccupancyGridMap; using costmap_2d::OccupancyGridMapBBFUpdater; using geometry_msgs::msg::Pose; @@ -104,11 +105,24 @@ LaserscanBasedOccupancyGridMapNode::LaserscanBasedOccupancyGridMapNode( map_length / map_resolution, map_width / map_resolution, map_resolution); } occupancy_grid_map_updater_ptr_->initRosParam(*this); + + // time keeper setup + 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); + } } PointCloud2::SharedPtr LaserscanBasedOccupancyGridMapNode::convertLaserscanToPointCLoud2( const LaserScan::ConstSharedPtr & input) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + // check over max range point const float max_range = static_cast(occupancy_grid_map_updater_ptr_->getSizeInCellsX()) * 0.5f + @@ -136,6 +150,9 @@ void LaserscanBasedOccupancyGridMapNode::onLaserscanPointCloud2WithObstacleAndRa const PointCloud2::ConstSharedPtr & input_obstacle_msg, const PointCloud2::ConstSharedPtr & input_raw_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + // Laserscan to pointcloud2 PointCloud2::ConstSharedPtr laserscan_pc_ptr = convertLaserscanToPointCLoud2(input_laserscan_msg); @@ -143,6 +160,10 @@ void LaserscanBasedOccupancyGridMapNode::onLaserscanPointCloud2WithObstacleAndRa PointCloud2 cropped_obstacle_pc{}; PointCloud2 cropped_raw_pc{}; if (use_height_filter_) { + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("height_filter", *time_keeper_); + if (!utils::cropPointcloudByHeight( *input_obstacle_msg, *tf2_, base_link_frame_, min_height_, max_height_, cropped_obstacle_pc)) { @@ -163,51 +184,77 @@ void LaserscanBasedOccupancyGridMapNode::onLaserscanPointCloud2WithObstacleAndRa PointCloud2 trans_raw_pc{}; Pose gridmap_origin{}; Pose scan_origin{}; - try { - utils::transformPointcloud(*laserscan_pc_ptr, *tf2_, map_frame_, trans_laserscan_pc); - utils::transformPointcloud(filtered_obstacle_pc, *tf2_, map_frame_, trans_obstacle_pc); - utils::transformPointcloud(filtered_raw_pc, *tf2_, map_frame_, trans_raw_pc); - gridmap_origin = - utils::getPose(laserscan_pc_ptr->header.stamp, *tf2_, gridmap_origin_frame_, map_frame_); - scan_origin = - utils::getPose(laserscan_pc_ptr->header.stamp, *tf2_, scan_origin_frame_, map_frame_); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM(get_logger(), ex.what()); - return; - } - // Create single frame occupancy grid map - OccupancyGridMap single_frame_occupancy_grid_map( - occupancy_grid_map_updater_ptr_->getSizeInCellsX(), - occupancy_grid_map_updater_ptr_->getSizeInCellsY(), - occupancy_grid_map_updater_ptr_->getResolution()); - single_frame_occupancy_grid_map.updateOrigin( - gridmap_origin.position.x - single_frame_occupancy_grid_map.getSizeInMetersX() / 2, - gridmap_origin.position.y - single_frame_occupancy_grid_map.getSizeInMetersY() / 2); - single_frame_occupancy_grid_map.updateFreespaceCells(trans_raw_pc); - single_frame_occupancy_grid_map.raytrace2D(trans_laserscan_pc, scan_origin); - single_frame_occupancy_grid_map.updateOccupiedCells(trans_obstacle_pc); - - if (enable_single_frame_mode_) { - // publish - occupancy_grid_map_pub_->publish(OccupancyGridMapToMsgPtr( - map_frame_, laserscan_pc_ptr->header.stamp, gridmap_origin.position.z, - single_frame_occupancy_grid_map)); - } else { - // Update with bayes filter - occupancy_grid_map_updater_ptr_->update(single_frame_occupancy_grid_map); + { // transform pointclouds + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("transformPointcloud", *time_keeper_); - // publish - occupancy_grid_map_pub_->publish(OccupancyGridMapToMsgPtr( - map_frame_, laserscan_pc_ptr->header.stamp, gridmap_origin.position.z, - *occupancy_grid_map_updater_ptr_)); + try { + utils::transformPointcloud(*laserscan_pc_ptr, *tf2_, map_frame_, trans_laserscan_pc); + utils::transformPointcloud(filtered_obstacle_pc, *tf2_, map_frame_, trans_obstacle_pc); + utils::transformPointcloud(filtered_raw_pc, *tf2_, map_frame_, trans_raw_pc); + gridmap_origin = + utils::getPose(laserscan_pc_ptr->header.stamp, *tf2_, gridmap_origin_frame_, map_frame_); + scan_origin = + utils::getPose(laserscan_pc_ptr->header.stamp, *tf2_, scan_origin_frame_, map_frame_); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_STREAM(get_logger(), ex.what()); + return; + } } + + { // create occupancy grid map and publish it + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("create_occupancy_grid_map", *time_keeper_); + + // Create single frame occupancy grid map + OccupancyGridMap single_frame_occupancy_grid_map( + occupancy_grid_map_updater_ptr_->getSizeInCellsX(), + occupancy_grid_map_updater_ptr_->getSizeInCellsY(), + occupancy_grid_map_updater_ptr_->getResolution()); + single_frame_occupancy_grid_map.updateOrigin( + gridmap_origin.position.x - single_frame_occupancy_grid_map.getSizeInMetersX() / 2, + gridmap_origin.position.y - single_frame_occupancy_grid_map.getSizeInMetersY() / 2); + single_frame_occupancy_grid_map.updateFreespaceCells(trans_raw_pc); + single_frame_occupancy_grid_map.raytrace2D(trans_laserscan_pc, scan_origin); + single_frame_occupancy_grid_map.updateOccupiedCells(trans_obstacle_pc); + + if (enable_single_frame_mode_) { + std::unique_ptr publish_st_ptr; + if (time_keeper_) + publish_st_ptr = + std::make_unique("publish_occupancy_grid_map", *time_keeper_); + + // publish + occupancy_grid_map_pub_->publish(OccupancyGridMapToMsgPtr( + map_frame_, laserscan_pc_ptr->header.stamp, gridmap_origin.position.z, + single_frame_occupancy_grid_map)); + } else { + std::unique_ptr publish_and_update_st_ptr; + if (time_keeper_) + publish_and_update_st_ptr = + std::make_unique("update_and_publish_occupancy_grid_map", *time_keeper_); + + // Update with bayes filter + occupancy_grid_map_updater_ptr_->update(single_frame_occupancy_grid_map); + + // publish + occupancy_grid_map_pub_->publish(OccupancyGridMapToMsgPtr( + map_frame_, laserscan_pc_ptr->header.stamp, gridmap_origin.position.z, + *occupancy_grid_map_updater_ptr_)); + } + } // scope for time keeper ends } OccupancyGrid::UniquePtr LaserscanBasedOccupancyGridMapNode::OccupancyGridMapToMsgPtr( const std::string & frame_id, const Time & stamp, const float & robot_pose_z, const Costmap2D & occupancy_grid_map) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + auto msg_ptr = std::make_unique(); msg_ptr->header.frame_id = frame_id; diff --git a/perception/autoware_probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp b/perception/autoware_probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp index a599f7b564c8b..ebb5b66625939 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp @@ -18,6 +18,7 @@ #include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map.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/universe_utils/system/time_keeper.hpp" #include #include @@ -98,6 +99,11 @@ class LaserscanBasedOccupancyGridMapNode : public rclcpp::Node double min_height_; double max_height_; bool enable_single_frame_mode_; + + // time keeper + rclcpp::Publisher::SharedPtr + detailed_processing_time_publisher_; + std::shared_ptr time_keeper_; }; } // namespace autoware::occupancy_grid_map 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 0d772e73c1ad8..4d442ad2c33db 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 @@ -43,6 +43,7 @@ namespace autoware::occupancy_grid_map { +using autoware::universe_utils::ScopedTimeTrack; using costmap_2d::OccupancyGridMapBBFUpdater; using costmap_2d::OccupancyGridMapFixedBlindSpot; using costmap_2d::OccupancyGridMapProjectiveBlindSpot; @@ -127,6 +128,16 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode( std::make_unique(this, "pointcloud_based_occupancy_grid_map"); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); + + // time keeper setup + 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); + } } } @@ -134,6 +145,9 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( const PointCloud2::ConstSharedPtr & input_obstacle_msg, const PointCloud2::ConstSharedPtr & input_raw_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + if (stop_watch_ptr_) { stop_watch_ptr_->toc("processing_time", true); } @@ -199,21 +213,37 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( return; } - // Create single frame occupancy grid map - occupancy_grid_map_ptr_->resetMaps(); - occupancy_grid_map_ptr_->updateOrigin( - 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); + { // create occupancy grid map and publish it + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("create_occupancy_grid_map", *time_keeper_); + + // Create single frame occupancy grid map + occupancy_grid_map_ptr_->resetMaps(); + occupancy_grid_map_ptr_->updateOrigin( + 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); + } if (enable_single_frame_mode_) { + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("publish_occupancy_grid_map", *time_keeper_); + // publish occupancy_grid_map_pub_->publish(OccupancyGridMapToMsgPtr( map_frame_, input_raw_msg->header.stamp, robot_pose.position.z, *occupancy_grid_map_ptr_)); // (todo) robot_pose may be altered with gridmap_origin } else { + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = + std::make_unique("update_and_publish_occupancy_grid_map", *time_keeper_); + // Update with bayes filter occupancy_grid_map_updater_ptr_->update(*occupancy_grid_map_ptr_); @@ -244,6 +274,9 @@ OccupancyGrid::UniquePtr PointcloudBasedOccupancyGridMapNode::OccupancyGridMapTo const std::string & frame_id, const Time & stamp, const float & robot_pose_z, const Costmap2D & occupancy_grid_map) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + auto msg_ptr = std::make_unique(); msg_ptr->header.frame_id = frame_id; 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 e0c7ef74988f4..34afd5edc7c37 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 @@ -21,6 +21,7 @@ #include #include +#include #include #include #include @@ -91,6 +92,11 @@ class PointcloudBasedOccupancyGridMapNode : public rclcpp::Node double max_height_; bool enable_single_frame_mode_; bool filter_obstacle_pointcloud_by_raw_pointcloud_; + + // time keeper + rclcpp::Publisher::SharedPtr + detailed_processing_time_publisher_; + std::shared_ptr time_keeper_; }; } // namespace autoware::occupancy_grid_map From 314d2a6a08f30e9411f31e3c6e503536f0db8462 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 9 Sep 2024 23:04:48 +0900 Subject: [PATCH 166/217] feat(goal_planner): dense goal candidate sampling in BusStopArea (#8795) Signed-off-by: Mamoru Sobue --- .../CMakeLists.txt | 10 +++ .../config/goal_planner.param.yaml | 4 + .../goal_planner_parameters.hpp | 6 ++ .../goal_searcher.hpp | 2 - .../util.hpp | 17 ++++ .../package.xml | 2 + .../src/goal_searcher.cpp | 53 ++++++------ .../src/manager.cpp | 6 ++ .../src/util.cpp | 35 ++++++++ .../test/test_util.cpp | 84 +++++++++++++++++++ 10 files changed, 188 insertions(+), 31 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.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 36013c5aa0fb9..626b47b6bdb0d 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 @@ -41,4 +41,14 @@ if(BUILD_EXAMPLES) endforeach() endif() +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_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 379dad254fbec..58a8f5d074fca 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 @@ -23,6 +23,10 @@ ignore_distance_from_lane_start: 0.0 margin_from_boundary: 0.75 high_curvature_threshold: 0.1 + bus_stop_area: + use_bus_stop_area: false + goal_search_interval: 0.5 + lateral_offset_interval: 0.25 # occupancy grid map occupancy_grid: 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 1272ea38451ee..440e57b53d07f 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 @@ -61,6 +61,12 @@ struct GoalPlannerParameters double ignore_distance_from_lane_start{0.0}; double margin_from_boundary{0.0}; double high_curvature_threshold{0.0}; + struct BusStopArea + { + bool use_bus_stop_area{false}; + double goal_search_interval{0.0}; + double lateral_offset_interval{0.0}; + } bus_stop_area; // occupancy grid map bool use_occupancy_grid_for_goal_search{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp index dd81650394740..af2e756e64ca5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp @@ -65,8 +65,6 @@ class GoalSearcher : public GoalSearcherBase const std::shared_ptr & planner_data) const; BasicPolygons2d getNoParkingAreaPolygons(const lanelet::ConstLanelets & lanes) const; BasicPolygons2d getNoStoppingAreaPolygons(const lanelet::ConstLanelets & lanes) const; - BasicPolygons2d getBusStopAreaPolygons(const lanelet::ConstLanelets & lanes) const; - bool isInAreas(const LinearRing2d & footprint, const BasicPolygons2d & areas) const; LinearRing2d vehicle_footprint_{}; bool left_side_parking_{true}; 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 8fbe2facc87d1..054405b94f617 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 @@ -123,6 +123,23 @@ std::vector createPathFootPrints( const PathWithLaneId & path, const double base_to_front, const double base_to_rear, const double width); +/** + * @brief check if footprint intersects with given areas + */ +bool isIntersectingAreas( + const LinearRing2d & footprint, const std::vector & areas); + +/** + * @brief check if footprint is within one of the areas + */ +bool isWithinAreas( + const LinearRing2d & footprint, const std::vector & areas); + +/** + * @brief query BusStopArea polygons associated with given lanes + */ +std::vector getBusStopAreaPolygons(const lanelet::ConstLanelets & lanes); + // debug MarkerArray createPullOverAreaMarkerArray( const autoware::universe_utils::MultiPolygon2d area_polygons, 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 2f107c5644f2e..00d7eb8c9debe 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 @@ -31,8 +31,10 @@ visualization_msgs ament_cmake_ros + 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/goal_searcher.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp index 54f0b6bfabf87..b9351e4588d5a 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 @@ -19,7 +19,6 @@ #include "autoware/behavior_path_planner_common/utils/path_utils.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" -#include "autoware_lanelet2_extension/regulatory_elements/bus_stop_area.hpp" #include "autoware_lanelet2_extension/regulatory_elements/no_parking_area.hpp" #include "autoware_lanelet2_extension/regulatory_elements/no_stopping_area.hpp" #include "autoware_lanelet2_extension/utility/query.hpp" @@ -107,7 +106,10 @@ GoalCandidates GoalSearcher::search(const std::shared_ptr & p const double forward_length = parameters_.forward_goal_search_length; const double backward_length = parameters_.backward_goal_search_length; const double margin_from_boundary = parameters_.margin_from_boundary; - const double lateral_offset_interval = parameters_.lateral_offset_interval; + const bool use_bus_stop_area = parameters_.bus_stop_area.use_bus_stop_area; + 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 double vehicle_width = planner_data->parameters.vehicle_width; @@ -126,9 +128,15 @@ GoalCandidates GoalSearcher::search(const std::shared_ptr & p lanelet::utils::getArcCoordinates(pull_over_lanes, reference_goal_pose_); 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 = utils::resamplePathWithSpline( - route_handler->getCenterLinePath(pull_over_lanes, s_start, s_end), - parameters_.goal_search_interval); + route_handler->getCenterLinePath(pull_over_lanes, s_start, s_end), longitudinal_interval); + + const auto no_parking_area_polygons = getNoParkingAreaPolygons(pull_over_lanes); + const auto no_stopping_area_polygons = getNoStoppingAreaPolygons(pull_over_lanes); + const auto bus_stop_area_polygons = goal_planner_utils::getBusStopAreaPolygons(pull_over_lanes); std::vector original_search_poses{}; // for search area visualizing size_t goal_id = 0; @@ -152,7 +160,8 @@ GoalCandidates GoalSearcher::search(const std::shared_ptr & p const double sign = left_side_parking_ ? -1.0 : 1.0; const double offset_from_center_line = - -distance_from_bound.value() + sign * margin_from_boundary; + use_bus_stop_area ? -distance_from_bound.value() + : -distance_from_bound.value() + sign * margin_from_boundary; // original means non lateral offset poses const Pose original_search_pose = calcOffsetPose(center_pose, 0, offset_from_center_line, 0); const double longitudinal_distance_from_original_goal = @@ -167,12 +176,20 @@ GoalCandidates GoalSearcher::search(const std::shared_ptr & p const auto transformed_vehicle_footprint = transformVector(vehicle_footprint_, autoware::universe_utils::pose2transform(search_pose)); - if (isInAreas(transformed_vehicle_footprint, getNoParkingAreaPolygons(pull_over_lanes))) { + if ( + parameters_.bus_stop_area.use_bus_stop_area && + !goal_planner_utils::isWithinAreas(transformed_vehicle_footprint, bus_stop_area_polygons)) { + continue; + } + + if (goal_planner_utils::isIntersectingAreas( + transformed_vehicle_footprint, no_parking_area_polygons)) { // break here to exclude goals located laterally in no_parking_areas break; } - if (isInAreas(transformed_vehicle_footprint, getNoStoppingAreaPolygons(pull_over_lanes))) { + if (goal_planner_utils::isIntersectingAreas( + transformed_vehicle_footprint, no_stopping_area_polygons)) { // break here to exclude goals located laterally in no_stopping_areas break; } @@ -492,28 +509,6 @@ BasicPolygons2d GoalSearcher::getNoStoppingAreaPolygons(const lanelet::ConstLane return area_polygons; } -BasicPolygons2d GoalSearcher::getBusStopAreaPolygons(const lanelet::ConstLanelets & lanes) const -{ - BasicPolygons2d area_polygons{}; - for (const auto & bus_stop_area_reg_elem : lanelet::utils::query::busStopAreas(lanes)) { - for (const auto & area : bus_stop_area_reg_elem->busStopAreas()) { - const auto & area_poly = lanelet::utils::to2D(area).basicPolygon(); - area_polygons.push_back(area_poly); - } - } - return area_polygons; -} - -bool GoalSearcher::isInAreas(const LinearRing2d & footprint, const BasicPolygons2d & areas) const -{ - for (const auto & area : areas) { - if (boost::geometry::intersects(area, footprint)) { - return true; - } - } - return false; -} - GoalCandidate GoalSearcher::getClosetGoalCandidateAlongLanes( const GoalCandidates & goal_candidates, const std::shared_ptr & planner_data) const 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 f9afe28d72d3a..32d6c55276876 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 @@ -59,6 +59,12 @@ GoalPlannerParameters GoalPlannerModuleManager::initGoalPlannerParameters( node->declare_parameter(ns + "ignore_distance_from_lane_start"); p.margin_from_boundary = node->declare_parameter(ns + "margin_from_boundary"); p.high_curvature_threshold = node->declare_parameter(ns + "high_curvature_threshold"); + p.bus_stop_area.use_bus_stop_area = + node->declare_parameter(ns + "bus_stop_area.use_bus_stop_area"); + p.bus_stop_area.goal_search_interval = + node->declare_parameter(ns + "bus_stop_area.goal_search_interval"); + p.bus_stop_area.lateral_offset_interval = + node->declare_parameter(ns + "bus_stop_area.lateral_offset_interval"); const std::string parking_policy_name = node->declare_parameter(ns + "parking_policy"); 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 656cdf91c0c54..69873b5e0fb80 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 @@ -16,6 +16,7 @@ #include "autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" +#include "autoware_lanelet2_extension/regulatory_elements/bus_stop_area.hpp" #include #include @@ -290,6 +291,40 @@ PredictedObjects filterObjectsByLateralDistance( return filtered_objects; } +bool isIntersectingAreas( + const LinearRing2d & footprint, const std::vector & areas) +{ + for (const auto & area : areas) { + if (boost::geometry::intersects(area, footprint)) { + return true; + } + } + return false; +} + +bool isWithinAreas( + const LinearRing2d & footprint, const std::vector & areas) +{ + for (const auto & area : areas) { + if (boost::geometry::within(footprint, area)) { + return true; + } + } + return false; +} + +std::vector getBusStopAreaPolygons(const lanelet::ConstLanelets & lanes) +{ + std::vector area_polygons{}; + for (const auto & bus_stop_area_reg_elem : lanelet::utils::query::busStopAreas(lanes)) { + for (const auto & area : bus_stop_area_reg_elem->busStopAreas()) { + const auto & area_poly = lanelet::utils::to2D(area).basicPolygon(); + area_polygons.push_back(area_poly); + } + } + return area_polygons; +} + MarkerArray createPullOverAreaMarkerArray( const autoware::universe_utils::MultiPolygon2d area_polygons, const std_msgs::msg::Header & header, const std_msgs::msg::ColorRGBA & color, const double z) 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 new file mode 100644 index 0000000000000..ca93505fe1eae --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp @@ -0,0 +1,84 @@ +// 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 + +class TestUtilWithMap : public ::testing::Test +{ +protected: + void SetUp() override + { + rclcpp::init(0, nullptr); + // parameters + auto node_options = rclcpp::NodeOptions{}; + node_options.arguments(std::vector{ + "--ros-args", "--params-file", + ament_index_cpp::get_package_share_directory("autoware_test_utils") + + "/config/test_vehicle_info.param.yaml"}); + auto node = rclcpp::Node::make_shared("test", node_options); + vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo(); + + // lanelet map + const std::string shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( + "autoware_behavior_path_planner_common", "road_shoulder/lanelet2_map.osm"); + const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); + + // load map + route_handler = std::make_shared(map_bin_msg); + } + + void TearDown() override { rclcpp::shutdown(); } + +public: + std::shared_ptr route_handler; + autoware::vehicle_info_utils::VehicleInfo vehicle_info; +}; + +TEST_F(TestUtilWithMap, getBusStopAreaPolygons) +{ + const auto lanes = lanelet::utils::query::laneletLayer(route_handler->getLaneletMapPtr()); + 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(), 2); +} + +TEST_F(TestUtilWithMap, isWithinAreas) +{ + const auto lanes = lanelet::utils::query::laneletLayer(route_handler->getLaneletMapPtr()); + 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); + + const auto footprint = vehicle_info.createFootprint(); + const geometry_msgs::msg::Pose baselink_pose = + geometry_msgs::build() + .position( + geometry_msgs::build().x(273.102814).y(402.194794).z(0.0)) + .orientation( + geometry_msgs::build().x(0.0).y(0.0).z(0.707390).w( + 0.706824)); + const auto baselink_footprint = autoware::universe_utils::transformVector( + footprint, autoware::universe_utils::pose2transform(baselink_pose)); + EXPECT_EQ( + autoware::behavior_path_planner::goal_planner_utils::isWithinAreas( + baselink_footprint, bus_stop_area_polygons), + true); +} From 40d87c2612806fe0e80d5c91202f6b71e544ad45 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 10 Sep 2024 03:19:09 +0900 Subject: [PATCH 167/217] feat(goal_planner): execute goal planner if previous module path terminal is pull over neighboring lane (#8715) Signed-off-by: kosuke55 --- .../README.md | 2 +- .../src/goal_planner_module.cpp | 45 ++++++++++++------- 2 files changed, 29 insertions(+), 18 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md index d1c2224d2233c..928e53b1ccff5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md @@ -107,7 +107,7 @@ If the target path contains a goal, modify the points of the path so that the pa - Route is set with `allow_goal_modification=true` . - We can set this option with [SetRoute](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/routing/srv/SetRoute.srv#L2) api service. - We support `2D Rough Goal Pose` with the key bind `r` in RViz, but in the future there will be a panel of tools to manipulate various Route API from RViz. -- ego-vehicle is in the same lane as the goal. +- The terminal point of the current path is in the same lane sequence as the goal. If goal is on the road shoulder, then it is in the adjacent road lane sequence. 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 dd37d1b30a2a8..56c7c42eec6ae 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 @@ -596,15 +596,25 @@ bool GoalPlannerModule::isExecutionRequested() const const Pose & current_pose = planner_data_->self_odometry->pose.pose; const Pose goal_pose = route_handler->getOriginalGoalPose(); - // check if goal_pose is in current_lanes. - lanelet::ConstLanelet current_lane{}; - // const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_); + // check if goal_pose is in current_lanes or neighboring road lanes const lanelet::ConstLanelets current_lanes = utils::getCurrentLanesFromPath(getPreviousModuleOutput().reference_path, planner_data_); - lanelet::utils::query::getClosestLanelet(current_lanes, current_pose, ¤t_lane); - const bool goal_is_in_current_lanes = std::any_of( - current_lanes.begin(), current_lanes.end(), [&](const lanelet::ConstLanelet & current_lane) { - return lanelet::utils::isInLanelet(goal_pose, current_lane); + 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 @@ -621,7 +631,7 @@ bool GoalPlannerModule::isExecutionRequested() const // 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_lanes && !goal_is_in_current_shoulder_lanes) { + if (!goal_is_in_current_segment_lanes && !goal_is_in_current_shoulder_lanes) { return false; } @@ -629,7 +639,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_lanes; + return goal_is_in_current_segment_lanes; } // if goal arc coordinates can be calculated, check if goal is in request_length @@ -651,7 +661,12 @@ bool GoalPlannerModule::isExecutionRequested() const parameters_->forward_goal_search_length); lanelet::ConstLanelet target_lane{}; lanelet::utils::query::getClosestLanelet(pull_over_lanes, goal_pose, &target_lane); - if (!isCrossingPossible(current_lane, target_lane)) { + + lanelet::ConstLanelet previous_module_terminal_lane{}; + route_handler->getClosestLaneletWithinRoute( + getPreviousModuleOutput().path.points.back().point.pose, &previous_module_terminal_lane); + + if (!isCrossingPossible(previous_module_terminal_lane, target_lane)) { return false; } @@ -2236,14 +2251,10 @@ bool GoalPlannerModule::isCrossingPossible( end_lane_sequence = route_handler->getLaneletSequence(end_lane, dist, dist, false); } - // Lambda function to get the neighboring lanelet based on left_side_parking_ - auto getNeighboringLane = + const auto getNeighboringLane = [&](const lanelet::ConstLanelet & lane) -> std::optional { - const auto neighboring_lane = left_side_parking_ ? route_handler->getLeftShoulderLanelet(lane) - : route_handler->getRightShoulderLanelet(lane); - if (neighboring_lane) return neighboring_lane; - return left_side_parking_ ? route_handler->getLeftLanelet(lane) - : route_handler->getRightLanelet(lane); + return left_side_parking_ ? route_handler->getLeftLanelet(lane, false, true) + : route_handler->getRightLanelet(lane, false, true); }; // Iterate through start_lane_sequence to find a path to end_lane_sequence From b56f38660f1115932acfdde714f4318e3d701fbb Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 10 Sep 2024 03:19:28 +0900 Subject: [PATCH 168/217] fix(raw_vehicle_cmd_converter): fix convert_steer_cmd_method condition (#8813) Signed-off-by: kosuke55 --- vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp index 0530840655816..362fb53eba67d 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp @@ -271,7 +271,7 @@ void RawVehicleCommandConverterNode::onActuationStatus( { actuation_status_ptr_ = msg; - if (!convert_actuation_to_steering_status_ || convert_steer_cmd_method_.has_value()) { + if (!convert_actuation_to_steering_status_ || !convert_steer_cmd_method_.has_value()) { return; } From a1cba1fb1fc9d09a3e8787f43a068a810105aced Mon Sep 17 00:00:00 2001 From: Hayate TOBA <105347690+bathteayo@users.noreply.github.com> Date: Tue, 10 Sep 2024 11:40:48 +0900 Subject: [PATCH 169/217] fix(autoware_component_monitor): fix unusedFunction (#8582) Signed-off-by: bathteayo <105347690+bathteayo@users.noreply.github.com> --- .../src/unit_conversions.hpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/system/autoware_component_monitor/src/unit_conversions.hpp b/system/autoware_component_monitor/src/unit_conversions.hpp index c8f3fa02da519..12ac4aaa6a9cb 100644 --- a/system/autoware_component_monitor/src/unit_conversions.hpp +++ b/system/autoware_component_monitor/src/unit_conversions.hpp @@ -20,41 +20,52 @@ namespace autoware::component_monitor::unit_conversions { +// cppcheck-suppress-begin unusedFunction template std::uint64_t kib_to_bytes(T kibibytes) { static_assert(std::is_arithmetic::value, "Template parameter must be a numeric type"); return static_cast(kibibytes * 1024); } +// cppcheck-suppress-end unusedFunction +// cppcheck-suppress-begin unusedFunction template std::uint64_t mib_to_bytes(T mebibytes) { static_assert(std::is_arithmetic::value, "Template parameter must be a numeric type"); return static_cast(mebibytes * 1024 * 1024); } +// cppcheck-suppress-end unusedFunction +// cppcheck-suppress-begin unusedFunction template std::uint64_t gib_to_bytes(T gibibytes) { static_assert(std::is_arithmetic::value, "Template parameter must be a numeric type"); return static_cast(gibibytes * 1024ULL * 1024ULL * 1024ULL); } +// cppcheck-suppress-end unusedFunction +// cppcheck-suppress-begin unusedFunction template std::uint64_t tib_to_bytes(T tebibytes) { static_assert(std::is_arithmetic::value, "Template parameter must be a numeric type"); return static_cast(tebibytes * 1024ULL * 1024ULL * 1024ULL * 1024ULL); } +// cppcheck-suppress-end unusedFunction +// cppcheck-suppress-begin unusedFunction template std::uint64_t pib_to_bytes(T pebibytes) { static_assert(std::is_arithmetic::value, "Template parameter must be a numeric type"); return static_cast(pebibytes * 1024ULL * 1024ULL * 1024ULL * 1024ULL * 1024ULL); } +// cppcheck-suppress-end unusedFunction +// cppcheck-suppress-begin unusedFunction template std::uint64_t eib_to_bytes(T exbibytes) { @@ -62,6 +73,7 @@ std::uint64_t eib_to_bytes(T exbibytes) return static_cast( exbibytes * 1024ULL * 1024ULL * 1024ULL * 1024ULL * 1024ULL * 1024ULL); } +// cppcheck-suppress-end unusedFunction } // namespace autoware::component_monitor::unit_conversions From dabeaa640f25cd7af3ea3333a3fb4533cc64cf5f Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Tue, 10 Sep 2024 13:39:58 +0900 Subject: [PATCH 170/217] feat(ground_segmentation): add time_keeper (#8585) * add time_keeper Signed-off-by: a-maumau * add timekeeper option Signed-off-by: a-maumau * add autoware_universe_utils Signed-off-by: a-maumau * fix topic name Signed-off-by: a-maumau * add scope and timekeeper Signed-off-by: a-maumau * remove debug code Signed-off-by: a-maumau * remove some timekeeper and mod block comment Signed-off-by: a-maumau --------- Signed-off-by: a-maumau --- .../config/ground_segmentation.param.yaml | 3 + .../config/ransac_ground_filter.param.yaml | 3 + .../config/ray_ground_filter.param.yaml | 3 + .../config/scan_ground_filter.param.yaml | 3 + .../autoware_ground_segmentation/package.xml | 1 + .../src/ransac_ground_filter/node.cpp | 16 ++ .../src/ransac_ground_filter/node.hpp | 6 + .../src/ray_ground_filter/node.cpp | 23 +++ .../src/ray_ground_filter/node.hpp | 8 + .../src/scan_ground_filter/node.cpp | 156 ++++++++++++------ .../src/scan_ground_filter/node.hpp | 6 + .../test/test_ransac_ground_filter.cpp | 2 + .../test/test_ray_ground_filter.cpp | 3 + .../test/test_scan_ground_filter.cpp | 4 + 14 files changed, 184 insertions(+), 53 deletions(-) diff --git a/perception/autoware_ground_segmentation/config/ground_segmentation.param.yaml b/perception/autoware_ground_segmentation/config/ground_segmentation.param.yaml index 304dcc8990fe2..4fe68a19fa6e3 100644 --- a/perception/autoware_ground_segmentation/config/ground_segmentation.param.yaml +++ b/perception/autoware_ground_segmentation/config/ground_segmentation.param.yaml @@ -19,3 +19,6 @@ radial_divider_angle_deg: 1.0 use_recheck_ground_cluster: true use_lowest_point: true + + # debug parameters + publish_processing_time_detail: false diff --git a/perception/autoware_ground_segmentation/config/ransac_ground_filter.param.yaml b/perception/autoware_ground_segmentation/config/ransac_ground_filter.param.yaml index 0d4a7d574499c..4b645dba95faf 100644 --- a/perception/autoware_ground_segmentation/config/ransac_ground_filter.param.yaml +++ b/perception/autoware_ground_segmentation/config/ransac_ground_filter.param.yaml @@ -12,3 +12,6 @@ voxel_size_z: 0.04 height_threshold: 0.01 debug: false + + # debug parameters + publish_processing_time_detail: false diff --git a/perception/autoware_ground_segmentation/config/ray_ground_filter.param.yaml b/perception/autoware_ground_segmentation/config/ray_ground_filter.param.yaml index 5b9e8c06595f7..ac29f25ddb729 100644 --- a/perception/autoware_ground_segmentation/config/ray_ground_filter.param.yaml +++ b/perception/autoware_ground_segmentation/config/ray_ground_filter.param.yaml @@ -12,3 +12,6 @@ min_height_threshold: 0.15 concentric_divider_distance: 0.0 reclass_distance_threshold: 0.1 + + # debug parameters + publish_processing_time_detail: false diff --git a/perception/autoware_ground_segmentation/config/scan_ground_filter.param.yaml b/perception/autoware_ground_segmentation/config/scan_ground_filter.param.yaml index 35d494a620b19..49c6c32624e75 100644 --- a/perception/autoware_ground_segmentation/config/scan_ground_filter.param.yaml +++ b/perception/autoware_ground_segmentation/config/scan_ground_filter.param.yaml @@ -16,3 +16,6 @@ radial_divider_angle_deg: 1.0 use_recheck_ground_cluster: true use_lowest_point: true + + # debug parameters + publish_processing_time_detail: false diff --git a/perception/autoware_ground_segmentation/package.xml b/perception/autoware_ground_segmentation/package.xml index ff61a6b600f54..6b0ae57aa805a 100644 --- a/perception/autoware_ground_segmentation/package.xml +++ b/perception/autoware_ground_segmentation/package.xml @@ -21,6 +21,7 @@ ament_index_cpp autoware_pointcloud_preprocessor + autoware_universe_utils autoware_vehicle_info_utils libopencv-dev pcl_conversions diff --git a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp index e2f96d862e1a6..83e0538bd56de 100644 --- a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp +++ b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp @@ -81,6 +81,7 @@ PlaneBasis getPlaneBasis(const Eigen::Vector3d & plane_normal) } using autoware::pointcloud_preprocessor::get_param; +using autoware::universe_utils::ScopedTimeTrack; RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptions & options) : Filter("RANSACGroundFilter", options) @@ -118,6 +119,15 @@ RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptio managed_tf_buffer_ = std::make_unique(this, has_static_tf_only_); + + 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); + } } void RANSACGroundFilterComponent::setDebugPublisher() @@ -204,6 +214,9 @@ void RANSACGroundFilterComponent::applyRANSAC( const pcl::PointCloud::Ptr & input, pcl::PointIndices::Ptr & output_inliers, pcl::ModelCoefficients::Ptr & output_coefficients) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + pcl::SACSegmentation seg; seg.setOptimizeCoefficients(true); seg.setRadiusLimits(0.3, std::numeric_limits::max()); @@ -219,6 +232,9 @@ void RANSACGroundFilterComponent::filter( const PointCloud2::ConstSharedPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + std::scoped_lock lock(mutex_); sensor_msgs::msg::PointCloud2::SharedPtr input_transformed_ptr(new sensor_msgs::msg::PointCloud2); if (!transformPointCloud(base_frame_, input, input_transformed_ptr)) { diff --git a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp index b36a7f5e55fc4..f9638086bf811 100644 --- a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp +++ b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp @@ -16,6 +16,7 @@ #define RANSAC_GROUND_FILTER__NODE_HPP_ #include "autoware/pointcloud_preprocessor/filter.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include @@ -85,6 +86,11 @@ class RANSACGroundFilterComponent : public autoware::pointcloud_preprocessor::Fi Eigen::Vector3d unit_vec_ = Eigen::Vector3d::UnitZ(); std::unique_ptr managed_tf_buffer_{nullptr}; + // time keeper related + rclcpp::Publisher::SharedPtr + detailed_processing_time_publisher_; + std::shared_ptr time_keeper_; + /*! * Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame * @param[in] in_target_frame Coordinate system to perform transform diff --git a/perception/autoware_ground_segmentation/src/ray_ground_filter/node.cpp b/perception/autoware_ground_segmentation/src/ray_ground_filter/node.cpp index fd8fcd4dc29e7..70ccffe2412a9 100644 --- a/perception/autoware_ground_segmentation/src/ray_ground_filter/node.cpp +++ b/perception/autoware_ground_segmentation/src/ray_ground_filter/node.cpp @@ -31,12 +31,14 @@ #include "node.hpp" +#include #include #include namespace autoware::ground_segmentation { using autoware::pointcloud_preprocessor::get_param; +using autoware::universe_utils::ScopedTimeTrack; RayGroundFilterComponent::RayGroundFilterComponent(const rclcpp::NodeOptions & options) : Filter("RayGroundFilter", options) @@ -69,6 +71,15 @@ RayGroundFilterComponent::RayGroundFilterComponent(const rclcpp::NodeOptions & o using std::placeholders::_1; set_param_res_ = this->add_on_set_parameters_callback( std::bind(&RayGroundFilterComponent::paramCallback, this, _1)); + + 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); + } } void RayGroundFilterComponent::ConvertXYZIToRTZColor( @@ -76,6 +87,9 @@ void RayGroundFilterComponent::ConvertXYZIToRTZColor( std::vector & out_radial_divided_indices, std::vector & out_radial_ordered_clouds) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + out_organized_points.resize(in_cloud->points.size()); out_radial_divided_indices.clear(); out_radial_divided_indices.resize(radial_dividers_num_); @@ -153,6 +167,9 @@ void RayGroundFilterComponent::ClassifyPointCloud( std::vector & in_radial_ordered_clouds, pcl::PointIndices & out_ground_indices, pcl::PointIndices & out_no_ground_indices) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + out_ground_indices.indices.clear(); out_no_ground_indices.indices.clear(); #pragma omp for @@ -275,6 +292,9 @@ void RayGroundFilterComponent::ExtractPointsIndices( const PointCloud2::ConstSharedPtr in_cloud_ptr, const pcl::PointIndices & in_indices, PointCloud2::SharedPtr ground_cloud_msg_ptr, PointCloud2::SharedPtr no_ground_cloud_msg_ptr) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + initializePointCloud2(in_cloud_ptr, ground_cloud_msg_ptr); initializePointCloud2(in_cloud_ptr, no_ground_cloud_msg_ptr); int point_step = in_cloud_ptr->point_step; @@ -312,6 +332,9 @@ void RayGroundFilterComponent::filter( const PointCloud2::ConstSharedPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + std::scoped_lock lock(mutex_); pcl::PointCloud::Ptr current_sensor_cloud_ptr(new pcl::PointCloud); diff --git a/perception/autoware_ground_segmentation/src/ray_ground_filter/node.hpp b/perception/autoware_ground_segmentation/src/ray_ground_filter/node.hpp index 54de09b37ad96..f27d4c774e3fe 100644 --- a/perception/autoware_ground_segmentation/src/ray_ground_filter/node.hpp +++ b/perception/autoware_ground_segmentation/src/ray_ground_filter/node.hpp @@ -45,6 +45,8 @@ #ifndef RAY_GROUND_FILTER__NODE_HPP_ #define RAY_GROUND_FILTER__NODE_HPP_ +#include "autoware/universe_utils/system/time_keeper.hpp" + #include #include @@ -72,6 +74,7 @@ #include #include +#include #include #include @@ -140,6 +143,11 @@ class RayGroundFilterComponent : public autoware::pointcloud_preprocessor::Filte pcl::PointCloud::Ptr previous_cloud_ptr_; // holds the previous groundless result of // ground classification + // time keeper related + rclcpp::Publisher::SharedPtr + detailed_processing_time_publisher_; + std::shared_ptr time_keeper_; + /*! * Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame * @param[in] in_target_frame Coordinate system to perform transform 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 40c00e082c60e..72481d13c41fb 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp @@ -30,6 +30,7 @@ using autoware::universe_utils::calcDistance3d; using autoware::universe_utils::deg2rad; using autoware::universe_utils::normalizeDegree; using autoware::universe_utils::normalizeRadian; +using autoware::universe_utils::ScopedTimeTrack; using autoware::vehicle_info_utils::VehicleInfoUtils; ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & options) @@ -85,6 +86,15 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & debug_publisher_ptr_ = std::make_unique(this, "scan_ground_filter"); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); + + 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); + } } } @@ -114,6 +124,9 @@ inline void ScanGroundFilterComponent::get_point_from_global_offset( void ScanGroundFilterComponent::convertPointcloudGridScan( const PointCloud2ConstPtr & in_cloud, std::vector & out_radial_ordered_points) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + out_radial_ordered_points.resize(radial_dividers_num_); PointData current_point; @@ -128,46 +141,59 @@ void ScanGroundFilterComponent::convertPointcloudGridScan( const size_t in_cloud_data_size = in_cloud->data.size(); const size_t in_cloud_point_step = in_cloud->point_step; - size_t point_index = 0; - pcl::PointXYZ input_point; - for (size_t global_offset = 0; global_offset + in_cloud_point_step <= in_cloud_data_size; - global_offset += in_cloud_point_step) { - get_point_from_global_offset(in_cloud, input_point, global_offset); - - auto x{input_point.x - x_shift}; // base on front wheel center - auto radius{static_cast(std::hypot(x, input_point.y))}; - auto theta{normalizeRadian(std::atan2(x, input_point.y), 0.0)}; - - // divide by vertical angle - auto radial_div{static_cast(std::floor(theta * inv_radial_divider_angle_rad))}; - uint16_t grid_id = 0; - if (radius <= grid_mode_switch_radius_) { - grid_id = static_cast(radius * inv_grid_size_m); - } else { - auto gamma{normalizeRadian(std::atan2(radius, virtual_lidar_z_), 0.0f)}; - grid_id = grid_id_offset + gamma * inv_grid_size_rad; + { // grouping pointcloud by its horizontal angle + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("horizontal_angle_grouping", *time_keeper_); + + size_t point_index = 0; + pcl::PointXYZ input_point; + for (size_t global_offset = 0; global_offset + in_cloud_point_step <= in_cloud_data_size; + global_offset += in_cloud_point_step) { + get_point_from_global_offset(in_cloud, input_point, global_offset); + + auto x{input_point.x - x_shift}; // base on front wheel center + auto radius{static_cast(std::hypot(x, input_point.y))}; + auto theta{normalizeRadian(std::atan2(x, input_point.y), 0.0)}; + + // divide by vertical angle + auto radial_div{static_cast(std::floor(theta * inv_radial_divider_angle_rad))}; + uint16_t grid_id = 0; + if (radius <= grid_mode_switch_radius_) { + grid_id = static_cast(radius * inv_grid_size_m); + } else { + auto gamma{normalizeRadian(std::atan2(radius, virtual_lidar_z_), 0.0f)}; + grid_id = grid_id_offset + gamma * inv_grid_size_rad; + } + current_point.grid_id = grid_id; + current_point.radius = radius; + current_point.point_state = PointLabel::INIT; + current_point.orig_index = point_index; + + // radial divisions + out_radial_ordered_points[radial_div].emplace_back(current_point); + ++point_index; } - current_point.grid_id = grid_id; - current_point.radius = radius; - current_point.point_state = PointLabel::INIT; - current_point.orig_index = point_index; - - // radial divisions - out_radial_ordered_points[radial_div].emplace_back(current_point); - ++point_index; } - // sort by distance - for (size_t i = 0; i < radial_dividers_num_; ++i) { - std::sort( - out_radial_ordered_points[i].begin(), out_radial_ordered_points[i].end(), - [](const PointData & a, const PointData & b) { return a.radius < b.radius; }); + { // sorting pointcloud by distance, on each horizontal angle group + std::unique_ptr inner_st_ptr; + if (time_keeper_) inner_st_ptr = std::make_unique("sort", *time_keeper_); + + for (size_t i = 0; i < radial_dividers_num_; ++i) { + std::sort( + out_radial_ordered_points[i].begin(), out_radial_ordered_points[i].end(), + [](const PointData & a, const PointData & b) { return a.radius < b.radius; }); + } } } void ScanGroundFilterComponent::convertPointcloud( const PointCloud2ConstPtr & in_cloud, std::vector & out_radial_ordered_points) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + out_radial_ordered_points.resize(radial_dividers_num_); PointData current_point; @@ -176,30 +202,41 @@ void ScanGroundFilterComponent::convertPointcloud( const size_t in_cloud_data_size = in_cloud->data.size(); const size_t in_cloud_point_step = in_cloud->point_step; - size_t point_index = 0; - pcl::PointXYZ input_point; - for (size_t global_offset = 0; global_offset + in_cloud_point_step <= in_cloud_data_size; - global_offset += in_cloud_point_step) { - // Point - get_point_from_global_offset(in_cloud, input_point, global_offset); - - auto radius{static_cast(std::hypot(input_point.x, input_point.y))}; - auto theta{normalizeRadian(std::atan2(input_point.x, input_point.y), 0.0)}; - auto radial_div{static_cast(std::floor(theta * inv_radial_divider_angle_rad))}; + { // grouping pointcloud by its horizontal angle + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("horizontal_angle_grouping", *time_keeper_); + + size_t point_index = 0; + pcl::PointXYZ input_point; + for (size_t global_offset = 0; global_offset + in_cloud_point_step <= in_cloud_data_size; + global_offset += in_cloud_point_step) { + // Point + get_point_from_global_offset(in_cloud, input_point, global_offset); + + auto radius{static_cast(std::hypot(input_point.x, input_point.y))}; + auto theta{normalizeRadian(std::atan2(input_point.x, input_point.y), 0.0)}; + auto radial_div{static_cast(std::floor(theta * inv_radial_divider_angle_rad))}; + + current_point.radius = radius; + current_point.point_state = PointLabel::INIT; + current_point.orig_index = point_index; + + // radial divisions + out_radial_ordered_points[radial_div].emplace_back(current_point); + ++point_index; + } + } - current_point.radius = radius; - current_point.point_state = PointLabel::INIT; - current_point.orig_index = point_index; + { // sorting pointcloud by distance, on each horizontal angle group + std::unique_ptr inner_st_ptr; + if (time_keeper_) inner_st_ptr = std::make_unique("sort", *time_keeper_); - // radial divisions - out_radial_ordered_points[radial_div].emplace_back(current_point); - ++point_index; - } - // sort by distance - for (size_t i = 0; i < radial_dividers_num_; ++i) { - std::sort( - out_radial_ordered_points[i].begin(), out_radial_ordered_points[i].end(), - [](const PointData & a, const PointData & b) { return a.radius < b.radius; }); + for (size_t i = 0; i < radial_dividers_num_; ++i) { + std::sort( + out_radial_ordered_points[i].begin(), out_radial_ordered_points[i].end(), + [](const PointData & a, const PointData & b) { return a.radius < b.radius; }); + } } } @@ -336,6 +373,9 @@ void ScanGroundFilterComponent::classifyPointCloudGridScan( const PointCloud2ConstPtr & in_cloud, std::vector & in_radial_ordered_clouds, pcl::PointIndices & out_no_ground_indices) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + out_no_ground_indices.indices.clear(); for (size_t i = 0; i < in_radial_ordered_clouds.size(); ++i) { PointsCentroid ground_cluster; @@ -456,6 +496,9 @@ void ScanGroundFilterComponent::classifyPointCloud( const PointCloud2ConstPtr & in_cloud, std::vector & in_radial_ordered_clouds, pcl::PointIndices & out_no_ground_indices) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + out_no_ground_indices.indices.clear(); const pcl::PointXYZ init_ground_point(0, 0, 0); @@ -470,6 +513,7 @@ void ScanGroundFilterComponent::classifyPointCloud( PointsCentroid ground_cluster, non_ground_cluster; PointLabel prev_point_label = PointLabel::INIT; pcl::PointXYZ prev_gnd_point(0, 0, 0), p_orig_point, prev_p_orig_point; + // loop through each point in the radial div for (size_t j = 0; j < in_radial_ordered_clouds[i].size(); ++j) { float points_distance = 0.0f; @@ -569,6 +613,9 @@ void ScanGroundFilterComponent::extractObjectPoints( const PointCloud2ConstPtr & in_cloud_ptr, const pcl::PointIndices & in_indices, PointCloud2 & out_object_cloud) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + size_t output_data_size = 0; for (const auto & i : in_indices.indices) { @@ -584,6 +631,9 @@ void ScanGroundFilterComponent::faster_filter( PointCloud2 & output, [[maybe_unused]] const autoware::pointcloud_preprocessor::TransformInfo & transform_info) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + std::scoped_lock lock(mutex_); stop_watch_ptr_->toc("processing_time", true); diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp index e87fd0c341a6f..12590afd5fb86 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp @@ -17,6 +17,7 @@ #include "autoware/pointcloud_preprocessor/filter.hpp" #include "autoware/pointcloud_preprocessor/transform_info.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware_vehicle_info_utils/vehicle_info.hpp" #include @@ -201,6 +202,11 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt size_t radial_dividers_num_; VehicleInfo vehicle_info_; + // time keeper related + rclcpp::Publisher::SharedPtr + detailed_processing_time_publisher_; + std::shared_ptr time_keeper_; + /*! * Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame * @param[in] in_target_frame Coordinate system to perform transform diff --git a/perception/autoware_ground_segmentation/test/test_ransac_ground_filter.cpp b/perception/autoware_ground_segmentation/test/test_ransac_ground_filter.cpp index e18c166adb8b3..a3f8b9d4b19b3 100644 --- a/perception/autoware_ground_segmentation/test/test_ransac_ground_filter.cpp +++ b/perception/autoware_ground_segmentation/test/test_ransac_ground_filter.cpp @@ -152,6 +152,7 @@ TEST_F(RansacGroundFilterTestSuite, TestCase1) double voxel_size_z = params["voxel_size_z"].as(); double height_threshold = params["height_threshold"].as(); bool debug = params["debug"].as(); + bool publish_processing_time_detail = params["publish_processing_time_detail"].as(); const auto pcd_path = share_dir + "/data/test.pcd"; pcl::PointCloud cloud; @@ -191,6 +192,7 @@ TEST_F(RansacGroundFilterTestSuite, TestCase1) parameters.emplace_back("voxel_size_z", voxel_size_z); parameters.emplace_back("height_threshold", height_threshold); parameters.emplace_back("debug", debug); + parameters.emplace_back("publish_processing_time_detail", publish_processing_time_detail); rclcpp::NodeOptions node_options; node_options.parameter_overrides(parameters); diff --git a/perception/autoware_ground_segmentation/test/test_ray_ground_filter.cpp b/perception/autoware_ground_segmentation/test/test_ray_ground_filter.cpp index 81efeff8111cb..1e494f683f181 100644 --- a/perception/autoware_ground_segmentation/test/test_ray_ground_filter.cpp +++ b/perception/autoware_ground_segmentation/test/test_ray_ground_filter.cpp @@ -121,6 +121,7 @@ TEST_F(RayGroundFilterComponentTestSuite, TestCase1) double min_height_threshold_ = params["min_height_threshold"].as(); double concentric_divider_distance_ = params["concentric_divider_distance"].as(); double reclass_distance_threshold_ = params["reclass_distance_threshold"].as(); + bool publish_processing_time_detail_ = params["publish_processing_time_detail"].as(); const auto pcd_path = share_dir + "/data/test.pcd"; pcl::PointCloud cloud; @@ -167,6 +168,8 @@ TEST_F(RayGroundFilterComponentTestSuite, TestCase1) parameters.emplace_back(rclcpp::Parameter("min_y", min_y_)); parameters.emplace_back(rclcpp::Parameter("max_y", max_y_)); parameters.emplace_back(rclcpp::Parameter("use_vehicle_footprint", use_vehicle_footprint_)); + parameters.emplace_back( + rclcpp::Parameter("publish_processing_time_detail", publish_processing_time_detail_)); node_options.parameter_overrides(parameters); auto ray_ground_filter_test = std::make_shared(node_options); diff --git a/perception/autoware_ground_segmentation/test/test_scan_ground_filter.cpp b/perception/autoware_ground_segmentation/test/test_scan_ground_filter.cpp index c6603dfd9a3e2..706ffff3ce511 100644 --- a/perception/autoware_ground_segmentation/test/test_scan_ground_filter.cpp +++ b/perception/autoware_ground_segmentation/test/test_scan_ground_filter.cpp @@ -122,6 +122,8 @@ class ScanGroundFilterTest : public ::testing::Test parameters.emplace_back( rclcpp::Parameter("use_recheck_ground_cluster", use_recheck_ground_cluster_)); parameters.emplace_back(rclcpp::Parameter("use_lowest_point", use_lowest_point_)); + parameters.emplace_back( + rclcpp::Parameter("publish_processing_time_detail", publish_processing_time_detail_)); options.parameter_overrides(parameters); @@ -200,6 +202,7 @@ class ScanGroundFilterTest : public ::testing::Test radial_divider_angle_deg_ = params["radial_divider_angle_deg"].as(); use_recheck_ground_cluster_ = params["use_recheck_ground_cluster"].as(); use_lowest_point_ = params["use_lowest_point"].as(); + publish_processing_time_detail_ = params["publish_processing_time_detail"].as(); } float global_slope_max_angle_deg_ = 0.0; @@ -218,6 +221,7 @@ class ScanGroundFilterTest : public ::testing::Test float radial_divider_angle_deg_; bool use_recheck_ground_cluster_; bool use_lowest_point_; + bool publish_processing_time_detail_; }; TEST_F(ScanGroundFilterTest, TestCase1) From d02c0122661d92d95dba73c0f5585e4c7e79c2eb Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Tue, 10 Sep 2024 14:54:43 +0900 Subject: [PATCH 171/217] refactor(autoware_lidar_centerpoint): use std::size_t instead of size_t (#8820) * refactor(autoware_lidar_centerpoint): use std::size_t instead of size_t Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../autoware/lidar_centerpoint/cuda_utils.hpp | 12 ++++++------ .../network/tensorrt_wrapper.hpp | 2 +- .../preprocess/pointcloud_densification.hpp | 4 ++-- .../preprocess/preprocess_kernel.hpp | 10 +++++----- .../lib/network/tensorrt_wrapper.cpp | 2 +- .../lib/preprocess/preprocess_kernel.cu | 19 ++++++++++--------- .../lib/preprocess/voxel_generator.cpp | 2 +- 7 files changed, 26 insertions(+), 25 deletions(-) diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/cuda_utils.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/cuda_utils.hpp index dcb264e672a16..25574de1779d6 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/cuda_utils.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/cuda_utils.hpp @@ -89,13 +89,13 @@ cuda::unique_ptr make_unique() return cuda::unique_ptr{p}; } -constexpr size_t CUDA_ALIGN = 256; +constexpr std::size_t CUDA_ALIGN = 256; template -inline size_t get_size_aligned(size_t num_elem) +inline std::size_t get_size_aligned(size_t num_elem) { - size_t size = num_elem * sizeof(T); - size_t extra_align = 0; + std::size_t size = num_elem * sizeof(T); + std::size_t extra_align = 0; if (size % CUDA_ALIGN != 0) { extra_align = CUDA_ALIGN - size % CUDA_ALIGN; } @@ -103,9 +103,9 @@ inline size_t get_size_aligned(size_t num_elem) } template -inline T * get_next_ptr(size_t num_elem, void *& workspace, size_t & workspace_size) +inline T * get_next_ptr(size_t num_elem, void *& workspace, std::size_t & workspace_size) { - size_t size = get_size_aligned(num_elem); + std::size_t size = get_size_aligned(num_elem); if (size > workspace_size) { throw ::std::runtime_error("Workspace is too small!"); } 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 index 1d731b5d819d7..d4c9fc85a085d 100644 --- 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 @@ -49,7 +49,7 @@ class TensorRTWrapper private: bool parseONNX( const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - size_t workspace_size = (1ULL << 30)); + std::size_t workspace_size = (1ULL << 30)); bool saveEngine(const std::string & engine_path); diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/pointcloud_densification.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/pointcloud_densification.hpp index 67c0d34a0e729..8934aed6dba82 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/pointcloud_densification.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/pointcloud_densification.hpp @@ -52,8 +52,8 @@ struct PointCloudWithTransform { cuda::unique_ptr points_d{nullptr}; std_msgs::msg::Header header; - size_t num_points{0}; - size_t point_step{0}; + std::size_t num_points{0}; + std::size_t point_step{0}; Eigen::Affine3f affine_past2world; }; diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/preprocess_kernel.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/preprocess_kernel.hpp index 5a39f4e8d1103..a6728538f1896 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/preprocess_kernel.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/preprocess_kernel.hpp @@ -21,14 +21,14 @@ namespace autoware::lidar_centerpoint { cudaError_t generateSweepPoints_launch( - const float * input_points, size_t points_size, int input_point_step, float time_lag, + const float * input_points, std::size_t points_size, int input_point_step, float time_lag, const float * transform, int num_features, float * output_points, cudaStream_t stream); cudaError_t generateVoxels_random_launch( - const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, - float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, - float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, float * voxels, - cudaStream_t stream); + const float * points, std::size_t points_size, float min_x_range, float max_x_range, + float min_y_range, float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, + float pillar_y_size, float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, + float * voxels, cudaStream_t stream); cudaError_t generateBaseFeatures_launch( unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, diff --git a/perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp b/perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp index 9e926aa29846d..6fbc09c968594 100644 --- a/perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp +++ b/perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp @@ -80,7 +80,7 @@ bool TensorRTWrapper::createContext() bool TensorRTWrapper::parseONNX( const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - const size_t workspace_size) + const std::size_t workspace_size) { auto builder = tensorrt_common::TrtUniquePtr(nvinfer1::createInferBuilder(logger_)); diff --git a/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu b/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu index 84d519cddf04c..349e895d36ce7 100644 --- a/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu +++ b/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu @@ -45,7 +45,7 @@ namespace autoware::lidar_centerpoint { __global__ void generateSweepPoints_kernel( - const float * input_points, size_t points_size, int input_point_step, float time_lag, + const float * input_points, std::size_t points_size, int input_point_step, float time_lag, const float * transform_array, int num_features, float * output_points) { int point_idx = blockIdx.x * blockDim.x + threadIdx.x; @@ -69,7 +69,7 @@ __global__ void generateSweepPoints_kernel( } cudaError_t generateSweepPoints_launch( - const float * input_points, size_t points_size, int input_point_step, float time_lag, + const float * input_points, std::size_t points_size, int input_point_step, float time_lag, const float * transform_array, int num_features, float * output_points, cudaStream_t stream) { auto transform_d = cuda::make_unique(16); @@ -89,9 +89,10 @@ cudaError_t generateSweepPoints_launch( } __global__ void generateVoxels_random_kernel( - const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, - float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, - float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, float * voxels) + const float * points, std::size_t points_size, float min_x_range, float max_x_range, + float min_y_range, float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, + float pillar_y_size, float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, + float * voxels) { int point_idx = blockIdx.x * blockDim.x + threadIdx.x; if (point_idx >= points_size) return; @@ -118,10 +119,10 @@ __global__ void generateVoxels_random_kernel( } cudaError_t generateVoxels_random_launch( - const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, - float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, - float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, float * voxels, - cudaStream_t stream) + const float * points, std::size_t points_size, float min_x_range, float max_x_range, + float min_y_range, float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, + float pillar_y_size, float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, + float * voxels, cudaStream_t stream) { dim3 blocks((points_size + 256 - 1) / 256); dim3 threads(256); diff --git a/perception/autoware_lidar_centerpoint/lib/preprocess/voxel_generator.cpp b/perception/autoware_lidar_centerpoint/lib/preprocess/voxel_generator.cpp index 86dc03719ca8e..f975449530e5c 100644 --- a/perception/autoware_lidar_centerpoint/lib/preprocess/voxel_generator.cpp +++ b/perception/autoware_lidar_centerpoint/lib/preprocess/voxel_generator.cpp @@ -51,7 +51,7 @@ bool VoxelGeneratorTemplate::enqueuePointCloud( std::size_t VoxelGenerator::generateSweepPoints(float * points_d, cudaStream_t stream) { - size_t point_counter = 0; + std::size_t point_counter = 0; for (auto pc_cache_iter = pd_ptr_->getPointCloudCacheIter(); !pd_ptr_->isCacheEnd(pc_cache_iter); pc_cache_iter++) { auto sweep_num_points = pc_cache_iter->num_points; From 284d04bfbc39d19b7de8a6fcacb8f5dbc7a84d4a Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 10 Sep 2024 15:13:24 +0900 Subject: [PATCH 172/217] feat(mission_planner): make the "goal inside lanes" function more robuts and add tests (#8760) Signed-off-by: Maxime CLEMENT --- .../autoware_mission_planner/CMakeLists.txt | 9 ++ planning/autoware_mission_planner/package.xml | 2 + .../src/lanelet2_plugins/default_planner.cpp | 25 +-- .../src/lanelet2_plugins/default_planner.hpp | 15 +- .../test_lanelet2_plugins_default_planner.cpp | 147 ++++++++++++++++++ 5 files changed, 181 insertions(+), 17 deletions(-) create mode 100644 planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp diff --git a/planning/autoware_mission_planner/CMakeLists.txt b/planning/autoware_mission_planner/CMakeLists.txt index 0c235510b968b..74bc8ddbc0a32 100644 --- a/planning/autoware_mission_planner/CMakeLists.txt +++ b/planning/autoware_mission_planner/CMakeLists.txt @@ -36,6 +36,15 @@ ament_auto_add_library(${PROJECT_NAME}_lanelet2_plugins SHARED ) pluginlib_export_plugin_description_file(autoware_mission_planner plugins/plugin_description.xml) +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/test_lanelet2_plugins_default_planner.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME}_lanelet2_plugins + ) +endif() + ament_auto_package( INSTALL_TO_SHARE config diff --git a/planning/autoware_mission_planner/package.xml b/planning/autoware_mission_planner/package.xml index a7c146f150e7f..b36a759d035ea 100644 --- a/planning/autoware_mission_planner/package.xml +++ b/planning/autoware_mission_planner/package.xml @@ -33,8 +33,10 @@ tf2_ros tier4_planning_msgs + ament_cmake_ros ament_lint_auto autoware_lint_common + autoware_test_utils ament_cmake diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp index 6c42195812a74..3cf6e73bc2bc6 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -28,6 +28,7 @@ #include #include +#include #include #include @@ -266,7 +267,8 @@ lanelet::ConstLanelets next_lanelets_up_to( } bool DefaultPlanner::check_goal_footprint_inside_lanes( - const lanelet::ConstLanelet & current_lanelet, const lanelet::ConstLanelets & path_lanelets, + const lanelet::ConstLanelet & closest_lanelet_to_goal, + const lanelet::ConstLanelets & path_lanelets, const universe_utils::Polygon2d & goal_footprint) const { universe_utils::MultiPolygon2d ego_lanes; @@ -275,20 +277,24 @@ bool DefaultPlanner::check_goal_footprint_inside_lanes( const auto left_shoulder = route_handler_.getLeftShoulderLanelet(ll); if (left_shoulder) { boost::geometry::convert(left_shoulder->polygon2d().basicPolygon(), poly); + boost::geometry::correct(poly); ego_lanes.push_back(poly); } const auto right_shoulder = route_handler_.getRightShoulderLanelet(ll); if (right_shoulder) { boost::geometry::convert(right_shoulder->polygon2d().basicPolygon(), poly); + boost::geometry::correct(poly); ego_lanes.push_back(poly); } boost::geometry::convert(ll.polygon2d().basicPolygon(), poly); + boost::geometry::correct(poly); ego_lanes.push_back(poly); } - const auto next_lanelets = - next_lanelets_up_to(current_lanelet, vehicle_info_.max_longitudinal_offset_m, route_handler_); + const auto next_lanelets = next_lanelets_up_to( + closest_lanelet_to_goal, vehicle_info_.max_longitudinal_offset_m, route_handler_); for (const auto & ll : next_lanelets) { boost::geometry::convert(ll.polygon2d().basicPolygon(), poly); + boost::geometry::correct(poly); ego_lanes.push_back(poly); } @@ -318,9 +324,10 @@ bool DefaultPlanner::is_goal_valid( return true; } } - lanelet::ConstLanelet closest_lanelet; + lanelet::ConstLanelet closest_lanelet_to_goal; const auto road_lanelets_at_goal = route_handler_.getRoadLaneletsAtPose(goal); - if (!lanelet::utils::query::getClosestLanelet(road_lanelets_at_goal, goal, &closest_lanelet)) { + if (!lanelet::utils::query::getClosestLanelet( + road_lanelets_at_goal, goal, &closest_lanelet_to_goal)) { // if no road lanelets directly at the goal, find the closest one const lanelet::BasicPoint2d goal_point{goal.position.x, goal.position.y}; auto closest_dist = std::numeric_limits::max(); @@ -334,7 +341,7 @@ bool DefaultPlanner::is_goal_valid( const auto dist = lanelet::geometry::distance2d(goal_point, ll.polygon2d()); if (route_handler_.isRoadLanelet(ll) && dist < closest_dist) { closest_dist = dist; - closest_lanelet = ll; + closest_lanelet_to_goal = ll; } return false; // continue the search }); @@ -350,7 +357,7 @@ bool DefaultPlanner::is_goal_valid( // check if goal footprint exceeds lane when the goal isn't in parking_lot if ( param_.check_footprint_inside_lanes && - !check_goal_footprint_inside_lanes(closest_lanelet, path_lanelets, polygon_footprint) && + !check_goal_footprint_inside_lanes(closest_lanelet_to_goal, path_lanelets, polygon_footprint) && !is_in_parking_lot( lanelet::utils::query::getAllParkingLots(route_handler_.getLaneletMapPtr()), lanelet::utils::conversion::toLaneletPoint(goal.position))) { @@ -358,8 +365,8 @@ bool DefaultPlanner::is_goal_valid( return false; } - if (is_in_lane(closest_lanelet, goal_lanelet_pt)) { - const auto lane_yaw = lanelet::utils::getLaneletAngle(closest_lanelet, goal.position); + if (is_in_lane(closest_lanelet_to_goal, goal_lanelet_pt)) { + const auto lane_yaw = lanelet::utils::getLaneletAngle(closest_lanelet_to_goal, goal.position); const auto goal_yaw = tf2::getYaw(goal.orientation); const auto angle_diff = autoware::universe_utils::normalizeRadian(lane_yaw - goal_yaw); diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp index 39b7fa8909a6a..ef5f34d4a3697 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -56,7 +56,7 @@ class DefaultPlanner : public mission_planner::PlannerPlugin autoware::universe_utils::LinearRing2d goal_footprint); autoware::vehicle_info_utils::VehicleInfo vehicle_info_; -private: +protected: using RouteSections = std::vector; using Pose = geometry_msgs::msg::Pose; bool is_graph_ready_; @@ -72,20 +72,19 @@ class DefaultPlanner : public mission_planner::PlannerPlugin void map_callback(const LaneletMapBin::ConstSharedPtr msg); /** - * @brief check if the goal_footprint is within the combined lanelet of route_lanelets plus the + * @brief check if the goal_footprint is within the route lanelets plus the * succeeding lanelets around the goal * @attention this function will terminate when the accumulated search length from the initial * current_lanelet exceeds max_longitudinal_offset_m + search_margin, so under normal assumptions * (i.e. the map is composed of finite elements of practically normal sized lanelets), it is * assured to terminate - * @param current_lanelet the start lanelet to begin recursive query - * @param combined_prev_lanelet initial entire route_lanelets plus the small consecutive lanelets - * around the goal during the query - * @param next_lane_length the accumulated total length from the start lanelet of the search to - * the lanelet of current goal query + * @param closest_lanelet_to_goal the route lanelet closest to the goal + * @param path_lanelets route lanelets + * @param goal_footprint footprint of the ego vehicle at the goal pose */ [[nodiscard]] bool check_goal_footprint_inside_lanes( - const lanelet::ConstLanelet & current_lanelet, const lanelet::ConstLanelets & path_lanelets, + const lanelet::ConstLanelet & closest_lanelet_to_goal, + const lanelet::ConstLanelets & path_lanelets, const universe_utils::Polygon2d & goal_footprint) const; /** diff --git a/planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp b/planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp new file mode 100644 index 0000000000000..78db6a5072a50 --- /dev/null +++ b/planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp @@ -0,0 +1,147 @@ +// 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. + +#include <../src/lanelet2_plugins/default_planner.hpp> +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +struct DefaultPlanner : protected autoware::mission_planner::lanelet2::DefaultPlanner +{ + void set_front_offset(const double offset) { vehicle_info_.max_longitudinal_offset_m = offset; } + void set_dummy_map() { route_handler_.setMap(autoware::test_utils::makeMapBinMsg()); } + [[nodiscard]] bool check_goal_inside_lanes( + const lanelet::ConstLanelet & closest_lanelet_to_goal, + const lanelet::ConstLanelets & path_lanelets, + const autoware::universe_utils::Polygon2d & goal_footprint) const + { + return check_goal_footprint_inside_lanes( + closest_lanelet_to_goal, path_lanelets, goal_footprint); + } +}; + +TEST(TestLanelet2PluginsDefaultPlanner, checkGoalInsideLane) +{ + // Test with dummy map such that only the lanelets provided as inputs are used for the ego lane + DefaultPlanner planner; + planner.set_dummy_map(); + // vehicle max longitudinal offset is used to retrieve additional lanelets from the map + planner.set_front_offset(0.0); + lanelet::LineString3d left_bound; + lanelet::LineString3d right_bound; + left_bound.push_back(lanelet::Point3d{lanelet::InvalId, -1, -1}); + left_bound.push_back(lanelet::Point3d{lanelet::InvalId, 0, -1}); + left_bound.push_back(lanelet::Point3d{lanelet::InvalId, 1, -1}); + right_bound.push_back(lanelet::Point3d{lanelet::InvalId, -1, 1}); + right_bound.push_back(lanelet::Point3d{lanelet::InvalId, 0, 1}); + right_bound.push_back(lanelet::Point3d{lanelet::InvalId, 1, 1}); + lanelet::ConstLanelet goal_lanelet{lanelet::InvalId, left_bound, right_bound}; + + // simple case where the footprint is completely inside the lane + autoware::universe_utils::Polygon2d goal_footprint; + goal_footprint.outer().emplace_back(0, 0); + goal_footprint.outer().emplace_back(0, 0.5); + goal_footprint.outer().emplace_back(0.5, 0.5); + goal_footprint.outer().emplace_back(0.5, 0); + goal_footprint.outer().emplace_back(0, 0); + EXPECT_TRUE(planner.check_goal_inside_lanes(goal_lanelet, {goal_lanelet}, goal_footprint)); + + // the footprint touches the border of the lanelet + goal_footprint.clear(); + goal_footprint.outer().emplace_back(0, 0); + goal_footprint.outer().emplace_back(0, 1); + goal_footprint.outer().emplace_back(1, 1); + goal_footprint.outer().emplace_back(1, 0); + goal_footprint.outer().emplace_back(0, 0); + EXPECT_TRUE(planner.check_goal_inside_lanes(goal_lanelet, {goal_lanelet}, goal_footprint)); + + // add lanelets such that the footprint touches the linestring shared by the combined lanelets + lanelet::LineString3d next_left_bound; + lanelet::LineString3d next_right_bound; + next_left_bound.push_back(lanelet::Point3d{lanelet::InvalId, 1, -1}); + next_left_bound.push_back(lanelet::Point3d{lanelet::InvalId, 2, -1}); + next_right_bound.push_back(lanelet::Point3d{lanelet::InvalId, 1, 1}); + next_right_bound.push_back(lanelet::Point3d{lanelet::InvalId, 2, 1}); + lanelet::ConstLanelet next_lanelet{lanelet::InvalId, next_left_bound, next_right_bound}; + EXPECT_TRUE( + planner.check_goal_inside_lanes(goal_lanelet, {goal_lanelet, next_lanelet}, goal_footprint)); + + // the footprint is inside the other lanelet + goal_footprint.clear(); + goal_footprint.outer().emplace_back(1.1, -0.5); + goal_footprint.outer().emplace_back(1.1, 0.5); + goal_footprint.outer().emplace_back(1.6, 0.5); + goal_footprint.outer().emplace_back(1.6, -0.5); + goal_footprint.outer().emplace_back(1.1, -0.5); + EXPECT_TRUE( + planner.check_goal_inside_lanes(goal_lanelet, {goal_lanelet, next_lanelet}, goal_footprint)); + + // the footprint is completely outside of the lanelets + goal_footprint.clear(); + goal_footprint.outer().emplace_back(1.1, 1.5); + goal_footprint.outer().emplace_back(1.1, 2.0); + goal_footprint.outer().emplace_back(1.6, 2.0); + goal_footprint.outer().emplace_back(1.6, 1.5); + goal_footprint.outer().emplace_back(1.1, 1.5); + EXPECT_FALSE( + planner.check_goal_inside_lanes(goal_lanelet, {goal_lanelet, next_lanelet}, goal_footprint)); + + // the footprint is outside of the lanelets but touches an edge + goal_footprint.clear(); + goal_footprint.outer().emplace_back(1.1, 1.0); + goal_footprint.outer().emplace_back(1.1, 2.0); + goal_footprint.outer().emplace_back(1.6, 2.0); + goal_footprint.outer().emplace_back(1.6, 1.0); + goal_footprint.outer().emplace_back(1.1, 1.0); + EXPECT_FALSE( + planner.check_goal_inside_lanes(goal_lanelet, {goal_lanelet, next_lanelet}, goal_footprint)); + + // the footprint is outside of the lanelets but share a point + goal_footprint.clear(); + goal_footprint.outer().emplace_back(2.0, 1.0); + goal_footprint.outer().emplace_back(2.0, 2.0); + goal_footprint.outer().emplace_back(3.0, 2.0); + goal_footprint.outer().emplace_back(3.0, 1.0); + goal_footprint.outer().emplace_back(2.0, 1.0); + EXPECT_FALSE( + planner.check_goal_inside_lanes(goal_lanelet, {goal_lanelet, next_lanelet}, goal_footprint)); + + // ego footprint that overlaps both lanelets + goal_footprint.clear(); + goal_footprint.outer().emplace_back(-0.5, -0.5); + goal_footprint.outer().emplace_back(-0.5, 0.5); + goal_footprint.outer().emplace_back(1.5, 0.5); + goal_footprint.outer().emplace_back(1.5, -0.5); + goal_footprint.outer().emplace_back(-0.5, -0.5); + EXPECT_TRUE( + planner.check_goal_inside_lanes(goal_lanelet, {goal_lanelet, next_lanelet}, goal_footprint)); + + // ego footprint that goes further than the next lanelet + goal_footprint.clear(); + goal_footprint.outer().emplace_back(-0.5, -0.5); + goal_footprint.outer().emplace_back(-0.5, 0.5); + goal_footprint.outer().emplace_back(2.5, 0.5); + goal_footprint.outer().emplace_back(2.5, -0.5); + goal_footprint.outer().emplace_back(-0.5, -0.5); + EXPECT_FALSE( + planner.check_goal_inside_lanes(goal_lanelet, {goal_lanelet, next_lanelet}, goal_footprint)); +} From 6979b5c1b7d538fb08295730e11f0e74784942ce Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Tue, 10 Sep 2024 15:14:18 +0900 Subject: [PATCH 173/217] chore(map_loader): update maintainer (#8821) update maintainer Signed-off-by: Yamato Ando --- map/map_loader/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/map/map_loader/package.xml b/map/map_loader/package.xml index d86767861c5ce..b8f92504a8b99 100644 --- a/map/map_loader/package.xml +++ b/map/map_loader/package.xml @@ -11,7 +11,6 @@ NGUYEN Viet Anh Taiki Yamada Shintaro Sakoda - Mamoru Sobue Apache License 2.0 Ryohsuke Mitsudome From 2fd7185f3a9c1ffb726a70da0cfd75710b266dab Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 10 Sep 2024 15:23:38 +0900 Subject: [PATCH 174/217] fix(tier4_camera_view_rviz_plugin): fix uninitMemberVar (#8819) * fix:uninitMemberVar Signed-off-by: kobayu858 * fix:clang format Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/bird_eye_view_tool.cpp | 11 +++++++++++ .../src/third_person_view_tool.cpp | 11 +++++++++++ 2 files changed, 22 insertions(+) diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp index 0c50f1ae1a0f4..1cca63152c543 100644 --- a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp +++ b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp @@ -52,6 +52,17 @@ namespace tier4_camera_view_rviz_plugin { BirdEyeViewTool::BirdEyeViewTool() +: m_sceneNode(nullptr), + m_fly_mode(false), + m_left_hand_mode(false), + m_removed_select(false), + m_pos_offset(0.0), + m_boost(0.0), + step_length_property_(nullptr), + boost_property_(nullptr), + fly_property_(nullptr), + left_hand_property_(nullptr), + fallback_view_controller_property_(nullptr) { shortcut_key_ = 'r'; } diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp b/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp index 09c7fe0c2677a..860ba7139c689 100644 --- a/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp +++ b/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp @@ -53,6 +53,17 @@ namespace tier4_camera_view_rviz_plugin { ThirdPersonViewTool::ThirdPersonViewTool() +: m_sceneNode(nullptr), + m_fly_mode(false), + m_left_hand_mode(false), + m_removed_select(false), + m_pos_offset(0.0), + m_boost(0.0), + step_length_property_(nullptr), + boost_property_(nullptr), + fly_property_(nullptr), + left_hand_property_(nullptr), + fallback_view_controller_property_(nullptr) { shortcut_key_ = 'o'; } From 0f5c5bf6e5de5eecc1d08176a3d5554dfbbf4952 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Tue, 10 Sep 2024 16:03:25 +0900 Subject: [PATCH 175/217] docs(map_loader): update the link of map_projection_loader (#8825) update the link of map_projection_loader Signed-off-by: Yamato Ando --- map/map_loader/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/map/map_loader/README.md b/map/map_loader/README.md index 92f7668c4d774..63f0b46571bb8 100644 --- a/map/map_loader/README.md +++ b/map/map_loader/README.md @@ -22,7 +22,7 @@ NOTE: **We strongly recommend to use divided maps when using large pointcloud ma You may provide either a single .pcd file or multiple .pcd files. If you are using multiple PCD data, it MUST obey the following rules: -1. **The pointcloud map should be projected on the same coordinate defined in `map_projection_loader`**, in order to be consistent with the lanelet2 map and other packages that converts between local and geodetic coordinates. For more information, please refer to [the readme of `map_projection_loader`](https://github.com/autowarefoundation/autoware.universe/tree/main/map/map_projection_loader/README.md). +1. **The pointcloud map should be projected on the same coordinate defined in `map_projection_loader`**, in order to be consistent with the lanelet2 map and other packages that converts between local and geodetic coordinates. For more information, please refer to [the readme of `map_projection_loader`](https://github.com/autowarefoundation/autoware.universe/tree/main/map/autoware_map_projection_loader/README.md). 2. **It must be divided by straight lines parallel to the x-axis and y-axis**. The system does not support division by diagonal lines or curved lines. 3. **The division size along each axis should be equal.** 4. **The division size should be about 20m x 20m.** Particularly, care should be taken as using too large division size (for example, more than 100m) may have adverse effects on dynamic map loading features in [ndt_scan_matcher](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/ndt_scan_matcher) and [autoware_compare_map_segmentation](https://github.com/autowarefoundation/autoware.universe/tree/main/perception/autoware_compare_map_segmentation). From 0f87e24f2df17f3c0759005a7dcd4c8d99000944 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Tue, 10 Sep 2024 16:22:41 +0900 Subject: [PATCH 176/217] refactor(tier4_localization_rviz_plugin): apply static analysis (#8683) * refactor based on linter Signed-off-by: a-maumau * add comment on no lint Signed-off-by: a-maumau * mod comment for clarification Signed-off-by: a-maumau --------- Signed-off-by: a-maumau --- .../src/pose_history/pose_history_display.cpp | 15 +++--- .../src/pose_history/pose_history_display.hpp | 4 +- .../src/pose_history_footprint/display.cpp | 36 +++++++------ .../src/pose_history_footprint/display.hpp | 14 +++--- .../pose_with_covariance_history_display.cpp | 50 +++++++++++-------- .../pose_with_covariance_history_display.hpp | 15 +++--- 6 files changed, 76 insertions(+), 58 deletions(-) diff --git a/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp b/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp index 931c675a23e7f..85c8a81ea7932 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp @@ -44,6 +44,7 @@ PoseHistory::PoseHistory() : last_stamp_(0, 0, RCL_ROS_TIME) PoseHistory::~PoseHistory() = default; // Properties are deleted by Qt +// cppcheck-suppress unusedFunction void PoseHistory::onInitialize() { MFDClass::onInitialize(); @@ -70,7 +71,7 @@ void PoseHistory::update(float wall_dt, float ros_dt) if (!history_.empty()) { lines_->clear(); if (property_line_view_->getBool()) { - updateLines(); + update_lines(); } } } @@ -103,10 +104,10 @@ void PoseHistory::processMessage(const geometry_msgs::msg::PoseStamped::ConstSha history_.emplace_back(message); last_stamp_ = message->header.stamp; - updateHistory(); + update_history(); } -void PoseHistory::updateHistory() +void PoseHistory::update_history() { const auto buffer_size = static_cast(property_buffer_size_->getInt()); while (buffer_size < history_.size()) { @@ -114,7 +115,7 @@ void PoseHistory::updateHistory() } } -void PoseHistory::updateLines() +void PoseHistory::update_lines() { Ogre::ColourValue color = rviz_common::properties::qtToOgre(property_line_color_->getColor()); color.a = property_line_alpha_->getFloat(); @@ -136,9 +137,9 @@ void PoseHistory::updateLines() for (const auto & message : history_) { Ogre::Vector3 point; - point.x = message->pose.position.x; - point.y = message->pose.position.y; - point.z = message->pose.position.z; + point.x = static_cast(message->pose.position.x); + point.y = static_cast(message->pose.position.y); + point.z = static_cast(message->pose.position.z); lines_->addPoint(point); } } diff --git a/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.hpp b/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.hpp index 21b875912d0ae..c47f6a3f099aa 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.hpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.hpp @@ -59,8 +59,8 @@ class PoseHistory : public rviz_common::MessageFilterDisplay history_; diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp index cd32df498bfd4..cc1ad7cf9b255 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp @@ -34,6 +34,8 @@ namespace rviz_plugins { +using autoware::vehicle_info_utils::VehicleInfoUtils; + PoseHistoryFootprint::PoseHistoryFootprint() : last_stamp_(0, 0, RCL_ROS_TIME) { property_buffer_size_ = new rviz_common::properties::IntProperty("Buffer Size", 100, "", this); @@ -68,7 +70,7 @@ PoseHistoryFootprint::PoseHistoryFootprint() : last_stamp_(0, 0, RCL_ROS_TIME) property_rear_overhang_->setMin(0.0); property_interval_->setMin(0.0); - updateVehicleInfo(); + update_vehicle_info(); } PoseHistoryFootprint::~PoseHistoryFootprint() @@ -78,7 +80,7 @@ PoseHistoryFootprint::~PoseHistoryFootprint() } } -void PoseHistoryFootprint::updateVehicleInfo() +void PoseHistoryFootprint::update_vehicle_info() { if (vehicle_info_) { vehicle_footprint_info_ = std::make_shared( @@ -93,7 +95,7 @@ void PoseHistoryFootprint::updateVehicleInfo() } } -void PoseHistoryFootprint::updateVisualization() +void PoseHistoryFootprint::update_visualization() { if (last_msg_ptr_) { processMessage(last_msg_ptr_); @@ -141,13 +143,13 @@ void PoseHistoryFootprint::processMessage( return; } - updateHistory(message); - updateFootprint(); + update_history(message); + update_footprint(); last_msg_ptr_ = message; } -void PoseHistoryFootprint::updateHistory( +void PoseHistoryFootprint::update_history( const geometry_msgs::msg::PoseStamped::ConstSharedPtr message) { if (history_.empty()) { @@ -166,14 +168,14 @@ void PoseHistoryFootprint::updateHistory( } } -void PoseHistoryFootprint::updateFootprint() +void PoseHistoryFootprint::update_footprint() { // This doesn't work in the constructor. if (!vehicle_info_) { try { vehicle_info_ = std::make_shared( VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo()); - updateVehicleInfo(); + update_vehicle_info(); } catch (const std::exception & e) { RCLCPP_WARN_THROTTLE( rviz_ros_node_.lock()->get_raw_node()->get_logger(), @@ -210,8 +212,8 @@ void PoseHistoryFootprint::updateFootprint() const float offset_from_baselink = property_offset_->getFloat(); - for (size_t point_idx = 0; point_idx < history_.size(); ++point_idx) { - const auto & pose = history_.at(point_idx)->pose; + for (auto & point_idx : history_) { + const auto & pose = point_idx->pose; /* * Footprint */ @@ -223,8 +225,8 @@ void PoseHistoryFootprint::updateFootprint() const auto info = vehicle_footprint_info_; const float top = info->length - info->rear_overhang - offset_from_baselink; const float bottom = -info->rear_overhang + offset_from_baselink; - const float left = -info->width / 2.0; - const float right = info->width / 2.0; + const auto left = static_cast(-info->width / 2.0); + const auto right = static_cast(info->width / 2.0); const std::array lon_offset_vec{top, top, bottom, bottom}; const std::array lat_offset_vec{left, right, right, left}; @@ -232,13 +234,16 @@ void PoseHistoryFootprint::updateFootprint() for (int f_idx = 0; f_idx < 4; ++f_idx) { const auto & o = pose.orientation; const auto & p = pose.position; - const Eigen::Quaternionf quat(o.w, o.x, o.y, o.z); + const Eigen::Quaternionf quat( + static_cast(o.w), static_cast(o.x), static_cast(o.y), + static_cast(o.z)); { const Eigen::Vector3f offset_vec{ lon_offset_vec.at(f_idx), lat_offset_vec.at(f_idx), 0.0}; const auto offset_to_edge = quat * offset_vec; trajectory_footprint_manual_object_->position( - p.x + offset_to_edge.x(), p.y + offset_to_edge.y(), p.z); + static_cast(p.x) + offset_to_edge.x(), + static_cast(p.y) + offset_to_edge.y(), static_cast(p.z)); trajectory_footprint_manual_object_->colour(color); } { @@ -246,7 +251,8 @@ void PoseHistoryFootprint::updateFootprint() lon_offset_vec.at((f_idx + 1) % 4), lat_offset_vec.at((f_idx + 1) % 4), 0.0}; const auto offset_to_edge = quat * offset_vec; trajectory_footprint_manual_object_->position( - p.x + offset_to_edge.x(), p.y + offset_to_edge.y(), p.z); + static_cast(p.x) + offset_to_edge.x(), + static_cast(p.y) + offset_to_edge.y(), static_cast(p.z)); trajectory_footprint_manual_object_->colour(color); } } diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp index 44625ad7deb41..241e682924fad 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp @@ -40,7 +40,6 @@ namespace rviz_plugins { using autoware::vehicle_info_utils::VehicleInfo; -using autoware::vehicle_info_utils::VehicleInfoUtils; class PoseHistoryFootprint : public rviz_common::MessageFilterDisplay @@ -59,17 +58,18 @@ class PoseHistoryFootprint void onInitialize() override; void onEnable() override; void onDisable() override; - void updateFootprint(); + void update_footprint(); private Q_SLOTS: - void updateVisualization(); - void updateVehicleInfo(); + void update_visualization(); + void update_vehicle_info(); -private: +private: // NOLINT : suppress redundancy warnings + // followings cannot be declared with the Q_SLOTS macro void subscribe() override; void unsubscribe() override; void processMessage(const geometry_msgs::msg::PoseStamped::ConstSharedPtr message) override; - void updateHistory(const geometry_msgs::msg::PoseStamped::ConstSharedPtr message); + void update_history(const geometry_msgs::msg::PoseStamped::ConstSharedPtr message); std::string target_frame_; std::deque history_; @@ -79,7 +79,7 @@ private Q_SLOTS: rviz_common::properties::IntProperty * property_buffer_size_; // trajectory footprint - Ogre::ManualObject * trajectory_footprint_manual_object_; + Ogre::ManualObject * trajectory_footprint_manual_object_{}; rviz_common::properties::BoolProperty * property_trajectory_footprint_view_; rviz_common::properties::ColorProperty * property_trajectory_footprint_color_; rviz_common::properties::FloatProperty * property_trajectory_footprint_alpha_; diff --git a/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp b/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp index 7708e6efaa104..c8fde566c5211 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp +++ b/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp @@ -92,16 +92,19 @@ void PoseWithCovarianceHistory::onInitialize() lines_ = std::make_unique(scene_manager_, scene_node_); } +// cppcheck-suppress unusedFunction void PoseWithCovarianceHistory::onEnable() { subscribe(); } +// cppcheck-suppress unusedFunction void PoseWithCovarianceHistory::onDisable() { unsubscribe(); } +// cppcheck-suppress unusedFunction void PoseWithCovarianceHistory::update(float wall_dt, float ros_dt) { (void)wall_dt; @@ -111,8 +114,8 @@ void PoseWithCovarianceHistory::update(float wall_dt, float ros_dt) lines_->clear(); arrows_.clear(); spheres_.clear(); - updateShapeType(); - updateShapes(); + update_shape_type(); + update_shapes(); } } @@ -131,7 +134,7 @@ void PoseWithCovarianceHistory::unsubscribe() spheres_.clear(); } -void PoseWithCovarianceHistory::updateShapeType() +void PoseWithCovarianceHistory::update_shape_type() { bool is_line = property_shape_type_->getOptionInt() == 0; bool is_arrow = property_shape_type_->getOptionInt() == 1; @@ -148,6 +151,7 @@ void PoseWithCovarianceHistory::updateShapeType() property_arrow_color_->setHidden(!is_arrow); } +// cppcheck-suppress unusedFunction void PoseWithCovarianceHistory::processMessage( const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr message) { @@ -166,10 +170,10 @@ void PoseWithCovarianceHistory::processMessage( } history_.emplace_back(message); last_stamp_ = message->header.stamp; - updateHistory(); + update_history(); } -void PoseWithCovarianceHistory::updateHistory() +void PoseWithCovarianceHistory::update_history() { const auto buffer_size = static_cast(property_buffer_size_->getInt()); while (buffer_size < history_.size()) { @@ -177,7 +181,7 @@ void PoseWithCovarianceHistory::updateHistory() } } -void PoseWithCovarianceHistory::updateShapes() +void PoseWithCovarianceHistory::update_shapes() { int shape_type = property_shape_type_->getOptionInt(); Ogre::ColourValue color_line = @@ -218,15 +222,15 @@ void PoseWithCovarianceHistory::updateShapes() const auto & message = history_[i]; Ogre::Vector3 position; - position.x = message->pose.pose.position.x; - position.y = message->pose.pose.position.y; - position.z = message->pose.pose.position.z; + position.x = static_cast(message->pose.pose.position.x); + position.y = static_cast(message->pose.pose.position.y); + position.z = static_cast(message->pose.pose.position.z); Ogre::Quaternion orientation; - orientation.w = message->pose.pose.orientation.w; - orientation.x = message->pose.pose.orientation.x; - orientation.y = message->pose.pose.orientation.y; - orientation.z = message->pose.pose.orientation.z; + orientation.w = static_cast(message->pose.pose.orientation.w); + orientation.x = static_cast(message->pose.pose.orientation.x); + orientation.y = static_cast(message->pose.pose.orientation.y); + orientation.z = static_cast(message->pose.pose.orientation.z); Eigen::Matrix3d covariance_3d_map; covariance_3d_map(0, 0) = message->pose.covariance[0]; @@ -242,11 +246,14 @@ void PoseWithCovarianceHistory::updateShapes() if (property_sphere_view_->getBool()) { Eigen::Matrix3d covariance_3d_base_link; Eigen::Translation3f translation( - message->pose.pose.position.x, message->pose.pose.position.y, - message->pose.pose.position.z); + static_cast(message->pose.pose.position.x), + static_cast(message->pose.pose.position.y), + static_cast(message->pose.pose.position.z)); Eigen::Quaternionf rotation( - message->pose.pose.orientation.w, message->pose.pose.orientation.x, - message->pose.pose.orientation.y, message->pose.pose.orientation.z); + static_cast(message->pose.pose.orientation.w), + static_cast(message->pose.pose.orientation.x), + static_cast(message->pose.pose.orientation.y), + static_cast(message->pose.pose.orientation.z)); Eigen::Matrix4f pose_matrix4f = (translation * rotation).matrix(); const Eigen::Matrix3d rot = pose_matrix4f.topLeftCorner<3, 3>().cast(); covariance_3d_base_link = rot.transpose() * covariance_3d_map * rot; @@ -256,9 +263,12 @@ void PoseWithCovarianceHistory::updateShapes() sphere->setOrientation(orientation); sphere->setColor(color_sphere.r, color_sphere.g, color_sphere.b, color_sphere.a); sphere->setScale(Ogre::Vector3( - property_sphere_scale_->getFloat() * 2 * std::sqrt(covariance_3d_base_link(0, 0)), - property_sphere_scale_->getFloat() * 2 * std::sqrt(covariance_3d_base_link(1, 1)), - property_sphere_scale_->getFloat() * 2 * std::sqrt(covariance_3d_base_link(2, 2)))); + static_cast( + property_sphere_scale_->getFloat() * 2 * std::sqrt(covariance_3d_base_link(0, 0))), + static_cast( + property_sphere_scale_->getFloat() * 2 * std::sqrt(covariance_3d_base_link(1, 1))), + static_cast( + property_sphere_scale_->getFloat() * 2 * std::sqrt(covariance_3d_base_link(2, 2))))); } if (property_path_view_->getBool()) { diff --git a/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp b/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp index 172124ba176ee..b6d680ced41d4 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp +++ b/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp @@ -63,15 +63,16 @@ class PoseWithCovarianceHistory void update(float wall_dt, float ros_dt) override; private Q_SLOTS: - void updateShapeType(); + void update_shape_type(); -private: +private: // NOLINT : suppress redundancy warnings + // followings cannot be declared with the Q_SLOTS macro void subscribe() override; void unsubscribe() override; void processMessage( const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr message) override; - void updateHistory(); - void updateShapes(); + void update_history(); + void update_shapes(); std::string target_frame_; std::deque history_; @@ -80,19 +81,19 @@ private Q_SLOTS: std::vector> arrows_; rclcpp::Time last_stamp_; - rviz_common::properties::BoolProperty * property_line_view_; + rviz_common::properties::BoolProperty * property_line_view_{}; rviz_common::properties::FloatProperty * property_line_width_; rviz_common::properties::FloatProperty * property_line_alpha_; rviz_common::properties::ColorProperty * property_line_color_; rviz_common::properties::IntProperty * property_buffer_size_; rviz_common::properties::BoolProperty * property_sphere_view_; - rviz_common::properties::FloatProperty * property_sphere_width_; + rviz_common::properties::FloatProperty * property_sphere_width_{}; rviz_common::properties::FloatProperty * property_sphere_alpha_; rviz_common::properties::ColorProperty * property_sphere_color_; rviz_common::properties::FloatProperty * property_sphere_scale_; - rviz_common::properties::BoolProperty * property_arrow_view_; + rviz_common::properties::BoolProperty * property_arrow_view_{}; rviz_common::properties::FloatProperty * property_arrow_shaft_length_; rviz_common::properties::FloatProperty * property_arrow_shaft_diameter_; rviz_common::properties::FloatProperty * property_arrow_head_length_; From cc5c1d33877a2100f617911d8b4cf92813be36ff Mon Sep 17 00:00:00 2001 From: Nagi70 <114723428+Nagi70@users.noreply.github.com> Date: Tue, 10 Sep 2024 16:36:11 +0900 Subject: [PATCH 177/217] fix(autoware_test_utils): fix unusedFunction (#8816) fix: unusedFunction Signed-off-by: Nagi70 --- common/autoware_test_utils/src/autoware_test_utils.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/common/autoware_test_utils/src/autoware_test_utils.cpp b/common/autoware_test_utils/src/autoware_test_utils.cpp index d870bcf9974a1..5bb1fd7633056 100644 --- a/common/autoware_test_utils/src/autoware_test_utils.cpp +++ b/common/autoware_test_utils/src/autoware_test_utils.cpp @@ -267,6 +267,7 @@ LaneletRoute makeBehaviorNormalRoute() return route; } +// cppcheck-suppress unusedFunction void spinSomeNodes( rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, const int repeat_count) { From 9ca894702f38491c3f1b1800a996f5601f90a363 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 10 Sep 2024 17:00:48 +0900 Subject: [PATCH 178/217] fix(tier4_localization_rviz_plugin): fix knownConditionTrueFalse (#8824) * fix:knownConditionTrueFalse Signed-off-by: kobayu858 * fix:merge Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/pose_history_footprint/display.cpp | 99 +++++++++---------- 1 file changed, 48 insertions(+), 51 deletions(-) diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp index cc1ad7cf9b255..5c392dc6fab1c 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp @@ -205,61 +205,58 @@ void PoseHistoryFootprint::update_footprint() material->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA); material->setDepthWriteEnabled(false); - if (!history_.empty()) { - trajectory_footprint_manual_object_->estimateVertexCount(history_.size() * 4 * 2); - trajectory_footprint_manual_object_->begin( - "BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_LIST); - - const float offset_from_baselink = property_offset_->getFloat(); - - for (auto & point_idx : history_) { - const auto & pose = point_idx->pose; - /* - * Footprint - */ - if (property_trajectory_footprint_view_->getBool()) { - Ogre::ColourValue color; - color = rviz_common::properties::qtToOgre(property_trajectory_footprint_color_->getColor()); - color.a = property_trajectory_footprint_alpha_->getFloat(); - - const auto info = vehicle_footprint_info_; - const float top = info->length - info->rear_overhang - offset_from_baselink; - const float bottom = -info->rear_overhang + offset_from_baselink; - const auto left = static_cast(-info->width / 2.0); - const auto right = static_cast(info->width / 2.0); - - const std::array lon_offset_vec{top, top, bottom, bottom}; - const std::array lat_offset_vec{left, right, right, left}; - - for (int f_idx = 0; f_idx < 4; ++f_idx) { - const auto & o = pose.orientation; - const auto & p = pose.position; - const Eigen::Quaternionf quat( - static_cast(o.w), static_cast(o.x), static_cast(o.y), - static_cast(o.z)); - { - const Eigen::Vector3f offset_vec{ - lon_offset_vec.at(f_idx), lat_offset_vec.at(f_idx), 0.0}; - const auto offset_to_edge = quat * offset_vec; - trajectory_footprint_manual_object_->position( - static_cast(p.x) + offset_to_edge.x(), - static_cast(p.y) + offset_to_edge.y(), static_cast(p.z)); - trajectory_footprint_manual_object_->colour(color); - } - { - const Eigen::Vector3f offset_vec{ - lon_offset_vec.at((f_idx + 1) % 4), lat_offset_vec.at((f_idx + 1) % 4), 0.0}; - const auto offset_to_edge = quat * offset_vec; - trajectory_footprint_manual_object_->position( - static_cast(p.x) + offset_to_edge.x(), - static_cast(p.y) + offset_to_edge.y(), static_cast(p.z)); - trajectory_footprint_manual_object_->colour(color); - } + trajectory_footprint_manual_object_->estimateVertexCount(history_.size() * 4 * 2); + trajectory_footprint_manual_object_->begin( + "BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_LIST); + + const float offset_from_baselink = property_offset_->getFloat(); + + for (auto & point_idx : history_) { + const auto & pose = point_idx->pose; + /* + * Footprint + */ + if (property_trajectory_footprint_view_->getBool()) { + Ogre::ColourValue color; + color = rviz_common::properties::qtToOgre(property_trajectory_footprint_color_->getColor()); + color.a = property_trajectory_footprint_alpha_->getFloat(); + + const auto info = vehicle_footprint_info_; + const float top = info->length - info->rear_overhang - offset_from_baselink; + const float bottom = -info->rear_overhang + offset_from_baselink; + const auto left = static_cast(-info->width / 2.0); + const auto right = static_cast(info->width / 2.0); + + const std::array lon_offset_vec{top, top, bottom, bottom}; + const std::array lat_offset_vec{left, right, right, left}; + + for (int f_idx = 0; f_idx < 4; ++f_idx) { + const auto & o = pose.orientation; + const auto & p = pose.position; + const Eigen::Quaternionf quat( + static_cast(o.w), static_cast(o.x), static_cast(o.y), + static_cast(o.z)); + { + const Eigen::Vector3f offset_vec{lon_offset_vec.at(f_idx), lat_offset_vec.at(f_idx), 0.0}; + const auto offset_to_edge = quat * offset_vec; + trajectory_footprint_manual_object_->position( + static_cast(p.x) + offset_to_edge.x(), + static_cast(p.y) + offset_to_edge.y(), static_cast(p.z)); + trajectory_footprint_manual_object_->colour(color); + } + { + const Eigen::Vector3f offset_vec{ + lon_offset_vec.at((f_idx + 1) % 4), lat_offset_vec.at((f_idx + 1) % 4), 0.0}; + const auto offset_to_edge = quat * offset_vec; + trajectory_footprint_manual_object_->position( + static_cast(p.x) + offset_to_edge.x(), + static_cast(p.y) + offset_to_edge.y(), static_cast(p.z)); + trajectory_footprint_manual_object_->colour(color); } } } - trajectory_footprint_manual_object_->end(); } + trajectory_footprint_manual_object_->end(); } } // namespace rviz_plugins From 8d1c01f19a05b90273d8d187d49f92c28e02848b Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Tue, 10 Sep 2024 17:14:27 +0900 Subject: [PATCH 179/217] feat(autoware_lidar_centerpoint): shuffled points before feeding them to the model (#8814) * feat: shuffling points before feeding them into the model to achieve uniform sampling into the voxels Signed-off-by: Kenzo Lobos-Tsunekawa * Update perception/autoware_lidar_centerpoint/src/node.cpp Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> * Update perception/autoware_lidar_centerpoint/src/node.cpp Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> * Update perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> * Update perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_config.hpp Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> --------- Signed-off-by: Kenzo Lobos-Tsunekawa Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> --- .../lidar_centerpoint/centerpoint_trt.hpp | 2 + .../autoware/lidar_centerpoint/cuda_utils.hpp | 4 +- .../preprocess/preprocess_kernel.hpp | 5 +++ .../lib/centerpoint_trt.cpp | 35 +++++++++++++--- .../lib/preprocess/preprocess_kernel.cu | 42 +++++++++++++++++++ 5 files changed, 81 insertions(+), 7 deletions(-) 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 f622fe18c6845..ce5ec3ea0abfe 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 @@ -102,9 +102,11 @@ class CenterPointTRT cuda::unique_ptr head_out_rot_d_{nullptr}; cuda::unique_ptr head_out_vel_d_{nullptr}; cuda::unique_ptr points_d_{nullptr}; + cuda::unique_ptr points_aux_d_{nullptr}; cuda::unique_ptr voxels_buffer_d_{nullptr}; cuda::unique_ptr mask_d_{nullptr}; cuda::unique_ptr num_voxels_d_{nullptr}; + cuda::unique_ptr shuffle_indices_d_{nullptr}; }; } // namespace autoware::lidar_centerpoint diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/cuda_utils.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/cuda_utils.hpp index 25574de1779d6..f1c767a3484bd 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/cuda_utils.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/cuda_utils.hpp @@ -92,7 +92,7 @@ cuda::unique_ptr make_unique() constexpr std::size_t CUDA_ALIGN = 256; template -inline std::size_t get_size_aligned(size_t num_elem) +inline std::size_t get_size_aligned(std::size_t num_elem) { std::size_t size = num_elem * sizeof(T); std::size_t extra_align = 0; @@ -103,7 +103,7 @@ inline std::size_t get_size_aligned(size_t num_elem) } template -inline T * get_next_ptr(size_t num_elem, void *& workspace, std::size_t & workspace_size) +inline T * get_next_ptr(std::size_t num_elem, void *& workspace, std::size_t & workspace_size) { std::size_t size = get_size_aligned(num_elem); if (size > workspace_size) { diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/preprocess_kernel.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/preprocess_kernel.hpp index a6728538f1896..92a9d483629fe 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/preprocess_kernel.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/preprocess_kernel.hpp @@ -24,6 +24,11 @@ cudaError_t generateSweepPoints_launch( const float * input_points, std::size_t points_size, int input_point_step, float time_lag, const float * transform, int num_features, float * output_points, cudaStream_t stream); +cudaError_t shufflePoints_launch( + const float * points, const unsigned int * indices, float * shuffled_points, + const std::size_t points_size, const std::size_t max_size, const std::size_t offset, + cudaStream_t stream); + cudaError_t generateVoxels_random_launch( const float * points, std::size_t points_size, float min_x_range, float max_x_range, float min_y_range, float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, diff --git a/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp b/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp index a1706d1f5601d..5f81b70ab6d15 100644 --- a/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp +++ b/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp @@ -20,8 +20,12 @@ #include +#include +#include +#include #include #include +#include #include #include @@ -104,6 +108,21 @@ void CenterPointTRT::initPtr() voxels_buffer_d_ = cuda::make_unique(voxels_buffer_size_); mask_d_ = cuda::make_unique(mask_size_); num_voxels_d_ = cuda::make_unique(1); + + points_aux_d_ = cuda::make_unique(config_.cloud_capacity_ * config_.point_feature_size_); + shuffle_indices_d_ = cuda::make_unique(config_.cloud_capacity_); + + std::vector indexes(config_.cloud_capacity_); + std::iota(indexes.begin(), indexes.end(), 0); + + std::default_random_engine e(0); + std::shuffle(indexes.begin(), indexes.end(), e); + + std::srand(std::time(nullptr)); + + CHECK_CUDA_ERROR(cudaMemcpyAsync( + shuffle_indices_d_.get(), indexes.data(), config_.cloud_capacity_ * sizeof(unsigned int), + cudaMemcpyHostToDevice, stream_)); } bool CenterPointTRT::detect( @@ -135,7 +154,13 @@ bool CenterPointTRT::preprocess( if (!is_success) { return false; } - const auto count = vg_ptr_->generateSweepPoints(points_d_.get(), stream_); + + const std::size_t count = vg_ptr_->generateSweepPoints(points_aux_d_.get(), stream_); + const std::size_t random_offset = std::rand() % config_.cloud_capacity_; + CHECK_CUDA_ERROR(shufflePoints_launch( + points_aux_d_.get(), shuffle_indices_d_.get(), points_d_.get(), count, config_.cloud_capacity_, + random_offset, stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync(num_voxels_d_.get(), 0, sizeof(unsigned int), stream_)); CHECK_CUDA_ERROR( cudaMemsetAsync(voxels_buffer_d_.get(), 0, voxels_buffer_size_ * sizeof(float), stream_)); @@ -147,10 +172,10 @@ bool CenterPointTRT::preprocess( num_points_per_voxel_d_.get(), 0, config_.max_voxel_size_ * sizeof(float), stream_)); CHECK_CUDA_ERROR(generateVoxels_random_launch( - points_d_.get(), count, config_.range_min_x_, config_.range_max_x_, config_.range_min_y_, - config_.range_max_y_, config_.range_min_z_, config_.range_max_z_, config_.voxel_size_x_, - config_.voxel_size_y_, config_.voxel_size_z_, config_.grid_size_y_, config_.grid_size_x_, - mask_d_.get(), voxels_buffer_d_.get(), stream_)); + points_d_.get(), config_.cloud_capacity_, config_.range_min_x_, config_.range_max_x_, + config_.range_min_y_, config_.range_max_y_, config_.range_min_z_, config_.range_max_z_, + config_.voxel_size_x_, config_.voxel_size_y_, config_.voxel_size_z_, config_.grid_size_y_, + config_.grid_size_x_, mask_d_.get(), voxels_buffer_d_.get(), stream_)); CHECK_CUDA_ERROR(generateBaseFeatures_launch( mask_d_.get(), voxels_buffer_d_.get(), config_.grid_size_y_, config_.grid_size_x_, diff --git a/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu b/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu index 349e895d36ce7..502ad04223ce9 100644 --- a/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu +++ b/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu @@ -33,6 +33,7 @@ #include "autoware/lidar_centerpoint/utils.hpp" #include +#include namespace { @@ -88,6 +89,47 @@ cudaError_t generateSweepPoints_launch( return err; } +__global__ void shufflePoints_kernel( + const float * points, const unsigned int * indices, float * shuffled_points, + const std::size_t points_size, const std::size_t max_size, const std::size_t offset) +{ + int point_idx = blockIdx.x * blockDim.x + threadIdx.x; + if (point_idx >= max_size) return; + + int src_idx = indices[(point_idx + offset) % max_size]; + int dst_idx = point_idx; + + if (dst_idx >= points_size) { + shuffled_points[4 * dst_idx + 0] = INFINITY; + shuffled_points[4 * dst_idx + 1] = INFINITY; + shuffled_points[4 * dst_idx + 2] = INFINITY; + shuffled_points[4 * dst_idx + 3] = INFINITY; + } else { + shuffled_points[4 * dst_idx + 0] = points[4 * src_idx + 0]; + shuffled_points[4 * dst_idx + 1] = points[4 * src_idx + 1]; + shuffled_points[4 * dst_idx + 2] = points[4 * src_idx + 2]; + shuffled_points[4 * dst_idx + 3] = points[4 * src_idx + 3]; + } +} + +cudaError_t shufflePoints_launch( + const float * points, const unsigned int * indices, float * shuffled_points, + const std::size_t points_size, const std::size_t max_size, const std::size_t offset, + cudaStream_t stream) +{ + dim3 blocks((max_size + 256 - 1) / 256); + dim3 threads(256); + + if (blocks.x == 0) { + return cudaGetLastError(); + } + + shufflePoints_kernel<<>>( + points, indices, shuffled_points, points_size, max_size, offset); + cudaError_t err = cudaGetLastError(); + return err; +} + __global__ void generateVoxels_random_kernel( const float * points, std::size_t points_size, float min_x_range, float max_x_range, float min_y_range, float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, From e6cc3edb29bf2ea5fe6d3eb7af8a66cad5dc619d Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 10 Sep 2024 17:16:18 +0900 Subject: [PATCH 180/217] fix(tier4_state_rviz_plugin): fix shadowVariable (#8831) * fix:shadowVariable Signed-off-by: kobayu858 * fix:clang-format Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/autoware_state_panel.cpp | 29 ++++++++++--------- 1 file changed, 16 insertions(+), 13 deletions(-) diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index b0467724df2ca..929b9334c8da3 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -699,43 +699,46 @@ void AutowareStatePanel::onMRMState(const MRMState::ConstSharedPtr msg) // behavior { - IconState state; - QColor bgColor; + IconState behavior_state; + QColor behavior_bgColor; QString mrm_behavior = "MRM Behavior | Unknown"; switch (msg->behavior) { case MRMState::NONE: - state = Crash; - bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); + behavior_state = Crash; + behavior_bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); mrm_behavior = "MRM Behavior | Inactive"; break; case MRMState::PULL_OVER: - state = Crash; - bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.success.c_str()); + behavior_state = Crash; + behavior_bgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.success.c_str()); mrm_behavior = "MRM Behavior | Pull Over"; break; case MRMState::COMFORTABLE_STOP: - state = Crash; - bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.warning.c_str()); + behavior_state = Crash; + behavior_bgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.warning.c_str()); mrm_behavior = "MRM Behavior | Comfortable Stop"; break; case MRMState::EMERGENCY_STOP: - state = Crash; - bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.danger.c_str()); + behavior_state = Crash; + behavior_bgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.danger.c_str()); mrm_behavior = "MRM Behavior | Emergency Stop"; break; default: - state = Crash; - bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); + behavior_state = Crash; + behavior_bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); mrm_behavior = "MRM Behavior | Unknown"; break; } - mrm_behavior_icon->updateStyle(state, bgColor); + mrm_behavior_icon->updateStyle(behavior_state, behavior_bgColor); mrm_behavior_label_ptr_->setText(mrm_behavior); } } From 9e5f648470c771c04d6ae0d1a16d7b83a9f8554b Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 10 Sep 2024 17:32:10 +0900 Subject: [PATCH 181/217] fix(tier4_perception_rviz_plugin): relocate tier4_perception_rviz_plugin and rename it to tier4_dummy_object_rviz_plugin (#8818) * chore: move tier4_perception_rviz_plugin package to simulation folder Signed-off-by: Taekjin LEE * chore: reorder codeowners Signed-off-by: Taekjin LEE * rename package to tier4_dummy_perception_rviz_plugin Signed-off-by: Taekjin LEE * chore: rename to tier4_dummy_object_rviz_plugin Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .github/CODEOWNERS | 2 +- common/.pages | 1 - .../tier4_dummy_object_rviz_plugin}/CMakeLists.txt | 6 +++--- .../tier4_dummy_object_rviz_plugin}/README.md | 4 ++-- .../icons/classes/BikeInitialPoseTool.png | Bin .../icons/classes/BusInitialPoseTool.png | Bin .../icons/classes/CarInitialPoseTool.png | Bin .../icons/classes/DeleteAllObjectsTool.png | Bin .../icons/classes/PedestrianInitialPoseTool.png | Bin .../icons/classes/UnknownInitialPoseTool.png | Bin .../images/select_add.png | Bin .../images/select_dummy_car.png | Bin .../images/select_plugin.png | Bin .../images/tool_properties.png | Bin .../tier4_dummy_object_rviz_plugin}/package.xml | 4 ++-- .../plugins/plugin_description.xml | 2 +- .../src/tools/car_pose.cpp | 0 .../src/tools/car_pose.hpp | 0 .../src/tools/delete_all_objects.cpp | 0 .../src/tools/delete_all_objects.hpp | 0 .../src/tools/interactive_object.cpp | 0 .../src/tools/interactive_object.hpp | 0 .../src/tools/pedestrian_pose.cpp | 0 .../src/tools/pedestrian_pose.hpp | 0 .../src/tools/unknown_pose.cpp | 0 .../src/tools/unknown_pose.hpp | 0 .../src/tools/util.cpp | 0 .../src/tools/util.hpp | 0 28 files changed, 9 insertions(+), 10 deletions(-) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/CMakeLists.txt (81%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/README.md (98%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/icons/classes/BikeInitialPoseTool.png (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/icons/classes/BusInitialPoseTool.png (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/icons/classes/CarInitialPoseTool.png (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/icons/classes/DeleteAllObjectsTool.png (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/icons/classes/PedestrianInitialPoseTool.png (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/icons/classes/UnknownInitialPoseTool.png (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/images/select_add.png (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/images/select_dummy_car.png (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/images/select_plugin.png (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/images/tool_properties.png (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/package.xml (88%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/plugins/plugin_description.xml (95%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/car_pose.cpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/car_pose.hpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/delete_all_objects.cpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/delete_all_objects.hpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/interactive_object.cpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/interactive_object.hpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/pedestrian_pose.cpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/pedestrian_pose.hpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/unknown_pose.cpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/unknown_pose.hpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/util.cpp (100%) rename {common/tier4_perception_rviz_plugin => simulator/tier4_dummy_object_rviz_plugin}/src/tools/util.hpp (100%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 33e2fc1ab8f5f..9b15e1245f0ff 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -35,7 +35,6 @@ common/tier4_api_utils/** isamu.takagi@tier4.jp common/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp takamasa.horibe@tier4.jp yamato.ando@tier4.jp -common/tier4_perception_rviz_plugin/** yukihiro.saito@tier4.jp common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp khalil@leodrive.ai common/tier4_system_rviz_plugin/** koji.minoda@tier4.jp @@ -217,6 +216,7 @@ 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/tier4_dummy_object_rviz_plugin/** yukihiro.saito@tier4.jp simulator/vehicle_door_simulator/** isamu.takagi@tier4.jp system/autoware_component_monitor/** memin@leodrive.ai system/autoware_default_adapi/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp diff --git a/common/.pages b/common/.pages index 3b1326b5b6dd7..362e6dffba002 100644 --- a/common/.pages +++ b/common/.pages @@ -41,7 +41,6 @@ nav: - 'tier4_camera_view_rviz_plugin': common/tier4_camera_view_rviz_plugin - 'tier4_datetime_rviz_plugin': common/tier4_datetime_rviz_plugin - 'tier4_localization_rviz_plugin': common/tier4_localization_rviz_plugin - - 'tier4_perception_rviz_plugin': common/tier4_perception_rviz_plugin - 'tier4_planning_rviz_plugin': common/tier4_planning_rviz_plugin - 'tier4_state_rviz_plugin': common/tier4_state_rviz_plugin - 'tier4_system_rviz_plugin': common/tier4_system_rviz_plugin diff --git a/common/tier4_perception_rviz_plugin/CMakeLists.txt b/simulator/tier4_dummy_object_rviz_plugin/CMakeLists.txt similarity index 81% rename from common/tier4_perception_rviz_plugin/CMakeLists.txt rename to simulator/tier4_dummy_object_rviz_plugin/CMakeLists.txt index af322a1ab85e3..e815cc61fb431 100644 --- a/common/tier4_perception_rviz_plugin/CMakeLists.txt +++ b/simulator/tier4_dummy_object_rviz_plugin/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(tier4_perception_rviz_plugin) +project(tier4_dummy_object_rviz_plugin) find_package(autoware_cmake REQUIRED) autoware_package() @@ -11,7 +11,7 @@ set(CMAKE_AUTOMOC ON) set(CMAKE_INCLUDE_CURRENT_DIR ON) ## Declare a C++ library -ament_auto_add_library(tier4_perception_rviz_plugin SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/tools/util.cpp src/tools/interactive_object.cpp src/tools/pedestrian_pose.cpp @@ -20,7 +20,7 @@ ament_auto_add_library(tier4_perception_rviz_plugin SHARED src/tools/delete_all_objects.cpp ) -target_link_libraries(tier4_perception_rviz_plugin +target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES}) # Export the plugin to be imported by rviz2 diff --git a/common/tier4_perception_rviz_plugin/README.md b/simulator/tier4_dummy_object_rviz_plugin/README.md similarity index 98% rename from common/tier4_perception_rviz_plugin/README.md rename to simulator/tier4_dummy_object_rviz_plugin/README.md index 6ec6a1a0e28a1..6908b0d9b0bd3 100644 --- a/common/tier4_perception_rviz_plugin/README.md +++ b/simulator/tier4_dummy_object_rviz_plugin/README.md @@ -1,4 +1,4 @@ -# tier4_perception_rviz_plugin +# tier4_dummy_object_rviz_plugin ## Purpose @@ -91,7 +91,7 @@ Using a planning simulator 1. Start rviz and select + on the tool tab. ![select_add](./images/select_add.png) -2. Select one of the following: tier4_perception_rviz_plugin and press OK. +2. Select one of the following: tier4_dummy_object_rviz_plugin and press OK. ![select_plugin](./images/select_plugin.png) 3. Select the new item in the tool tab (2D Dummy Car in the example) and click on it in rviz. ![select_dummy_car](./images/select_dummy_car.png) diff --git a/common/tier4_perception_rviz_plugin/icons/classes/BikeInitialPoseTool.png b/simulator/tier4_dummy_object_rviz_plugin/icons/classes/BikeInitialPoseTool.png similarity index 100% rename from common/tier4_perception_rviz_plugin/icons/classes/BikeInitialPoseTool.png rename to simulator/tier4_dummy_object_rviz_plugin/icons/classes/BikeInitialPoseTool.png diff --git a/common/tier4_perception_rviz_plugin/icons/classes/BusInitialPoseTool.png b/simulator/tier4_dummy_object_rviz_plugin/icons/classes/BusInitialPoseTool.png similarity index 100% rename from common/tier4_perception_rviz_plugin/icons/classes/BusInitialPoseTool.png rename to simulator/tier4_dummy_object_rviz_plugin/icons/classes/BusInitialPoseTool.png diff --git a/common/tier4_perception_rviz_plugin/icons/classes/CarInitialPoseTool.png b/simulator/tier4_dummy_object_rviz_plugin/icons/classes/CarInitialPoseTool.png similarity index 100% rename from common/tier4_perception_rviz_plugin/icons/classes/CarInitialPoseTool.png rename to simulator/tier4_dummy_object_rviz_plugin/icons/classes/CarInitialPoseTool.png diff --git a/common/tier4_perception_rviz_plugin/icons/classes/DeleteAllObjectsTool.png b/simulator/tier4_dummy_object_rviz_plugin/icons/classes/DeleteAllObjectsTool.png similarity index 100% rename from common/tier4_perception_rviz_plugin/icons/classes/DeleteAllObjectsTool.png rename to simulator/tier4_dummy_object_rviz_plugin/icons/classes/DeleteAllObjectsTool.png diff --git a/common/tier4_perception_rviz_plugin/icons/classes/PedestrianInitialPoseTool.png b/simulator/tier4_dummy_object_rviz_plugin/icons/classes/PedestrianInitialPoseTool.png similarity index 100% rename from common/tier4_perception_rviz_plugin/icons/classes/PedestrianInitialPoseTool.png rename to simulator/tier4_dummy_object_rviz_plugin/icons/classes/PedestrianInitialPoseTool.png diff --git a/common/tier4_perception_rviz_plugin/icons/classes/UnknownInitialPoseTool.png b/simulator/tier4_dummy_object_rviz_plugin/icons/classes/UnknownInitialPoseTool.png similarity index 100% rename from common/tier4_perception_rviz_plugin/icons/classes/UnknownInitialPoseTool.png rename to simulator/tier4_dummy_object_rviz_plugin/icons/classes/UnknownInitialPoseTool.png diff --git a/common/tier4_perception_rviz_plugin/images/select_add.png b/simulator/tier4_dummy_object_rviz_plugin/images/select_add.png similarity index 100% rename from common/tier4_perception_rviz_plugin/images/select_add.png rename to simulator/tier4_dummy_object_rviz_plugin/images/select_add.png diff --git a/common/tier4_perception_rviz_plugin/images/select_dummy_car.png b/simulator/tier4_dummy_object_rviz_plugin/images/select_dummy_car.png similarity index 100% rename from common/tier4_perception_rviz_plugin/images/select_dummy_car.png rename to simulator/tier4_dummy_object_rviz_plugin/images/select_dummy_car.png diff --git a/common/tier4_perception_rviz_plugin/images/select_plugin.png b/simulator/tier4_dummy_object_rviz_plugin/images/select_plugin.png similarity index 100% rename from common/tier4_perception_rviz_plugin/images/select_plugin.png rename to simulator/tier4_dummy_object_rviz_plugin/images/select_plugin.png diff --git a/common/tier4_perception_rviz_plugin/images/tool_properties.png b/simulator/tier4_dummy_object_rviz_plugin/images/tool_properties.png similarity index 100% rename from common/tier4_perception_rviz_plugin/images/tool_properties.png rename to simulator/tier4_dummy_object_rviz_plugin/images/tool_properties.png diff --git a/common/tier4_perception_rviz_plugin/package.xml b/simulator/tier4_dummy_object_rviz_plugin/package.xml similarity index 88% rename from common/tier4_perception_rviz_plugin/package.xml rename to simulator/tier4_dummy_object_rviz_plugin/package.xml index e6b022f730ef3..8264e087bf6a1 100644 --- a/common/tier4_perception_rviz_plugin/package.xml +++ b/simulator/tier4_dummy_object_rviz_plugin/package.xml @@ -1,9 +1,9 @@ - tier4_perception_rviz_plugin + tier4_dummy_object_rviz_plugin 0.1.0 - The tier4_perception_rviz_plugin package + The tier4_dummy_object_rviz_plugin package Yukihiro Saito Apache License 2.0 diff --git a/common/tier4_perception_rviz_plugin/plugins/plugin_description.xml b/simulator/tier4_dummy_object_rviz_plugin/plugins/plugin_description.xml similarity index 95% rename from common/tier4_perception_rviz_plugin/plugins/plugin_description.xml rename to simulator/tier4_dummy_object_rviz_plugin/plugins/plugin_description.xml index 853a471c7c6e4..152cc48569284 100644 --- a/common/tier4_perception_rviz_plugin/plugins/plugin_description.xml +++ b/simulator/tier4_dummy_object_rviz_plugin/plugins/plugin_description.xml @@ -1,4 +1,4 @@ - + diff --git a/common/tier4_perception_rviz_plugin/src/tools/car_pose.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.cpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/car_pose.cpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.cpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/car_pose.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.hpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/car_pose.hpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.hpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/delete_all_objects.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.cpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/delete_all_objects.cpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.cpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/delete_all_objects.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.hpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/delete_all_objects.hpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.hpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/interactive_object.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/interactive_object.cpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/interactive_object.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.hpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/interactive_object.hpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.hpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/pedestrian_pose.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.cpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/pedestrian_pose.cpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.cpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/pedestrian_pose.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.hpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/pedestrian_pose.hpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.hpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/unknown_pose.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.cpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/unknown_pose.cpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.cpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/unknown_pose.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.hpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/unknown_pose.hpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.hpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/util.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/util.cpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/util.cpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/util.cpp diff --git a/common/tier4_perception_rviz_plugin/src/tools/util.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/util.hpp similarity index 100% rename from common/tier4_perception_rviz_plugin/src/tools/util.hpp rename to simulator/tier4_dummy_object_rviz_plugin/src/tools/util.hpp From 284eac6fc5d1999a77178dfe6a9e242721115b6e Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 10 Sep 2024 17:32:26 +0900 Subject: [PATCH 182/217] fix(tier4_state_rviz_plugin): fix constVariablePointer (#8832) fix:constVariablePointer Signed-off-by: kobayu858 --- common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index 929b9334c8da3..738fac93d3705 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -171,7 +171,7 @@ void AutowareStatePanel::onInitialize() return; } - QPushButton * button = qobject_cast(abstractButton); + const QPushButton * button = qobject_cast(abstractButton); if (button) { // Call the corresponding function for each button if (button == auto_button_ptr_) { From 8f03403d657b1c4306e8146dace920b75f1f782f Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 10 Sep 2024 17:34:50 +0900 Subject: [PATCH 183/217] fix(ndt_scan_matcher): improve error message in ndt_scan_matcher (#8833) Fixed an error message in ndt_scan_matcher Signed-off-by: Shintaro Sakoda --- localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index 16f297e5a1d48..3aac972e591b4 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -416,7 +416,10 @@ bool NDTScanMatcher::callback_sensor_points_main( "is_succeed_interpolate_initial_pose", is_succeed_interpolate_initial_pose); if (!is_succeed_interpolate_initial_pose) { std::stringstream message; - message << "Couldn't interpolate pose. Please check the initial pose topic"; + message << "Couldn't interpolate pose. Please verify that " + "(1) the initial pose topic (primarily come from the EKF) is being published, and " + "(2) the timestamps of the sensor PCD messages and pose messages are synchronized " + "correctly."; diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; From 129c1fe0fdf723cedbc42286e431b01b9088522a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 10 Sep 2024 17:55:30 +0900 Subject: [PATCH 184/217] feat(crosswalk): suppress restart when the ego is close to the next stop point (#8817) * feat(crosswalk): suppress restart when the ego is close to the next stop point Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * add comment Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/crosswalk.param.yaml | 5 ++++ .../src/manager.cpp | 6 ++++ .../src/scene_crosswalk.cpp | 30 ++++++++++++++++++- .../src/scene_crosswalk.hpp | 9 ++++++ 4 files changed, 49 insertions(+), 1 deletion(-) 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 7d6b7700b7bc8..9ff4ccc808b7c 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 @@ -60,6 +60,11 @@ timeout_set_for_no_intention_to_walk: [1.0, 0.0] # [s] timeout_ego_stop_for_yield: 1.0 # [s] If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough. + # params for suppressing the ego to restart when the ego is close to the next stop position. + restart_suppression: + min_distance_to_stop: 0.5 + max_distance_to_stop: 1.0 + # param for target object filtering object_filtering: crosswalk_attention_range: 2.0 # [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk 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 5ea2d42782317..0bd708f7b1705 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 @@ -54,6 +54,12 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) cp.stop_position_threshold = getOrDeclareParameter(node, ns + ".stop_position.stop_position_threshold"); + // param for restart suppression + cp.min_dist_to_stop_for_restart_suppression = + getOrDeclareParameter(node, ns + ".restart_suppression.min_distance_to_stop"); + cp.max_dist_to_stop_for_restart_suppression = + getOrDeclareParameter(node, ns + ".restart_suppression.max_distance_to_stop"); + // param for ego velocity cp.min_slow_down_velocity = getOrDeclareParameter(node, ns + ".slow_down.min_slow_down_velocity"); 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 f30ed9d7a68da..639ee214bca9c 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 @@ -201,6 +201,8 @@ CrosswalkModule::CrosswalkModule( collision_info_pub_ = node.create_publisher("~/debug/collision_info", 1); + + vehicle_stop_checker_ = std::make_unique(&node); } bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) @@ -1284,7 +1286,8 @@ void CrosswalkModule::planStop( PathWithLaneId & ego_path, const std::optional & nearest_stop_factor, const std::optional & default_stop_pose, StopReason * stop_reason) { - const auto stop_factor = [&]() -> std::optional { + // Calculate stop factor + auto stop_factor = [&]() -> std::optional { if (nearest_stop_factor) return *nearest_stop_factor; if (default_stop_pose) return createStopFactor(*default_stop_pose); return std::nullopt; @@ -1295,6 +1298,13 @@ void CrosswalkModule::planStop( return; } + // Check if the restart should be suppressed. + const bool suppress_restart = checkRestartSuppression(ego_path, stop_factor); + if (suppress_restart) { + const auto & ego_pose = planner_data_->current_odometry->pose; + stop_factor->stop_pose = ego_pose; + } + // Plan stop insertDecelPointWithDebugInfo(stop_factor->stop_pose.position, 0.0, ego_path); planning_utils::appendStopReason(*stop_factor, stop_reason); @@ -1302,4 +1312,22 @@ void CrosswalkModule::planStop( ego_path.points, planner_data_->current_odometry->pose, stop_factor->stop_pose, VelocityFactor::UNKNOWN); } + +bool CrosswalkModule::checkRestartSuppression( + const PathWithLaneId & ego_path, const std::optional & stop_factor) const +{ + const auto is_vehicle_stopped = vehicle_stop_checker_->isVehicleStopped(); + if (!is_vehicle_stopped) { + return false; + } + + const auto & ego_pos = planner_data_->current_odometry->pose.position; + const double dist_to_stop = + calcSignedArcLength(ego_path.points, ego_pos, stop_factor->stop_pose.position); + + // NOTE: min_dist_to_stop_for_restart_suppression is supposed to be the same as + // the pid_longitudinal_controller's drive_state_stop_dist. + return planner_param_.min_dist_to_stop_for_restart_suppression < dist_to_stop && + dist_to_stop < planner_param_.max_dist_to_stop_for_restart_suppression; +} } // namespace autoware::behavior_velocity_planner 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 ebb9d715ccd6a..be2a7d199c666 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 @@ -18,6 +18,7 @@ #include "autoware/behavior_velocity_crosswalk_module/util.hpp" #include +#include #include #include #include @@ -115,6 +116,9 @@ class CrosswalkModule : public SceneModuleInterface double stop_distance_from_crosswalk; double far_object_threshold; double stop_position_threshold; + // param for restart suppression + double min_dist_to_stop_for_restart_suppression; + double max_dist_to_stop_for_restart_suppression; // param for ego velocity float min_slow_down_velocity; double max_slow_down_jerk; @@ -428,6 +432,9 @@ class CrosswalkModule : public SceneModuleInterface static geometry_msgs::msg::Polygon createVehiclePolygon( const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); + bool checkRestartSuppression( + const PathWithLaneId & ego_path, const std::optional & stop_factor) const; + void recordTime(const int step_num) { RCLCPP_INFO_EXPRESSION( @@ -453,6 +460,8 @@ class CrosswalkModule : public SceneModuleInterface // Debug mutable DebugData debug_data_; + std::unique_ptr vehicle_stop_checker_{nullptr}; + // Stop watch StopWatch stop_watch_; From 382d0564c5610d19b8c493d15d4e7588c33735d9 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 10 Sep 2024 18:21:20 +0900 Subject: [PATCH 185/217] docs(control_evaluator): update readme (#8829) * update readme Signed-off-by: Daniel Sanchez * add maintainer Signed-off-by: Daniel Sanchez * Update evaluator/autoware_control_evaluator/package.xml Add extra maintainer Co-authored-by: Tiankui Xian <1041084556@qq.com> --------- Signed-off-by: Daniel Sanchez Co-authored-by: Tiankui Xian <1041084556@qq.com> --- .github/CODEOWNERS | 2 +- evaluator/autoware_control_evaluator/README.md | 14 +++++++++++++- evaluator/autoware_control_evaluator/package.xml | 2 ++ 3 files changed, 16 insertions(+), 2 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 9b15e1245f0ff..0563b9a1b7598 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -61,7 +61,7 @@ control/autoware_vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier 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/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/predicted_path_checker/** berkay@leodrive.ai -evaluator/autoware_control_evaluator/** daniel.sanchez@tier4.jp takayuki.murooka@tier4.jp +evaluator/autoware_control_evaluator/** daniel.sanchez@tier4.jp takayuki.murooka@tier4.jp kosuke.takeuchi@tier4.jp evaluator/autoware_evaluator_utils/** daniel.sanchez@tier4.jp takayuki.murooka@tier4.jp evaluator/autoware_planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp evaluator/diagnostic_converter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp diff --git a/evaluator/autoware_control_evaluator/README.md b/evaluator/autoware_control_evaluator/README.md index 71bd5c0142570..59c09015bd7b5 100644 --- a/evaluator/autoware_control_evaluator/README.md +++ b/evaluator/autoware_control_evaluator/README.md @@ -1,5 +1,17 @@ -# Planning Evaluator +# Control Evaluator ## Purpose This package provides nodes that generate metrics to evaluate the quality of control. + +It publishes diagnostic information about control modules' outputs as well as the ego vehicle's current kinematics and position. + +## Evaluated metrics + +The control evaluator uses the metrics defined in `include/autoware/control_evaluator/metrics/deviation_metrics.hpp`to calculate deviations in yaw and lateral distance from the ego's set-point. The control_evaluator can also be customized to offer metrics/evaluation about other control modules. Currently, the control_evaluator offers a simple diagnostic output based on the autonomous_emergency_braking node's output, but this functionality can be extended to evaluate other control modules' performance. + +## Kinematics output + +The control evaluator module also constantly publishes information regarding the ego vehicle's kinematics and position. It publishes the current ego lane id with the longitudinal `s` and lateral `t` arc coordinates. It also publishes the current ego speed, acceleration and jerk in its diagnostic messages. + +This information can be used by other nodes to establish automated evaluation using rosbags: by crosschecking the ego position and kinematics with the evaluated control module's output, it is possible to judge if the evaluated control modules reacted in a satisfactory way at certain interesting points of the rosbag reproduction. diff --git a/evaluator/autoware_control_evaluator/package.xml b/evaluator/autoware_control_evaluator/package.xml index d7300e6a3bfb4..52f5a04092713 100644 --- a/evaluator/autoware_control_evaluator/package.xml +++ b/evaluator/autoware_control_evaluator/package.xml @@ -6,6 +6,8 @@ ROS 2 node for evaluating control Daniel SANCHEZ takayuki MUROOKA + kosuke TAKEUCHI + Temkei Kem Apache License 2.0 Daniel SANCHEZ From 0401a3636989a618626e7be9a7ada0ab99db27f8 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 10 Sep 2024 18:30:58 +0900 Subject: [PATCH 186/217] fix(tier4_dummy_object_rviz_plugin): fix functionConst (#8830) fix:functionConst Signed-off-by: kobayu858 --- .../src/tools/interactive_object.cpp | 2 +- .../src/tools/interactive_object.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp index ca55bc20276e9..bcd56256bde34 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp @@ -221,7 +221,7 @@ boost::optional InteractiveObjectCollection::transform( return {}; } -size_t InteractiveObjectCollection::nearest(const Ogre::Vector3 & point) +size_t InteractiveObjectCollection::nearest(const Ogre::Vector3 & point) const { const size_t npos = objects_.size(); if (objects_.empty()) { diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.hpp index c1ec65a0488bd..c0942d9a6cdd1 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.hpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.hpp @@ -124,7 +124,7 @@ class InteractiveObjectCollection const std::array & uuid) const; private: - size_t nearest(const Ogre::Vector3 & point); + size_t nearest(const Ogre::Vector3 & point) const; InteractiveObject * target_; std::vector> objects_; }; From 1fcdddac2b47003480406c87b09cb2c19a4596f3 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 10 Sep 2024 19:17:57 +0900 Subject: [PATCH 187/217] fix(tier4_localization_rviz_plugin): fix constVariableReference (#8838) fix:constVariableReference Signed-off-by: kobayu858 --- .../src/pose_history_footprint/display.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp index 5c392dc6fab1c..662ce97b162cd 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp @@ -211,7 +211,7 @@ void PoseHistoryFootprint::update_footprint() const float offset_from_baselink = property_offset_->getFloat(); - for (auto & point_idx : history_) { + for (const auto & point_idx : history_) { const auto & pose = point_idx->pose; /* * Footprint From 86410ce1f4ab43ce38768040279ab61130d8df19 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 10 Sep 2024 23:00:22 +0900 Subject: [PATCH 188/217] fix(tier4_camera_view_rviz_plugin): fix unusedFunction (#8843) fix:unusedFunction Signed-off-by: kobayu858 --- common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp index 1cca63152c543..b042040ea1b32 100644 --- a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp +++ b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp @@ -154,6 +154,7 @@ void BirdEyeViewTool::activate() setFallbackViewControllerProperty(); } +// cppcheck-suppress unusedFunction void BirdEyeViewTool::deactivate() { } From 5e187059f7e09f801e4e0c8f03b27dccbe1c35b8 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 11 Sep 2024 00:05:27 +0900 Subject: [PATCH 189/217] refactor(goal_planner): reduce call to isSafePath (#8812) Signed-off-by: Mamoru Sobue --- .../goal_planner_module.hpp | 41 ++--- .../src/goal_planner_module.cpp | 143 +++++++++--------- 2 files changed, 96 insertions(+), 88 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 2adac879a6bb2..fe859b458c7bb 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 @@ -309,6 +309,17 @@ struct PoseWithString } }; +struct PullOverContextData +{ + PullOverContextData() = delete; + explicit PullOverContextData(const std::pair & is_safe_path) + : is_safe_path_latched(is_safe_path.first), is_safe_path_instant(is_safe_path.second) + { + } + bool is_safe_path_latched{true}; + bool is_safe_path_instant{true}; +}; + class GoalPlannerModule : public SceneModuleInterface { public: @@ -505,6 +516,9 @@ class GoalPlannerModule : public SceneModuleInterface // TODO(Mamoru Sobue): isSafePath() modifies ThreadSafeData::check_collision, avoid this mutable 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}; std::unique_ptr last_approval_data_{nullptr}; // approximate distance from the start point to the end point of pull_over. @@ -572,26 +586,17 @@ class GoalPlannerModule : public SceneModuleInterface bool hasDecidedPath( const std::shared_ptr planner_data, const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, + const PullOverContextData & context_data, const GoalPlannerParameters & parameters, const std::shared_ptr goal_searcher) const; bool hasNotDecidedPath( const std::shared_ptr planner_data, const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, + const PullOverContextData & context_data, const GoalPlannerParameters & parameters, const std::shared_ptr goal_searcher) const; DecidingPathStatusWithStamp checkDecidingPathStatus( const std::shared_ptr planner_data, const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, + const PullOverContextData & context_data, const GoalPlannerParameters & parameters, const std::shared_ptr goal_searcher) const; void decideVelocity(); bool foundPullOverPath() const; @@ -615,9 +620,9 @@ class GoalPlannerModule : public SceneModuleInterface bool canReturnToLaneParking(); // plan pull over path - BehaviorModuleOutput planPullOver(); - BehaviorModuleOutput planPullOverAsOutput(); - BehaviorModuleOutput planPullOverAsCandidate(); + BehaviorModuleOutput planPullOver(const PullOverContextData & context_data); + BehaviorModuleOutput planPullOverAsOutput(const PullOverContextData & context_data); + BehaviorModuleOutput planPullOverAsCandidate(const PullOverContextData & context_data); std::optional> selectPullOverPath( const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates) const; @@ -627,8 +632,8 @@ class GoalPlannerModule : public SceneModuleInterface void setDrivableAreaInfo(BehaviorModuleOutput & output) const; // output setter - void setOutput(BehaviorModuleOutput & output); - void updatePreviousData(); + void setOutput(const PullOverContextData & context_data, BehaviorModuleOutput & output); + void updatePreviousData(const PullOverContextData & context_data); void setModifiedGoal(BehaviorModuleOutput & output) const; void setTurnSignalInfo(BehaviorModuleOutput & output); @@ -676,7 +681,7 @@ class GoalPlannerModule : public SceneModuleInterface const std::shared_ptr & safety_check_params) const; // debug - void setDebugData(); + void setDebugData(const PullOverContextData & context_data); void printParkingPositionError() const; }; } // 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 56c7c42eec6ae..dde3a554fca3d 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 @@ -276,11 +276,15 @@ void GoalPlannerModule::onTimer() RCLCPP_DEBUG(getLogger(), "has previous module path shape changed"); return true; } + // TODO(soblin): never call isSafePath on thread pool side + const auto local_context_data = PullOverContextData(isSafePath( + local_planner_data, parameters, ego_predicted_path_params, objects_filtering_params, + safety_check_params)); if ( hasDeviatedFromLastPreviousModulePath(local_planner_data) && + // TODO(soblin): use DecidingPathStatus in ThreadInputData !hasDecidedPath( - local_planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, - objects_filtering_params, safety_check_params, goal_searcher)) { + local_planner_data, occupancy_grid_map, local_context_data, parameters, goal_searcher)) { RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path"); return true; } @@ -546,6 +550,10 @@ void GoalPlannerModule::updateData() resetPathReference(); path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); + context_data_ = PullOverContextData(isSafePath( + planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, + safety_check_params_)); + // update goal searcher and generate goal candidates if (thread_safe_data_.get_goal_candidates().empty()) { goal_searcher_->setReferenceGoal( @@ -875,8 +883,15 @@ BehaviorModuleOutput GoalPlannerModule::plan() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (!context_data_) { + RCLCPP_ERROR(getLogger(), " [pull_over] plan() is called without valid context_data"); + } + const auto context_data = context_data_.has_value() + ? context_data_.value() + : PullOverContextData(std::make_pair(true, true)); + if (utils::isAllowedGoalModification(planner_data_->route_handler)) { - return planPullOver(); + return planPullOver(context_data); } fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); @@ -1120,7 +1135,8 @@ std::vector GoalPlannerModule::generateDrivableLanes() const return utils::generateDrivableLanesWithShoulderLanes(current_lanes, pull_over_lanes); } -void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) +void GoalPlannerModule::setOutput( + const PullOverContextData & context_data, BehaviorModuleOutput & output) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -1136,11 +1152,7 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) } if ( - parameters_->safety_check_params.enable_safety_check && - !isSafePath( - planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, - safety_check_params_) - .first && + parameters_->safety_check_params.enable_safety_check && !context_data.is_safe_path_latched && isActivated()) { // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk @@ -1166,8 +1178,7 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) // set hazard and turn signal if ( hasDecidedPath( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_) && + planner_data_, occupancy_grid_map_, context_data, *parameters_, goal_searcher_) && isActivated()) { setTurnSignalInfo(output); } @@ -1237,40 +1248,29 @@ void GoalPlannerModule::updateSteeringFactor( bool GoalPlannerModule::hasDecidedPath( const std::shared_ptr planner_data, const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, + const PullOverContextData & context_data, const GoalPlannerParameters & parameters, const std::shared_ptr goal_searcher) const { return checkDecidingPathStatus( - planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, - objects_filtering_params, safety_check_params, goal_searcher) + planner_data, occupancy_grid_map, context_data, parameters, goal_searcher) .first == DecidingPathStatus::DECIDED; } bool GoalPlannerModule::hasNotDecidedPath( const std::shared_ptr planner_data, const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, + const PullOverContextData & context_data, const GoalPlannerParameters & parameters, const std::shared_ptr goal_searcher) const { return checkDecidingPathStatus( - planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, - objects_filtering_params, safety_check_params, goal_searcher) + planner_data, occupancy_grid_map, context_data, parameters, goal_searcher) .first == DecidingPathStatus::NOT_DECIDED; } DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( const std::shared_ptr planner_data, const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, + const PullOverContextData & context_data, const GoalPlannerParameters & parameters, const std::shared_ptr goal_searcher) const { const auto & prev_status = thread_safe_data_.get_prev_data().deciding_path_status; @@ -1288,13 +1288,7 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( // If it is dangerous against dynamic objects before approval, do not determine the path. // This eliminates a unsafe path to be approved - if ( - enable_safety_check && - !isSafePath( - planner_data, parameters, ego_predicted_path_params, objects_filtering_params, - safety_check_params) - .first && - !isActivated()) { + if (enable_safety_check && !context_data.is_safe_path_latched && !isActivated()) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: NOT_DECIDED. path is not safe against dynamic objects before " @@ -1333,11 +1327,7 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } - if ( - enable_safety_check && !isSafePath( - planner_data, parameters, ego_predicted_path_params, - objects_filtering_params, safety_check_params) - .first) { + if (enable_safety_check && !context_data.is_safe_path_latched) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path is not safe against dynamic objects"); @@ -1401,20 +1391,21 @@ void GoalPlannerModule::decideVelocity() } } -BehaviorModuleOutput GoalPlannerModule::planPullOver() +BehaviorModuleOutput GoalPlannerModule::planPullOver(const PullOverContextData & context_data) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + // TODO(soblin): move DecidingPathStatus to context_data if (!hasDecidedPath( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_)) { - return planPullOverAsCandidate(); + planner_data_, occupancy_grid_map_, context_data, *parameters_, goal_searcher_)) { + return planPullOverAsCandidate(context_data); } - return planPullOverAsOutput(); + return planPullOverAsOutput(context_data); } -BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() +BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate( + const PullOverContextData & context_data) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -1424,7 +1415,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() } BehaviorModuleOutput output{}; - const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(); + const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(context_data); output.modified_goal = pull_over_output.modified_goal; output.path = generateStopPath(); output.reference_path = getPreviousModuleOutput().reference_path; @@ -1441,12 +1432,13 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() return output; } - setDebugData(); + setDebugData(context_data); return output; } -BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() +BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( + const PullOverContextData & context_data) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -1460,8 +1452,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() if ( hasNotDecidedPath( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_) && + planner_data_, occupancy_grid_map_, context_data, *parameters_, goal_searcher_) && needPathUpdate( planner_data_->self_odometry->pose.pose, 1.0 /*path_update_duration*/, *parameters_)) { // if the final path is not decided and enough time has passed since last path update, @@ -1496,7 +1487,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() // set output and status BehaviorModuleOutput output{}; - setOutput(output); + setOutput(context_data, output); // return to lane parking if it is possible if ( @@ -1506,7 +1497,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() } // For debug - setDebugData(); + setDebugData(context_data); if (parameters_->print_debug_info) { // For evaluations @@ -1520,7 +1511,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() path_candidate_ = std::make_shared(thread_safe_data_.get_pull_over_path()->getFullPath()); - updatePreviousData(); + updatePreviousData(context_data); return output; } @@ -1529,18 +1520,26 @@ void GoalPlannerModule::postProcess() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (!context_data_) { + RCLCPP_ERROR(getLogger(), " [pull_over] postProcess() is called without valid context_data"); + } + const auto context_data = context_data_.has_value() + ? context_data_.value() + : PullOverContextData(std::make_pair(true, true)); + + // TODO(Mamoru Sobue): repetitive call to checkDecidingPathStatus() in the main thread is a + // waste of time because it gives same result throughout the main thread. + const bool has_decided_path = + hasDecidedPath(planner_data_, occupancy_grid_map_, context_data, *parameters_, goal_searcher_); + + context_data_ = std::nullopt; + if (!thread_safe_data_.foundPullOverPath()) { return; } const auto distance_to_path_change = calcDistanceToPathChange(); - // TODO(Mamoru Sobue): repetitive call to checkDecidingPathStatus() in the main thread is a - // waste of time because it gives same result throughout the main thread. - const bool has_decided_path = hasDecidedPath( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_); - if (has_decided_path) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } @@ -1554,7 +1553,7 @@ void GoalPlannerModule::postProcess() setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); } -void GoalPlannerModule::updatePreviousData() +void GoalPlannerModule::updatePreviousData(const PullOverContextData & context_data) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -1564,8 +1563,7 @@ void GoalPlannerModule::updatePreviousData() auto prev_data = thread_safe_data_.get_prev_data(); prev_data.deciding_path_status = checkDecidingPathStatus( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_); + planner_data_, occupancy_grid_map_, context_data, *parameters_, goal_searcher_); // This is related to safety check, so if it is disabled, return here. if (!parameters_->safety_check_params.enable_safety_check) { @@ -1573,9 +1571,8 @@ void GoalPlannerModule::updatePreviousData() } else { // Even if the current path is safe, it will not be safe unless it stands for a certain period // of time. Record the time when the current path has become safe - const auto [is_safe, current_is_safe] = isSafePath( - planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, - safety_check_params_); + const auto is_safe = context_data.is_safe_path_latched, + current_is_safe = context_data.is_safe_path_instant; if (current_is_safe) { if (!prev_data.safety_status.safe_start_time) { prev_data.safety_status.safe_start_time = clock_->now(); @@ -1594,8 +1591,16 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (!context_data_) { + RCLCPP_ERROR( + getLogger(), " [pull_over] planWaitingApproval() is called without valid context_data"); + } + const auto context_data = context_data_.has_value() + ? context_data_.value() + : PullOverContextData(std::make_pair(true, true)); + if (utils::isAllowedGoalModification(planner_data_->route_handler)) { - return planPullOverAsCandidate(); + return planPullOverAsCandidate(context_data); } fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); @@ -2503,7 +2508,7 @@ std::pair GoalPlannerModule::isSafePath( return {false /*is_safe*/, current_is_safe}; } -void GoalPlannerModule::setDebugData() +void GoalPlannerModule::setDebugData(const PullOverContextData & context_data) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -2532,9 +2537,7 @@ void GoalPlannerModule::setDebugData() if (utils::isAllowedGoalModification(planner_data_->route_handler)) { // Visualize pull over areas const auto color = - hasDecidedPath( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_) + hasDecidedPath(planner_data_, occupancy_grid_map_, context_data, *parameters_, goal_searcher_) ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green const double z = planner_data_->route_handler->getGoalPose().position.z; From 14a499efeab6033163893f945e6297093ec48ac5 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Wed, 11 Sep 2024 00:11:11 +0900 Subject: [PATCH 190/217] refactor(cluster_merger): remove unused variable and rename topic (#8809) Signed-off-by: badai-nguyen --- .../autoware_cluster_merger/launch/cluster_merger.launch.xml | 2 +- .../autoware_cluster_merger/src/cluster_merger_node.cpp | 2 +- .../autoware_cluster_merger/src/cluster_merger_node.hpp | 4 ---- 3 files changed, 2 insertions(+), 6 deletions(-) diff --git a/perception/autoware_cluster_merger/launch/cluster_merger.launch.xml b/perception/autoware_cluster_merger/launch/cluster_merger.launch.xml index 40bdf643fbecf..2d365323bbc65 100644 --- a/perception/autoware_cluster_merger/launch/cluster_merger.launch.xml +++ b/perception/autoware_cluster_merger/launch/cluster_merger.launch.xml @@ -6,7 +6,7 @@ - + diff --git a/perception/autoware_cluster_merger/src/cluster_merger_node.cpp b/perception/autoware_cluster_merger/src/cluster_merger_node.cpp index ada95b905d320..554196787c028 100644 --- a/perception/autoware_cluster_merger/src/cluster_merger_node.cpp +++ b/perception/autoware_cluster_merger/src/cluster_merger_node.cpp @@ -37,7 +37,7 @@ ClusterMergerNode::ClusterMergerNode(const rclcpp::NodeOptions & node_options) sync_.registerCallback(std::bind(&ClusterMergerNode::objectsCallback, this, _1, _2)); // Publisher - pub_objects_ = create_publisher("~/output/clusters", rclcpp::QoS{1}); + pub_objects_ = create_publisher("output/clusters", rclcpp::QoS{1}); } void ClusterMergerNode::objectsCallback( diff --git a/perception/autoware_cluster_merger/src/cluster_merger_node.hpp b/perception/autoware_cluster_merger/src/cluster_merger_node.hpp index 2213d413d7031..907d59491a5d9 100644 --- a/perception/autoware_cluster_merger/src/cluster_merger_node.hpp +++ b/perception/autoware_cluster_merger/src/cluster_merger_node.hpp @@ -47,7 +47,6 @@ class ClusterMergerNode : public rclcpp::Node tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; - rclcpp::Subscription::SharedPtr sub_objects_{}; message_filters::Subscriber objects0_sub_; message_filters::Subscriber objects1_sub_; typedef message_filters::sync_policies::ApproximateTime< @@ -58,9 +57,6 @@ class ClusterMergerNode : public rclcpp::Node std::string output_frame_id_; - std::vector::SharedPtr> sub_objects_array{}; - std::shared_ptr transform_listener_; - void objectsCallback( const DetectedObjectsWithFeature::ConstSharedPtr & input_objects0_msg, const DetectedObjectsWithFeature::ConstSharedPtr & input_objects1_msg); From 6034a9f2bafb87b5ba84b53056122b2eafe4edc2 Mon Sep 17 00:00:00 2001 From: RyuYamamoto Date: Wed, 11 Sep 2024 08:58:01 +0900 Subject: [PATCH 191/217] 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 Signed-off-by: RyuYamamoto * fix: update media Signed-off-by: RyuYamamoto * fix: update component name Signed-off-by: RyuYamamoto * fix: rename include file Signed-off-by: RyuYamamoto --------- Signed-off-by: RyuYamamoto --- .../CMakeLists.txt | 1 - .../media/diagnostics.png | Bin 22762 -> 23706 bytes .../src/diagnostics.hpp | 34 ---------- ...diagnostics.cpp => diagnostics_helper.hpp} | 46 ++----------- .../src/localization_error_monitor.cpp | 38 ++++++----- .../src/localization_error_monitor.hpp | 5 +- .../test/test_diagnostics.cpp | 64 +----------------- .../config/localization.yaml | 4 +- .../localization.param.yaml | 2 +- 9 files changed, 33 insertions(+), 161 deletions(-) delete mode 100644 localization/autoware_localization_error_monitor/src/diagnostics.hpp rename localization/autoware_localization_error_monitor/src/{diagnostics.cpp => diagnostics_helper.hpp} (58%) diff --git a/localization/autoware_localization_error_monitor/CMakeLists.txt b/localization/autoware_localization_error_monitor/CMakeLists.txt index 93cfb7ba7a0d9..1c6f12499ca98 100644 --- a/localization/autoware_localization_error_monitor/CMakeLists.txt +++ b/localization/autoware_localization_error_monitor/CMakeLists.txt @@ -5,7 +5,6 @@ find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED - src/diagnostics.cpp src/localization_error_monitor.cpp ) diff --git a/localization/autoware_localization_error_monitor/media/diagnostics.png b/localization/autoware_localization_error_monitor/media/diagnostics.png index 74aacb68a2b7cefcd199bc3ae8ee120e6b545e4d..1ab1a6514724448689a594c3129ff50975f63b92 100644 GIT binary patch literal 23706 zcmdqJ1Cu7f+veN0ZQHi(etO!Twr$%srfu7HPusR_Piy_U&!GQq+0)m&868i-N1YGvB9|Z;Rvt|2)zx+wSoJ6Empneu_DC6*- zV{B(}4QFLLQ)f2=M-w13TRR&QdM6`C6BAn}b35l7&|ZO`Osp0v8qT7QCI-$HcD6(+ z7B(h7CxL)im{{13+MAfTj%=aUpKaT5d{SB#8Kl!B9L?5azvrlsf#wosq?gf;5njk_*b9pyrF+&d49P zLGzP@r2H4RvQOSgiG%Bi^DQ1bdz~B+$atN0%5NsS-ELB@cY0?&-(L={T6aQ;paO}| z&?5bKfP|62gzLn}sD9FXAr$EI+-Gw{3OCD`JKktNS%;E?#<{{NKvl+yFpjb zlhJzN#EYas!=vBccc>JgHX#cqj+QcxgopW?(~lx|~0Ofk&)r5bM;!w5H(?*HWl}Z5&@|*YxD-z!N%z3^&2u8v%|Ys?+U84kJkOixW|FBz!{!&4a692@uV0J3 zC)|n`he5mXMDFWSwQVKNmpChM35A@*U*!)v;9fUG!C>ft+4tyCNP0L-O}Nw%+VA=lbNK}$h%byvn>#ohI@d7idV zFRgoxo>O-wDj+$VPV){AlMHm7N1>^?e*Q9c3@v`xtdqxn+5@S-)t%@#mc5fq%#}QM zWiAO`DJGEgC!sVEEwcNJb~Xn+?X@|M*7_WOo6 z+A!VVOWhdy5e4BSj7pDnu!*@Bc%HSe*+pIk3QE-z@myvhoo#Z&^477*SGM|Xe=ojv9K`gp z8dO?Ad{5`~VBS=Q6VNA8Q^#qZSMMk;RgK7W0oYf*kZ!Mo8`Me_HsHl~=E#An+=1*h zO-Tv;Oj^$~J^PL3>g1my0pFb@NYnZa!Rx3tmBF~TF^(gZ2&S4Kuxbl7{{k;bO^L{s z<-n}3Smx~v;`Gigl-`N%tX4y%Rf_35j?74qJ@gR}gLG{Hn!SxckUw?%NzK{^R&}P1 z(KD?!TjpZ_SREa^P!Jz4do8EGgU-;=%JkL%cZ*=!T^&Rwt@v5?0r9&P+1~+CLLEL> z`}j|j+nH4Kh9l(Ki_pK=9;$*#4TY6mv&~{?NCEf&24^Y+0bij5{>%3sUQ00U!Mw&$ zGj~+)`%z6YvnzkDD(qi~CPCf1zl#I3tU%-TW0>4MoR8lU5RZ9R1?ovF!aN7m>|kpX zr`fN4f06R(ztEE{DuRP;J^U2I*!m06p19N#H z&5~eRKFt^96;)k^%=o#nuBx(qE9?)RPLHBT3d;50zRQ$3{1i-ki>vbhSrjtqpnLtC zAZ|jFjG3=c0vFl-nI#CVW`yUSt9qvCU{+#Jbv^S;AXS@g&oEumDebeItWJC*r8#Ec3=a@Y5As6&)oyJ`j|^b8J_Rljc!+>Iwt83_SC)oGLHG3HSu3LkPOcia7gJ%8W@S|L zjl%Iy92cTQ#MG)J10f<(vbd5nvr-*l38ndX?mAmD;p0CoQwD&P)m0AE#uj%QuPH7U z(k-S~q2yYN7L_I@78Ny{AqDYOmnRE_XvI>CoD6|aXI}hgZ87no_6VaY0YoM(RRHnHp+}~uOE`k zV!yZ=_U$B9ceB-u^#q|xM6y{B@^X6BtbAf)PC`3s!R{~FSd)wHX;t-r^qgrT#fU!l zFe;_O?N9`2bmm4#01j;`c1swd)Vz04XBxxFNVZq|ORYGb?oJdfs8wm?C94(%b^QYDtl#>WQ}YZ^7@Z|GL*ooV=o(7KMsK$#aDJT50}PFu|h{dd)( z?g}Wuf3)N~Cz9(O49;qhjSq2F?Isr#HR*FvM^~zk=N%LWT*rJAXI|V?fI)wPDEG%9 z=o~JG#I*f+y}T-+9$p*t*6Y=g<_TBk5$pZ4G4``_l~^N0?A$f$hbh6;Wm&~<41N2v zSf9-vbFK^bva>B0cvPu*=gb2ctFzBJeYw`h@5zV3qt7R~3E!SYtPvAj4yT24kE~lg z==F-ORo6ZEOzMZ{+87Hfsxd_0t#Qz>!Zw@Xn@z{HQpf~#M1Pl|diJM~A3$~Dyiw^L9Zd?{iTf#lN->G>6(G_0L% za#DrUNU306P071W8Q)VYRM;qjldU(W&vf1=k>xXdlh0%rZ@+b;XQSm6RZnEJ8jrgj zHx?%a#y3?7^2V|_F^Fc~d<_TeX~_U)&$dkDyvrNL9v@KOQWZ$hY%g1gV~lxT5MYW> zV0bwGMKDVwj?jMew6K#)54KY1mvGYxQ)A!W5tJ-UYCC1l2?NW7nr5Z-Q9{d{%>Z{g zZRpR8XXMSlz#03mCuOUd^6nAX9)}57divBwP?IgZAQJ_>H~6eWqz-Ihiy=QG4)y zt(E%6epzIG(l}p-#c!01bnSH2c{`}9z-vFlWWK#Imyx|csQuePhx%f5NpXF_W0tXJ)eJRuh4zdcz+H0sLa7~y1mtLBqPo}N3y3s!=?HZt3CdO;D+pt z;Dn>Opy$haWW4>VP-nV7txMoOvBwMOlU?Al<@$^D1x^-vxS;f!JOf&0B@mY2sJo{W zMde(krB$8P`xKbs?#;1wKZ#80ulvkcvsIio>idg+0JIEP^JVb40*sJ88vaft2z$6B zrFOF)`Y51JWO6z_)r)NS*c?gQW@A!LF<06TTBz%Q$Z(mVSr>eCL@R(Xn#zj z#s$2q2x%&U6H)FfSi=zQ3Fq!N|;%vwE=#+wf5G%VUz`OCh+K&gPR z4ew2NuPlKoj$Da`*{f<|G*_+>SAMQ^pjfIel3w2u52c%I3b+F?k2jR5vTv9*s3C{x zChbUOLkYTbtq-o%vZjtqNXbi2_#x77_eTn3Gn2Nnn|^J=182~u$niz5`QQ{-=V4}D z;w!bS(dlrMl9021+t`&vLE3Z80jpZ3gkIkY_x#LOPJ8bx4f~AO+a=ZSlI% z=MXBUIe?9#D%TqcA;IzBJO8W*@^@BM(5*E)<4$j-KY>TrEKIH_w4$A&l!Kf7i$gq( zx_cYY%K<7;uQMGD7}&coGGSEbTkMm(jT?;u9(T;+gnX)C;jd^~R{?`+lmPU-mRHu4Tj@!&QBjg0OFNYUr` z-c!+8GaGK9`l9VKur)NTTj0KcVF5k}7pa#WQS|5~^k5}>CEl!beZ_&XUQ8R65WYNc zLtkA|quLg$_m=4Ta2_GkiW1sn59qamJWIAcCfhGt%rho&makOKw3gJ2V9%;)76iyR zeF}&So(%^Yh7EL;;<*z)OC{8r}(J zRh7!RK3`$pJOQ}@yFpIK(;Ir?uM6ruY3(a8AQf0jG1B`Ub2DcJULGP>J0y3)5T{RYT*^P>>alYYMN{hZqT__-}UOhd2^+Or0Ba8|mv(4q`gjfQY2}`#Ox2(6FcCjfZY%a~sUf!+Wf37He_FptvHIqwV9pY#5nJ=q zhKzmDlKLUN*PD)}8Rs{{$#Em)JZ;L8cQ74j#s25*$&D_6?0uMAvw!Q##bqKX4?si2 ze2|lOYa6mANt6FRzxL`oPQ{kP0~}*!JxrLrsmDwZs4~zwXs5wX^-+#nQREbG6ZNd) zb9O1@Xe4%cwLZ5{apn3oFQ4(=CAR!>_jfhW zp+*)@#+-vcg;7thMtVXzx;>*ROvof;y~{}urJvk-SoQm_T{Jxu@no2`G%8@X2Vm>9 zgmfc%iY!5AH0iH|*CIPq6&S|QeG?ME5Y2{g8W|AFp^mM29`_;bg)kgtCZbrPz1F5_DY`$a51uh7h&f&Phiz{dGu&( zbr|t`npoRs%jNxsX4SGoW9@iu8n+2alU!o>7%vNh@K-;JKE% zOul2pVm_)6>c?`!k-T7!5T^;j!9$m|%pNR@Za^pci$PnY|t9IbIm?0j34m9AUuLoj*dz91@NeZo~aXAFhE|7pw$z9$YdcMTat zpYp@WAG?m+vn~Kuya@1A;*h>)p-u&5I*l`CC0Cs+4t`-J8#2gcRi?c;Uf-a`sF*Mk!b9R&2?t8JzSjdbv-gOp9=xw=4p zG#nCeydZ?EV75ppR`^@Y$=Qcs~l`y31qvuiM_OGCwJQVCf_4KUOB(t?M6=!g*T}K=kaOwUGWRFi?U_H>?Fh zzA13OE0~?u2#gR^k+`AJV@g*zFda`qmD)Rnqx3*ko7ss7?XDOgedo9pScb=qK05Ar zZE5GP$>PgskH_zd@+{OS!{1+#A6}V&D?2d*6&u|(Sgu&2(y9PsYxM0eyCIpS)d~2C zUIDE(!=*1t@;=^td2HJ_3j|mABZZRSRyz9c?4fkZ1#_2(fM4KUzwtL4t#J#!!wkyq zTp*if{bF-mKn%>H2j8M_7Ejl}0vO$mR8LOQKjiOGWqZ7M1WNA3%k8zJweP`4)YFuv zXfT+^Va)a4O(s|lCX-v0d?raB*V3a=#myOeO2S#JqsIwY1hEiU@^yKl z+yQ6L34Dc;)LL?xesxl6W)U~k}<>y6^*_MXS)BYXlz zM`0`=8TXacR%Tc=oAaG|ukrovWy=_yf|8 zFwNwOxI>jIETPI+aqDyG3hi&r(sNOtaQJma&Kq_D8x?U7^$VXh5_${;>;G z_TSE(iR0mD2KY`xR3uyCWO-xVJ)dl1F(%D8ClXD~C25F*is%OD>$`8_nv+Vh$K{pA zWXd$NZ$-Hsc40j@dEF&Q^YO7K4(nd6?UwQ;OOHoLa&@ZPgtncQ&+#(Xd2)W$34WE2 z$iICFf2~$BM73)x7tYV+OKBqLeEZAwPNIwA)CY&LFTs$rtHnOTQBB46>W-Z<{qE{( z*PWQ3=mF{FGV<&I=ClFrY^Nq@!rvxZ{d*&cAHo~WzK4wWg+gz$3vmufyvJ<6)> zp{($*QiHC!swSE;9TDKtdn{ZSGVpmYhoZJPDL7-LWGQdChF@Lan!}1` zS_yfL2kMYC)eQH@iNjp5^Rp!V=u&?$7eNcX`B|Wf%^8-kM@5tD?L*I-?Ctas1i?}( za{HO5ViAJpUG;Zdh&n58^WW$lfzYR*tkY#*@Fb_N9YacJc=-G!&C+yScuRWxkBYj7 z#qJDzOgTRON_tt0hGL2Qy!G{<;S0pw0VnFWXi7$lt}auw4Yk|CBt7|*>3|T~mg8vU zl9S7yAX)hSs3xw9Wb>Q+BBWzZt2*zOmE_GlJ(u^?(xjEN>1C>tHQKpIw~Rb)?XS!B zM~tJcYjQ`DLW))cX++wJC5R4mtHIo9vu#*AyS=u*^K{0Q`M-(_tN#efF8>Sn8%n3% z+4-wj2{9{OTOd+iSg0@F^D>1nqIr5pjy`$DVXTw!3%~!gSDAfi?|Une2>;h}%l1*hgppv#67qhM zV34zRXc`X-?Nur=sS2UTjf9U!LJv&YjdoFL>DlDZfqTH&w?TZ`9R z!3JtffUu2h&bI58HTH#J*b|hk?3HJmPHEk2Xe$weSGo(O8-yK*y(M`o|V&6-MBSW*%3 zoIK)L{^T}QE|XDVU)wW6CQjrL5C}*+NIQ`uGuhT&NeaM;h<|j3hcYnWMJJbPsusvF zlP|*K%%#U86ZtjQ--|YphL9g-q&wY4opdal^=nB88l{<`pH8`k3{-dPZ8|Xwn|Szp zq~!Ve@fO;+t``>`CL*2tu6FOO?=dxZPz>#3E2`eu4H*`uWdx<6i1i6cs{=bT5Uu!9%1_p4pl|Z|1oJh^b)4;YAZ@%R%aPW{0 z%;e!2aKGLj|%)c8yE_zFG&u72%Ea7)iuaud_ zG{a+TCjdLa6&OtdAeJSQm_W%6fTQWO!S>`Ke;;qRMFV@PlFzjzATCM`jOY>HQtv?I zP6@^iO)|1lA|*BhEwJ&WVyCGiCFH7nTPXRYtZXgwVq+*$%vY zLLxDO9$PuhPKpCd&yyM+5@QJ$=|+sic*mg8b+2C1!Pu#ktAlhD?(7X3R61PkycOI2 zv^>44*9$g(p~DrEfu-SjAt}WczoFPEeEef%eFt31kRBcE*c|8g%BsPbz@ecn{Ij^{ zGL41Y{|J~L=Gp|SO9$-}%Lr*h47Og1>=xBBU!9<@_Bx_?*62oO!y*{k(sC|lG{A0< zQ0)I9^c~CujbiE<%+>I;r$>-`9H}DczLiZz)_V#y)Og>Ym5>*nxq0q~Gj*2vo5?sb zZ|sXbc^nN_M5ltw&yyS`+A>4UU(rV%7yEMFhxBShj)30-+AflBhI2O`i{Iyvgpn`a zI7M3gC>&++!2ETEICuD|R_5?dS@nIy4;HRO4=#-4m}Z5pzs}?8qJ{)R>8h6`!IDtP z>-7s5Ft2`eC~G?JoQgVL4sEXCbFP{xKgvxbA}=HzN3r0}M%DzAuf%-5=x*+>mE zLz=U|gO&V5p{~z47L^va4B>Q|y`K9VR9W$%lP6Ziqidqr&BRpxC4qe^Afx^dL_>0O zXwMbq-Fl;w-49WP%J`|EV^LTZ@lYX{UbbUW*dwS5Yx%zX9QZ8)h1DZ?gEti>lLso6 zlhT>y$5Y~0r`3s2Qps#B&MrVW*xt8H z4Z4<`XSk#(NFs)(t^|KN%_ZohW+wveNLRKJI|cUdSu;7}FQPkOW2#-`H(1vyyr^eY z(7gib;cl-nKxarnK`;C-sPvd;C@7~O?-LS*oVGx=6MMGH7g!8$6krpS-CulQ&la5a z*F)5sMVR9)IHBN;or999P}yemL$|5Ld*r&Ji_7w>t^(*a0VaS#&-zLCthv*$D~)#> zJF(^J(2C~Fz3vWS0B}5;mN^+v$FEoGEsl@HT4ou~jX=a}5~Y?P#W5y#Dnd7SzpNFy zg;3vcbV!c92?(0Yta(VAKP^I|ihhG{B)UvqFM5;K=XY6O?=bFcIg#RpviqCCFSmCc zuOEs=^gkW5-=QFf2HoB6Ka(P!_kLB#KD;Q^t%<_78Rl7zf8fltyaSri1pmoc8}CIK z;YUibJEKQFYY~KFdyN3#?})*@lO~4j``=yw>b!Yen-0#mw!+xT&+wm`L zJHUT>5kHB3S%BP7NOmQY-!YX&s9B-ppL`9Mo14=EGl|E2Ve_A%cEJOC z;*VKi;E(z(O0olIkNGy-jSm;d#8(_@GPfr!#s_u?u7#hZ1&i&qW}r!DK>{< zFOriXWa<|itnNwGXmskf`_lW@pJMT|0NQ%5U0ga5>~Mw$*Zhf}J$GU5*s<@s#!`S# zR|!oI+aS)f3_04dNLk8fFdkcc+Ea_u-!^y<#8` zaJ#m!*->PHi|1acXoR9_cCmQv(Cyy_D(l*y=@Ik*_L1L;I6wyk(KR?woVfIhTD zabeNcVC8D4;_3i4QeR7z{ZD+VzfQL3yg^0B9U}b^as+HQ+A5158TME46dM?s~ z3#$K#e%Nm1#~9)7RakKL=2=&z2PVYCJzccK(h-@n|LZ*YT18I-**+j+K5V0J%YI5Qi-Z1OG<#AN7^`jcb)-cb$w& zg`fm!+ecTf)S+k7Mia5fn--tv8X70)z(@h1Bs*Gg#gB=%GmqaI@+h1~|Xk zGq)1i=V!;uCLgN3iOQ5W+YMBLRQD5H9nu|oUh`4{D zHGc(&ZSDAbRN5B$xTznq7tJdl(!L&LYrXE;gFz^0M6X}}=x8=ro=eN+@_BceRmsBj0`@MlY#)ue;At(b>I0qAcAl^qh+Iyg&Z;9x(`Z zJ^p72c1BXxsL|gB^y4@ThI@6sr>i2cxr6$7T|B^&E7b!IX~3^GXIY{dvZob3SHqzEvl3eL;hJ{UE)h-hwY2of*{V zbhmyl5gc)Q#X>&ul`JYuj?*ySh{+wJF*1sS2EFDpJUIjF$)pmU<57L4*jti8JfIxsq@pvEW{>sZ*t>a;Kk+Vo`u zLkt_i;Vb~1c&+hjK1^rT z_!sV*eaKLc8zK}&OCECI>fg;(B|FSz?1z*lK;KQ%S_&C`niTz(-FKBSmi{^QT|b%` zjvMCd%nvo9jte&SF2u(EZd;G7#xRcF&TXlI&2CoZqF$f>m}no$aKc`&h-ECycS>u{ zD7;A;DI0)d8)P$CQG*^=ymdRSAT zz0map_Pr{gyg8A|zb&q+&}_E5u;he>-!-CK&nvE*1^jqd5!#(@dy8LJt7&3oksKm} zLgeXnh&#aDsSo5cT0c&W<|pMvQ1LuH(T2X zL)fcmptDqO^lG@Nrp+EZc)K{(d;>|OXJ_AbKdNdk7l@H1%zf|q zhjs1|xyx5S70H(PWp`JFfypMfCmQF1qJg)E)u}Vj&#IyR25~ZPw>MIa$=_4X<+(e= z`mT+tg}TJ2Y=78?-PKY9E~Dt~MRQBVfk2(n`>V~P4?P1lq{o_Wd;kh&w%?r-1NyCI z_zSmH`?WVMjz$1H@^LNnA*n(Lo~RI0A8b61KjkT+=qWdUFrB^4NEIc!=Pat@y0!kW zai;E(=0P*SM9kCEHdm!kB`K7O&w{1qn;nw1`Ggpq(0^upayZWe_x3Z;tBtf0X|aqs zvRsafDIZlp)0tpAFBR)u8uqo=W}vO7cNgvUW4-A^uH_ZxS6t2Tv6ZP13lY`g_wa>U z#!3#EafUw_tSUQVz3*?-M;*-2{3Kt=1psBbf`WKhEUsSO2beX%KYz~73=IK z!v-N4xOI0Eqtffa8MD*-#6>}X1Sr!O7%D4FvIqr4C`7~1Zx>Y$}xD1E)*|_p= zspeW@&vTv$n1Kl5slA`q}%xKQ9N@$2`e|hdNURt zAso&(2j4#DhQYT?5!R@ON@hIIyc(Jx%!4G@RGcgpg}86`@wlq%qT1Cf0NXrb<#Lz; z?=f^r>9R7dtbYxwJdT=&gGwLD(x6{Tg9tu%p802KFQ)CT8{uOABn; z8t~h)k^;cArP76n$n?1z^PQ*G#CE`Mk1}H3-$_-%4Zr6$hqOkvH8wy-wzn77-FRsr zJvRy{x7Hb@jHdPr;6l9Wn0;VGhqgrS^?V z*O?44)`KVTb*0Vblo+qhC=gP}nsunG!S6?DmUQy*9*5)A!leTiPGWRkxvdGAL@a{ z=wy=l^|Ka~%kdEkLBHdL47=Q0iDna{HPt)dPPS#Y)&=(VVq{{**P3c(u)kmxKNrd*{mm?u}bKr$kIDO>u6-m0!S?9jI}|W>kNIGT*7Q)`6o5 z6N3HyM^y4k^)T0{ zkB$Y>WL=}UpRFRO(p-#Lwge|H4qcuW$5Jciro2`xEmlBLEMoC|!fL6+lftBBPod$z z+62{TFqNFS2)V4%J zLAM0OhebCD2_0-d>#?p+8bbX68?Ja8>hJ}X&7m?WvCkoq^%6J3U6%RPFKY@Y6ginX zx&HxHWPo2~WvwoSerG)1FG<*&uIyeO6gfFMNi_;bbTgY){|zD~&25M%@C~eWTe1#` zE5>X`1T1ylg?-*lZj+OoO^P5`qV$WjXjQPaJi^=zgse=l{r@1QagH60F<@1nQzSP3 z&iPzh04Kq}===&Z-ZAqE1%qhK0v-CC~K^3JbC7cwcb!c z{H7noWB>_wH>$Z#q6m-=we1O9zg96sE+k|7*lfYiB*gUC@-RG`k>IoGw2Z zH7q}nrBQctENVGN8%d|P>787qFI=Ts4Dn3KeWbf8QFJihcH&~16=|EK;dBIACl&~C|C$-emv29pW6Fq!G1aaAJQWI|4c2A`FSK& zyjUR0e+M!D_gq$K|1@}izVb7}`}xQsz$(>R&3;vvI;dzs)*CHXb}*vp&2H zWKxL_e1{*w@WZIZZYS1eqb1^9mm}_FOi;S%fAK1*|420=0c0r2KiUm|=x7ZhMLc%6 zzj&hV=~cB&GFBoC@slDXHI#^O(l;m7 zg3{#q7HrVyR9|Z4F(=mi!vtG)c7&<#vpw|^;>GnnJDNxlrQYb7=*ivVxv`G^CipNO zKGOV`+tAccOmyFAt%iQ%22>IM%U z3$(S2J{OX=PBhVVT1NGp{O|g5Trldt3A&@<%Et$@B;23JLI%p;f$ z5xXB1;Yna5G0MV&A=T9bx&ysYcsH-x{U000-s$cBk2SrhijaLkKrp(BSMy%; zT|a*fjFlcA8{QKBPZ0F8Hj(-_(o<8dUh*xUp&u-GMD#@Cw&=kOL*Bo?YgnkM{;Ea- z!tWIR8v%B=sUb8LZ~dB883F{PJ$m7&(7}p9S-C_60`5>QF?Xw9Ha=KDKq!yb!Wo?V zVXJI)0z6d=p$V+5c?S7pm)|{v|C+7g2lMfg1V)uEDm_+}rl1}E zQ0A@dQkch+a4ISw1FXCvA_7YCncFp>8dCtGIn@jwh^`5!8wv;v$~UKj zj`V^j6|`sVsTO=($@w%$>kuDDIdT+}CaCyOhp$Q)2Dw*fZ2B29FSKCuTWXRiGLr8i zd)BLd0*aI-81?nMTj*DNwfQ)o!GioZbX2XHntPVSfmupopqTQF}>Xl_~RFjdUuB@M`2U9Z+O?ACf%u#EtdfcICjs+
;YTNpSF)&fwm1{ZN0GC_r6tqLDFS;_+)r)He)Z5G^qV*HFLy~q?EE~n zhK9$ra%L2DS<9(YCtJlIlQ@%I9F4?2G7^r5iQ;%zB_@5NUXD7vk(TafVf&x)Eq}c7a^UwwdzpgbSqBVxS#t5~T*VYmSZS;fe}UK*-t}rz%A{ygeiQF$T;Sw;7~VJ>j6hN>}V`>+YEB=f%jbieMUT4VaZ!IY{j0aly|2>I+xMo2$4=W&zINc_w(h6Zd~7OBWAbqCihA0hN+ zTyaXWa;91WAlAVa4Nh_r;M|~%J9nl{de+iCY_wb~;fq&&j%lv>oRcA!qo2wQ5U+-@MU9A6F8upJH2D3=+QD0su093l><7GbWi^v4MC$B1to<1Vf)ZUyt%*1JXPovt`$W60Ma=jBv%u zfVdf8-WfIB$yUM&e+8qH{SEKN598B^Q${e_VJ7{Hc8QGwkxeGNw+;b&^VgpnVvaeL z@LiQBd$^QPx-baijaw}hV_BrsgY~Wl&4rllt&BcU)&Ffo7_W;#6kCH(egG~$8j`8O z8abE~-#^2P_2pp)`w!8f_*q=e#0>GVD+$4Hc7Fx2Fc(h^ccz~UNh3#?yYm5G4cU91 z!O1aHBLrGoXzwvyfB#T)PR);5KGa$nhn|;RB<0s0m2xd(31V&3WA#J*eFq#9xEq76 zSeKK$vu7zD9vSp_=R33C7sKXQ*W2F+b%$phr7l&<#g_#j8Pe(6PjFhr(hsM13e4K0 z7zQsw(Bo5kqKOPI@n1hP>sa^tf)!qk=RBx_v37pwpb!3i1u6?kL;-v=81_bM zwwM_uLahqNUX4^tR%L)DF`2q089z`=g4Mh8v6g$dnv|4he|QN~5Vp9~F9{cdqpl>$ zmdM_!TRPV|cTemXHBjhax<3!wbZc;|z)}#wt!F_JUu!h0Wblz;e7ytoj5EAyj7RXJ zf0Bxpgh_$@;WB`lOqjeU7{C<%;Vk&-1$@#{=AWz&ueR?J9WQ@+8KHjhCfgF&r(7Q_ zXR82ZC|Wq;*^Z(hh;Q9i__!~|_LnVuOGa;KV_l_H554sdBWHFXi}LzGntUImb20(R zJc{M&2^NZH({kAo0Yf@=efKPy*c+) z<#rByJFK&h?hYI|0~$uOw*{#?*N0o}l%{N%|C7tE;e8yv>6e0b|@U%N{%;fzCh|z|-(ENY= zmJ6b@wvRWfxIP$-IJ`nETYcl`@9|$0&&9WX!b)W%KlWb3@8fLu^fz9oM>Xs2D#>;l zWOw+_Fji?G7J|en&bR}yEMVaNkcM?1)exG30!Cz1A9RYcU2Q%zHH)zNm)nEuYnJOQ zfgmqSLNIsQ+uK8CodQM?kY>#bw;BL8apXpLPa;@mfy3hvDHk|+|JmI`3jj8vY012u2wUnr<#i_6nI)y$q1u=@j0?2-o-L?=fZS{NW= zs&W^{{6aPP(jIMhX9=4MZ~%atInMw#loLKL2rif>8n!0VbYqelDUC@l@;9w^fWJ^m zH|FQ(r+n^s{|D7Q38|I^wNReO$%LoDo;AU#Ogj)wP|0m@z+tx(!hPbOf4|R`O1U9{ zfN+=o^IrflMn%c<%qgRSIXO9s7q%0&`eL}eyt;z!ZuBD%s0{i)liX7}nNih;_8VRb z$-;R)x%86^MQ4Fn8BNbNsmkg9$jYowFAWuGi-n>%qCAw16R=a*P=h?Vyvbuy-l~QZ zsYALZUP7 zejVmuB7kEPkrWXQXz0wSRxB*eUT&B3$V(n8P&XUx$^3j*m3Krll^-V@I>XJev~C~N zwG5+uJ&7TJI}Fod|I%a=4STo@|Dyf33KoCza+Tmi6SZlkQ+lq7va+@l5Gjd~`~7OJ z4rehte~Q9o2g_PAcY05ls83200?uE;7lNZb`rO8tut>cd+dZ2EwygKam}>gdmt*x! z&r>i(F}veS+n%O6+X0Ugc(R2y8-L7{|53_W1;xQcZFs0kq=RJuDx04s0j}JTQ zr}})cZ$Rm+Vy?hT@7>v0i9zUu%kx_-?8~TPgW#|@ZbFmJIuUzbxEEGv2N%JiEGQuN z3YK>w46Zg=!$IMp&4N1d6Jt4tiQ_08Xlf>x{|m1LZSV#Neob_YJ5m*l7Oo>mc_0wK zVMcRW17xs{w&<&wof}ZHuW?&N@2_=*FDxuT$9>;fwHCYd+AI5Y5{rZn3qXbO)%SmH z{xPH&&C!X-2Xu2`P0x?WCbjPt@fp+QA%opB`-?ro-) z<52x!QQ3~8nhDaA%|9k1)1@ouqN3!MKddEp$)i;X<}9{2X>O);YKN977!<)ubq81rLl%tJt0nkwvftP~GXdspH*Gl&XR__5w;;Ufzr- zY>=dn&n=y){I&W!6TZk_a5}ID>e#@tnZgwDRXu<1BM0sIjQqbEu$2Vk6vHDX9G4qu zvokY${WwFg=%MICmd4BCiK`e}Z4MM4AOD5w9q>Bz)1IeMbV9@;md&E^J28{f2lsvL zG+jx_t@W^-LKE;1{4&`r>*i-46EBCRiA?pOKy|^h#?sg1WS_hA@A2N~|0yOa{T8{& z`)rMbHY)tpT%#oS)7vTzAEc$FHG_#OCHWd{mu|7+r%VjCqGCsSa`J79Cb34vF!_z= z1y_o>+UsWU@vZO&B^2aem9Fp(NKgAJb%ys(XNA2K(fTi#UInel^Zbw^-2{@q1QnT+ zklu#=5rK=b_m284prAheqTL@7WiLFnNCAnK`ANM;)sq4obA5GqY?~U^>&=$EyMZkA zZtMCh=Vwt#rnP#K^p=YuMm~#uL3htws-%_Gu+8m_2>VY3n`X|>E?5FhftX{EwVpP% zWmo8rR2lq_gTLg~WyZ^2uTy|w%WA}B6OgG$>*F$OwPT7HH~3J0Esj5xT3qkBP6Vw> zm4QY)HLOd3I4EqZ^3+Rak6F#z-sn_mqd+`#*L60Zz{uGIVK#lh5j%=>cdb`u#iG6#I>|n44@jim4#c%srh*-dhGnLc zzX9h|vsOwjgqPe(wqTl1<4hdcDcLHfcmI-Kml^x-fPxI+lT0~m#;+b@!)m(U>*3Fmt19H49|E5y?rYvWo2(#UUnm~@ z+M-#q6rE}Gu>wV2836Q;A+9VANvtL8dV10+(5hBb!E!^8-!W_1&(EL4<0KwWH`vH8 zO`(-jRmv~5aV5;beZ2Jei+4!5gH6uXRXRQS*ao~r%nt3^4zQHU z=TFwSXG0@~daH${Ib&r^3XH z$M(t#BF_^bukAH@VwodynooHJEQeP$;xh(1CfD86N+YrUPN)}asafpz`K8^6X?UE( z?68dr4mBLW%49(2}&!8q0XXqsXjf(5{2N9gHHEmBSB={igXYfxqn~_c>s6J%&6Z z@}KDS?cCJ~G>@@{)0gpOx|Z$uzHM?&QlTV+j-@HTUo+D2^rZ^LA>F$$Lqnn@gMfwi zPfxag&3=OEWFK=JyxXBebU)Vzjp@gso#Cc$#DxjSpX zH$gjT4K|dM=QX7kelmGEG?x8mbs-a*oQM~@%W=h@!P}&5U5~GL-@~H8Ozf-s+@wZ% zVMHg+@l94=CqG6~AgzBU#VF?&#rEsfk&c_D>v58*;^t5LyDfUHb0sO6B+Vt>qx`pr z;|_vD$~}@?xfK3K2NO0d?y+P$wo|r zuoAKcFaxci&`{&mT|yc)$mEBrDSPeQG@SixTq(*R+hgTyvx+i@lLJYAC5L7spM;`w zL>vB}C7p68_jmr&J-@Z?W-1Qnp=Lbm*0iv%T`6JqJKB@iwbHsQApj=5x&10`)Qf*y zUNeUWdnZaSvFwfM=;4LtO))|0<56(w9jxQkNb#G;%D1d3sn!0s+w} zXKYtrO0-kF(8xlLQI3r*@8Pqk`t+s3#(1`f5P0Z7yUG%>` z;wv#4)@PaiuzY!DUv)A*&>k%4IyGQM#{JBJ9nYhmP_#euLG~jSBm;n957a3$3cUDqYhX9TpttK-_jmmThVl<5QMPQKe1AScHHF2E?5%Oz)XXr(HkD;zMy6`IL2}&Dk2}0wav_O z$OoQ+hT$bJ^lMAY7{~J8O0`Drt{V@#>z;x8jbv_{k{yx5Ch zEy?RvJRnxt><(a3yOFNp9i?-Tn+I1N?ch)dUFJIHJVX%YMV(?7^yRmiQb_1ZetxD= zp&gr5VGj)#{}U=lzv)Jg-E}#!xHhcTXEJL%YvJDxMDD1bq)U*y`Klxii;z|7?l6TX zcFS1yW0?vjLV6p{#y@553oELv)*}o=4AcO8*khbR1F5+nx0Z~=MBOt}cAQm&3JFlced~F?{o|V?;XkiB*isvM5$ktB%7^vY(-7m2!#&E+me{=qwvJmU(^V-ya4(lF>FaecZ`or03`%rjX(B*QoSGq(GGc~oZ z$E2p2YRsV0f+`DcEFkfoJK>$L_q>@-Y8co2^U60TRSr~Zt8A<|Td*3B<++!}+wG6F zmbIThOYZgFH1GaB2WjznV_y|wAXe|U3mgCs2bagt3tB6Y`hrN~F6TBdXvk{5LBz6Bu8k1jB-=l=Lkr;3$y?xvgwox_PGh2!H zXfWPqha}F4ba?kqUI{5JsBgpDdh3i;2|39)j@ti09D(L?Mgyzt47)mkdq}%1+K&K- zCJMkkb?#FVj}`sF2krga!m20YdsGKnG`_Oc4&hM3V4q7cwlSEXYZkfaOEM91bZbgL z!_J?Is^VzT8enz=(so6UBrc8nY2xg>Om|jvoHZsl0tO~#1A>f%6$0<;pKDK52PSzP zuoL(;{o4WfR^^rjusuuKYlKI8!%N8WN5--NcYJ??ED`Lq&=Sp!Xl^gEr8%0<78MbJ zkDFHSZXkENYzXV=6k*m1q!?zWKvHXh%6@lgTLb8fhbV3cYDoaCt?ZiTS7-z1FT z3UuXogwa+get&+gN1hEp0$81VtP4AP zn`$-6Bf^mE>8_VsA$5Qn$2w%Aj%iN?Swe@#Y9g4<^r|PTX`klCA5@TVh**#(uT0&H zT#7*GUrN&JiXa9R1`HF(2(;wJ@oJKH%L2?ql2FcqqUocq|Jq)oGh9_+UvK)7UU~Aw z7nY+-1OotsN+~%Hu7uRly5?Y`V8!ZCfFxl8y|)t2Z+So{Jz@urOh@dUbQfF(e z`TT&_iKWJHR=R*A>U)U;*B2@=s$-7xdglze0S9)*eX<|qUyEF1mJ!pylHWvd5?Sy> z@4eAuakcEHSH9yF={@#*CgB&rEN}JtKq0=ytOAYMp$Io7A`x-wik@1dW|MskJ_L47 zTxO~W@Hdki1wEkWrV@Pmvk^~ynMm-a4P5x)Pm*f)vlM|@lNmr(n!hh+x?vKI+FkhR zfER*b^6;0S(XI)@*wX+xs1<_|$lBXf`5tWV8J(*`!8Si96Zq?KZ!NgEa*k%M7_-a4 z@-Ds8_lrnmSgI5)Fj(0r_7}GLUZRlakkqpr<=D#w-M>UM$t)|@uhq8%erR>rHE|Uf zDCxWo;w+D0!kokBPtR1hRVhe2Bk=X^{q~BaSEx+sC@!=pk5W=*9Ks2?oRxpKC%dw=;-dB2iTkmFM@sl4nTJBS zOXkb;tL$l7ew5C^>fc=yDJPq{M9W&n( zdBVzANpdwZAwv(XNt~QH--bIcHVHR6lS9!yW7s5YHdqWt^;zhZR7_9QgHM#3HwGf8dE@r+05Uyve+Qk^U4^#phJmD zH6~;<+!XwRV4k@!DYr`VY~fIccBw871UH9Yu)Q9q@EonAMqdbu}@+hbTUh2V(wuX+_Y@@roL5DyZk-A}T7BG+Qk! z^`hY#_bbyiNy-qup?#`uo0WzaTqn11kM8&WF^kgV<3*~jn}RxI3S@q)@ZEV5+@NW+g9~C~MT%Bmhmi^n&cZ}OPJ z#2-WrvyA1ZQ8>BmPL^3q!Pg3EixZ1|-*gm1h@FTpAp>u@nd9Q5NR=on-)^yuOTMx{ z+t$v=)j!Jn15Q$RclCKi+aTPsy3a+WxrxjO;buLBF>+b?rDx2{Z$Oob|M&G-XrPqf2>DqMQ^iCf<&C>CJ)vS?fenK+vcY=+?8;opQfWYGQ}mqmN& zv>C!tIuHY}@khH8c@iL-HW&TzBjZ=phD*keiGg$nbU<3$1FD5^HiJ1EdI~aH+l7;T z$5cP6T%#~Wgz!R$;hCvVX|(8SKW3PAct0)o9ye6H=>+x;z2sw%bElQ4U9ZnM3!heq zTIA=sJ2^(5O`o_Bx6543(wc#q20qvM<~~Ytd%30;SJ{#@9+S-r=WjD8@f$TBqKbH& zWqGhT0k?l#&av_4Gl|zmVCHx#MTfZp-yCa~7D-N~l=-jT-;1ZxoFLWv&)bY-4Nv}E zBtJ^p?~&m=^MI{fnYq8k`~QQZ zOZNUhaWsJG{~br~5B#5Tv{&x`C631OD0dbj6H_^hT-tS{SrGm`+J&_DC_?bzSU327 zZ#_D8B`nR`QH{0?@3(z>)}D>JJBCpB=wcYi9at#C%Wr$-ot#SB-NTRkjNR7{n|UMJ z*N$?w-894}FWi75?A=GBuZ=xR-YB{HnG1k1L)u1adSi!1osX!4J;r3WEosQtxxQDsp_@J0*8V@~ zT-D-wm1W>CUr-3c9E47OTCAjlKBiGP(=A|>@alMia&-BouknPdF~9Q-g)BukDqj-{~o*9EKCH`5mtgAaN; zr@eC5k!Ep=9;zq-!0NtQm|{meo5f@91H*aH|4{Q0Xd-5PJveuhwIgn)e>gDc6l#AV zN~|n5)uz{*qcW`{?#A*k$h~92_p;Ze@VHJRSVj{6^IYT|>0YNJr{d^vx~{r|km_-% z*e}$X{CY0q-l6^Z-^1JMEBrAp6hlju2=wp%6CiyH-TrK?lS2~wKMbFlXn8h7OfOXS zDiWH=|4{t!|DgD{Agwe8m5Cn;X(aFCUZ-CdkbaP+|2L4%mj3*I2Jm;(dAOGW(bkZP R*9PGL1sPT88cDOz{{?ex+~xoP literal 22762 zcmd4(W0WRM)GdlWWmk1omu=g&ZL`a^ZQHiZF59+kyURHB?!C_$-=A~u{dsfb$c)Hb zk&ziAVvUG7XRdI0Sur?hOlSZA04E_XtOx)AMf{|zAi;l*#vd24KPON}K?!BZpUn%> zDC{SX;UuE&q-1O2Yj_Dr34BmU+M(=yS@S!=J)sC>3i&=wN@VgR;9%5J_922+ zu0EXrGJnWHSJ#}ISQ-4FIBL!H?HvwJcq5nN@ySis=j{&HqSjV+!C#;PzjB1`Tuu3Z zQf`04`3WEc@DC+Hp#^?{5~vZ%|KuRsko^C%8%?Hs$Aib^esMh%`p;O5=QlYZ&t|LL zmJ9F4s-H{Ji3jR`nnNQ0bJeUdhs{apG1rfhi{| zSZ*D5AOqri-|wwfUwhIyuOuY!r^TC?)~`ipoxxplM4=F-ha=;R#$3}(<0yoYUfm>2IjKD+0eF` zcj%(2&cVJXDsKFMGgriVcN+L@cdnJ)%-cWygh!ODGN-}AN6`IKsxZyVxZ4EDa}7JS ztFC%p0Up%m6zlD+y?j+9J{%7faDy9#&QC&i`S@;YlC^F{PL~)P$kn33L{H_OLSUg@ z0_4btAf885q<07e=Z}2i4Z*JR^Z_4PdC7o{j z9m0!ez6p%KbdGNXQlq{zzLqCDaZ|ht^?_O8&Vp_bh62|E%w9kB*u7qHaR)aC*S03; zozH(UJFxoxk?guh>$XsW|BCT2v*wmBn*P4M@Q1+Y3l4+B3pY`TDD>;Vak5}}oCZ^9 zo=}g%TgE*4z|LD(?`L}ShSl@|JBxjOg_hZd3C_*@v4gA1`cx=c!=L23`=yb2z`d}| z2t8F9L@+x72d|20R<$KxW`Z!uo^iWquSi?n8-`jOzoQG0U5zGq@jP@nVqUzr8^l_s zK#Bgkg=0{yAasN6_q_fcrnA<;Care6;E5@o0Ge#8cgYMmgXk8PFqLCYb6G2Z2@5Z! zuibfv{8tw;y$%;_`P@Hg^(wM&PL00$YpBaAe_>;Qsffad!w?uf*7n8soNhr)$7FKF!6{V(qJk3o896cDr**T8*tUR@%7jVe}puZd_qx83%c`-?^Ri=vC z!VIoriR->ldZC@By!I+AX*tRJdV=G;%P8_MjUyL06_NzW%5`Sx%+^xYj6=0?*dZy zB51sk8lF-KoGa7*#eL}{Z+R70yQi$pIQ(a0HKh!B9}c1m91{yc8QmLQ6lOa7>_gj2 zv6L9Pbxp8xxv#H>=PPRLU_f1zL+IW(X<_&`iDq1#)1ImMGS-GT_EJBPuX`#xJpUzf_X5)p;YyJ{mag#y}LO`ZcQ(`p+(J zpon>wa@$VOkApJtw%%-wUmJTqsSl49<{z3h2u**RPku`B(UlVz}`3HD*~fj)3olkgdY;onpF_tE95)o zg{Hz(CnEuYWn<19TmK##6tSuSAuvBp;!Er6>!a58hDE>_UHl|c@1G02k?W8)eDa8S zi*|1IXwgkk7$~vKTAEF^s9nc?8{xEBqmR{Ny)7QD2PeyBGwM9y^tC+{Z5CsB%56#5 z(_*zdt1{-kk0XxmY`Bv9YIa6IxZLP>2cepi!083@oN`WSZ@{r`W_i7^PA5)p$%oNt zN@m}y2rr7SUzxdGELY-oK1W8Fy6ESRW|4|r9SJ2iZ=dR#P;+>={@m>Gh7wzPE*b9v z`If{VQ?9u>6qY%gX?rbl|7Kb_Fe~y84FOludU3>MjWfcO^LfU-asskqH6dWL(HPhP zSI*B|Ppn4WEC?r-QDgt&p}Df~8cWXnYk%<;jJ>d!i&+`*an~7N6mLqloR{gS5yN5O z_O$LD&Y4{J{l}CK4oAxMV6Zr|)p!AVTB9}dS=v3BE0!}E@BVmg0mIoNs}ejVubDNC zXIV^%l!A|ad})H!;p7Ws^WO?+3)JF#%a`;6%RkNwW*=Ovi$&_sv)s*AXDT+@?B1t* zRb@2Heh~ASwzft_-9x(OEHkaD-(=uiI%4w(0d6Yw&E1FeMI(@zixM`c;`?(q}%;B0Dob2+h0n+janvz`=XF z`rzgK;8%v@2ZMiJOsUW+gnD)vKyus8#1&({vf-+ls=lN|2c9)A z7Dr)rQcIV+34D7JO`}by{vJ7JcsVgotgYAYuNq2E-;I)rerYFbrqXKXigqt^M(2(U zbK+!9`o6r7hg)*at0+b3iEy8Qn#Q+WD7~5I`qb{-o={g!b#6C8)J_uec+yHt)I6Ll z8P?=bm~y&4Ka`TXK_ZwOQyGJFw41AcT>NJ4cG8`1yJ_UF==vV1HlImZz$WKj^?q1T zc!^GahpVf)kVwGq`)I?Pd0!^l>FWzzF$h8upyABVXat@`6CH`A6o4bVyY~LDSVCx_GD~#4svw+Uw8`aw9zV`lra>~{iHk=F?n&wswQc~m zdv*v&1T|S^+5dp{>7f4o0P$ z2VTemT6cGrPN%fpPya>o88Q3h9~BWLA+YQG%x+G4+&t6ylNJLw-Gj!EKw@zd` z#^K&4#G8tw``U>=B)sQi!k}Vv>jbv{=YXKcNmrR1T^kUwYPR{8z1FsIvv#_m&&v2K z;8snlHO>K{<8Q90$3LXm!+Rf-s~baHwKh>08UTOD7%2Zde_=e}SHnkVq-ua_C4*WG zHQ&-{m;8DHxTdwJCMibHSQZ5Nu690A`^xP&V_2b|_v;4-{JA(L&7=maKnj$2da2H^ zW2Am~=RJa711!Hs!eJs!D_aj1CIUyG=8p8>y(Und%yu*b&HG-%5JsH6slDE#W`Wpq zbK>ly{lF_E76hy43|u}ss{uhq5c`0e2P3D`W>WoDKL)SY_DM|VlbS#^u+b~YbrJVP z62=LAsrI3YjnsVXNQwcTp`@46WcD@~7^5jA2E2iCXwJ z<{jKhxh9;-F;AKr5^-KlP&`*@e!BNEF>>9*@_ulrElumR9$K_2NSd@8_lmHhP<0C9 zbz$mEq+~UC+QTR99!K*x>cnRS^_wU`+p<`sMN6FiU^(7K{=#51yE7Fk6x6f*#ib2( zCRWVFqu^RYw|sw)6qSkL2?&NbM{FC+Q!fB&nPehAY{;=HXCMw91gJ=_Z(K#pzz=J9GBhX?azpa3I`(vy9i9KeBTDw_$x zY0lg`KW2XnDEAW^OSomg>1)|S$hDH@^s|Og+|}*`^-6|zL#6^pSTL~KN{+iC7uDv* z^e^&LMgK52RHoJi6_E<`$lt@P&Oa&N*PW-; zd16TWzZ+zw-BQQ1*(Ta^khf3i@5Gqz6@e&D>dSn+kta@IAt2NasT9Gg+u;ZCN{N%M zn1G|VNYJNc1hTzo?d<7dfV7bKy%`=c=V57U-J&sLe1jRUd2jEiBepXS1d{pIpDjSi zBtA3dm-8HU^2^Ss``p~&d8rR!$q-!GHP?C@AMGy1C*C0e0B7^XiepHy#JXZR$WCwX z-TgbD6y8biftmOojWZnFxYc7 z98N%nWEVr71Jbe2Cg^8r^bbm5lRjVLC`nE^qWgsocTiTBf-Cp-}uU&q15CC_L56 z;khtK;jE~^!jVw8g`<;fzlLoreBej*!G`+>tp!|R{=`q@FU^15+PdS75i6+@qkY=zAS{4n6E z|1h7f?mc`fo6IGb0&8L_+0&KS5AP0V_OK6P=|M1XH39QMQh4b#lPjPpN1aGO51EyV7rdVNqbU9Mj zu4m_1CC$r}CX-Pkt4{(4>FoYxM?uugmC4bdf!<}cq+DTrs?bDqB9`Hh{ZE+mZuL-= z`uw=}*;F*$w4WIJq)NA0eN;s*dOO{Jsonm(Z?zP>=BSnEqgo9I^{y^ow79U)76X3s zB~H3$SVah{A*~c{37UjuS@w}qJp$)Mmkj|Ji`HIuh4Imae8zSLBNvxlYGcsmI$~0x zoQzJ#kyese=DEee>SBJwiJO$I(KQc^5mUYMRr zB~a-(&Y67uRa+_Rh(77F?RW7oYA?oKsHPL*v8Gt4xG>CS1eY!qVfWYcxD2QK;HS}U9JNg@P?jQ00M8r@bA`XwN4JzaC%Yo-?)$SLt z-0>zh-1#XaW|Lk~Pqy<}B)7p2wzgiH^^}s}?1H0ZA-G}%%Rc(-sM!&7i*wa}K3FAh z>2GhYhN>g$mS%WOpGWITcF^xJ4s7jTpnJ9^26=JzZ1<$|P`yrIjiOV-|EPN)S#mNW z>L&^bKU~bcG zYDI56uIfp5$gA|eC?d4Fma1R^@YM(V`3?HBv0NEbvha~yrF)BbD2`>K1~Tw`hQgg3 z9mz+w`m;xv5Mf(Uc;WH7&;VpzsI1q0WnXtjm!6$Yg;1`4qeLrh za~SJJ5PXhH!dhd4<9XsVsm9#GQb*Rn)Chs&i_r@Ig%-GNS`n&V9$?Tz$Ani8bJXBV z&Mc_&yeBLBeGbM|jfrVV_JT|q>EZn~*gVP7i<{G%^#v!txB#x14RW7q5wk}{OTg69X<4zKQI$5aA)9)ud5nP(jvpVngv;ZtUZ*5l2HUTK&MhccW=HCO1u zRrQD&4p#}DpA>Cu`U7L`RX18e#Uj_d^rj#oJKf(G=_Z`c8o}R;7oFXMsxC_@d%Vpm zK?&-l?C8)ZB)#ej$$?uC3(hZ8>k}ORRZ|EM?y&gnzAZk^0JFNOKuC;&10va=T`u_O zR54)gYBcW@oLHg$V^wWQFO^Eu$Iph~Q+FB9Ayx0VHrVH%j6_axb*5H8E%mmh03?sW9`?Q;8w}m9MCYF{o||hG zRhl(&|0^V{R$aQ-_#XwEgBPvf`Lx_wZG%Z6hel3izU43n8ES)297@-A?qJv;whQtP zSR1O2N`BaprK%;xKgBrU^M}k9j6_BvhWB4s$2(e);(X(HYwnAGwlF!2U2l%lyqo{e z(2`GhtYW`rR+1Q>i(FgQ5hxR6zYOyqRw`5%wAMW_KMao=`HK#B%n~>6S|{g2LZHz& zy?Al#tZoDX7mFs&IB%Ae{zaa_R;#o3HHT83%r8?6)oDQ}^S7iiCRvy~Yt2oS7>*ck z+V-ch`Quwles3Y?G3trcM8r#!(C=R;Dhn0JG=gDVEOYDK&o4JAq8ysO=RVjKgu<*U zm;Skp6Jj<3hc2e#*;-mm{mKw?^!XG09|}FxP(#K6kML(|f|={BMKG6EB#$wx_c8vH z!RA_JwwU701v;>?tN&x$?Pt;$0zw9huT*DiM(&gV8mxu&fk6UNBCZ|HEP$bo7cEqc zj{$#h!Prf{Z3HN}iDjrwE2s1qh5O7CMPhxX1nqIKruXWTAU67#C3}6ucB(xE)8b+~ zd_dq2rh6iY2K>e&2=}|2L=-MUN~nQeZyC=WKoE^;b-ShiW8CZH2%phTi7(+1yx&cE3erCLxa6ThT9_5RY<+3S4J!=4B_Wxz+q^{on^m_x(NLV@EbZ#3}$z%yNm7 zji}ngRv~xlKQ&>pkE#s$R)v7cdGX7D3`knQ%L^0Vlp9;PLGX^%dyXD|!j_l>E&^2% zczyoG;Q|*__611EM=vzj}7Om|DNc= z-pz}5@}&svi`~f2waWl~uA96mlr;Zj20|ZrDsUtg&n#&{$a_+n)R9>JZLyyWXS|PL z;yo!Rc{f80T?GPF5TJT+T2DTD9_oR;~lc-py}g&>Bzl>(J*6s2t=nh-P*@Zlla&2D7UWu`yOQp zWANPH8&m3q%)!P3N(Cx^$#0*{Z1ib4Zj>OS8HAL~5o$%XmcnY#iUHC4qIhPV?{pRC z`WYx~#Ih&*;&!F|Y11wAu&s&k9$_gqRi!Seo3?^PzW;JG{6*& zM7*hjH+=<`jiWG!hD2PM1GGVKs=Z2OGjN>RKfnQY#pz$EriaVt_ekIxg&0SB795FR zTvC&RLuqApili|B;#!K#{BSLtY?LW<7CE( z>I2DS-n1>%tuge|XKBV;%!a004FcAKv# z$~uVSvTbk0ob!|pYXVBuS4C@?rz4gjWzT&241o#@SN&HhubE0IWyPXZMC>`JKrr=8 z>vHnoEgTnpqaIPxs3`<*XDsL%t`CXeUioC!dkQFV(4|Ddx^EFgCf`nkJBUB*; z)OrR;E2uB=^@mYfsQ7j(1w6=3H<9wbN@jklc6|%AyUR1v3tc$=(EnMTE=E1Gnl1TR73)-}6A(nXFEJ zNb}Ai(GwXqWodsK^YVDBXSAm&r*@}ALPIP8_Wk9l@7CEDW~dh=Nb@rbLl0K^-fF=< z!|Lc)p%9o~8kjT#rr&#%bKX7q1J^7F6f6kWl}+^#p(0Z0lUTQR&v!&2LdkvzBbbkm zx7u@_cn(L#a8zjWV&zVp)2>XcCj#1CP<~!Hp zO8;&vRy4TTdj&B@Pw}s=aYaBjW*}OrAq_R?Dxa_zRE(hu%S@w3Qq0AP;pR)2opFW>16TxuDW^r}>(i;neDJ{GLE~ zPAxW2RlI0#a{%l+eT5|crgifV1r`5)sJ1LAlmCZZivrB67GzfgClDLEQ|Rybu*?I} zWaUH?f6=X8EY7aF6_^DQs5@`nF5XQ?QGhiQ3nVa;KW~Ah9ag@SC&1fmu@Y>}-xpu@ z{f(x~6ZbJ)HCvihZzF6qp_}B$29;v?f;4%oirjz2(Ko(|iSq!ddl3}<#x$(AwvtkY zz6%M|1&NM^pp4>$H9SX@{;K1QIC2e176qY7?LS4c@d;B~PgX&n>m>HNbgFZp4I9t) z>8~jxYqsFzL(5&H2nV)lIlkEbUu;=d?UdWST2rMWtWQnLZ23~11Drr$e$Suv+ZH#v zQMhGIs#a7VyaBdNp9+Q<9y-Pv+RN|^66pQ`UCgaA(*IivfDo+-@%~XfXK|^z>G_dj zIsDH2rF=$o6vG_NP5A zxNc z(?gG%=murrw=|`JAq5!}J*L z6l8JYB4RD?7F_^7z8t+{Sr`%+Lm^Uv?OR9l{cNg04xhnn;!Egs9(FfF+| z3@1Ns6!8C{f4!W;EY{-1UU`b;SK-p@?1ZCmAt|`_6FSkDL@vHlB99%U=H6!$LGtPI zC!SHw67c(SGL)m>gW7@k;>X+Zb_5aL|NS zT8Md=D4+zU1bh@=!=&t z4fUH$YgIC+9eE^&#dO$=c`hlV*ORU0Za>6_x&WBO`}cG#S$a$O)+S2O;V8W2q~!>v zqM}*dZobr7@qaWQ7^Jn%7b;02^X=@ceg&XHD*9-xs&b&@=BO7y0z?7=etqPK>-ngD zKJL=Aw0v0mcZzDUOz1g89Dx`KY|vc68_F@a~Z$ zA;gdfy#nqyE)YE7Y;$WSc75bzK^xwBZ^oTnt3EL{#)LzQOBLHQii0n3Y;ZKUQt@Iw z_+ml4{ryJ1%H6`BIi@R0TLjBkWnG^+S&6&8G41*6! z`~z@|M)B2KlFxeSjwSmC2aF{MyT0ukle-6XsFMWIOf1#2w0Eh9*U-L&XN$IxE)9pZ z5L&w#m3{wGR!-M=>EqebWF&4jtx zf&~;_{7ll0+Zja4ibvi1aaHr(@qf-ox9&nBph#Y@eDYq=$kQ&?3qebiO`t9jF00FH zPp=5)c$*nWy1#HRi;qDH6Q{}C)NVfkO1`yFwGz`#0WfQpuVTc}UV)C;b%Q{Hx3`;9 z$X@SFc0CUy3qQEkeq<~B}mP&WFU0dk~U{IYr&aY)TT{36C>S-)-_W(VKwoRv=>mA)y`FCu}!`DM+>~#Lu27 z$+s`~rnA}oUU0&Of*2~tqqLI|hgo)>9B>div)2pgcQ zU${ar-VVz7`9g8-wmHzSH&FipPIIZwfY0;kexqDybO1ieXFzCUof~+z9vK$_-+Md% zKyUU%`q6L-RA7V>fXOO|n2Z=Y;@rPWf|d_!;m;75S;()+KJ4=bF%4*YzE{7WEmn)e ztjE=|$pDN&3lIR&ZGVq+S|r3710y+{3c3YFgJ2b&gvi5Y*8P$Z%rfBS!NB3P@$i2< zs5f36NkiH}b}V%j@Si-V$L=pPxw^|#qLWVJ!64yDYGtW~$oNR8- zltyiOAO>K5Klj~(;aPFWEFi3ZnCKorgRourIeMuKsF@H6eb zFHo!mBvOpjQ=V~*czPb8e#zFl(`$)dCR2qa1F7gc!d|W*T5qt5N}$0c)I$rM{X!vr zbL`%(KGSyS60n2!yG~nhyaEu+jt=>Y{$yg3(G~hd)W~JO?=3Wvcu9-V-?$Ey+fH->Y`_=wwz)yQ zQ2ry=Bt&O#hT|%1+^Q+TVt3&NkGXjssasZ2AY?`+k%H*oD_0^0YJlY!;mQ_YWrXE1 zEjb7*Pn=u77>kLD?wzZIR=(yy!m&sZHH)WDqPk2uB3u}dMBt8+a+~hupr+Q-MM*&e zZHfIXaWCQjRx0->|dca@m>7cPkgPwfES=8jswD z_8=zUCAb(2axLHN&wR`P2?n+yk?a?PLXYtca(HXWTfTn^@fvr!uHHpddmafXe4sPd1LyFQ?@+c!t1nF zr{6A@kR#)3zI#RcIOa9CP7+abE#8%3z>KgqWiC#6sX84Seoqb zjLnKouzl&XIp9qA;>Rm3#TvIf{hgXsmCENAwhQs47EebpN^@X2G3C6b_9^Ah7811- z#Tosn);W|2%wM-(CcL1XY<}I_HQ%%+ zvh)zm$yN`vnKpLxNyynlI&r2EvJJiec*=5D)|O?T*66aRkE_hV>|z3`bUs)Nte@m` z%67VzgSWsI#p9w;!Q}ElyXoh%O*d=*n{23+YU1Mwmn_Lrjm>?kR|Q3u&0K2T-jxAT z@iNC?26!&w5C9P1GRk=dB`2p@^g%D%z z>I-4un#mYiik)5IpU0*-`HS6=d%T!~WiB}rhR&2eD^f>$DV*kirVONojE5UN4JE2G z%M&@;N^K`3rBKl2+8blx>y(K*+DRVsZ2klXEx!w%N;c^LcA&Z>kbl(_6|G$OQ|MR=fgNMm+6ASH)UZJhH z+(B@wMe~K~Q@JL&a!Y=md7H399)*}TSBe%Al^s&eCSA)Rl~QWX&4(ic!`|C$#Anqy zvl0gxpJNAO8ml|F5SnOjX^w_$?;xE21cOM?6H@e3*B8OpoQ_<$7%TpV2k>>Sb|4K} zbgftCqji@;F9)BXWlZ1KW0h7EdzU%Q^vKY`{(3aKf!onfNjHqn*scRU;k6H!S*?zI zyRMnKO9#!Ij$$3H5E~IIM0PX2hV5>1wXgosrzQE-0dUT2p3X?NUccazxCG~u!w2;b z4G`piP5!DUejmn~hL0s1qwD)cy4q1d&d_~Jng|^qN3%ZtyxgOAjh09;(Y0V~#kewP z+~bNhpxB?)WES8Z{gRcTj{L?>8LeowM-Mlax3TcZ@KZfQmp{C~OKJK`Ro2@Qf*E7~ zVAgaLIE&b1U#maJ-Bo9;g53ML1XRFnfsuCR9U>+iA0YR8s=s2$P=Uz?b)5}2W=mpb z?O@Nn>a_-hGRZu24NWn3twxoUXsw)=_xp;jN{E_alZmwWy^LRf_dH}P)m4+J=9 zCQTxVP-yuc6-Ol3pRWwtHyv=-T_=V=!!vDX0;eN{S#+h%^;XtNe{g7s;llD@IC|3N zr(1ozUDW1&5Lo~2XrqE0i^o|m;{9?QKT`QOF0x%P#x_`)KvT=ecxJE_ZUerI-f)M7y<86h+GHSP+VL)(c;@ zPGw3a)y-5-$MpMO%Eh@4pVvK!X{^;WgYA|@i>p(d_efo&MoA&C=g6l{jwgk zZ0lxabE{K~H(m&8&XGe?3l1_y!xi6Q%3$x)GBu^*`eL!YjLWYJgW)l`?PMRr-#u6I z!2&g^%9YipnA(AbE+i-2H1>#@7yRV^t&2F*g)n}|`P&X!ICa|5#3xRcrDa;`RedBm zETuMAX=~I6=aObkk>+M97}dA19oyJ(hZ>ovZLaj(MOr}wEVw03GE_HPz=|->Zb8aZ z(vKMP9}=li(!XdHkS_d}N}sQs#S@z?WXt4jFa zz|R#koEi;Wxg^(r_$fO(dS4&do&gOIfVi6NzKt@kj)~yd3zoRl3-Y#E>@7P{ovofp zGnVUVaYdYB!XCKGir^?I<&K+_tvVv+K<2^>o4h=Fvm?bQYTkq2$DA(TZ4I!oJmO1fX>TeCrByox2l((WSNfP<)n1}lVrdKH2kIM7d&}>3i9osOb9*PURP_()`4c7;CPSlcp4b%QP2I?s$rfjW_ zv5I7Wu101x6&OIV+T+ZpSmq~{En1e>NbcG18|7t*_oSm%=ygR|H}R6$pbxirE7#}G zGjeAYTL;X$rFw8)Px4YBfnRmc-p%ku$SSQ9^jp?>uCu{f6!=wsRxiAA&(fX}3J~@p z^lq=JfqW#j4xrzC$q^EVDGSd4OTrLq5KCS+&hKnMc)!WOq7$ta%!QYdcbn&aq$-(N zE+OAjn??9pS6mq&{1%_>aDdi?W;$<9y%JZ>B^*zMVq`k;1rZ_Vx1 zYR|nAvI625#NR*Pg`JK7K%IG1Iob5V$EzbdcO^?Fq_`v<^QSTH8;UA$%vIfo4>h6O z)ldq}d!4fpm|1*G$+EuD0%%VTGv3L|%lc@!hRpgSPxl%kgl6)H+WXB93)Hd7 z)yeD>HPm7|Y^b#?D=T9y&Fc%}dUHJ-S3o&y2W6?68$eP>xz4#@Pjrnsjk6kZ%hN%B z=PgDq?ONx!!GUftSU*Nox7!W`-GflSyAQ(MiWc~CdUdLo)@G%2oNcF?;gRM-gUN6g z9;R^*ltqjp8O!0{>X~ZiCdTe^l^y-`niO~7@@Inq1Yd6ePwy*$i2`X8^CRjv1A-kL zC;YQql!!<(Xey_S{Fr0__U{;Hhz0*gBFG&K7>&KCb{VP@cOjT>nUb=OumU3Ptwyf| z`PRM#8Ntmh@%3O zdEUhLdfvL2mcsSQE4sQc6g|}QH3`4NbAV^c^5Xawh)Yy|HaUhqvnu=tvZtl=a1p95 z2Xi|mG8X;sofMv6pCifqJ2IZxqVv+$O$S<^i^~VuD1^=&?on5}+g)e$d|~-W*|Os* zz+>>-U7@6Wpg4CYUTL(b_G%--9Ah5s0@$aeryv}_0&DdgFpSqbbJf3Vasi0__=2q9 zLo|&790_wv`qU%hY-UAlUQ43nNqFY zw>f4CgJes=4?R~I+o1xot#&VuV7>{j=$}iV^pS8$ki>a|w#4T7gJCfLU5ChHLHPlz zwk*p7$8l%u24=LxN&l_)`DZ|!yB>6_MM|!XnWy5MnL3q)--%sJ$2rC0_qm~}@4&`Z z^;t*RUL6t8CV`J+t2g-1h>!Vn6E>gK516gqdzukjV$_To@(?+i@%z#2og8*e5w&ob z)o;S_nulW#e0qmCqUAE^4UE}u-Y@dvyZ5}2g5%~krRzyQ*_k?R4Lrn{qtHAFc@2qm z|F%^Yz4MS6=~GL8axz%`MamR;>|^>LVRY*qw9myl&I6HgD@$6~5YbLxHfZmUqQ++) z#uq!n-*U?!twkU4>!pd?DS-nB*pE0}j@B3k^N!5)!~V$u8`9SU??=816-1qRPmNlL zmams8vFbhnjpF$o%1DPAF%@V$J}8Ve8%3@rhi7O~ib1~Vvu6fAc{=k)QwiaLW2p2jQLO*^&$s-aCVU-{SxqAhPu?B8AyJ;8nLP+H?39$G9EJKIG} zLRrX}LZ|1TOytlG1r6}xBlOKkQf!{hyL(6JMZ0^tkcOp<{FS03bTumINK)!yI1K)I z6WEInrlimB{tp8lhTV4(cBdD#q!{#I-9*^|VvT{V0r;r)z%uG+QAuTFBw{wVcC0$f zYeDU<9!#Cj$Nxm(Yk&I^ikPdeF5$mgTsi|(^mZh=6a)f+_GYma%i=Rzk zG3igvwqtt6q`;v`lqCV;!_k%saVWavTFYpXX?EsAR+nD*AQUGIu6?-Z_sV#~8UqrmYk-Vw5^_5DB#usG+Mr2cKhCul#46Z`vwwvh$1 z(egm?;N5%U-68<27^=Zjy%;{;{%96S7(Fob$vpY*+kh=D4*IR`sLCbFZ<(+BtXK^`xK~35XML-$%?okNN;4m8-R1924p*1gw z^or@h!x))?{IS@?(~`lbg$n6MB!w4cUO+7n#NSI%6WgYm+;{d7QJ9}Lh`tvr#n`Q&cvmNTiBKsLZ5OT zA*I{7{J)JrcF#9rLPEmHS|Pst9Nj>RolDV|Fo#+6TEcy0!mPl6-7I&rlEhWXMFr?$ui6^Uo+uJ zx0%%E@eKD9j#lykhk(e`3zocZysgYqm`On*uD}M?$T!hhro0v?{y$n2BSm)4W3`M4 z{iE>@URtLz-thPmY!ja1+&wv!t8xH&dDYpWkxVhDputQ9U$z0KV_NbMv(3k9GPJnU zc~eUH%%T(P9o1`mW8xk+}uQ{4J)Oj#`ufX*Oa2`vndb>q=a1UzKTYNtO#n8(yxS^ z>eS){=DVi?)<@NhnP9~maaT66^M5F>2S=0UIN&*$ItiF#+yl}mj8S3^nK6VPC)`{E zBcl^Niv@wKel))7W7Sx`raSjBi{Q@(F=E6rf7yGQ5pV?G94`v3AegXE&}Jq*81J6e z@z~E-NVI#b$y}{8hs!}MW~GcrDt^<=iYJ(dvQsNdZ6IxN5Pd+(iCpf@$NxJkbTOU? zex78i#ZG3c>S%gb}Xq;wALbGuko8oIg4!?#46{JQp$ z&FyoJ{&xmvRC3zl?P+zgO60ZUM|G>6hoA0X1N6QKTT5Ixd!P5|ihOF(Lw%1vBd-wPI?QDXy`X zXy)6ve*mfI&0GA{4oqHSas;%5NOm?BOpuCUsfH=jxytc?5)6B*JH{KwS-I-j>8VzP z&aqx8#fmjCUiRVTwln&^fl#!fNOd)pw-8msT%B`NLM|RTIoa)Ll$?5D9hdbYw4@}Q zwYC?AW;w(taWzYp@11S$VKId(TY#^LOG}XzE02E=Dt>$nGtilM zV!D(%kLv%7G;uYk^$6?Hg-WH!4aiFtP#sTD)Zw-g}q?*As9=tpD&0MJSPiwmG|bEu|#a%i7c z@Xj~U@@&}T;huBAE53%eWokPd^!Bq3`ga!}ll(bhuRq}u=kRe+_Kn`-zZB^txp;x`5{6d~6RWylL z#r++&?SHYG*7BR_?oS#Uu*FX>flLg9Hd3+}#;qfWcipcI}(5PMsfc`nLP7tKP19)_T`bPvM8BSXmFd8xNnx zZGakv>xyM_^&VC|LI6P1u@nOoj)Jd}kWE%fm^{}odZv($%tzBJiW}0;zQ%K3_8G8x z_j3_%<;C>qjy0PjFS?nRH2>~ss5^hu3``ot))`;2?8D)MCPgs%dF zXE(0QOnU-PHFHydGS81w1!v8V)kua1Moi=@1eZg%Ju7=?Icg0Pp38E7cPpjq-`=#A zvd_V2Wm=6rTpza_YlJ5rc~`TF43!j!uk;p8<~ecJcRV3jkRHtgOiN)mmLe~3$m}*& zJG4}>V!vv(p=9g0UI7)eg zoqm4{hX!@{t?=($06|wiVPUte)cQ*~KQh=Vx8!dI7mD}%~Wb_OMN_BTih`~ zhcy7l+gaRCYT!b#wF?sozll#4BkphPyEd*cW@QS^lEkiM&rejT9UX@;qtX`fP=aC& zA2WU*DZ>>c+;_Ti zP+i~j11*+X%l1^Db0sa+JuC1c;ro>+(JcLuIB$D)b}!_lmjvCafpV8u-8W zI0I}oyDu2SIA%uV@y`cN3mmgRPYAxGbNPLvWy&+-{PtFE3B@;Vy`ADjmhvu><;Jimq6FTVV|;mc@;0Q$=RRZfw$YjLDBj{?u#=f zI~=|H7CdU~9<@3a0$96H>{vwveqTFi=3+6qti)Ic(7#Ibl4hj@TG; zvMWB1U`|;2++;YT=65m9IPHyE{XKZ~!Nu99vQ{gt+852hPW4AuHrjz=2d4KGMP*cH zpFyh*ooN2=CETLzZB9oJx|d8Y%Z01`fP!vI1hMU@ap8MtA~ zal&ZdnVvw#9o89rG(yPTO}uASXw1f0A_gAqG=$3E@^#oBe}W%^$cf(Q`N9xeWKxr-?^t&gVWl)oW|L*vXt=k zBY|}&1ceLqO(c+lOv|Jt4xqPuF%3m$%U>wVY~f9FXIYD@S{+>NRo(C+gm-elT0hwJ z7uUv2L{bm|ckkQe@5@q}bJZP_sZPjPztB@LAG>4I8N_G#t#(y?OC>%T(ldW_xB29c z*i!8DD|3Dvdjm)E)0z4D9B5;Y$Z3y8gtXMHECY+Fm?4*Rlsa<>ZjSHoxDKLZ<*(L# zlHZu$3dB@BV}pg~Nb#<>%R@`EyACU{CN8&r&r@WeW%Uw;B@!2sA?GEm{37v38}#x| zWFbSozR)=Y@sJ4J`Nq~&UL75@y~CvpjClFSCXpy!9WHbx-}f%@b=(K<(q^ws2H+Yl z-M68j!{PAiyWyujo|#pNHp!t&p`FMKii!;Ec_qWX$mr8E7^4FlC>RRGazxi&KTpZX zoobq>MjEd??q6*9;<&x6X`1%1j!2Gfrtvq_TT@DXw{dG4da5w-6z&u=T#v@7GSgRE}Nc%1aq6}sIwt2VMG*P}n%(U$J z>TaCv#w<&6I~H7^I7h-)id-#ea)}dJ?dOkKS$ceOimX<-zX7j;+T1SJ)pwq(p0BX& zTn9JD+XXezlN6i8XH{*04DSk|FswAb6WMQE$0AsaI3Tg2K_Wu>_cdBLsM`<<(=lT@ zqW3SWa7a9HTYm3&EfCP`=z^jJ7K-3J<<0ZB?B=MC&t-p z+HT@Ci2r#i$tKL)jHB9SX|1_VdOqoKrl9V00pcpPv-hrKokQ7xMj8T&$ zF2m0ZyzNz{)S7KA1jBTCaT6!-UfFuLJ^|!%he%*`yEZ^ScGP1zaI-Nh@?`QXKpt|XVD zpJR9L;}vrr%{HK;mM2nU%t22ak9Gjl_DgWMI(Iw+cvYq#y3p+wz40pUwZ1I&LZ+m- z&ETv^KkEKpiVQ~5fD%-MQrRf3r zDGkF`zv0Vvy5&hC(^l?=aqsGSbw7&<5%{?@ zC1dTFxo{Rk7<$Cj>C2u;8+=&iOo~!gGyK=JEft2=I( zQ~#~=Z%IOTatc-o<9FIG^(iwHUSP&J;>gb*?LwpI{&FpjCqm*-7Lel28$cMxN!KZ|ZW~GAvqmZT{ek;&^)8v@ znk=mCg8pgLK{|Ruo(;CcMhBRT{nxvG*K2fzA@PI5OclJ0ZTj9&kKx#EADv9;II5c) zYkcnD#}oIzI3Vk^SIZX&V}P40Z~iDB@v3uK*xif}wWzq*vL;bBX?cY16H9tZ;~(;O zL6b(xCIbgROX^9rsjo*IZnh#=WcY~)eoX!0d8%I5Z1d)c!A3FVs_8D%NfbSD9tAI? z_Z`_Mj35j%hRg1@w+w$WWE5%QI>^3Vn+Mj4EaH%a3}xd2NRG{M_5doWM)m zC!HGf{qQ-XM@fQO|8FjK2f8JR1g*B5S0;0!j02d59#tF)@u>XOU;Luy0NjKY6fA_u zbf54Np-E#xuJ?wOZ zZiWDcA;rZu6{F8irPu?{?7sW0CHmjd>hb@6HeEJhL8OE+5^d$C+2lKSx>>3ekXkqR zk*!68e;g{lt=Y^+`^41ijhBDA`RuE5!ey(k+t%>_G~QB+bGziz>L7|ip>mbzSH^)^ zk1&+*Jh&e&K7A&9HXu3)$F>w;z~yyf!5yq3^Aq;NPDxPvoKSvb+j`w5g zvbu0k&`m_k!~VD#7@vk%Y|tX9C~rWu*Zz({D_&a(p_$xk1Ug>3v^~wRl;l3Xi#P53 zP}-vMW39vWIin4Voh-*jj1~9QGTm#=mVJW=lZ=hxmzAF-n<)dR0uhZT(jH6?PjI># z&)o%TBqO43M;npi%m(67+3?a>l-V1gEmtTPS@oo+l*$Eb7T^Li2l8aU6QtySpGQ zWh95D;R#tcT7;&IwI|qTRUR@eU;7YgpSg)Py&vk6?Rmo{dav9;wy;N@R3DwEOX#C!J4nYK^ z{wo4!B`AHhAOt;G`m$B=wB8Lf>9b$xj0ssmF|9jucI3$lc(S@6;Y4lszW554%WeV# zTlgT_Z^N(|@}Gt9{J#&C>eZ^p#qXGYLj%wf_oA2uXxCWW%krfedZ1&?jb(PZVyO(d zcSjhp7D&fpmu%#~)y_(O7U!q|nBSLKFn8}~qDwACCuSCVzY#t{E0BIeG41Sp@)RXr zeIS=FpHt+p-{kz$IOkVB=hjXx*b#xci_i1bvfX zysT0zdg+t2|8h!HisU3cOpp3UADfN=Sf~9lTj?EKLrE%z`!_<^lwX3x(XrS61fuYr zTuVij*#s!}gKKQ|$vhx`1Z4q*$U)htvhheW7-f22sc8W%>$$fB1lCbv(L1~&%XCPI z_#%y2t}(OoEr-NFyf`}O?f6)E6WG11@7ld^K_sOkgKG9H7xjfx?gmibWkh4{b^g2; zsgx{0l?wxC*^UQQq-zxBV0O=EuIW#bQ*y#%I`l3dm>L^pP=TaA@*E#Oc0XNfV0A#B zm@FE2)Pp2?p@ML3a4!tJY)gJ9pK*TtSi z_7M&NXnTV@Iw+@QsZHOK`8y^qxJ;*H_cm0as)R|b`IVhritHw|WwxW3iN){hLU=M7 zY`Yd|6%%t!etgI{>gT)V&N)x|k?C^t>eaaMnc;oQT-uRoMxTqlXBiX0n?xX<@6T|K zarL}ym#A(QXShSy{#O}$CQt?YxBBuiClJSnmYStWg?I+m$H}Y@0^YiN%Ra>Td*ZxJ zcMpdb6$?CCl-U}=XoJETQl)%h-gWwL)|pCHbKaaxMC0^M;v@UDW@Adqh4Gu-C*Sz4 z$UxDKi*b1_q348lgN^_a;mSni-6CFHF^e3t9grU?@0y*S!mgj6#++^Es2T5F=rT)+ zH%URY^9S&v>(i}yb2~XOO-i0R_(9O}Cvh(wqt%K?jONAFScZ?d?#F?QnZDzKnJ)Gj z=qwWUF%6uu!$979ps9ul`mp9?|NS0s4FVT8`O9W6OIr%s z4zka?sN~BeQ`eu*0jl$!SDblyY57Mxf4p|ShS2*6|NRq>qJ8SsVWr{1C-tkro2TDb zIF@l1ypb%DateJvLXv-N`luW`DK+V~sjZaFkuf}LZ@#_D{ouN2ID4u|JnxCb3X2LR z|Hk!8-Cu9iHKWO)2O;9L{B~#0ynNu-(%EP%6NLR|_bZHel71p5%k$T09yfIe#MQrL z!H$pu1CR7PkQC`M3h}B3p!ktsY}v#^<ax>P)aKRL@ckzx6)F?9p9|o&6EjpJF0e zQ~VG`tadf4Bac9*>BysUEbXlqj2+QtRIXY;T*;S8$(Xiar^VM36EGYjMOlgjhughUh*ezeUl7-;QLFxpg{Dkc zHvLoF9AV-#`pRuBFo*%~=`PAQn^|7OJ+!uPe4AjP`ap3W(Qm>J)7*;gdCLz`w@bcq zEda4k6l*AA>o~+frtE;~IF6%n$>qd{vcXDu6Xbu?lHhfZsWVY?nF@sCYR%x;GFz<= z5!qg8@uOdrpVi8jb7@3kTQ!#~&i?&;b2yVLh$48Q5e335o&3d#y+XM$_5V>^0R)$I zae0(Jf7nZ;U_mkL{DEB*8v8;5nED=0-`{g#SmYK53iL`K#^r1UF4hFACaolW=FTQ? zo6W3wXBmw0`Z?7-x%>y@RqSX=@2DBxeIFo`)nj$s zvOrlVH)b0_3-ubKmg349_)pMYUyn%VP~XmjrJ4)ZZK6@no269UKkQj^NY`X^GXEP| z_PP8BbI1Da9%{54chLRB&yk;UvI1jdAL#j-0OsfMHDSRiCeYw>N5hELetw9fI7s~6 znIYD@*SneY&EZ6Qi8#mEkMr8EmlBJSZN9u%3DFf$J61il7b@suLn$=X0*|!!;rSRx z=@p9R{Emk7a--j7?0nRsI3ELF?WM9Cl{GZ*^%|^`if2BozGW4Zfk4EH6Mm8NBV+0L z{MZs+IfYM1?j1bObJd6T2b8#}2g2rcW=D>KHGE=6}y4kGj~#gH;!wPlCe*UG4e5Jku+Hj-sGh$2zODKLw7o3Cr zMzv^P_4YrL(sHp^8D*e}m`af~?|GDNfj>Ygk9eFBP@IQ&evXV*?m12fL F{|}+<01E&B diff --git a/localization/autoware_localization_error_monitor/src/diagnostics.hpp b/localization/autoware_localization_error_monitor/src/diagnostics.hpp deleted file mode 100644 index bd92c28daad78..0000000000000 --- a/localization/autoware_localization_error_monitor/src/diagnostics.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 DIAGNOSTICS_HPP_ -#define DIAGNOSTICS_HPP_ - -#include - -#include -#include - -namespace autoware::localization_error_monitor -{ -diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy( - const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size); -diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy_lateral_direction( - const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size); - -diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( - const std::vector & stat_array); -} // namespace autoware::localization_error_monitor - -#endif // DIAGNOSTICS_HPP_ diff --git a/localization/autoware_localization_error_monitor/src/diagnostics.cpp b/localization/autoware_localization_error_monitor/src/diagnostics_helper.hpp similarity index 58% rename from localization/autoware_localization_error_monitor/src/diagnostics.cpp rename to localization/autoware_localization_error_monitor/src/diagnostics_helper.hpp index ef7f0faf12373..af038db5b1c11 100644 --- a/localization/autoware_localization_error_monitor/src/diagnostics.cpp +++ b/localization/autoware_localization_error_monitor/src/diagnostics_helper.hpp @@ -12,7 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "diagnostics.hpp" +#ifndef DIAGNOSTICS_HELPER_HPP_ +#define DIAGNOSTICS_HELPER_HPP_ #include @@ -21,16 +22,11 @@ namespace autoware::localization_error_monitor { -diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy( +inline diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy( const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size) { diagnostic_msgs::msg::DiagnosticStatus stat; - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = "localization_error_ellipse"; - key_value.value = std::to_string(ellipse_size); - stat.values.push_back(key_value); - stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; stat.message = "OK"; if (ellipse_size >= warn_ellipse_size) { @@ -45,16 +41,11 @@ diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy( return stat; } -diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy_lateral_direction( +inline diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy_lateral_direction( const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size) { diagnostic_msgs::msg::DiagnosticStatus stat; - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = "localization_error_ellipse_lateral_direction"; - key_value.value = std::to_string(ellipse_size); - stat.values.push_back(key_value); - stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; stat.message = "OK"; if (ellipse_size >= warn_ellipse_size) { @@ -69,31 +60,6 @@ diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy_lateral_direc return stat; } -// The highest level within the stat_array will be reflected in the merged_stat. -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::localization_error_monitor + +#endif // DIAGNOSTICS_HELPER_HPP_ 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 fb96a55dd0dc1..3f9a02834c74d 100644 --- a/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp +++ b/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp @@ -14,7 +14,7 @@ #include "localization_error_monitor.hpp" -#include "diagnostics.hpp" +#include "diagnostics_helper.hpp" #include @@ -56,36 +56,38 @@ LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & o ellipse_marker_pub_ = this->create_publisher("debug/ellipse_marker", durable_qos); - diag_pub_ = this->create_publisher("/diagnostics", 10); - logger_configure_ = std::make_unique(this); + + diagnostics_error_monitor_ = std::make_unique(this, "ellipse_error_status"); } void LocalizationErrorMonitor::on_odom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg) { + diagnostics_error_monitor_->clear(); + ellipse_ = autoware::localization_util::calculate_xy_ellipse(input_msg->pose, scale_); const auto ellipse_marker = autoware::localization_util::create_ellipse_marker( ellipse_, input_msg->header, input_msg->pose); ellipse_marker_pub_->publish(ellipse_marker); - // diagnostics - std::vector diag_status_array; - diag_status_array.push_back( - check_localization_accuracy(ellipse_.long_radius, warn_ellipse_size_, error_ellipse_size_)); - diag_status_array.push_back(check_localization_accuracy_lateral_direction( - ellipse_.size_lateral_direction, warn_ellipse_size_lateral_direction_, - error_ellipse_size_lateral_direction_)); + // update localization accuracy diagnostics + const auto accuracy_status = + check_localization_accuracy(ellipse_.long_radius, warn_ellipse_size_, error_ellipse_size_); + diagnostics_error_monitor_->add_key_value("localization_error_ellipse", ellipse_.long_radius); + diagnostics_error_monitor_->update_level_and_message( + accuracy_status.level, accuracy_status.message); - 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(); + // update lateral direction error diagnostics + const auto lateral_direction_status = check_localization_accuracy_lateral_direction( + ellipse_.size_lateral_direction, warn_ellipse_size_lateral_direction_, + error_ellipse_size_lateral_direction_); + diagnostics_error_monitor_->add_key_value( + "localization_error_ellipse_lateral_direction", ellipse_.size_lateral_direction); + diagnostics_error_monitor_->update_level_and_message( + lateral_direction_status.level, lateral_direction_status.message); - diagnostic_msgs::msg::DiagnosticArray diag_msg; - diag_msg.header.stamp = input_msg->header.stamp; - diag_msg.status.push_back(diag_merged_status); - diag_pub_->publish(diag_msg); + diagnostics_error_monitor_->publish(this->now()); } } // namespace autoware::localization_error_monitor 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 919951bca3998..49abacfa60f38 100644 --- a/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp +++ b/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp @@ -16,12 +16,12 @@ #define LOCALIZATION_ERROR_MONITOR_HPP_ #include "localization_util/covariance_ellipse.hpp" +#include "localization_util/diagnostics_module.hpp" #include #include #include -#include #include #include @@ -34,12 +34,13 @@ class LocalizationErrorMonitor : public rclcpp::Node private: rclcpp::Subscription::SharedPtr odom_sub_; rclcpp::Publisher::SharedPtr ellipse_marker_pub_; - rclcpp::Publisher::SharedPtr diag_pub_; rclcpp::TimerBase::SharedPtr timer_; std::unique_ptr logger_configure_; + std::unique_ptr diagnostics_error_monitor_; + double scale_; double error_ellipse_size_; double warn_ellipse_size_; diff --git a/localization/autoware_localization_error_monitor/test/test_diagnostics.cpp b/localization/autoware_localization_error_monitor/test/test_diagnostics.cpp index 1cc5640d78290..7d21a995e913e 100644 --- a/localization/autoware_localization_error_monitor/test/test_diagnostics.cpp +++ b/localization/autoware_localization_error_monitor/test/test_diagnostics.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "diagnostics.hpp" +#include "diagnostics_helper.hpp" #include @@ -81,65 +81,3 @@ TEST(TestLocalizationErrorMonitorDiagnostics, CheckLocalizationAccuracyLateralDi ellipse_size, warn_ellipse_size, error_ellipse_size); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); } - -TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus) -{ - 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 = autoware::localization_error_monitor::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 = autoware::localization_error_monitor::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 = autoware::localization_error_monitor::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 = autoware::localization_error_monitor::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 = autoware::localization_error_monitor::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 = autoware::localization_error_monitor::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 = autoware::localization_error_monitor::merge_diagnostic_status(stat_array); - EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); - EXPECT_EQ(merged_stat.message, "ERROR0; ERROR1"); -} diff --git a/system/system_diagnostic_monitor/config/localization.yaml b/system/system_diagnostic_monitor/config/localization.yaml index 62bf17775c3fb..1100f2edac67c 100644 --- a/system/system_diagnostic_monitor/config/localization.yaml +++ b/system/system_diagnostic_monitor/config/localization.yaml @@ -34,8 +34,8 @@ units: - path: /autoware/localization/accuracy type: diag - node: localization - name: localization_error_monitor + node: localization_error_monitor + name: ellipse_error_status - path: /autoware/localization/sensor_fusion_status type: diag diff --git a/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml index 14226a0371193..ff6a85d150ee8 100644 --- a/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml +++ b/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml @@ -27,7 +27,7 @@ localization_error_ellipse: type: diagnostic_aggregator/GenericAnalyzer path: localization_error_ellipse - contains: ["localization: localization_error_monitor"] + contains: ["localization_error_monitor: ellipse_error_status"] timeout: 1.0 localization_stability: From cea9357215019eae06e01688a664fe119b81eb35 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Wed, 11 Sep 2024 11:38:22 +0900 Subject: [PATCH 192/217] feat(autoware_lidar_transfusion): shuffled points before feeding them to the model (#8815) feat: shuffling points before feeding them into the model to achieve random sampling into the voxels Signed-off-by: Kenzo Lobos-Tsunekawa Co-authored-by: Amadeusz Szymko --- .../autoware/lidar_transfusion/cuda_utils.hpp | 14 +- .../lidar_transfusion/network/network_trt.hpp | 2 +- .../preprocess/pointcloud_densification.hpp | 6 +- .../preprocess/preprocess_kernel.hpp | 12 +- .../preprocess/voxel_generator.hpp | 4 +- .../lidar_transfusion/transfusion_trt.hpp | 2 + .../lib/preprocess/preprocess_kernel.cu | 140 ++++++++++++------ .../lib/transfusion_trt.cpp | 33 ++++- 8 files changed, 143 insertions(+), 70 deletions(-) diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/cuda_utils.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/cuda_utils.hpp index 17a7c7ee9c165..e9ad61cd1804b 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/cuda_utils.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/cuda_utils.hpp @@ -89,13 +89,13 @@ cuda::unique_ptr make_unique() return cuda::unique_ptr{p}; } -constexpr size_t CUDA_ALIGN = 256; +constexpr std::size_t CUDA_ALIGN = 256; template -inline size_t get_size_aligned(size_t num_elem) +inline std::size_t get_size_aligned(size_t num_elem) { - size_t size = num_elem * sizeof(T); - size_t extra_align = 0; + std::size_t size = num_elem * sizeof(T); + std::size_t extra_align = 0; if (size % CUDA_ALIGN != 0) { extra_align = CUDA_ALIGN - size % CUDA_ALIGN; } @@ -103,9 +103,9 @@ inline size_t get_size_aligned(size_t num_elem) } template -inline T * get_next_ptr(size_t num_elem, void *& workspace, size_t & workspace_size) +inline T * get_next_ptr(size_t num_elem, void *& workspace, std::size_t & workspace_size) { - size_t size = get_size_aligned(num_elem); + std::size_t size = get_size_aligned(num_elem); if (size > workspace_size) { throw ::std::runtime_error("Workspace is too small!"); } @@ -116,7 +116,7 @@ inline T * get_next_ptr(size_t num_elem, void *& workspace, size_t & workspace_s } template -void clear_async(T * ptr, size_t num_elem, cudaStream_t stream) +void clear_async(T * ptr, std::size_t num_elem, cudaStream_t stream) { CHECK_CUDA_ERROR(::cudaMemsetAsync(ptr, 0, sizeof(T) * num_elem, stream)); } 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 index d237361a436e2..1057703643ec1 100644 --- 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 @@ -63,7 +63,7 @@ class NetworkTRT private: bool parseONNX( const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - size_t workspace_size = (1ULL << 30)); + std::size_t workspace_size = (1ULL << 30)); bool saveEngine(const std::string & engine_path); bool loadEngine(const std::string & engine_path); bool createContext(); diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/pointcloud_densification.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/pointcloud_densification.hpp index 2d03978497f72..8c4a76ef3e080 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/pointcloud_densification.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/pointcloud_densification.hpp @@ -53,7 +53,7 @@ struct PointCloudWithTransform { cuda::unique_ptr data_d{nullptr}; std_msgs::msg::Header header; - size_t num_points{0}; + std::size_t num_points{0}; Eigen::Affine3f affine_past2world; }; @@ -75,11 +75,11 @@ class PointCloudDensification { return iter == pointcloud_cache_.end(); } - size_t getIdx(std::list::iterator iter) + std::size_t getIdx(std::list::iterator iter) { return std::distance(pointcloud_cache_.begin(), iter); } - size_t getCacheSize() + std::size_t getCacheSize() { return std::distance(pointcloud_cache_.begin(), pointcloud_cache_.end()); } diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/preprocess_kernel.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/preprocess_kernel.hpp index 1f5fe3ae3907f..eb45766f1d598 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/preprocess_kernel.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/preprocess_kernel.hpp @@ -49,6 +49,14 @@ class PreprocessCuda float * points, unsigned int points_size, unsigned int * pillar_num, float * voxel_features, unsigned int * voxel_num, unsigned int * voxel_idxs); + cudaError_t generateSweepPoints_launch( + const uint8_t * input_data, std::size_t points_size, int input_point_step, float time_lag, + const float * transform, float * output_points); + + cudaError_t shufflePoints_launch( + const float * points, const unsigned int * indices, float * shuffled_points, + const std::size_t points_size, const std::size_t max_size, const std::size_t offset); + cudaError_t generateVoxels_random_launch( float * points, unsigned int points_size, unsigned int * mask, float * voxels); @@ -56,10 +64,6 @@ class PreprocessCuda unsigned int * mask, float * voxels, unsigned int * pillar_num, float * voxel_features, unsigned int * voxel_num, unsigned int * voxel_idxs); - cudaError_t generateSweepPoints_launch( - const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, - const float * transform, float * output_points); - private: TransfusionConfig config_; cudaStream_t stream_; diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/voxel_generator.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/voxel_generator.hpp index 19bd8c14787de..9f32c27a8841b 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/voxel_generator.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/voxel_generator.hpp @@ -38,8 +38,8 @@ namespace autoware::lidar_transfusion { -constexpr size_t AFF_MAT_SIZE = 16; // 4x4 matrix -constexpr size_t MAX_CLOUD_STEP_SIZE = sizeof(autoware_point_types::PointXYZIRCAEDT); +constexpr std::size_t AFF_MAT_SIZE = 16; // 4x4 matrix +constexpr std::size_t MAX_CLOUD_STEP_SIZE = sizeof(autoware_point_types::PointXYZIRCAEDT); class VoxelGenerator { 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 4ba3474fc1d72..06dd65b4b805f 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 @@ -100,7 +100,9 @@ class LIDAR_TRANSFUSION_PUBLIC TransfusionTRT unsigned int box_size_{0}; unsigned int dir_cls_size_{0}; cuda::unique_ptr points_d_{nullptr}; + cuda::unique_ptr points_aux_d_{nullptr}; cuda::unique_ptr params_input_d_{nullptr}; + cuda::unique_ptr shuffle_indices_d_{nullptr}; cuda::unique_ptr voxel_features_d_{nullptr}; cuda::unique_ptr voxel_num_d_{nullptr}; cuda::unique_ptr voxel_idxs_d_{nullptr}; diff --git a/perception/autoware_lidar_transfusion/lib/preprocess/preprocess_kernel.cu b/perception/autoware_lidar_transfusion/lib/preprocess/preprocess_kernel.cu index 1b18b3dbcc006..49131218ff698 100644 --- a/perception/autoware_lidar_transfusion/lib/preprocess/preprocess_kernel.cu +++ b/perception/autoware_lidar_transfusion/lib/preprocess/preprocess_kernel.cu @@ -47,6 +47,97 @@ PreprocessCuda::PreprocessCuda(const TransfusionConfig & config, cudaStream_t & voxels_ = cuda::make_unique(voxels_size_); } +__global__ void generateSweepPoints_kernel( + const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, + const float * transform_array, int num_features, float * output_points) +{ + int point_idx = blockIdx.x * blockDim.x + threadIdx.x; + if (point_idx >= points_size) return; + + union { + uint32_t raw{0}; + float value; + } input_x, input_y, input_z; + +#pragma unroll + for (int i = 0; i < 4; i++) { // 4 bytes for float32 + input_x.raw |= input_data[point_idx * input_point_step + i] << i * 8; + input_y.raw |= input_data[point_idx * input_point_step + i + 4] << i * 8; + input_z.raw |= input_data[point_idx * input_point_step + i + 8] << i * 8; + } + + float input_intensity = static_cast(input_data[point_idx * input_point_step + 12]); + + output_points[point_idx * num_features] = + transform_array[0] * input_x.value + transform_array[4] * input_y.value + + transform_array[8] * input_z.value + transform_array[12]; + output_points[point_idx * num_features + 1] = + transform_array[1] * input_x.value + transform_array[5] * input_y.value + + transform_array[9] * input_z.value + transform_array[13]; + output_points[point_idx * num_features + 2] = + transform_array[2] * input_x.value + transform_array[6] * input_y.value + + transform_array[10] * input_z.value + transform_array[14]; + output_points[point_idx * num_features + 3] = input_intensity; + output_points[point_idx * num_features + 4] = time_lag; +} + +cudaError_t PreprocessCuda::generateSweepPoints_launch( + const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, + const float * transform_array, float * output_points) +{ + dim3 blocks(divup(points_size, config_.threads_for_voxel_)); + dim3 threads(config_.threads_for_voxel_); + + generateSweepPoints_kernel<<>>( + input_data, points_size, input_point_step, time_lag, transform_array, + config_.num_point_feature_size_, output_points); + + cudaError_t err = cudaGetLastError(); + return err; +} + +__global__ void shufflePoints_kernel( + const float * points, const unsigned int * indices, float * shuffled_points, + const std::size_t points_size, const std::size_t max_size, const std::size_t offset) +{ + int point_idx = blockIdx.x * blockDim.x + threadIdx.x; + if (point_idx >= max_size) return; + + int src_idx = indices[(point_idx + offset) % max_size]; + int dst_idx = point_idx; + + if (dst_idx >= points_size) { + shuffled_points[5 * dst_idx + 0] = INFINITY; + shuffled_points[5 * dst_idx + 1] = INFINITY; + shuffled_points[5 * dst_idx + 2] = INFINITY; + shuffled_points[5 * dst_idx + 3] = INFINITY; + shuffled_points[5 * dst_idx + 4] = INFINITY; + } else { + shuffled_points[5 * dst_idx + 0] = points[5 * src_idx + 0]; + shuffled_points[5 * dst_idx + 1] = points[5 * src_idx + 1]; + shuffled_points[5 * dst_idx + 2] = points[5 * src_idx + 2]; + shuffled_points[5 * dst_idx + 3] = points[5 * src_idx + 3]; + shuffled_points[5 * dst_idx + 4] = points[5 * src_idx + 4]; + } +} + +cudaError_t PreprocessCuda::shufflePoints_launch( + const float * points, const unsigned int * indices, float * shuffled_points, + const std::size_t points_size, const std::size_t max_size, const std::size_t offset) +{ + dim3 blocks(divup(points_size, config_.threads_for_voxel_)); + dim3 threads(config_.threads_for_voxel_); + + if (blocks.x == 0) { + return cudaGetLastError(); + } + + shufflePoints_kernel<<>>( + points, indices, shuffled_points, points_size, max_size, offset); + cudaError_t err = cudaGetLastError(); + return err; +} + void PreprocessCuda::generateVoxels( float * points, unsigned int points_size, unsigned int * pillar_num, float * voxel_features, unsigned int * voxel_num, unsigned int * voxel_idxs) @@ -169,53 +260,4 @@ cudaError_t PreprocessCuda::generateBaseFeatures_launch( return err; } -__global__ void generateSweepPoints_kernel( - const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, - const float * transform_array, int num_features, float * output_points) -{ - int point_idx = blockIdx.x * blockDim.x + threadIdx.x; - if (point_idx >= points_size) return; - - union { - uint32_t raw{0}; - float value; - } input_x, input_y, input_z; - -#pragma unroll - for (int i = 0; i < 4; i++) { // 4 bytes for float32 - input_x.raw |= input_data[point_idx * input_point_step + i] << i * 8; - input_y.raw |= input_data[point_idx * input_point_step + i + 4] << i * 8; - input_z.raw |= input_data[point_idx * input_point_step + i + 8] << i * 8; - } - - float input_intensity = static_cast(input_data[point_idx * input_point_step + 12]); - - output_points[point_idx * num_features] = - transform_array[0] * input_x.value + transform_array[4] * input_y.value + - transform_array[8] * input_z.value + transform_array[12]; - output_points[point_idx * num_features + 1] = - transform_array[1] * input_x.value + transform_array[5] * input_y.value + - transform_array[9] * input_z.value + transform_array[13]; - output_points[point_idx * num_features + 2] = - transform_array[2] * input_x.value + transform_array[6] * input_y.value + - transform_array[10] * input_z.value + transform_array[14]; - output_points[point_idx * num_features + 3] = input_intensity; - output_points[point_idx * num_features + 4] = time_lag; -} - -cudaError_t PreprocessCuda::generateSweepPoints_launch( - const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, - const float * transform_array, float * output_points) -{ - dim3 blocks(divup(points_size, config_.threads_for_voxel_)); - dim3 threads(config_.threads_for_voxel_); - - generateSweepPoints_kernel<<>>( - input_data, points_size, input_point_step, time_lag, transform_array, - config_.num_point_feature_size_, output_points); - - cudaError_t err = cudaGetLastError(); - return err; -} - } // 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 94760d4d91720..42e017a2dfdda 100644 --- a/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp +++ b/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp @@ -19,8 +19,12 @@ #include +#include +#include +#include #include #include +#include #include #include @@ -74,6 +78,22 @@ void TransfusionTRT::initPtr() voxel_num_d_ = cuda::make_unique(voxel_num_size_); voxel_idxs_d_ = cuda::make_unique(voxel_idxs_size_); points_d_ = cuda::make_unique(config_.cloud_capacity_ * config_.num_point_feature_size_); + points_aux_d_ = + cuda::make_unique(config_.cloud_capacity_ * config_.num_point_feature_size_); + shuffle_indices_d_ = cuda::make_unique(config_.cloud_capacity_); + + std::vector indexes(config_.cloud_capacity_); + std::iota(indexes.begin(), indexes.end(), 0); + + std::default_random_engine e(0); + std::shuffle(indexes.begin(), indexes.end(), e); + + std::srand(std::time(nullptr)); + + CHECK_CUDA_ERROR(cudaMemcpyAsync( + shuffle_indices_d_.get(), indexes.data(), config_.cloud_capacity_ * sizeof(unsigned int), + cudaMemcpyHostToDevice, stream_)); + pre_ptr_ = std::make_unique(config_, stream_); post_ptr_ = std::make_unique(config_, stream_); } @@ -125,15 +145,20 @@ bool TransfusionTRT::preprocess( cuda::clear_async(voxel_idxs_d_.get(), voxel_idxs_size_, stream_); cuda::clear_async(params_input_d_.get(), 1, stream_); cuda::clear_async( - points_d_.get(), config_.cloud_capacity_ * config_.num_point_feature_size_, stream_); + points_aux_d_.get(), config_.cloud_capacity_ * config_.num_point_feature_size_, stream_); CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); - const auto count = vg_ptr_->generateSweepPoints(msg, points_d_); + const auto count = vg_ptr_->generateSweepPoints(msg, points_aux_d_); RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lidar_transfusion"), "Generated sweep points: " << count); + const std::size_t random_offset = std::rand() % config_.cloud_capacity_; + pre_ptr_->shufflePoints_launch( + points_aux_d_.get(), shuffle_indices_d_.get(), points_d_.get(), count, config_.cloud_capacity_, + random_offset); + pre_ptr_->generateVoxels( - points_d_.get(), count, params_input_d_.get(), voxel_features_d_.get(), voxel_num_d_.get(), - voxel_idxs_d_.get()); + points_d_.get(), config_.cloud_capacity_, params_input_d_.get(), voxel_features_d_.get(), + voxel_num_d_.get(), voxel_idxs_d_.get()); unsigned int params_input; CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); From 8802025ff09745539d90fb127485932aeb1cb431 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 11 Sep 2024 12:36:44 +0900 Subject: [PATCH 193/217] fix(autoware_behavior_velocity_intersection_module): fix virtualCallInConstructor (#8835) fix:virtualCallInConstructor Signed-off-by: kobayu858 --- .../src/manager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 d3a75a6817a9d..18fee7b736dac 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 @@ -471,7 +471,7 @@ void IntersectionModuleManager::deleteExpiredModules( MergeFromPrivateModuleManager::MergeFromPrivateModuleManager(rclcpp::Node & node) : SceneModuleManagerInterface(node, getModuleName()) { - const std::string ns(getModuleName()); + const std::string ns(MergeFromPrivateModuleManager::getModuleName()); auto & mp = merge_from_private_area_param_; mp.stop_duration_sec = getOrDeclareParameter(node, ns + ".stop_duration_sec"); mp.attention_area_length = From f4de4f359b9a22837a65b67d1d96278a11e49d92 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 11 Sep 2024 12:37:13 +0900 Subject: [PATCH 194/217] fix(autoware_behavior_velocity_intersection_module): fix unreadVariable (#8836) fix:unreadVariable Signed-off-by: kobayu858 --- .../src/manager.cpp | 1 - 1 file changed, 1 deletion(-) 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 18fee7b736dac..8efef723295b3 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 @@ -327,7 +327,6 @@ void IntersectionModuleManager::launchNewModules( continue; } - const std::string location = ll.attributeOr("location", "else"); const auto associative_ids = planning_utils::getAssociativeIntersectionLanelets(ll, lanelet_map, routing_graph); bool has_traffic_light = false; From 55a59dd5eb9c7300d65e7be860c2f7ba8afc94dd Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 11 Sep 2024 12:38:03 +0900 Subject: [PATCH 195/217] fix(tier4_dummy_object_rviz_plugin): fix unusedFunction (#8844) fix:unusedFunction Signed-off-by: kobayu858 --- .../src/tools/delete_all_objects.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.cpp index 40984facf4459..91a1f544c25e8 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.cpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.cpp @@ -78,6 +78,7 @@ void DeleteAllObjectsTool::updateTopic() clock_ = raw_node->get_clock(); } +// cppcheck-suppress unusedFunction void DeleteAllObjectsTool::onPoseSet( [[maybe_unused]] double x, [[maybe_unused]] double y, [[maybe_unused]] double theta) { From a82865ec24b40043decea73d360bfda55e4dbca6 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 11 Sep 2024 12:38:29 +0900 Subject: [PATCH 196/217] fix(tier4_state_rviz_plugin): fix unusedFunction (#8845) * fix:unusedFunction Signed-off-by: kobayu858 * fix:unusedFunction Signed-off-by: kobayu858 * fix:revert Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/include/autoware_state_panel.hpp | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/common/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp index c1ab9018e12f9..3c106467b9beb 100644 --- a/common/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp @@ -223,17 +223,6 @@ public Q_SLOTS: // NOLINT for Qt label->setText(text); label->setStyleSheet(style_sheet); } - static void updateCustomLabel( - CustomLabel * label, QString text, QColor bg_color, QColor text_color) - { - label->updateStyle(text, bg_color, text_color); - } - - static void updateButton(QPushButton * button, QString text, QString style_sheet) - { - button->setText(text); - button->setStyleSheet(style_sheet); - } static void activateButton(QAbstractButton * button) { From f2a46a959dc0d1680d1312f8234212f29c706dfb Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 11 Sep 2024 12:38:44 +0900 Subject: [PATCH 197/217] fix(tier4_state_rviz_plugin): fix unusedFunction (#8841) fix:unusedFunction Signed-off-by: kobayu858 --- common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index 738fac93d3705..8109be3d7aca6 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -24,11 +24,6 @@ #include #include -inline std::string Bool2String(const bool var) -{ - return var ? "True" : "False"; -} - namespace rviz_plugins { AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(parent) From 3ef3cd99f4c5f1dd039e05b623c6574ebd36cc69 Mon Sep 17 00:00:00 2001 From: Mitsuhiro Sakamoto <50359861+mitukou1109@users.noreply.github.com> Date: Wed, 11 Sep 2024 12:46:56 +0900 Subject: [PATCH 198/217] feat(external_velocity_limit_selector): integrate generate_parameter_library (#8770) * add parameter description Signed-off-by: mitukou1109 * use parameter listener Signed-off-by: mitukou1109 --------- Signed-off-by: mitukou1109 --- .../CMakeLists.txt | 8 +++++ .../external_velocity_limit_selector_node.hpp | 18 ++-------- .../package.xml | 1 + ...al_velocity_limit_selector_parameters.yaml | 30 ++++++++++++++++ .../external_velocity_limit_selector_node.cpp | 36 ++++++++----------- 5 files changed, 55 insertions(+), 38 deletions(-) create mode 100644 planning/autoware_external_velocity_limit_selector/param/external_velocity_limit_selector_parameters.yaml diff --git a/planning/autoware_external_velocity_limit_selector/CMakeLists.txt b/planning/autoware_external_velocity_limit_selector/CMakeLists.txt index 40f0ebb2a3eba..ca758d1262b48 100644 --- a/planning/autoware_external_velocity_limit_selector/CMakeLists.txt +++ b/planning/autoware_external_velocity_limit_selector/CMakeLists.txt @@ -4,10 +4,18 @@ project(autoware_external_velocity_limit_selector) find_package(autoware_cmake REQUIRED) autoware_package() +generate_parameter_library(external_velocity_limit_selector_parameters + param/external_velocity_limit_selector_parameters.yaml +) + ament_auto_add_library(external_velocity_limit_selector_node SHARED src/external_velocity_limit_selector_node.cpp ) +target_link_libraries(external_velocity_limit_selector_node + external_velocity_limit_selector_parameters +) + rclcpp_components_register_node(external_velocity_limit_selector_node PLUGIN "autoware::external_velocity_limit_selector::ExternalVelocityLimitSelectorNode" EXECUTABLE external_velocity_limit_selector 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 ab27f3727e847..2aa06079dadbc 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 @@ -15,6 +15,7 @@ #ifndef AUTOWARE__EXTERNAL_VELOCITY_LIMIT_SELECTOR__EXTERNAL_VELOCITY_LIMIT_SELECTOR_NODE_HPP_ #define AUTOWARE__EXTERNAL_VELOCITY_LIMIT_SELECTOR__EXTERNAL_VELOCITY_LIMIT_SELECTOR_NODE_HPP_ +#include #include #include @@ -45,21 +46,6 @@ class ExternalVelocityLimitSelectorNode : public rclcpp::Node void onVelocityLimitFromInternal(const VelocityLimit::ConstSharedPtr msg); void onVelocityLimitClearCommand(const VelocityLimitClearCommand::ConstSharedPtr msg); - struct NodeParam - { - double max_velocity; - // constraints for normal driving - double normal_min_acc; - double normal_max_acc; - double normal_min_jerk; - double normal_max_jerk; - // constraints to be observed - double limit_min_acc; - double limit_max_acc; - double limit_min_jerk; - double limit_max_jerk; - }; - private: rclcpp::Subscription::SharedPtr sub_external_velocity_limit_from_api_; rclcpp::Subscription::SharedPtr sub_external_velocity_limit_from_internal_; @@ -76,7 +62,7 @@ class ExternalVelocityLimitSelectorNode : public rclcpp::Node VelocityLimit getCurrentVelocityLimit() { return hardest_limit_; } // Parameters - NodeParam node_param_{}; + std::shared_ptr<::external_velocity_limit_selector::ParamListener> param_listener_; VelocityLimit hardest_limit_{}; VelocityLimitTable velocity_limit_table_; }; diff --git a/planning/autoware_external_velocity_limit_selector/package.xml b/planning/autoware_external_velocity_limit_selector/package.xml index 803e32237e938..c04ccef871626 100644 --- a/planning/autoware_external_velocity_limit_selector/package.xml +++ b/planning/autoware_external_velocity_limit_selector/package.xml @@ -17,6 +17,7 @@ ament_cmake_auto autoware_cmake + generate_parameter_library rclcpp rclcpp_components tier4_debug_msgs diff --git a/planning/autoware_external_velocity_limit_selector/param/external_velocity_limit_selector_parameters.yaml b/planning/autoware_external_velocity_limit_selector/param/external_velocity_limit_selector_parameters.yaml new file mode 100644 index 0000000000000..dd99a87ee1a29 --- /dev/null +++ b/planning/autoware_external_velocity_limit_selector/param/external_velocity_limit_selector_parameters.yaml @@ -0,0 +1,30 @@ +external_velocity_limit_selector: + max_vel: + type: double + description: Default max velocity [m/s] + normal: + min_acc: + type: double + description: Minimum deceleration [m/ss] + max_acc: + type: double + description: Maximum deceleration [m/ss] + min_jerk: + type: double + description: Minimum jerk [m/sss] + max_jerk: + type: double + description: Maximum jerk [m/sss] + limit: + min_acc: + type: double + description: Minimum acceleration to be observed [m/ss] + max_acc: + type: double + description: Maximum acceleration to be observed [m/ss] + min_jerk: + type: double + description: Minimum jerk to be observed [m/sss] + max_jerk: + type: double + description: Maximum jerk to be observed [m/sss] 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 f2038a11362b5..2052c8438bcfa 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 @@ -28,23 +28,23 @@ namespace { VelocityLimit getHardestLimit( const VelocityLimitTable & velocity_limits, - const ExternalVelocityLimitSelectorNode::NodeParam & node_param) + const ::external_velocity_limit_selector::Params & node_param) { VelocityLimit hardest_limit{}; - hardest_limit.max_velocity = node_param.max_velocity; + hardest_limit.max_velocity = node_param.max_vel; VelocityLimitConstraints normal_constraints{}; - normal_constraints.min_acceleration = node_param.normal_min_acc; - normal_constraints.min_jerk = node_param.normal_min_jerk; - normal_constraints.max_jerk = node_param.normal_max_jerk; + normal_constraints.min_acceleration = node_param.normal.min_acc; + normal_constraints.min_jerk = node_param.normal.min_jerk; + normal_constraints.max_jerk = node_param.normal.max_jerk; - double hardest_max_velocity = node_param.max_velocity; + double hardest_max_velocity = node_param.max_vel; double hardest_max_jerk = 0.0; for (const auto & limit : velocity_limits) { // guard nan, inf - const auto max_velocity = std::isfinite(limit.second.max_velocity) ? limit.second.max_velocity - : node_param.max_velocity; + const auto max_velocity = + std::isfinite(limit.second.max_velocity) ? limit.second.max_velocity : node_param.max_vel; // find hardest max velocity if (max_velocity < hardest_max_velocity) { @@ -113,18 +113,8 @@ ExternalVelocityLimitSelectorNode::ExternalVelocityLimitSelectorNode( pub_debug_string_ = this->create_publisher("output/debug", 1); // Params - { - auto & p = node_param_; - p.max_velocity = this->declare_parameter("max_vel"); - p.normal_min_acc = this->declare_parameter("normal.min_acc"); - p.normal_max_acc = this->declare_parameter("normal.max_acc"); - p.normal_min_jerk = this->declare_parameter("normal.min_jerk"); - p.normal_max_jerk = this->declare_parameter("normal.max_jerk"); - p.limit_min_acc = this->declare_parameter("limit.min_acc"); - p.limit_max_acc = this->declare_parameter("limit.max_acc"); - p.limit_min_jerk = this->declare_parameter("limit.min_jerk"); - p.limit_max_jerk = this->declare_parameter("limit.max_jerk"); - } + param_listener_ = std::make_shared<::external_velocity_limit_selector::ParamListener>( + this->get_node_parameters_interface()); } void ExternalVelocityLimitSelectorNode::onVelocityLimitFromAPI( @@ -223,10 +213,12 @@ void ExternalVelocityLimitSelectorNode::clearVelocityLimit(const std::string & s void ExternalVelocityLimitSelectorNode::updateVelocityLimit() { + const auto param = param_listener_->get_params(); + if (velocity_limit_table_.empty()) { VelocityLimit default_velocity_limit{}; default_velocity_limit.stamp = this->now(); - default_velocity_limit.max_velocity = node_param_.max_velocity; + default_velocity_limit.max_velocity = param.max_vel; hardest_limit_ = default_velocity_limit; @@ -237,7 +229,7 @@ void ExternalVelocityLimitSelectorNode::updateVelocityLimit() return; } - hardest_limit_ = getHardestLimit(velocity_limit_table_, node_param_); + hardest_limit_ = getHardestLimit(velocity_limit_table_, param); } } // namespace autoware::external_velocity_limit_selector From 31d93a1b5f298bc3e841c3d69e3efa42392f3410 Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Wed, 11 Sep 2024 13:48:36 +0900 Subject: [PATCH 199/217] fix(control): align the parameters with launcher (#8789) align the control parameters Signed-off-by: Zhe Shen --- .../config/autonomous_emergency_braking.param.yaml | 10 +++++----- .../config/control_validator.param.yaml | 2 +- .../config/lane_departure_checker.param.yaml | 8 ++++---- .../param/lateral/mpc.param.yaml | 4 ++-- .../param/longitudinal/pid.param.yaml | 2 +- .../config/vehicle_cmd_gate.param.yaml | 2 +- .../config/obstacle_collision_checker.param.yaml | 4 ++-- 7 files changed, 16 insertions(+), 16 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml index f13e95c6db8e5..d5c6356c38897 100644 --- a/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml +++ b/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml @@ -2,15 +2,15 @@ ros__parameters: # Ego path calculation use_predicted_trajectory: true - use_imu_path: false + use_imu_path: true use_pointcloud_data: true - use_predicted_object_data: true + use_predicted_object_data: false use_object_velocity_calculation: true check_autoware_state: true min_generated_path_length: 0.5 imu_prediction_time_horizon: 1.5 imu_prediction_time_interval: 0.1 - mpc_prediction_time_horizon: 1.5 + mpc_prediction_time_horizon: 4.5 mpc_prediction_time_interval: 0.1 # Debug @@ -29,8 +29,8 @@ path_footprint_extra_margin: 4.0 # Point cloud clustering - cluster_tolerance: 0.1 #[m] - cluster_minimum_height: 0.0 + cluster_tolerance: 0.15 #[m] + cluster_minimum_height: 0.1 minimum_cluster_size: 10 maximum_cluster_size: 10000 diff --git a/control/autoware_control_validator/config/control_validator.param.yaml b/control/autoware_control_validator/config/control_validator.param.yaml index fdac1d15b58b2..2735a7e935ddc 100644 --- a/control/autoware_control_validator/config/control_validator.param.yaml +++ b/control/autoware_control_validator/config/control_validator.param.yaml @@ -5,7 +5,7 @@ # the next trajectory is valid.) diag_error_count_threshold: 0 - display_on_terminal: true # show error msg on terminal + display_on_terminal: false # show error msg on terminal thresholds: max_distance_deviation: 1.0 diff --git a/control/autoware_lane_departure_checker/config/lane_departure_checker.param.yaml b/control/autoware_lane_departure_checker/config/lane_departure_checker.param.yaml index 2724c28e2536a..84741ae396d07 100644 --- a/control/autoware_lane_departure_checker/config/lane_departure_checker.param.yaml +++ b/control/autoware_lane_departure_checker/config/lane_departure_checker.param.yaml @@ -1,9 +1,9 @@ /**: ros__parameters: # Enable feature - will_out_of_lane_checker: true - out_of_lane_checker: true - boundary_departure_checker: false + will_out_of_lane_checker: false + out_of_lane_checker: false + boundary_departure_checker: true # Node update_rate: 10.0 @@ -12,7 +12,7 @@ include_left_lanes: false include_opposite_lanes: false include_conflicting_lanes: false - boundary_types_to_detect: [road_border] + boundary_types_to_detect: [curbstone] # Core 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 166bd9f1e8ad8..b358e95f86f99 100644 --- a/control/autoware_trajectory_follower_node/param/lateral/mpc.param.yaml +++ b/control/autoware_trajectory_follower_node/param/lateral/mpc.param.yaml @@ -14,7 +14,7 @@ curvature_smoothing_num_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num) # -- trajectory extending -- - extend_trajectory_for_end_yaw_control: true # flag of trajectory extending for terminal yaw control + extend_trajectory_for_end_yaw_control: false # flag of trajectory extending for terminal yaw control # -- mpc optimization -- qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp) @@ -47,7 +47,7 @@ # -- vehicle model -- vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics input_delay: 0.24 # steering input delay time for delay compensation - vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approximation) [s] + vehicle_model_steer_tau: 0.27 # steering dynamics time constant (1d approximation) [s] steer_rate_lim_dps_list_by_curvature: [40.0, 50.0, 60.0] # steering angle rate limit list depending on curvature [deg/s] curvature_list_for_steer_rate_lim: [0.001, 0.002, 0.01] # curvature list for steering angle rate limit interpolation in ascending order [/m] steer_rate_lim_dps_list_by_velocity: [60.0, 50.0, 40.0] # steering angle rate limit list depending on velocity [deg/s] 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 68fb172b19d2a..5c5d65a13b2d5 100644 --- a/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml +++ b/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - delay_compensation_time: 0.17 + delay_compensation_time: 0.1 enable_smooth_stop: true enable_overshoot_emergency: true diff --git a/control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml b/control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml index 526c4bb4b3d52..8b11cdb85a0b9 100644 --- a/control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml +++ b/control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml @@ -2,7 +2,7 @@ ros__parameters: update_rate: 10.0 system_emergency_heartbeat_timeout: 0.5 - use_emergency_handling: false + use_emergency_handling: true check_external_emergency_heartbeat: $(var check_external_emergency_heartbeat) enable_cmd_limit_filter: true filter_activated_count_threshold: 5 diff --git a/control/obstacle_collision_checker/config/obstacle_collision_checker.param.yaml b/control/obstacle_collision_checker/config/obstacle_collision_checker.param.yaml index 883b4d8259f49..e3c78c90e2ed1 100644 --- a/control/obstacle_collision_checker/config/obstacle_collision_checker.param.yaml +++ b/control/obstacle_collision_checker/config/obstacle_collision_checker.param.yaml @@ -4,8 +4,8 @@ update_rate: 10.0 # Core - delay_time: 0.3 # delay time of vehicle [s] + delay_time: 0.03 # delay time of vehicle [s] footprint_margin: 0.0 # margin for footprint [m] - max_deceleration: 2.0 # max deceleration [m/ss] + max_deceleration: 1.5 # max deceleration [m/ss] resample_interval: 0.3 # interval distance to resample point cloud [m] search_radius: 5.0 # search distance from trajectory to point cloud [m] From bfdec4257f5b4149f8a5c0722beced7110016659 Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Wed, 11 Sep 2024 13:48:52 +0900 Subject: [PATCH 200/217] fix(other_planning_packages): align the parameters with launcher (#8793) * parameters in planning/others aligned Signed-off-by: Zhe Shen * update json Signed-off-by: Zhe Shen --------- Signed-off-by: Zhe Shen --- .../config/costmap_generator.param.yaml | 4 ++-- .../config/freespace_planner.param.yaml | 14 +++++++------- .../config/common.param.yaml | 4 ++-- .../config/obstacle_stop_planner.param.yaml | 10 ++++------ .../schema/obstacle_stop_planner.schema.json | 12 ------------ .../config/common.param.yaml | 4 ++-- .../config/surround_obstacle_checker.param.yaml | 14 +++++++------- 7 files changed, 24 insertions(+), 38 deletions(-) diff --git a/planning/autoware_costmap_generator/config/costmap_generator.param.yaml b/planning/autoware_costmap_generator/config/costmap_generator.param.yaml index 5dbd1e3380c20..dc2e74deb3ef9 100644 --- a/planning/autoware_costmap_generator/config/costmap_generator.param.yaml +++ b/planning/autoware_costmap_generator/config/costmap_generator.param.yaml @@ -7,7 +7,7 @@ activate_by_scenario: false grid_min_value: 0.0 grid_max_value: 1.0 - grid_resolution: 0.2 + grid_resolution: 0.3 grid_length_x: 70.0 grid_length_y: 70.0 grid_position_x: 0.0 @@ -18,5 +18,5 @@ use_parkinglot: true use_objects: true use_points: true - expand_polygon_size: 1.0 + expand_polygon_size: 0.5 size_of_expansion_kernel: 9 diff --git a/planning/autoware_freespace_planner/config/freespace_planner.param.yaml b/planning/autoware_freespace_planner/config/freespace_planner.param.yaml index b34ffe698aa36..2a483b109662a 100644 --- a/planning/autoware_freespace_planner/config/freespace_planner.param.yaml +++ b/planning/autoware_freespace_planner/config/freespace_planner.param.yaml @@ -9,7 +9,7 @@ th_stopped_velocity_mps: 0.01 th_course_out_distance_m: 1.0 th_obstacle_time_sec: 1.0 - vehicle_shape_margin_m: 1.0 + vehicle_shape_margin_m: 0.5 replan_when_obstacle_found: true replan_when_course_out: true @@ -19,13 +19,13 @@ max_turning_ratio: 0.5 # ratio of actual turning limit of vehicle turning_steps: 1 # search configs - theta_size: 144 + theta_size: 120 angle_goal_range: 6.0 lateral_goal_range: 0.5 longitudinal_goal_range: 1.0 curve_weight: 0.5 - reverse_weight: 1.0 - direction_change_weight: 1.5 + reverse_weight: 0.7 + direction_change_weight: 2.0 # costmap configs obstacle_threshold: 100 @@ -36,10 +36,10 @@ use_back: true adapt_expansion_distance: true expansion_distance: 0.5 - near_goal_distance: 4.0 - distance_heuristic_weight: 1.5 + near_goal_distance: 3.0 + distance_heuristic_weight: 2.0 smoothness_weight: 0.5 - obstacle_distance_weight: 1.5 + obstacle_distance_weight: 1.75 goal_lat_distance_weight: 5.0 # -- RRT* search Configurations -- diff --git a/planning/autoware_obstacle_stop_planner/config/common.param.yaml b/planning/autoware_obstacle_stop_planner/config/common.param.yaml index be0667c158878..6c547c8cd83dc 100644 --- a/planning/autoware_obstacle_stop_planner/config/common.param.yaml +++ b/planning/autoware_obstacle_stop_planner/config/common.param.yaml @@ -4,9 +4,9 @@ max_vel: 11.1 # max velocity limit [m/s] normal: - min_acc: -0.5 # min deceleration [m/ss] + min_acc: -1.0 # min deceleration [m/ss] max_acc: 1.0 # max acceleration [m/ss] - min_jerk: -0.5 # min jerk [m/sss] + min_jerk: -1.0 # min jerk [m/sss] max_jerk: 1.0 # max jerk [m/sss] # constraints to be observed diff --git a/planning/autoware_obstacle_stop_planner/config/obstacle_stop_planner.param.yaml b/planning/autoware_obstacle_stop_planner/config/obstacle_stop_planner.param.yaml index 96d94b98769db..ca5869bce0eb6 100644 --- a/planning/autoware_obstacle_stop_planner/config/obstacle_stop_planner.param.yaml +++ b/planning/autoware_obstacle_stop_planner/config/obstacle_stop_planner.param.yaml @@ -2,8 +2,6 @@ ros__parameters: chattering_threshold: 0.5 # even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] max_velocity: 20.0 # max velocity [m/s] - ego_nearest_dist_threshold: 3.0 # [m] - ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg] enable_slow_down: False # whether to use slow down planner [-] enable_z_axis_obstacle_filtering: True # filter obstacles in z axis (height) [-] z_axis_filtering_buffer: 0.0 # additional buffer for z axis filtering [m] @@ -18,8 +16,8 @@ # params for stop position stop_position: max_longitudinal_margin: 5.0 # stop margin distance from obstacle on the path [m] - max_longitudinal_margin_behind_goal: 3.0 # stop margin distance from obstacle behind the goal on the path [m] - min_longitudinal_margin: 2.0 # stop margin distance when any other stop point is inserted in stop margin [m] + max_longitudinal_margin_behind_goal: 2.5 # stop margin distance from obstacle behind the goal on the path [m] + min_longitudinal_margin: 5.0 # stop margin distance when any other stop point is inserted in stop margin [m] hold_stop_margin_distance: 0.0 # the ego keeps stopping if the ego is in this margin [m] # params for detection area @@ -36,7 +34,7 @@ # params for slow down section slow_down_section: longitudinal_forward_margin: 5.0 # margin distance from slow down point to vehicle front [m] - longitudinal_backward_margin: 5.0 # margin distance from slow down point to vehicle rear [m] + longitudinal_backward_margin: 0.0 # margin distance from slow down point to vehicle rear [m] longitudinal_margin_span: -0.1 # fineness param for relaxing slow down margin (use this param if consider_constraints is True) [m/s] min_longitudinal_forward_margin: 1.0 # min margin for relaxing slow down margin (use this param if consider_constraints is True) [m/s] @@ -55,7 +53,7 @@ # params for deceleration constraints (use this param if consider_constraints is True) constraints: - jerk_min_slow_down: -0.3 # min slow down jerk constraint [m/sss] + jerk_min_slow_down: -0.6 # min slow down jerk constraint [m/sss] jerk_span: -0.01 # fineness param for planning deceleration jerk [m/sss] jerk_start: -0.1 # init jerk used for deceleration planning [m/sss] diff --git a/planning/autoware_obstacle_stop_planner/schema/obstacle_stop_planner.schema.json b/planning/autoware_obstacle_stop_planner/schema/obstacle_stop_planner.schema.json index 868f669ad2004..cb2765233c5a0 100644 --- a/planning/autoware_obstacle_stop_planner/schema/obstacle_stop_planner.schema.json +++ b/planning/autoware_obstacle_stop_planner/schema/obstacle_stop_planner.schema.json @@ -16,16 +16,6 @@ "description": "max velocity [m/s]", "default": "20.0" }, - "ego_nearest_dist_threshold": { - "type": "number", - "description": "[m]", - "default": "3.0" - }, - "ego_nearest_yaw_threshold": { - "type": "number", - "description": "[rad] = 60 [deg]", - "default": "1.046" - }, "enable_slow_down": { "type": "boolean", "description": "whether to use slow down planner [-]", @@ -288,8 +278,6 @@ "required": [ "chattering_threshold", "max_velocity", - "ego_nearest_dist_threshold", - "ego_nearest_yaw_threshold", "enable_slow_down", "enable_z_axis_obstacle_filtering", "z_axis_filtering_buffer", diff --git a/planning/autoware_static_centerline_generator/config/common.param.yaml b/planning/autoware_static_centerline_generator/config/common.param.yaml index be0667c158878..6c547c8cd83dc 100644 --- a/planning/autoware_static_centerline_generator/config/common.param.yaml +++ b/planning/autoware_static_centerline_generator/config/common.param.yaml @@ -4,9 +4,9 @@ max_vel: 11.1 # max velocity limit [m/s] normal: - min_acc: -0.5 # min deceleration [m/ss] + min_acc: -1.0 # min deceleration [m/ss] max_acc: 1.0 # max acceleration [m/ss] - min_jerk: -0.5 # min jerk [m/sss] + min_jerk: -1.0 # min jerk [m/sss] max_jerk: 1.0 # max jerk [m/sss] # constraints to be observed diff --git a/planning/autoware_surround_obstacle_checker/config/surround_obstacle_checker.param.yaml b/planning/autoware_surround_obstacle_checker/config/surround_obstacle_checker.param.yaml index 5ec10572ffe83..7f72420b3a6fd 100644 --- a/planning/autoware_surround_obstacle_checker/config/surround_obstacle_checker.param.yaml +++ b/planning/autoware_surround_obstacle_checker/config/surround_obstacle_checker.param.yaml @@ -9,7 +9,7 @@ surround_check_side_distance: 0.5 surround_check_back_distance: 0.5 unknown: - enable_check: true + enable_check: false surround_check_front_distance: 0.5 surround_check_side_distance: 0.5 surround_check_back_distance: 0.5 @@ -17,22 +17,22 @@ enable_check: true surround_check_front_distance: 0.5 surround_check_side_distance: 0.0 - surround_check_back_distance: 0.5 + surround_check_back_distance: 0.0 truck: enable_check: true surround_check_front_distance: 0.5 surround_check_side_distance: 0.0 - surround_check_back_distance: 0.5 + surround_check_back_distance: 0.0 bus: enable_check: true surround_check_front_distance: 0.5 surround_check_side_distance: 0.0 - surround_check_back_distance: 0.5 + surround_check_back_distance: 0.0 trailer: enable_check: true surround_check_front_distance: 0.5 surround_check_side_distance: 0.0 - surround_check_back_distance: 0.5 + surround_check_back_distance: 0.0 motorcycle: enable_check: true surround_check_front_distance: 0.5 @@ -49,9 +49,9 @@ surround_check_side_distance: 0.5 surround_check_back_distance: 0.5 - surround_check_hysteresis_distance: 0.3 + surround_check_hysteresis_distance: 0.1 - state_clear_time: 2.0 + state_clear_time: 0.2 # ego stop state stop_state_ego_speed: 0.1 #[m/s] From 86fdd768a9743114dee0f6aa85762cfb1283ce24 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 11 Sep 2024 15:39:56 +0900 Subject: [PATCH 201/217] feat(mission_planner): add option to prevent rerouting in autonomous driving mode (#8757) Signed-off-by: kosuke55 --- planning/autoware_mission_planner/README.md | 23 ++++++++++--------- .../config/mission_planner.param.yaml | 1 + .../src/mission_planner/mission_planner.cpp | 6 +++++ .../src/mission_planner/mission_planner.hpp | 3 +++ 4 files changed, 22 insertions(+), 11 deletions(-) diff --git a/planning/autoware_mission_planner/README.md b/planning/autoware_mission_planner/README.md index 452d0a64d5c9c..b5993d0106add 100644 --- a/planning/autoware_mission_planner/README.md +++ b/planning/autoware_mission_planner/README.md @@ -19,17 +19,18 @@ It distributes route requests and planning results according to current MRM oper ### Parameters -| Name | Type | Description | -| ---------------------------- | ------ | ---------------------------------------------------------------------------------------------------------------- | -| `map_frame` | string | The frame name for map | -| `arrival_check_angle_deg` | double | Angle threshold for goal check | -| `arrival_check_distance` | double | Distance threshold for goal check | -| `arrival_check_duration` | double | Duration threshold for goal check | -| `goal_angle_threshold` | double | Max goal pose angle for goal approve | -| `enable_correct_goal_pose` | bool | Enabling correction of goal pose according to the closest lanelet orientation | -| `reroute_time_threshold` | double | If the time to the rerouting point at the current velocity is greater than this threshold, rerouting is possible | -| `minimum_reroute_length` | double | Minimum Length for publishing a new route | -| `consider_no_drivable_lanes` | bool | This flag is for considering no_drivable_lanes in planning or not. | +| Name | Type | Description | +| ---------------------------------- | ------ | -------------------------------------------------------------------------------------------------------------------------- | +| `map_frame` | string | The frame name for map | +| `arrival_check_angle_deg` | double | Angle threshold for goal check | +| `arrival_check_distance` | double | Distance threshold for goal check | +| `arrival_check_duration` | double | Duration threshold for goal check | +| `goal_angle_threshold` | double | Max goal pose angle for goal approve | +| `enable_correct_goal_pose` | bool | Enabling correction of goal pose according to the closest lanelet orientation | +| `reroute_time_threshold` | double | If the time to the rerouting point at the current velocity is greater than this threshold, rerouting is possible | +| `minimum_reroute_length` | double | Minimum Length for publishing a new route | +| `consider_no_drivable_lanes` | bool | This flag is for considering no_drivable_lanes in planning or not. | +| `allow_reroute_in_autonomous_mode` | bool | This is a flag to allow reroute in autonomous driving mode. If false, reroute fails. If true, only safe reroute is allowed | ### Services diff --git a/planning/autoware_mission_planner/config/mission_planner.param.yaml b/planning/autoware_mission_planner/config/mission_planner.param.yaml index 9b7dcffbc687b..ecfbdab9e569f 100644 --- a/planning/autoware_mission_planner/config/mission_planner.param.yaml +++ b/planning/autoware_mission_planner/config/mission_planner.param.yaml @@ -10,3 +10,4 @@ minimum_reroute_length: 30.0 consider_no_drivable_lanes: false # This flag is for considering no_drivable_lanes in planning or not. check_footprint_inside_lanes: true + allow_reroute_in_autonomous_mode: true 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 2b1b943e002a8..992879a5b3b74 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp @@ -47,6 +47,7 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) map_frame_ = declare_parameter("map_frame"); reroute_time_threshold_ = declare_parameter("reroute_time_threshold"); 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"); @@ -240,6 +241,11 @@ void MissionPlanner::on_set_lanelet_route( operation_mode_state_->is_autoware_control_enabled : false; + if (is_reroute && !allow_reroute_in_autonomous_mode_ && is_autonomous_driving) { + throw service_utils::ServiceException( + ResponseCode::ERROR_INVALID_STATE, "Reroute is not allowed in autonomous mode."); + } + if (is_reroute && is_autonomous_driving) { const auto reroute_availability = sub_reroute_availability_.takeData(); if (!reroute_availability || !reroute_availability->availability) { 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 1181ef54273ae..99384e9ddeb3b 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp @@ -135,6 +135,9 @@ class MissionPlanner : public rclcpp::Node double reroute_time_threshold_; double minimum_reroute_length_; + // flag to allow reroute in autonomous driving mode. + // if false, reroute fails. if true, only safe reroute is allowed. + bool allow_reroute_in_autonomous_mode_; bool check_reroute_safety(const LaneletRoute & original_route, const LaneletRoute & target_route); std::unique_ptr logger_configure_; From 2f7bd8e0a106ad4966be3e8968efdc456e374fac Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 11 Sep 2024 15:44:20 +0900 Subject: [PATCH 202/217] fix(autoware_behavior_velocity_intersection_module): fix unusedFunction (#8666) * fix:unusedFunction Signed-off-by: kobayu858 * fix:unusedFunction Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/debug.cpp | 19 ----------------- .../src/util.cpp | 21 ------------------- .../src/util.hpp | 16 -------------- 3 files changed, 56 deletions(-) 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 a53b6e7cd7f92..ffffa4da8f4a1 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 @@ -159,25 +159,6 @@ visualization_msgs::msg::MarkerArray createLineMarkerArray( return msg; } -[[maybe_unused]] visualization_msgs::msg::Marker createPointMarkerArray( - const geometry_msgs::msg::Point & point, const std::string & ns, const int64_t id, const double r, - const double g, const double b) -{ - visualization_msgs::msg::Marker marker_point{}; - marker_point.header.frame_id = "map"; - marker_point.ns = ns + "_point"; - marker_point.id = id; - marker_point.lifetime = rclcpp::Duration::from_seconds(0.3); - marker_point.type = visualization_msgs::msg::Marker::SPHERE; - marker_point.action = visualization_msgs::msg::Marker::ADD; - marker_point.scale = createMarkerScale(2.0, 2.0, 2.0); - marker_point.color = createMarkerColor(r, g, b, 0.999); - - marker_point.pose.position = point; - - return marker_point; -} - constexpr std::tuple white() { constexpr uint64_t code = 0xfdfdfd; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp index 0d38c94ae3439..c48588bc5386d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp @@ -336,17 +336,6 @@ bool isOverTargetIndex( return static_cast(closest_idx > target_idx); } -bool isBeforeTargetIndex( - const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, - const geometry_msgs::msg::Pose & current_pose, const size_t target_idx) -{ - if (closest_idx == target_idx) { - const geometry_msgs::msg::Pose target_pose = path.points.at(target_idx).point.pose; - return planning_utils::isAheadOf(target_pose, current_pose); - } - return static_cast(target_idx > closest_idx); -} - std::optional getIntersectionArea( lanelet::ConstLanelet assigned_lane, lanelet::LaneletMapConstPtr lanelet_map_ptr) { @@ -360,16 +349,6 @@ std::optional getIntersectionArea( return std::make_optional(poly); } -bool hasAssociatedTrafficLight(lanelet::ConstLanelet lane) -{ - std::optional tl_id = std::nullopt; - for (auto && tl_reg_elem : lane.regulatoryElementsAs()) { - tl_id = tl_reg_elem->id(); - break; - } - return tl_id.has_value(); -} - std::optional generateInterpolatedPath( const lanelet::Id lane_id, const std::set & associative_lane_ids, const tier4_planning_msgs::msg::PathWithLaneId & input_path, const double ds, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp index 9c32a9e6e3658..6167e7a366295 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp @@ -76,25 +76,9 @@ bool isOverTargetIndex( const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, const geometry_msgs::msg::Pose & current_pose, const size_t target_idx); -/** - * @brief check if ego is before the target_idx. If the index is same, compare the exact pose - * @param[in] path path - * @param[in] closest_idx ego's closest index on the path - * @param[in] current_pose ego's exact pose - * @return true if ego is over the target_idx - */ -bool isBeforeTargetIndex( - const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, - const geometry_msgs::msg::Pose & current_pose, const size_t target_idx); - std::optional getIntersectionArea( lanelet::ConstLanelet assigned_lane, lanelet::LaneletMapConstPtr lanelet_map_ptr); -/** - * @brief check if the given lane has related traffic light - */ -bool hasAssociatedTrafficLight(lanelet::ConstLanelet lane); - /** * @brief interpolate PathWithLaneId */ From 64453f27e0793126461022e419613d88010b1968 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 11 Sep 2024 15:44:52 +0900 Subject: [PATCH 203/217] fix(tier4_adapi_rviz_plugin): fix unusedFunction (#8840) fix:unusedFunction Signed-off-by: kobayu858 --- common/tier4_adapi_rviz_plugin/src/state_panel.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/common/tier4_adapi_rviz_plugin/src/state_panel.cpp b/common/tier4_adapi_rviz_plugin/src/state_panel.cpp index d34fcd9010779..6d2980a7f2c4a 100644 --- a/common/tier4_adapi_rviz_plugin/src/state_panel.cpp +++ b/common/tier4_adapi_rviz_plugin/src/state_panel.cpp @@ -26,11 +26,6 @@ #include #include -inline std::string Bool2String(const bool var) -{ - return var ? "True" : "False"; -} - namespace tier4_adapi_rviz_plugins { From c97d28cfcfa8ccdaa03c4342be1bb3dbc646524d Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Wed, 11 Sep 2024 18:57:54 +0900 Subject: [PATCH 204/217] docs(map_loader): update the link of pointcloud_divider (#8823) update link Signed-off-by: Yamato Ando --- map/map_loader/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/map/map_loader/README.md b/map/map_loader/README.md index 63f0b46571bb8..7870ff73c5408 100644 --- a/map/map_loader/README.md +++ b/map/map_loader/README.md @@ -48,7 +48,7 @@ where, - `A.pcd`, `B.pcd`, etc, are the names of PCD files. - List such as `[1200, 2500]` are the values indicate that for this PCD file, x coordinates are between 1200 and 1220 (`x_resolution` + `x_coordinate`) and y coordinates are between 2500 and 2520 (`y_resolution` + `y_coordinate`). -You may use [pointcloud_divider](https://github.com/MapIV/pointcloud_divider) from MAP IV for dividing pointcloud map as well as generating the compatible metadata.yaml. +You may use [pointcloud_divider](https://github.com/autowarefoundation/autoware_tools/tree/main/map/autoware_pointcloud_divider) for dividing pointcloud map as well as generating the compatible metadata.yaml. #### Directory structure of these files From 67d021163dfd920404cd650a8ed9a06a219464ee Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 12 Sep 2024 08:21:48 +0900 Subject: [PATCH 205/217] chore(cluster_merger): add node test (#8810) * chore(cluster_merger): add node test Signed-off-by: badai-nguyen * fix: rename output topic Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- .../autoware_cluster_merger/CMakeLists.txt | 3 + .../autoware_cluster_merger/package.xml | 1 + .../test/test_cluster_merger.cpp | 163 ++++++++++++++++++ 3 files changed, 167 insertions(+) create mode 100644 perception/autoware_cluster_merger/test/test_cluster_merger.cpp diff --git a/perception/autoware_cluster_merger/CMakeLists.txt b/perception/autoware_cluster_merger/CMakeLists.txt index ce666be317d6c..13ea807104c32 100644 --- a/perception/autoware_cluster_merger/CMakeLists.txt +++ b/perception/autoware_cluster_merger/CMakeLists.txt @@ -19,6 +19,9 @@ if(BUILD_TESTING) list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_uncrustify) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() + ament_auto_add_gtest(cluster_merger_tests + test/test_cluster_merger.cpp + ) endif() ament_auto_package( diff --git a/perception/autoware_cluster_merger/package.xml b/perception/autoware_cluster_merger/package.xml index 41bcdb27b1387..879cf1da2a565 100644 --- a/perception/autoware_cluster_merger/package.xml +++ b/perception/autoware_cluster_merger/package.xml @@ -12,6 +12,7 @@ ament_cmake_auto + autoware_test_utils autoware_universe_utils geometry_msgs message_filters diff --git a/perception/autoware_cluster_merger/test/test_cluster_merger.cpp b/perception/autoware_cluster_merger/test/test_cluster_merger.cpp new file mode 100644 index 0000000000000..d530832659a2f --- /dev/null +++ b/perception/autoware_cluster_merger/test/test_cluster_merger.cpp @@ -0,0 +1,163 @@ +// 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 "../src/cluster_merger_node.hpp" + +#include +#include + +#include + +#include + +using autoware::cluster_merger::ClusterMergerNode; +using tier4_perception_msgs::msg::DetectedObjectsWithFeature; +using tier4_perception_msgs::msg::DetectedObjectWithFeature; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto detected_object_validation_dir = + ament_index_cpp::get_package_share_directory("autoware_cluster_merger"); + node_options.arguments( + {"--ros-args", "--params-file", + detected_object_validation_dir + "/config/cluster_merger.param.yaml"}); + return std::make_shared(node_options); +} + +TEST(ClusterMergerTest, testClusterMergerEmptyObject) +{ + rclcpp::init(0, nullptr); + const std::string input_cluster0 = "/input/cluster0"; + const std::string input_cluster1 = "/input/cluster1"; + const std::string output_cluster = "/output/clusters"; + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + int counter = 0; + auto callback = [&counter](const DetectedObjectsWithFeature::ConstSharedPtr msg) { + (void)msg; + ++counter; + }; + test_manager->set_subscriber(output_cluster, callback); + + DetectedObjectsWithFeature msg0; + DetectedObjectsWithFeature msg1; + msg0.header.frame_id = "base_link"; + msg1.header.frame_id = "base_link"; + + test_manager->test_pub_msg(test_target_node, input_cluster0, msg0); + test_manager->test_pub_msg(test_target_node, input_cluster1, msg1); + + EXPECT_EQ(counter, 1); + + rclcpp::shutdown(); +} + +TEST(ClusterMergerTest, testClusterMergerEmptyWithNotEmpty) +{ + rclcpp::init(0, nullptr); + const std::string input_cluster0 = "/input/cluster0"; + const std::string input_cluster1 = "/input/cluster1"; + const std::string output_cluster = "/output/clusters"; + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + DetectedObjectsWithFeature msg0; + DetectedObjectsWithFeature msg1; + msg0.header.frame_id = "base_link"; + msg1.header.frame_id = "base_link"; + // Create object for cluster 1 + { + DetectedObjectWithFeature feature_obj; + + feature_obj.object.kinematics.pose_with_covariance.pose.position.x = 10.0; + feature_obj.object.kinematics.pose_with_covariance.pose.position.y = 5.0; + feature_obj.object.existence_probability = 1.0f; + feature_obj.object.classification.resize(1); + msg1.feature_objects.push_back(feature_obj); + } + + DetectedObjectsWithFeature latest_msg; + auto callback = [&latest_msg](const DetectedObjectsWithFeature::ConstSharedPtr msg) { + latest_msg = *msg; + }; + test_manager->set_subscriber(output_cluster, callback); + test_manager->test_pub_msg(test_target_node, input_cluster0, msg0); + test_manager->test_pub_msg(test_target_node, input_cluster1, msg1); + EXPECT_EQ(latest_msg.feature_objects.size(), 1); + rclcpp::shutdown(); +} + +TEST(ClusterMergerTest, testClusterMergerNotEmptyWithNotEmpty) +{ + rclcpp::init(0, nullptr); + const std::string input_cluster0 = "/input/cluster0"; + const std::string input_cluster1 = "/input/cluster1"; + const std::string output_cluster = "/output/clusters"; + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + DetectedObjectsWithFeature msg0; + DetectedObjectsWithFeature msg1; + msg0.header.frame_id = "base_link"; + msg1.header.frame_id = "base_link"; + // create objects for cluster0 + + { + DetectedObjectWithFeature feature_obj00; + + feature_obj00.object.kinematics.pose_with_covariance.pose.position.x = 10.0; + feature_obj00.object.kinematics.pose_with_covariance.pose.position.y = 5.0; + feature_obj00.object.existence_probability = 1.0f; + feature_obj00.object.classification.resize(1); + msg0.feature_objects.push_back(feature_obj00); + } + { + DetectedObjectWithFeature feature_obj01; + + feature_obj01.object.kinematics.pose_with_covariance.pose.position.x = 10.0; + feature_obj01.object.kinematics.pose_with_covariance.pose.position.y = 5.0; + feature_obj01.object.existence_probability = 1.0f; + feature_obj01.object.classification.resize(1); + msg0.feature_objects.push_back(feature_obj01); + } + + // Create object for cluster 1 + { + DetectedObjectWithFeature feature_obj10; + + feature_obj10.object.kinematics.pose_with_covariance.pose.position.x = 10.0; + feature_obj10.object.kinematics.pose_with_covariance.pose.position.y = 5.0; + feature_obj10.object.existence_probability = 1.0f; + feature_obj10.object.classification.resize(1); + msg1.feature_objects.push_back(feature_obj10); + } + + DetectedObjectsWithFeature latest_msg; + auto callback = [&latest_msg](const DetectedObjectsWithFeature::ConstSharedPtr msg) { + latest_msg = *msg; + }; + test_manager->set_subscriber(output_cluster, callback); + test_manager->test_pub_msg(test_target_node, input_cluster0, msg0); + test_manager->test_pub_msg(test_target_node, input_cluster1, msg1); + EXPECT_EQ(latest_msg.feature_objects.size(), 3); + rclcpp::shutdown(); +} From 1322e0cf40f9e223585e0766be9adac25c42b00e Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Thu, 12 Sep 2024 09:03:40 +0900 Subject: [PATCH 206/217] docs(static_obstacle_avoidance): update envelope polygon creation (#8822) * update envelope polygon creation Signed-off-by: Go Sakayori * fix whitespace Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori --- .../README.md | 8 +++++++- .../images/path_generation/polygon_update.png | Bin 131110 -> 134929 bytes 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md index e1a914b488790..30b1d67a2b804 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md @@ -748,10 +748,16 @@ The envelope polygon is a rectangle box, whose size depends on the object's poly ![fig](./images/path_generation/envelope_polygon.png) -The module creates a one-shot envelope polygon by using the latest object pose and raw polygon in every planning cycle. On the other hand, the module uses the envelope polygon information created in the last planning cycle in order to update the envelope polygon according to the following logic. If the one-shot envelope polygon is not within the previous envelope polygon, the module creates a new envelope polygon. Otherwise, it keeps the previous envelope polygon. By doing this process, the envelope polygon size and pose will converge even if perception output includes noise in object pose or shape. +The module creates a one-shot envelope polygon by using the latest object pose and raw polygon in every planning cycle. On the other hand, the module uses the envelope polygon information created in the last planning cycle in order to update the envelope polygon with consideration of the pose covariance. + +If the pose covariance is smaller than the threshold, the envelope polygon would be updated according to the following logic. If the one-shot envelope polygon is not within the previous envelope polygon, the module creates a new envelope polygon. Otherwise, it keeps the previous envelope polygon. ![fig](./images/path_generation/polygon_update.png) +When the pose covariance is larger than the threshold, it is compared with the maximum pose covariance of each object. If the value is smaller, the one-shot envelope polygon is used directly as the envelope polygon. Otherwise, it keeps the previous envelope polygon. + +By doing this process, the envelope polygon size and pose will converge even if perception output includes noise in object pose or shape. + ### Relationship between envelope polygon and avoidance path The avoidance path has two shift sections, whose start or end point position depends on the envelope polygon. The end point of the avoidance shift section and start point of the return shift section are fixed based on the envelope polygon and the other side edges are dynamically changed based on ego speed, shift length, lateral jerk constraints, etc. diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/polygon_update.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/polygon_update.png index 1503fe58382a5c3c1de7579605b7aff349577d91..e2b9c219733ac23ec64f338531eee8bd79168795 100644 GIT binary patch delta 106724 zcmY&<2RN1g`#(DBoDj#}JEM$jGO|}jMphwYW*j8Pe8`bwi^wLFQ7U_@j+u;%BH25# z$>#q)pU)3g%Z(6q@QcvfP(zvE zZ7=gL0s7>O8YMI@!AE{lp@7QJ@g@3NRG_$VVHE?uET)Ns3k*o^!lbT6`pfPkGqOI67j zZS^~g_!+m__i8)Rj8B$~=W9M?5uUdmV>v(4K5qZs+|{$D?XboC9?I8@o|%?*m{4KN z?R|XcncOERpu)SnM6A9X{Fw;2bYV$563rZf8!J-iliV!qI!KEKCIoF zgeEIS+#6Q!-no+joq3#CG7qus++C8--3ysG=TDAlzVNpB(52>JA!AXpol(N&S;Nl2 z&65*{G<({b-S2mf&c08!DV-?wh2yWr-=??}FqQt`t*4Q$MDohzY4Mt}Om}V~PWJ!% z5mcG-fQ~X|+0x+HkpF(fnL?oxXvNySJ5_{IFQatY*a}%h7wS9V*AdGsGeE|2z0#`Y ztB;x@O!c213#{SDd@TRrA|4g!rj}pP~zdh{E06k_SojjduRLKnkpjTn$m(wTqPGd6E1_V zGaneL`tNc@*hp-3X{n$T1*M+1N-5KSBUSu`xEA;6*=*&GZs|oRO7S`orQV?DfWiOv zu8o_0x-xY&&+zXJV)&))E-fsNR(t}hq;h+5&4>T*fJ4W?q?2U5#&7+%W!n0RIOks( zW;E1)HwnL0p~r}aAP)ch`E%^?MmFkyYX&LC!oX0}L#|u?cmLnHisBc>@Xr522diiT zSCQ{sr8%z{0DB<`o+=w|6YEUK2g~ZNi8kN5TQ3L})FdE#Z2o(U^*OU0_ z?d8AG`O&@7&CRVYGyy`TGr5dw{=G#%#FO+DbKy%5m)o~s1IPqadR$T*<==_$@qh(x zbEQkx{_pzqG_Y3=?()f&Fj4N@EGIEc@y#mgQ0G@^?Yg3$x!0O)cZ&zR`xe&?U|pKI`S~qXH8s!6TuPGQ)QKVOBH^wnL*ZTC%-$U= zzO_ku*FQHMZ+%${zL4hl z2Pgda7szT$*+GBIeTOZ5>kvGtAIJR`v)nhPK4sO6I~QgJHc{OAV*BCr@U`s5$8!zF zi={OaUNw`!4R;>)t2GSeggqMfF_r3I_J*0Vy*LERfNFsv$oE{q>fAvTexmkKzDm&< z;9X>LujG1^q686Rhq&)q=L6=JeIIa%_n`ibrl0qdbQ^C)EyZE$+ZiA1dnW0?R6oif z3YUq&9$UisI*PAj;M`OrL3`ulGK-nB;T_*h?v$cZS*k+ZPmFu_$-lM! z5Nz3ng?Q(#ue_P1z2hpfH)N#mb6UNDBRLB7O2Z5mv@6|GH&a;34IA6+V4HM1YC2kL zunKv*pya>wBEnxd)-GQD`^lf59%~6Im!6_V1SO374)@ok)ysyZ z`U(fFEPiuOgTLjRIoylx;OpRgoSxVHad^a`~$QQ~-+=WE12 zA`z<1l|A}hF+S$qxB7&PY2j_%0^{Dv-edzYt=Y#czlAjSr)spn8r#8kEi9xz5Ymud zZ$4UEVGZ~#!X{MxRhgu2Hcqyej6t+u+w5&!2W!B-7xSYLo8ksY@jKNe_rSwng-6tI zbQx#6p?>&sp*tnZh%yY_QB_qnZ(@fitb6f2HXRGj0%M12!_`^Y_U8guJQ`N3E&a=5 zozc(Rp$BDf2R8pUq)8hnzu-Z%KTCwy?ti+#RtsWi z_)OiscRuA#FIzwhnN%&A)Y#Wj5dCY1EAM=p{C7((hLtA-hkO-iB!kQ3xRex+4cru7 zl_#grLW=v2d1?q(Q!dASy{UPfBP2;*q3*-!qn~bz5V8K2fA5X6;|Zp{gT^`}0j^ayJ+d5dhw`UPUglMTo02!>XYOX#04gC00xEv?j~OC!sy89Bgv5@lL71U!nC&7EGDy7TcGK)KToa#RwU!95+4lIT1<`SbO zvJKvuNG8{V$ZwiDh=-2zsaT2DAYG~Px$l;~mS-MfjcUjnY(YEyy?67`6~SPFr|a-m z2YActxAi4I9WvYk{jO~VKdtdO-t1Vv|NK?oqeag{kRkF^wW#r}`~gAm3XUk4EvIQeXg7&!LOjx)uPd@fJ+_=$M-Y!u_CzeUy* zhWBYiYb*_o`%bPZoE>{hwNV@G=QJNKUu6@DbBeBY8vYpYtS3+Mr>oey2xAr4thi9! zgnh@k&Zky7_qm`@5DP!p9B|Hoj)&(iNq=MuTXYjY2|;wg)6ku^Jeh{4TD)16+kenA zdgA@6r+fJP`s(yY7V6^cZ4>jCKLZjh2&ZM;DfJrE3eQ=j5?K9OU0oH_QM^qT+D`RV zT78z@-{z$!>4!4uo{^ZcE722k?a#q1oxJ&W@f8rl0}D;H+(N2LxMklT_Ro6*C|Kh! zaQW$d7PMFAJN{kKH}R|P0A$3Yf|GHE7bmV8)Do(L5p2OD>ja-~pkK~}hS$v9Hnp5L z0d=OgB?)7sYS^fO@VzWBscI(c{I2QG)`7eTm7dI{bqg`cuouCu7Bssfm1FNrt%IuQ zydV*b!J5`#XzjE}bVrz9f=@^O!1_3%aE!^s0X|S*%5JGR^pnmrp!$ac(~2aeUcjj6 z^>;Mzxh5IotJiL`sIfl-aej9Bm1pYmd>r))3c$P%wG$mZw)B#~s}&IGwGD=QdE z)^QRm4q(DE3k;O{F@qYcey!FWZxT^ayaMYvwNIsX+vu!!aL$v>K>=g(4ODuwbisS$ zzCmlll^OC{(yN|>ORco*|AHmKuf@h~_du0%Vm2xsY&<<&Q4oz(3!oi2@BongBLq(F zZ4a;;38)eUb|U_yV|N+ojY}`6SHUW8tb-3;^1vwd9^eX-)N*-<=Ik8^d4!Wt>2%KH zg=ugn=6p{bL&#o5-)n}P{@TZJkXwTD^}%x$O^IUcuFXr|?gNkBfX#W9#IX~7hHYh| zZe3Jf`EmOcUuI;-G-7Xg1$T53cfHbv$4E^ER;&yb>f1t>FUkJC=KH&><1jX51citu zDa==o^}^$hI{>(h#Y#<#%wI2{`)E|nisOH=1x9KAoVgHNJ14Cs7qt7$^ucoa-!T^h z;OthiU})pbnd=#|?VKncci<7hW#I(yMDXw3sW9?a+Q?)h-*0ZJxd{Mz(w3VWLwv~2 zoRCL(Jvnu2Bg`;Hk!kjh1%N>o;od9?foNVnRU<#XBCU7W_Mu&>pESa61o&;g#GmLD03-wKEA~!%K^RYTN?F9zuyWX^C<;ZFh zT*+Km^<;V0=4P#|Gg0@5nF|E);GevWAC5VzXWi|@b9e2Z4;M+f`Zj6eoP9An4e)0X zA?>2`&Nsht%l@;mRI9oI^}^L7w!wEh&>pYS9J=0C{L<#UWeD=_&C&NIDgUGuMM?Zr zK9VFU31%1k*3^A_t5N?)E#k#fOMO!d=gZbgUS8!0sp~|ny?t{8gy59UOTtqK%9Xv%1LHE?AH^PZ;VSOxIY&&F{d3FjEZ*HB6Zt+k1n&;(MeK8P zc;Q_lUo4ejs_Y&_==O4c!VH7YfLwKH zuzO4!%jkU>jxgpz@`-}_6E$}IN(Ougf9oo#4>6LD2JoDhE_%1sVd;-Uc$jtjb*>b^ zcTx!&p#GVI?B`n2J<*kGTtu7%;N~H6)!eavVUESxBa>BCb_sBIvB57zu=Fu-C)`t{ zrlmSS$$&)Sk2+@pFSu)~pfn&-aTb3BnFGenVHedv^`|Y7F{Vd4A&AmZm8xQ|6FC!@ zK$-OVm%4V&8V4z|!7QEt5S8NWa@+Vn4)!l!+~UIT_h`~*Z+^HP6#(&kRiQ~r_h+E% z*RS6V2naZp`p)t{RY5gZ9nY+}6tjf>62gCVi(6^<^(_|sAAwe7zX}dY1!wUJR#6Kd zBU+4x-~NpeiqOXtop+>f#|=IfZ;bj&L@%=g?hK19x`I_q!P8Yp%V_w2{PCXDXmxe< zm?9vfWL5uDOJ4GRls<11H#i_wb%l@U7g!SA4lRxUxOWJgItfhJwmMq-FL~|J0sACY zliejm#6bB~uaW^b^zwfL_TtSg(^>2EQTdObLwxf1z4WjJeD;4Afe%}}|E$-~pW7eG z)&LLvtJ_FW0%pxfxcuGl66AD{&gH1t;kWPM&aNv?+l z%I(Dc0>ya#^l4j_?ZA%y3~Kry(Ta)o$!mhEgm;wLzDV}N(9Rgb#7p4yJ~CvuYoCAD_gDxkDT zO(3xDp48r$cSF{r(a-(*SAIa?E2oI-1Z&0yECERw|Ngq)t>TA6M%{zAb?qVqIW|ui zN>Y61lT9B1F8<-@S7FW=dNy|0ZT#W?mCS#atuq~L-J8f|f6lK3u&DP`rMjtSThBk# zHmudZPMUiW!Mc2Uy7!^MXV`LB@Wb(zJ3eWg96@^?h6D3g9?6FfLZ{m~?os@&P*}LV zD59{J#MYi#uV%!S_k!#5owC%0{ zz_lSu#vk@&m8Rjl-nun_AU(`}1aNLctmJ5scPNjsbWgq8!1s>0Bow3e8^;bh8-c-! z#1(p*^F3=Grv_4VL*!H;y-kaQxYa@L2RRSIXP>xQp)X42};0J*fx)qQKa8 z-;H&(2|N{YYuf#uH4L6>G=8-HVe;UN89F^!ls#O1mEk@*e~O3fckE&%%HRGm8$Q~f zjR$Ip?&4bGwq6Ygii1g&@WFbz@(iZR5)?Fw&m=#8GR1x{-ZQ1v^USEow#%FOUSFN) ztYbVOVvx@z|Hg52?|B)_zT`ef-#ZzCy8v3mtt`4pIyw*@=S2%G|M{cpT7K;m)Tf65 zZ!Rrqg9Gx73mm(P8o7z6lJ{*miQA5$%I6t4s`deaA1_GKTfQW>p@=Btm`aD{M#}v& z9b$79SIWN#c}EMBW9hD22X3~N8QOCDWyUdxwFkJ|*!ilW@a*JGMekOh(a>7Mx&mIi zZ4mx&Jb+ghXyh9<4KGV{QQj2je^0mvVtIz^5=ckmEz3|7(A7$y*sX@JJk*w5*0-!> z37)*bDBS0g!_-VC=c`vmB~=Oe7ra%|HuQz_kg?9W(*rHcPq%@HI!|R zGZ5&}eQ6q+{H%rs0c&-Ojl9DE@hyW2C@ZyEIp`k`@$dv3OG)Ab_%ms%1cmedig*B94RT?xI5XNZTu7Z~aF97#KR3OVWRI zff=Pp_g#Z6sB+Qp^T7AC#=MF?g@zBb+1(dd9ww06@Wiv@zTzblNW<8|KKb@oob1|C z)9Q?RJ=_G%2K1rz&k>fs<37+@j94#9xN+k#Ko*l@0u|je;ry+WPFSBrUo}Rdu`tO{ zej>^fm6yA zU!f4-@|WVR55?AVMdze@?nnz7#Tlth8z0Zn{fVHMzFbKeg+pBaF4yt=wzQxZNrFb! zrvK2nitIj*?*iaN=vHp+a%V1dSol(gzGAl<4bx^nsn(_v;2HW3fnjy77z$G-@F_zkk=CFsg9PtFw_3DFN@Bi;EM zd8GGvGF(L?ilPd?0aiul*FA4)?`YZFh_5 zJ2td^VKsE@QVbYe!!|`QdtvFEogTnQG2)W-kA-K*AB(IyDU0l>Q>!hhxTU%oPFh5c;? zf3AH(D3Y=mcO>}!BawTOuB0bk^jg=z1Pu0KJL#?B;67LjfM&${K3{%*cgA$r27`@h z<3)U*q3r7bfE!mbMTFWR8iJZ)m`Jq~3C*1HB_h-}Odn-Z?; ziDLBLT$Ek z<8%S1sj4m!G|Ef=a1k%4z6+n8?-mhoH_K6ycHkhkx!5mJpLBp1?AuD5&Mx}(UfGO_ z_IA$6*B-7A{X{XF)wUot)Ulk+ommcToRe)_`uyN_4~1RN&F4@@DKE}ha9w9R?;c@P z@M8`P)urduC4K9j?;zSVbo|c>*FKi+S_P8_0TF-R)uQ}oB6$x_JBa9g#Ae4`o)X$q z=)Hc_eErzWVcOV08hVs^%VV<=$^Wh1Zgh!IZJO^Q?`S-AxL7RP>k(h6Rc~qtqK#Cy zb#Eh*p7j!Awlj0OPnb2<*I&nM2aoQuUBlHRi}2aKYNNgL=8K>S;O^_cDYlMz=B3GE z{dN2o3s%LF<@B^T6fyM3r_y^AmKxk_c8;jgRPn!t^ne0?hjZTrR-kP4>N!R!7Q?A+ zct-`iGSgAonnHQu4A4Xhx`*RF2Q~XGPSP1cjiTV8REj={;ky%JNP}nB?Bz%i#A=#t z@TVO&k@_Z$f}5-}!EkBjJGvXQhv>I6G|{Ql&(?pFoGUMHBfj@GmX|v_@2&|~WiJQLSu;!bKIiW= z1*F6_qZ*1MaO{wjh)IUCM?fb>LG>bxB*ziw&NMty2LFb(Qh$e}(Nn1#Q51B(;6wGC z0@~asoi;2MP8~@aY96BLbC9G|PNE4jhFtT5m;l`r0d-G1`*}DrETJxmnisoPHTf z<*Otesx4|#5x8lB2smdE%KzT)KB5z#!n07TJ?GARqAJhRw5!5d14?8jFKXxBX@|1( zu5IS0)EGY+J6i-)D1WAWQ+icKHj5wdW|7c07^B8F8=}#SY!=FLg56_Y1SYSEuKL_1 zvGa;cwPRye=tR?Vwu=600>~&Rwc7GIh5r_kCvBCYXPuc&ie$Ylnx<@+XFu>5$(i5I z{+LFO3gR<0%N3*94?MX_# zu_#7EN2)Z6D0-9{nXn}WMYXpdt3;6K2jv`-(QR#Ym3;;; zS3v%a%NH)gKE~=;P1K^IHrn%ugQyMO%FfCt-hEp+GDtQ3Ea1;h7Q>ay_NEtgz5^9^ zfgncA;_FY~_8 zcq|BjL5Wep)zqRCKITl?{p|NePH`LpoU^SV6{P%8^meujt+u_Q2Gh^V2%dy!iyIpj z1*h}X1HGMlStQb2bIv3Y<>H)9&!)Zy52c!So8!spISw+7`_E6-)@FYVX+1_*8t8aV zKZ_08htCQ!_R!JGU)b!BOycYgOL!o6^Rt9nuj;mgZ4%GhuzTUDnA(;I`Ff69JN4B{ z2F5zkr+R!Bi_h!Cl%|MX70Tqy;}mU^GK#cf6P8uwI{K&qwcP1Y4ye1KeC3Qs|4LFo zt5Kt{jMNoLq@+7kv7+{c7P45Rm=-VSmDEy9RmqLENF2fO7y>HzhOU?%W0tCr9a|lm z98SiW*w$v(ppe~yIkPjE7Jn8^Hl(?&m=m4u$2H^Jq3*2naJ3U#+IaSTh)~9@iqL=iD)#(vV5Aj`^eqBtSm@t>} z*MaCCxK}Ut5HxxX(RumJ-!Ow~6E(@`a8-8@nY2BTI<{}Zs8ogog3>XA*|8MdnSWw3 zdMQH(DEWZ;BaSPce;OTOW9o8GIT4|&4&#^$CA;MWBlbdwdOB`=Ru@Q;#)o_o)`19~Oe6=}=VDv{1Q^up6)I94j@vZ;F?Cy{=D3$NuZ6?uTJ zo}Qy>%6AE!rM0N8^PK|e+d=onm?ak4PzfkTg;!Igh(h_L=M}7tv0AQ&R=+GsU2BYY4@Pu~J; zrsj3J;Z(TLQZ&tHdhMF|lsx>&$#)9Mu`%`8zdd_zadDb&Q#`&!t zt?|%`XS(vLGwe`2`g0Tx>|Y)#voD}G&&3y?fgb8o(TehvT)r3~LZ-(QV~GdX9}Jiu zLsuU2ueP7pk3k~Y1!EcQNoe#2Rr7%AGT7*Gb@O86SQJU&v$WGY{OM0U#gAlxj=ArI z`KQxm`uD>p@MnpNuMvgfoCnIA1<~v2yw^KuF+goBF-F1Gc&DjH zYVtR+vFg($Wr`16kg{0XJ*DvScHgur(OqNd`Qz+HG2lFUje@?9&|q(Y0P80TU(6$x z|ABx}yy7;$3%)7tNX^QJ)sUK;pRQc~(s1d9w)E;niBePvU*=Ahfq^uB`}O+5jRFSz zDZ|BFN3N~Y=r}3Z>Cz6neIRT{t12Uj+j*M$pIP*9LI6tOlMEBpWxq_(OF2$?k#nBu zrxH2n0?fZ^E+0uK=Wo@F+Y0Y0Uk72nb6rn3N6}B^VbIE`$^zq8=nM?(q4?VAtF^|c z%HOIMgAlik^Sk)+M*=Y+B9xi~?n!Hd*kn|?fFw153BSLk6jA;@jVhyq-Qt>A$c3vF z5IS2eJWo65`6p6NW+D-$LyG1vKA#IUmq_XqHpNw+k>Ss648{3?R#wS!Wu2BV(a*}@ z99N@mj3zZJVJX5S3?;4+L^3vb&BW?VXi2iGFslk&?xS1{;e8o7;yEpjiAKc1XNQPS zpAqXL4|N{a>{19NA3i3NtYgdLmpz2axlZt^R7*@xL-O|Lca>dNUZa)V0TH+i9f(LDzVK+ECD{)}bKAL+ zPFuY{o*;w#+TD;G1;VB?G&GCK_;T}_C(|qLa zp!z@Q>vA`7&anhO^}vjM1l!8wHY?uDRMk<1-&ea-7MBURUZmc=HH&UN|8purOV}#N z0ZxwT*y3>kt-CBPcus(>+N#R)uS4T}_4 z_uF{JJ;!GAPCrK>PWL^1;QOwdL|y`wuFfmnRhwx0w$uP`Hq}(^l@RtR*??Lx;C+|}cHHuNNzcv>HP-7wu;86YQkw9V{df@q1M3*A`~Zj~K{C3G zJ>b@Rg3ss<0WE2JfmY6!es7+{om)Ycuu;|lfrkHsn?NKN@vM#5LU7C%&_wD8EEefi z2C1yS#u6FVEnU-YgIjn%%^s#T)fC&~ijcBX02dyPZgHNLgtCFk} z887_)=fBgELK5{LeYwrn;0nIfr_}_ZshaHO^uQysX?$1-f0hlblL4u+D`rGQ_B477 z??r8Rdx-sXKlk4}o#w8H%^Jy!*@0nSGxy!VN$TGzF8H4thyUddQ=eK`$Io%K zTG8{kL>m06OS+gW4gnfJxLVf1nnfplx<5Ov&g3>naWVZzmtnkvd)S*VLeoQ_*U>WI zHWuZNZ~g?$go9*ElHH(>j=Ly8Tbc~_GAuw-(Jqbk@u2hnW*?q2JY%5` z$6hs{2Qxfuh=KDK0p9lwQNM)*UQCz9RLUK9&y}|g?v~+$pyO`*1OjFZzH_yh>7(4T zK@DyNhaY<~>dLhE8C@&r=2^yT!T!6;$!9%GfgQj|aY6aqIsCI5gL8J6-oba20`u^F ziyZ{IIQD|(a?XwmGi;;y$GWb*yIZS}6pk8QMgqQaIg@tnlS!yQ-pP&c|D}rL;|L4f`EJF4z!|2HwCMn$^L%dGBy(}Jb}nb{(|@NPJn~8who;&G=Qoy z=9m+-0Gv;r8qf^a06K?Xf8kD!T)|r#8*lxAiO{qp4W!lsileW0gG{iszHJr{O6T2y z9V5gt_f&(`^NT=*PMhBL=@GPkR6h<{SAn0@?2T`#+3WoQ+@up#rk~)5jRX9%=;vDg znI}$3(1(|W;17tzI(&!3S=Iv`(CRVqlP2!icL8 z%ld5ouem{o;@@7#@K^)B*GD1SHQ<}fH9<6~0vnT5I@dxozyrn=j(*R62Y9-KoU)GB zcf{s`?_|)POrtf(8mfEX-g+>_f#>ln_(rs>Va>s2ye-qG5pc3Q+(0HdlDmC(`P?v& z!n*Ocpk<->?a_GxZ6UwNkEC4(e@x z06my{?m$WY!&HKAjVj`+b?BSSa$AQ8huwaLh%;HW7Kk<#f zpqsbf4^po5d%N-Kv=2I+ozlYX;JvIpgX|Wd#eTTyH;5`8LMpF6uV(E>kahd1Z%{(B zu~Ja`m9BsK53Qk~v%rr___sLzX$Fzy`~=o*>CZ%fN6m7{>%;1wU@1-l+TU2MS2!v0 zOPxIPW$5lkTYruB-&$OJ6PdgcwRkqyDd|Ou<8M4j_R8E^ zn{LEA2$R{1nWsIRi43fTjl$Uwbm~`gc6uaB>j>H%d2@IVQ|;n5NeAg!V?c~m3(tZG zU;02k765{C-Rt`9wB;U%?0v`7J?fKZUa_)kwWs6d0DIN4_>T2w0Rz@Eo4u&-56+>MhRqrM&BSM2s(TxVn*bpp}l9d?2I5oqY!H}lbK z$zST26U@BQ;aujgnpBs@O>{PwG?~W9)ymUKaN4f=e1jt<)-qL5Y(w>~nkFtI0`UuU z0j~=+@6Yrmai{Y_cbD0|=dZOo_`$%p(qGmrMp}ab`mw4ZpM~iV^hf{>UfoTl^4K^ zHfvw-z4-p_W>x;Fi!dunY&_Pr@(akMvuzd_$ZnJ{6!Rxv*Y~HJloasN{S4@)X{SSG zr6$m`QJwr$kI(IeP~{2O!ZHRjL7Q|o!d51wItWSZnC<5ve3}KeA!}~}96WhzObx!B zFj`~;?Awf*L~w-V<(pq%w3Sq=;b;he8MJ4(q%umSQH6PJurQv^3+ZeXxGAD0Y^zSz z54>TIKgw*jmYQr>l0vvPR#|81UQ|LW5iDpOxHMivWPj*6sRdH*dTAvEXRs3s>d+$J zC*@~cIR|1-g~OkYG2vLZ8xlc2Ms z$E^&U`Me*y7=V9Q0938gjE4hSCpA?d*_yazzm1^T z=0g-h)zP3m=8t~zl^6nOmR?6juch{v6OvCbloMV^D!_0LtaGfT9Ob6_9rSc~!(5H6 z5l^c@qYyInAFG2mTW1c*E~1=AaS{22q9-rOt}&Sco7y-dLuadX&`1vxbJkCq9g<6@ zc$hz7vaso#mloLych}j^rwYVK!EVIG`rk`0WKQyto4W>c*HOK`Mki1E1j}vkRH&Hs znlic|u+m^?qrQcNX5oED#zkRmGj@lJX@;nch>cK!+n;s1(?B~(V=6Wzlq2NU6TE#- zQU({{SdIRwIga$`xraq#Z{go|@Ux*(xuzl=Wa`2> ztunM6hkNVmRzbVB`(P^f7U>V~8%viC9|=U#ty8LM%iT2B#69|9Pq)r++(Le%R^q!^ zi!g<`A95G%uvuH>7<{#<2J4(dqZA*>I{$=eGAW_=cXP*GxA2eA36D3sDPltwkFiKD=1I|P zZ`e)R(BINswi8Exf?rK?1y#&IOZe^6s)JrJT* zqIgpb`A+Q95dONLpX-WqZfg8KsOpS)R4kB(qMw}#>N&!w>CkF!j4h0R$@38Ja31A5 z7m)KZ_PX{gO}6A?On_LkZDyNH;7`8`>aoN!oCb-%0jb>VzqSc3_UZ+&=;yD`T}Q#8 z#Izf;Lffs2S-nJi+E+{G^yGJqAvSwziHU~BVZV;Dgw`62ufTc>I&M&oE9J^=Q{{=I z+mK-sC;1gbp>xjSS8PV*-7B81$~&!+c@DYT%*`a-4-2FFBCjY@!$b z4H~k8$NKh##1Aj;oD|JwSe90w4a2XHtJA3R#$=j0{ua-9QpLRX+>j5`28^Xw z!%SfJ#F)6nLfDNZTsE#_2yqu4J0(uP?C>NNzZarGo5u$X)=|Z{Naw)WtF4ZWGzg8B zFj5BqD5V`ihFm4Uk5BGa7ytVu6&S?G}JmdMs_5(%qQ3Lc(J&aKoX=V37q$)s<& zT+sV#p9=cUf7GIqUJ=HAK<|fx;>oMLMrRmbfFNTns3br6G(ZLbJ6ZFMseY_f4dRW~ zi*cQ6y3}E6@{^8QjT=I0)Ro~RaWCYNEEMv;RGzU_5ED|7ubSU=2eHh$?k_eAxhT88JiSMBwU0aR;ZW-F7O;xRMCd)7Xq7d8 zQc5fbqMO`b;m87SAp6QD%WE?`Io&#kz4c(ezjuEQj1A4^VR$FhkGPV#KYcIgs2?%p$#Y zndWC@?n&Bah8RotcSM4J?Yey{{2M(qO{*#xqvqMWBrjcOifhibYDp8aLC!v&YRP4}hvyHONM_g}J!E;tIb z(8m@j&`NlwVy_ond*axS+{`Hx@#bZguDy}R?@j3)XJeBjgRqka($$AsJk31i28(8fw zYv6+D!_F^rm_(yo9nyxZ`}VC7xoSqGSdtYz)uAoe{^9dwthB~Rz3#QuZ0A*e+0`K}d z!_7vFjM331aWtw5UV-9BCS4uwn2h*)Lo+yjHUkW1zg@TAo8pzS_m^*?T1#)6`^#^a zybkAl8g^|tl2M*cgp~ZM$+yi>`;Wc35w}gwD`UQL=6$S|ogR{$<8-}5-o$N}Os7Q9 z!iCWiBVvXgOP$5v3Zw6kfcw3@FS&I2Vfvv4$OKO+g>huBd(q{hAuRzEN{s9G&+B5v z;5y6^=z%PDYFsOi1>Ac`*hLFh9G+mHcRq>sRo~3x-T4HCk0)T9zbS@v@5ZNm#*r}0 z;Xa+;+MzqVJJc;Z7)J&i2y)DrZ~?0p6(dYg4x-t3glj?QYh{zmnG1Sc4SIU|xI;zG zHI}(-POSQqpKqV9;5uktL9cE6zK;v_trvuU&GD=0&oQf2yx(5YLhGuWT~&*6IT7x` zQLQ^u@#XtyUd^<~!6ni3RcM>6O2Zr`3>rz?LR)c`x^K#^1;MCEipf^{l9#p9Hf!6$ zpyW0xxz=m6PH?T(m1@_Ny@gx$)290Gb`$twDYC0#BI)zrD_x%CqutJP$X*3`<2%FlrMY(e zE=ATNrVS%Y5rvz^&dg9B5!)|&GxYs8G?Xm#eV*FX=V!?W?9{T4rSZQe=NNpMf(ovF3>q>5Qfm>!1r1@*s`-q3PsO(A96r-)zpyZeANK z5Tz<1{<-fW+CkYHe(ie}%EgLJUh6>!TE$8k7r*cOuqCZv>j_ro#cH$^@naDj!bSyM zcg;W%;dIvvi zj1H9RN{~rS*1L3;i?%F7GxZJR*&>n6Wa~U~TPSc+uzW)T&zw8TjyI z@~CZ^w-S@IqBwWt-5%Z>Sh$55uh`e0Bc6C8kiOwzsFm>cT*X6~O-8y9kGQyFoy#N~= z)*(Pe3cLL?Q((^g^)qNz+*#?#*4K9%-{-O{UxQG;rNvK7u?F5~ky@9x@3`!DUabG| z&9Qup@4!-jep3xeAKcY!N`z#!&pF(vLBXx%KDAPf#eLPzy<)zOMDlnoPb(AJ>AxYf zYVswulUC@e8p|dtk9B$Yas)s%-=$(r(fZAc?d20VBj-dqexI3)`xAd?m7Z2obk0!w zv8@Jt$6{X=1k(+~aZF0ACHu@N1!f`-ZnFMPBcV|3mT-F~|~LCM4E$ihrQrU9Zbr4ZD) zr%r&AP5HoK(a{n-Gf!qSkQAAs`<@~UKHrvvxph$Va`jv$6`fws3MN!!?;4jN!LZtx zy6VD@_k`Do$ir^^oVw7Td5u4t15NRW8T8Ju!RxFw(Uqfu&%X-(jnZS23?u$9 z9o{L6lYFXtmko$eed7!?deF+Q!t2)PNB2aYXo<~u42dyM$L~=xJvEy!Y0&GeprzBZ zdGfs4t>~j(75%iQjtM$tDlEdcG>Jyl_3bC`&zy|Th-(wjh9hT0XJ13O?dtu|V=&{ER*KGTr^c;*pJ!ap%iR_Vj zE5E8(8DBoFmT*DptsbS$d3Nn#$)fXE3potVR}Ix9{u>V>SErx(UbmA7$YD4uNU;Ce z9W|tjvHTfudL?&UxQpnC)A zFCc|YmI7f@C2CC8L?4bc%Dr9_rT z9!7KiGP*~k^HWCDCn8sKb4N9X_-ltL{TqD(MFz-{!IewNVm>hsmdT{Qy35FCDO5O3UYJ8Lg;-|Ec{#6 zOZ$PrNLo&c-xS`{UmQdY{vTy;0aVr3$NfroiIfOP2nYyDry!k&1_h)$q+8f@BMs6e z-6HO5KIl=pcPNeTT=EYw~oCIX>3-6l)@-o3-j+)wAJog{K z5SpMbB^-|JM!Q57;EogZqu9(vG$xKCl4JH$8WITaCZX36q-yzU!*Q>(D_ML=K@n!s zGXCve{tX-p zy*>Z${?Z0<=*>JV1U1j-B@a9X>`4(Swguq?{HQv$Ui@736p8` zA)zRHf!vox%M8_dsaox~JTuW|Pe2{RW#uwO0K=moO-9NQ>qW!FabuKc zRK8HgWirWqUDf(R(=)LLJ--qI>4-J^qIzlW6cNYHZ*!B$rM#Wu8U~tC;<#*M=!F~ zsyN8-9@^w^`&N@h8FehZrN~l>-%T*|I24Nh>Wa3114@i0F%3dDs5pMzU!@58-s8?P zTS-l_ARhj3X&*f#B2IyKK)|qQ#F6OF&d{uv_{=jy)1X0x-O-@=`8YEu$QEUjvn*xR}IYP;IdO25u`Di z%MqvN4m+NBpKV`u(*Sr$wD`A@G<~G)v6<)f=~cX#h)G9!pe*u3aaQ^h zmeb^y!KB@tcXf+(QVSmjFt_ZzG_E^-#PWuKtW%WSLg(fADlc*Jd4958itA^UN4P>3 zQVxyFZ}GY0raJweW3`#SlBA>qQllY9>CX!2Nsz3y0&gBfow9u38#0Kl;39X-f zpaexq+jeZ1^f7wJn}r-G@0dR@87&bW#`p10qp|V^RlX{~DA2*`#ha&SDG5nind($c zUvam^_cGg@6b(?Fk!t5wXC6J1aF&4+fjl($Rgks(LWil^yWTz7LXQfYLSc0`y6<{EuB^bu*Y}?{cyTS)Wa8(T{Bg& zOESG5gKGuF>6d`q@9qr*gPH#N!BO>YyXubg7=b|GuP0*Gh71lgn&0pX@b%$2;7p`g zm!8yU36U0rMuwfL77)~{lAd`dbjZ7w@k)YHEzDZx3T~l%0IMgcq=MHXM2)p`TmZG* zfo>xD#)p{#k0WDhpy&1>F2e`oaqllYgH8Dc6OfL*ebkPe8YyyAT@9k__9ZS< z5=-~8iJ&Gnu{uu9xy&-!F!6^Khf(8G0jl#8!%Al!>{D>6&O3*BHtGfRk==)T>~D-% z=m~v22p1dMf!99&!P$$z{4Qu<>W6GKc>;5M-xjnZ_qiyY@_^hbKKu+A$o(0pce<@t zHlk80y9wG;x*tv+d^@_!QyA)`OajBM4jofjdrAIjOF6{6@ z?~6c%yBN(;4z$MbRsu1%RDqO3d*LBia(-%Mvu2((Bdlp zhqNWKP4N9C{S`M5@SVzU+e^SPVbkxe64iMhL4w!u-In5tDl(NXY+_$QtXek;#TeXe zCQFw&;HHY|4CpIQ~#}-)&5XloR7}=4)_~ARYRA9phzJJ zWKY--a z_=*4dDI|w48O7QXP6q${(>D=rldPra5E1)s!8P4N;{Ql_AIia}1mMe z4H{nWa#eCl^OP72n5}#NCgNY+1q$S7ia4uJ9|K0UFt*(pfk-83xvwS6!P9ZBNK{}>GzmQ)LJHHV7v#IQtE;JFA4tycRM>m~bz;qd zyt`iQ^0-b$^m@V1)J?b^+4&K;>vA_|`@j3aTn3C4?dmCY3j)$q5dxQ-vI4tHkX#*A zc-DOn*M5-2b_r-A@ton=q&dI|+D_E-cK?Ggy1BlZn57U4$fOC6lVH^zh#dP&QV0$P ziw2yI1r=rcS@-=K{X9^Z6D}f$&)E4g|B(n#pZ}$a{w@mdPbH(0Vj3kU#FKk4kVS@l z1P)p=$o;h%bZ)}=O>Y1+>kMRg8;S}t_-lTm6L^QQz=#{Ileshqbqg~(H(>(1tGaGW zD8W9{j9Bj8_thomG?7yh;2b!}%GTEQ$8yQ+zt0KKQutun4TtK^1dL3+9vB7xB){f- z(I_XCfa%q#A9A2t!EQWU0Q!?JfzJjvJmCK|KwxOq089KvBqEmOriooGnBW$f!B{{N~&!c;nR< zO0Q#Os_CH%AO`jqcBvcJ_~o1dN=Wz>K_$hP%q9R&;MYC<+P?t%IaDcg@?rnog48c1Xm(BT6*cP-+RNAzE>!SdvQII z5u{6lg1_X?rmZR(_uFpgCql1)#oiL<4?M(QGW5xxDV)cYZ`@S$=n|eNq-O#y7VK1G z5ROuu5dH$h<+lwe#L&xjcny!RT>KJz`8!z^yyU)qVkzYA{f>7TeW9)B7d(Hip-ik} z_aZa(J-1&sTtRh(Iz;C6wwp-PsUY1Y1!_Bxe+xJ>Z{Spm37M|Il|FSrppCq;TFe{t zTm>5WQ@+romq60u!VMAmje~$16V)~c4$*x(sqc^To1O>g8KY7`hPuTr zZ1UN-n(77ACjhWbnN2l={9kSF2R`kxAIGLfQ?>#Q?BT=>n80s&pVQ23l|U7HdkrhN zdckmxP`EO>2%HVDJyDT)OJTtEg%<+i@;~^u3Mv{R#Gk@9hj?r$G^Z);BqXr5i=X6d zH#E95->FYq0FhvCtEA%eF(UqS)64@*11xVKbWENB3f50qsB*~5aA;llXBX(RSm!gD zKp)1?N(@bLHEt*;=bA;0BfL6r77sNf*NuYKZxB=vcym1ctmNGc)I4)=)hv*@-fgp= z0FaxF#?)a=Udjw0rZ-++FbF-6(S8F!Vxcx6A+3No)d0r=okap3Q};rgXUxPeP`7bF z!{BnUmedTGc++Rf;(RwSZF{Oq+I3p#RQo*$uK0C4b-+cW@yZw&$Dh~~R<7bN^3kyc zXoW*jy7~FlnY_&Jz0x*^pz3HQd=HdTqE5%vuevvamC&m#e-+c34lv~ZLz+Xf3Zr6S!oby z7BTM0@KUfFhd`c-zGyAx{?wDyDc_!UVYjAD{!#0uG<*+y8tUU)Xz5NkutIpqnXz)u zfM!o2goG+18D5!lCSGP7k1|vdNUYVjP-45#dZYANRSONzxLp#__2<0j0FGJ9x41P3SWHN zRv^p%?kM@5e=T11w|&S)Qfuj+qVQ+E&zhaRxlehN}};=G7ZLq*p%ZM(f`#=FjM1q`r5en-~Z2*9cJ{J96R>~TRI&yj#&Kd!gq5h5~T z++K$asZLd)k@Gr*I2DIjh*$rcsekgcaf+Q(2nlhvojl5v&~N+9nVJ;4u!0Ajug36A z4`?F8GGz1*`9E{S%`ybkN#Xb=DH#TcinFnl*;yJauG)X@dh*82p5{k1><%Daxna=k zff6M)qtN~Xk%&!L+!=ri0V-zPqpl)+c+H$pGr_D0+*)y~(2kq$%0h6BgFcrbyor0# z9Z2ZGl=ef5dn;7~6sG67DOGPOyT)~Q)7@SDUiQ=8^5U7;XPN#Wo&!*a5qH(?jskFB zPDOFOvCJPBL2l9JXp?0+*f1 zVs0%Wn~?hOXzVT6M|KXc5MCrcwHJKXC?!253c47Ck4H7~>3icP=yt)ceTqpFFQUunZvToU5t@;}053N}vBy z7P6k39JocJO9>d0H$(Pd)Ty_;T~3{ej!O9b{v}tGs<%-b-DhpLl&UWTfiUy%>q@Ed+`M?U7N+2Dp5?rfyJfLNRa*^+72+O zj#K5juP8)W8}$#>#J>kRhw#d@J$#K4j)>l*JpAscW=5cs?=dVCx;mJXw;a8BnAYEY@(JB zLC@0`RE%Aza~fA_>iX5BQgz<7X>^AWU$@K{G(ua6&v5F`xF-wPaPrc+(u1`qBEa z_~qH8+@*mzsLs5msEWWz#s7vc=Pp@@ryFapxZ`GEbLe~eAq~E^L5fdA8aH|a_G%h6 zz;xJ>cRxt$p(P=ReGb!;WhaDL2qV80Y;k{A^b3wUs_^f#4JWA+6n25;g<5#bZISKv z2)P7nWRN&e-6%Pt zIOpp>0A>jNUI1`*{Wt^Qu&c#cRC4P@u`Y}%GY;a;u`jftnhfp?1erNO+k(0QJ6cg_ z)Y+46Da(gMc#)=#4@IM{jyG3?=m@T>@j*OhnGunkoFVxmxgTjNlZ2}(9*}^rB4X?2 zqUVS3h7^Xlx~1H8umvfK3ju@QaL$3Es)$DVA&YSh`BvnefJL1rY2+CpFVU4kgjXfI zQwjD3`UC8GFGAGg8OrQZB&I<4X)pMt9Ax;5;U?AFuVAy%psVMo{{e?-1YV8gBAq6^ zVJjKsdr%sk85j3e8>ytzC}Wy^Z5fvMyMXX z$E6gU6ar4>Yn3;o#v`wzwG$L_`x<3oYjC`Jy4UH{9xxvd_@t(MJ9_Oltrf5s~n4)YjM|m zaOWQBU#IaE;H#x@DZf@kPKgJE!oO(c|8Ud=0Y_~NUiALgPc=ONa9QOvW&9H@`J2bR zy|E$vjev#o-;;t(1cH~$9}}xw{ChO~m#k0>IP#J(S7rELtQw{yi1T&a7w;zUl_Ufh zG0BfUdu)HB#nx#4Vot7Y2^UBHeO1m_FrFkwCO%1I`G94CxKde-?jL905OGIx=Esjj zZ5#-MVS==H{tmbkgt1dVF}__oC-x@AtF}z=X)mW-Zw2=Tg6&oB0}i$t?wPZ zE++x&d`_GF*(A8+4zT18x0=W~4@Ln%$AGMb3F(9r{Kb=5uCV~A50J?Pg^?`g!&-Z=n>)z3F`edwW2 zyE$rfY>UL@Q|%2Cu_Ao0?*YUTj^zQJ7D7GjWpl68{^i{JUSbt22(tClD6t}5)7!s^ zMUi7j`;i+X&+B!Pmo#TX`-XIz*bzIWx2$UT(&+m7BuUra^<9H{(a^0gD1lt+`mdw1=`wE~H8UgPt;^a)WH%@LHgiGuImdS_2$b<-8JW%yU8<>~T z@7nMAI}*YK{vrc5IS_3ylDFL}lx7M;=OpsA_}wR+C@n(3u|-OwMDF{5#Ctn)C0@x( z5JmtaNI93HM;w4H_PXBgKws~|RO>z{2+lt^srTGif+C#dqf{Jz_}fulE|FTrLo7fmhJv-J@UF9r7c!Aq#Z={JZU?RcLrpQq?c0?dec#GswVG~d4=OA8$C-s+(NWeJT+h@8#=l7?gA6pbFA)*k;xXWs%SWCHDEi>W2P#s3afI$?hlz0z5cAOJb_ozBN@|#+W9nn4#R<~AxlMj&4>p5vDNL1Iwm?2C=3mi8ZyCn#N9|?6@%v;~5PCLD6vweNbGuYo;3|6C6 z*~K$^diz|ng-^>ukJ3;%gL~KzDxC_^IW>5>ZtlXy2_+sr@r}hQc(p4|-u-xq(`J3d zen1?o<}bA52&3R;$1o?dmI&{FB@1Efidv_|s2~E9ISv>fKkl%37x%EiIhY{9gaGxh zfk1IiK~ZcnK4YU@3P$dvgeX1bNkd!tW5g49M<2sqTmqB|ad7z?9NwrI#T37ilHwMh zOQ9bA8=X^sdH62|;I9%RNmop=w)b|^+h=;Syn4@*l`)*i2pCa)g)bx4z0$keUq9T7zF1~cf-xL-mL=|CCY`~a!#D;?Bwu%(%p+ch*K0i;a-Hpqp`8PIKTlcn(qG`#ljqb(?)vfr z13}BI-GZ$mR7y()$T)B4z(u6yJ1uA((^7hiFch|2;H$>+^()E(vikggdlc!f4mB%^ zb%qZC(vpBtePjOYKQA7UrnOjBjt)|KmJ%d_L{ACdv=x3NlGFUPv&q7dvJ~VmSCaTU z$MfW5vJh5CR{H+XPE}4>)Qef+i-HkQ{6)w!a3X+vL$RO(^Xc!oyZD)wO)}1U8V1oD z|Gqn9U#xWP@v*u*6aLN@=MSZaauiEjBYAX6@JT%S_xWU5(|-7q5k~dudCboVE~D~v zW%12vk=rcNyLfHeGrv|vcAy0#AU+!3#r6S+1HW;$>?gNa9*!T#7v+hD-vR{%Mfs;s zpL`Scrpg}uL3A)dcQYE#u zTggPesPclKq%UEGvt%%5yOtk*^&N!!ZDR!GtgmGeaY)<1Yh+9mRq`DEJmZ@Ge#Qj< z`;b3STEtyX(Lri$@j`M5#aQ4}9WQ_3!+I}{Febn>@&B3+26+Lpx9cEv#WpGhS$*@0ZPRPS6D?Lr^kMw> zW=08oWQlu3m8D*;(2w!Dil&n0CM(-Xe2K7}hY~3wB4HzPh!`^F7)5az(e1al8L1f5 zA7)d(r6*&bc~WK|IP5)MXmoTK^qk+nu6^S~iuba;L(E2x%!)170!k|uQq{Un+(W?O zRkshSy$%l>951d1h?Vvm2_#tA(ZC35UKm>G177tmGg(|p*%==5wELt5x@EvbJ_f;Fk7U zcpi={1)h0(kzpGXpBrPD4iYTEL!Q}|1+Ne%t+n+jjtMulo713D!=vYA2nF};EK4;t zOV%yVe8_Mq^I^CqrH?hLppx%gSFbFlRctfYmvgFu@?34{0lwcdn z%^2s_-tRkleC$NWz+iN`GbQO*5bGa2BFVL=R@7U2)N|y6ns)zd+-|9qfLraT@AQgh zI@&k8gQr|}#TIG0&bD>j`U&t0F!3dhTV9b6rI)DNBv3x>`m0wJMo>-e!fymJQAJbJX@C%1=lGji`fKe)RqVsu$Dcq) z9no7Rq)Z`!*8IeH%2`1n$YMwl4{v4-9&5_kBwb0EQPLU*gunmc*@J+ zj?dCrqTzAr+LpnrPT>RK*ZNTJY@?$It9GMBPWbiw1LgoHkB9{|;A{0t?Xff<@z_%0lp=G?-QoDGxVljcaToaO~)n zYb_psYh-`hu!HYC>x4+8UbpL=+2nfKQ#t=)V`h#jren`9Z);V5X3wJzlVuV~12-+d zpn#T-kF3UQh(M(K*#k z#$7*sHfPQzi&i3y1bbrKS?eDhC?D`65_biG7Br9O9x}G(F^33ogWW6^DY|9twV^U~rU;agmKWR_&Jl z!YJC>s&d-Au5as4{mK6+FEzdp{}uQWjxOc9%DUl=qUv<>FDPIh9`3wkvh(=er~E*` z33+|cl$kPa2?0$?DnLAd`Y9*!ytlXA*@2Hg?bOEf*{1>6?n69F_ymjp?+FI||CwQ> zS}Vuax_m!{+7LDi!r45b9=gEgPys@e%Bd8hB#o86P|**jMATfl(r+ohj^wsfTbOF8 zo}gSb8oC+cU%H-2SqCs6Uh6FVw5|xe`uOv$+*Koln#PntAcq928G-4qCmP2m#OpjG z7Vz}k5Oh8`I0{H@76?1>*ucV6R#Pf8pXFy$3=o&}VNqwJvTbN+@^iK_6@qs;R+Fvd}{ez_I5}7)? zBuc;a(u2Q48S5-*S2&KO)?sn%WwJT>V0hl0g0UxaEiOW^{LF@(I{ROCQp;I%=V&M$ z0CzWU2JxWatM^>hdH%7Ju?+ztR~~G z#P#E!T*smB28fkrBa|OFO>|zH2q+Esf%#Ls#Qz8lFK@RwuO$%1m1oy?i<8c(mOJf= z&&r+*qh)4((#eG5~*D>DU6yy3TM_cr5YMk)+*qD!xrGfWz%wL$u@B7<0I^uO4 z9b81EA#r3xF~6nVbu7fjQ(UcvHl5q#lCbkxP082dO(YQAOX|AW8OJcO@^+nor_~&dU|>e ze{JWMJA6Su3AA9W!RW|!4C;JxXn_L^3MODsc(65U)Hr(pg91;LA(;Kg=f_iRVE?LW zDIYhI`Lq0(iT%(0YT%?16KfiDiZQnGoc5wwK>L|EkbppsM=m(2W^g8@9sQZo~}X)AO6 zU(W~CjwOTTsHiq7K~iXMe`n0Jr!I-JNpxrh zI{j9kH#I3KmCu{udGr(4KqxpB$=asYdSO>f8W8NSP}KzQaxOOxmi_17mS7{ z#(v;Y{nsY(K9ZY-<(n}p*c#&+wXFL3|7>WmO6Y%fG;HtH=Ru}i_X`RJ6PBj0yzhNU zwzlS9nwjXqAkJ^xJ#J+0U>umx%n{K;an zU0m1HCrvTTh8$||y>YjkaFP9m#(=R0=sXktEtO}E2n91d)}mY4v^fy%H*?|5pPTyi zSMLnR)zumM2I7uYx5aL-wx?Z$Hbp>zv?pe07C3sGf z_PH8g)K?KWCu)zOr^Tm)>Fz}{$iGyA~SRc9w6>-2~-mX(sEzC~IlbV(hDlWD% ziOhWHsG?k?~QlAU9 z73~jQY+0%$YGzee-+c#z9UP23zD$7>C&v`A7GmBL@bB z*g>x8XlZHbFUal;tis3M+Li2h>~x2i`k7^db~YNz;$n8aW@KHGGBB$-VdELZW{MS^$0%H`#E+t*>U5xAX!+8QkZ*t)jL_IdMxHb;xR}xi+CbQ~`-H}t$HI$|x zPa678!e`5>!3~UTZVmi>#iyNt;eFp&B`hVW-=&Yy28I?@huN_=-}{~Xz(_myGFV?k z5poJY7M1oPpMAZ9l6qFm#f%0Uf3NxfG#VqiJgi|WPF-Q@yzVq&*bFR8ccEN{NKGU2 z>aA6TJvB*s_NaoToiC#g<7%rKJ>A;7z7oo#uWhd2uu)MVSoU-Iqm}P?PXz21rWMJf%a|eLipJ>>B*ZzvV>ojc{2Jd=dY$b9c<+RKhrf4gc(Y;)CMG zB;YN)9G#FQ4}T1|?t6bj7r&ml?&+vT3>MmeRZMxVNc{)GUvnenKRpPHJ#6pU7IzND z3Nxbi%>v;E9ou?41V+s^hS(X6C7Ch{N#8ggx$TtMOhPPe<1VjX?+{RK;HIY{4gO5< z9RdySc(%mcewS{#SgI(AQ7fGrBGwFWC`i)2odGH()Cv%JCg*V z9UBze;pGPW=T{BwQ_8wm)#O!Ueqf(^eVxqdi<~o*m=c8&y+lF1@?owE{zxA@O zqgjo;@q)MUgE-El8NbVW)ZBtc>EaUG*a`+YUKPq=E(|oO4_R{wc7^%Gs8<97JEg{()&p zi4Pp9j;^sU*%4f$KTy-aTV%T5dGSqFF_8cEd|}UZgvH$M7@CE&N$yc{hH$FP}#jZ(TnNhbk%B2 zP_L)z$u}DJZE`y(z^Lc_pq*1~S5+y^1L30H7{Wl&uWF$#7H(POO;CVmj&?i=KcN!N z1cttP`KDZnL^HBVl!-2)dQk~eFYty8ltl4S&oIT`lGp~IHFjyQBj2>CCnq2kY;JB! z!(cr-Q#Fy?Hu)IC?>kNy^qF| z9vn^4kkWY#tnR&;dpuJs7%Y5dLdN5E1yv;*h=?8!`!88FIrhi6GywU7fU=EEfo|N^~vgC>yQ*I&;$xc_W9Nu^m-7kk9=cKb-bpkDd54LYJ zL$h18J#~KbrMjBb?=(m&9?q`DC_mhg&(Mqgrf=9UEjj^5ylg z=X20+9UC{<8w;a)<_$rY&7A|? z2oxGHWv~*;UzwPIxo~s7i^tgamC#FHl<^Vuei+)shHp!n3;#}@aQDTU4EC@e;uQ4S!Ojlf;KsOseJlg&Q%N9yqZm}4v2u4Gz zD$m?mkL%(KkoG#D4G)s-7M#l<5C{ z9gl?8p>)&JL#OcC(@D(wEnY)YhzFYafq(@H&}cvWaUfxoxEw25IxVm7t=(fRq9Hw+0jep>nM zQsAIN>?eAiVG3HrHr#4}A_Ss;S~XAmjxL-UujIM9Ea~KWU4(qV$KE3h=~KcJ4{GR| z87-O*B}(9uHgcF^5rU<$^i)OAJQ!k;^wn*RCo$=I3AMRFvz%2WMfuuRQWAfnIfJ`d zS4m}_gUg$)-p$Li!t{^tbzLFT@{b`6Q&S#TRJO)z{#bmOs0)ctu=}12V@oz}y)aDH zS-E6yQN)j3MhaxfHPr+gy#DRT5@;Ll>f)f;MEJ+`Jha%SM%HHI3m>j@FVyd3ar&hy z4k~=!39Sm7&a2<-9PdT`^r>M-miYcu%1W>}I)0sEscksRKy}#tDs(a*HC9RE;GG4tsn*9 z%DVY5w>ZHR{CcaI)N-T20@%|pKJ)$LCnC(q!>KoGn0Cw!tGv*0VQ_A;*+}#HRu!*y zA^HV6y2VXmd}x{qE@kH-?c>6-#$zEaHPNhRO!?q#caT$1`rO)=+TxO8<>*xAW4WSN zvJc~|H6Q)Zy&gNNW-qeI&St7I`ZcuHzlYd+kC-B`JzC%G>Z)U|>vb&a#zQA39Nq+> z@h#$=EHpgl^qlc>_blKlfB@_6#j_u}`Lvd4-pw>bwqEu7)qPK^Wiu~Th3P(DFuDkd zU8}cM$N@$2QGejQr*pE%mNic|ab z*Cb|@gQ20D25T?slH)*O91+8`3PUrlcuYEKd1+Krq8H_A56O)=nO_xoc_Qm~M%#6J zeW%`cZ>Mi+jANrqM*2S}gIST#HRVi|FMhXmkt%A3nhj z^sXp3CopP-=935pVhwy(vpiRaJCav#9@}QCDm;F01c?=3jZ3rP^fVE*g;)mZx#HwB zxhQMpEgwa`7-gMXdFpm7J$2`y*cnDf{sUe*CrR?u^iM*aIW+hbqw1C10#lr~H%a$4 zm6ek2ge~2mxT7#WVNIm4RNPge_c?-&4halyjq{J@g(ti4|OG;&FO+7y=j87% zy!$F5Q2<0nSCTyr8HD66zo|T2>xP}~{S5c@LL9Cs;feM5c>TbHiApbW7ap{&nfERobo$QB0G`+ta;P12w}!I@ z5${iIJ!KrC3r_hp>tVf+N!wGmK9j0GaNx~Yc85o(RdTjAnzU|_Y9fR!ziMZ!k)37X z{W~fiGoOgDpDf>dCGHe{GJHQZFLo!4@(r%$z08YMtsRA!W6BAL7lrz!T$J|2O(O=q zip1d5`F^qN#t|}`OjlIsf#`%Cg&}ewlb&$GjevbIMEdv@_OG`1h%NayQ$$B7IA{`; zE89?#>t0bCU~91o`R7 z$*le87aQ}O5y?WWIxPy=3iK$Eyr^CHh>$zBc6i%l4TGse13?Y&_#06)AO};tQ0*(rC8*7wMCg zj55ONz?A)M15+jE_3|>f-)}8?u#uK+C-+th36`3=gX?tgbp5KhuFO4a9?6u~O%T)u zFJ`_o1v!tOs4zWuh^JN06JtzzXDRshw++Oo^IG2ZP+C;{^2;*6OEG0{O;}8#vQwb3 zh}=Gcvt}?oYK~sT9rSy;jzE(h9 zP<8SC;0GxU%-4$3E#ys0RRWiVKPbEAHLVBR`=5|$n!jgPms@#zGIp2RZR(M{Vc=b* z^s`P$CC$%W;|KyI^0rkK7ZM34`b=UsjSrQB10r5F{@gQ+V#WRy^&P{731NIvT5-7b z0WH@p2#D`UikF!T8@a76?`6brmj=Nu0nPU`}(3K6{bOqI7aoS9}shi||7gdmx zk$6L>RTxw~$jS;HI1#o2eFu$p4d2ya>OL}3yyWi0^t4tefmSc(8bfld=d~3kx)O0gU-(ks3DFx&F~ZN}ilBGHFk-`u#~@tdEqUbOTBik{By#xqw6Da2f4Y5PGAp6`Ix3 zjl;F+kpui`_n14kZ%%$tYWcNlH~ur)u+Q~VgYww^_F6+4ZDc$0w;x}XAvp}3h zgiy(!d9&Y6St=Zz+iRz@$|#M?^cZZxy>MP_8jAu<(?Z?fpSVoTS7h|fZ=(Z5 zuw~IZvvhs+{g@s}{@5Ax=R0>WVLHNOs~YRe^19uOL43*`3i23+JgIkiudTnlNUPYS zdmj^L+bCnNmjDS??)4_{rYAq5#E6V&f4|MZ=&s{3RULcxLjh%PXuOf=*V;!lbv1-6 zYKZS?#^z__D#c#U>QpU$ibCc{gfgG4pVF5s4WZDEMMp5P=>^;*CCP5Tdyp$x)C|+4 z`e}=Pb#^fJC6VnR;}a*uITK6ibr6_T&7Be6T>fVL~QqvL(n8a=O861U}3pRs%Qd=w>#|2A?$ zCEwFgEBXM&7JX;no9F{x)@Qq`_g_e{i#7*riZ^&ADW&%XFrX7Sf%We})fg%q5e3QG^Q?bMu0g)My@!IRFP4_ywVKTE(frLU*a+^BEn4?4OZ( z43KtvC0vQjH|mt?)QaCLxcPZ3VAeG(Gu6!Uu`FnfslPwQ>k`|0rnWI-lc|6bu{a1> z4cl>F*t+ujvqvFJy@g%<2Oia8CnzX)E1BZRrYpUx4ZqyO!NehufAwfO&$utvE7kF5 z=>dWX&V4QGw~E*g_~ZxeB2*-iU{K_8&#C4J0xsn))oR}TpKQW@6&m?|XnvDKe6$VY&W8!_PeT?~RKq z8)O4eiMN=QU#bMocFL}7C*%FT*Z5Jld_p!DN=A{JqvFbE`I6tAX$D3b@n z35iTayw**l&JJ|$98TKY@%H!IXO_!u4NYGaP4jABi@AerL&a;VYm0CLFgy`yyFq>I- zTW&&aK>}CRpFrtp$X|idXTd$2Jro6p=T=`j)1g*f*vs=DbzvA70|OH3CPahACQI@^ z9ur(BztZ)s9#OGh+T7Sczq$EoV*a-6^CeS1vt^}`9(VoD^Y94O?qwY%H8l)0H0=Pi zW?J5Mq8RGE5cCs~Bs+?nE-v5N!47Oi;GN}6zw zW*v$tX$8@Q;&aTG=QnxOJ)JEyUl&r)bsJK?_A^;l+AO@Xp7lcAEI8)XeCg|#Bg@M_ z8TMgZ-jsr98NrY=)+zh9x!T=MY`UjnHzYTy?}K%WJi7?}hYM1v%4IMUuHI|FLjO3C z*}kKY_YK-}ZEv-P-|MdQq5l5&>y2OEhcetvRw@UO-8yq}adpa*4GjqBO6Z#1rcY}xJ)HM)E3e_2{yEch&rI;`m3+o@i({H&h@ zU&(ZYW&B&euPWE?9{=7`f6uD7U)TdqBf39qj%N9@7X|&i99LSYJ(zvPvf!ivLh?oo ziq?dr3}(N_sIE^}hQyVD&o1A*!aX_l`aT|)FORiwAQ3rC|ExntX-_n?v6)}rF7poE z>9H;QGf~|^zS7@siVE2U`7v|pbzNVb2tFlF`&x#^;l8-UA^WZ4i!z=5U4vWaOc*Qc za=UnC!k4`Fg<-9Qj1~Bqf@$bO@mD69pe!7{zSv^%NJHrvLNzN;j{Mt`zs5J!p5M`NiG**m@N153B zzD)OyMrYiabUXoC($BES0%k!W$*pUC#80w~j=Pxv5E ztcWKSKFk{@fLr$94#?>L9LkJpbX<4gJ=5m5^Z3=3G?~vP$bN@VvYzcIEQTVvchv5; zbXdri`Q}-@0Xv({P5`0%DR0Vdz&AmGg9V33cA6Muei|o4>D>p^674AGUz%G?1R7C@ z?uKZQ9Aze|v&0Vd4-B=}h}{N2cjz7=XL*v?J}pW#P5KjoYQ-ULg_4gC9@TFOQ;`Kc zrd7yP^)Wahcg^fMBOj@{I2*0*+TpVb694h-O0-DSyN5~Icz|E}IiZiGzwr+X%!#BI z7`}eT#0%YM^2K?t1VEtuIz0QMMz+1j9Fi~wH%gu4*^?$RZtf$!aqIq65>Lrn?ANpzwD^na(Lvf0pKuEwLiWv( zXf)AKHhlj}F7g>wg?d%1_M%h}(p0)s-;g%_AGY3tEv{(m(nSLV2*Di!!GpU?aCdii z4Q?AJxVyW%yF0<%HMqOq%K7?q-+u1>2lZ6#ReQ}b-ZAD3I6j{P+Qg&`UFG1p$~ z0un0o>&4g`1yv%72#c|OMu)tLJpnm-ZFe%3zUznHW2;g&t7%kms+20DjwTa#n66aASx##>C^*uJ~E&@YcrPhrP4naKSF?iftEz_D;WP=_o!8R8I)mD7YWzOwHk2%9eD~$#fdPcKdn`Rv| zr`Yw&(=;wS=8j87z(pwdgx<{&tySn4N|1W^!vO>2w8?iQs#*l~Cl9MM3mjt7k%}b$ zGSsqEv>%up`9w4P2mQGKp$>EVzQrx{#QY4L(LsA{ZR_v(Csh|0WQmKt)9_qBhbAXe$4^c=4-X6p0^vrsWK79&ialzdp%nLrE+xu&q`AGTo%5;#_aQudjqx8&qKDb3WW8F;CiWPs z*>y!2wg+G=ulN0JTE?@DYBv;ftD*7A9`HN$072ZxpW!Rc(YAue&&Lv;ls356x%b z`r_%{gq^F@1#BDBb2wv6NV7de{XLO$xmTTU$noPx*8;rkFZ<``1k0(qx+Y@6Up1-s zi^{~B1QDn6C!)o6g5}^vp??DdrJ>W$S340sWH@`szds%+AU3p{0nPn3SMD&?G4*PYdeDWAX#`pJin@ zKpO5YDQbMpmcOW`sO;cDez58s;TJ54=f@1M0I8^!@NEb4qTzB16rWOG{TvdBf#vBh z-=Cr3gM=TGE-Yc99D6g`|qk zjPcK6&Fo!(G^QwPM!`b7Ef$!Zl5o7M!f*h4DsUeDQ75QVLi2g-EJoKRDs&XSRtH7| zM}aFL=N(GHP5+OqMXAGCyy2X5>t5}X*14B|XBPcvbhVYs_d@rMr(0OokI6S1-G zxzD{oH2P0doHgosNovzs`wg-WLVJLh753XmmOotUO8JP3N#=QZ_M73Edhzgm2b8l- zuG%=)VU_K--&#%+uNac)Ngyz3wZ4K;VdqF$(16X46ECj}Yv~qetYFC%6qc^t1qv~X zJmD}aJ&hb@euh2)T}uP_>G!%!F$r(aoYBWZ{;85`;LRW}Ni9NAq1o2cu>q?e)rHJp z0?p|QI^sZ#ZN^vsuFZAX0p;7#Qn%m7Tqj&tklymDT^=2!XCKbrU|e|Hbm|2zW4`65 ziU|B&%~B5r!KS&`gtFw+Zf~5(3swDC6YMW3PCLj!G!-v;KYjMNTp226d|U>=D^k^y;AF4H{Zr8;_=s+bUbVOmpS(FOdQi&BPzGR1Ovq`#}W7R zKV3er4qRxeoWl!O1|P23SU(Ge(& zzM_{sS!Od}vx2t7Iu(_mh^b!3N2e2%ibJ{Px^mXkt8MCeW(j&QnQ+M{40~Xr8Y44v z%t2-vE;AY6elW8AlW+_r;sup*ybHXKSW>+=u^NmGy!ig)FI{)kH(gZ*8xWgSfX%ks zBUpf}Eq^u-mi{IAK4X}1GWuG#vsvKkAu#7@l?`~M@`1*o^LJYw=KJ%u!Q)Yh_rTW$ zS2Q6Z^aTPZPDFU8GR>X2OtSTPQHol}3E@RCpT}G9SAEy-bAg24aOFW+tNSQK1-zT;n#59^*4I&fLgQGg=5zF$^R%`nwRedtM!2fUixT9_jH9nbaYpCSVUIF-Mk@d zCnVr#S~{ih(P{QVV3S#m`QB1}Z5Q#{q~0gxB1vM83_0Pc{iP;?5;JsZ)pDQ|2MEaW zJ%p=phn70$Zc-O6{I0qoi? z{R7IYHAy5A{lTS)&=a#OaQII$VWFX0M@P$*SO1xxWs)J-DJ9p?-@T7aN;#wwE70cfKv%01uVs#r- zV1Q2B1Dn(J8c8(7u+aWP@xdhf77d?SP`-Q%w0NmUnr)qA=&q3NKMyIp;cBPVxRQp2qBW+dHp3RX-Tdho*Yli(h6&u~_8b+ikIg@Q+G0oyD|sA- zX?5@IpW6EikgMM|>-vO$l5!+^*J6bMypaiMjB@gB1(6OuNr*dsmR}2g1f?m?O39LC zQc=_i3zX1Yj{+q84b{EK1N+x~Z-~zzQg4AgUm-hdv_>H@WTgb*g&aO>q$D|CqH@~Q z|5+?)$sd*GMq!*D19ULC%B(3&b6%4CcBl|K1toq;hGeS};w%OAPUTD@-=r!SCxxs>B`=jx}o zxn$T3Fr|d!qFUW}DWh}j(I$oxwg*|G%qH%;FxLRM_T=HQ zVw0TiBT%mfzt>EjXjJdKazVeEwPXIjYy{bw!p6^{R0Xv24}xWNawt2_`yg|gp!grw zdHQZ-GVG5-I(vyr1|t_bcTIk4ubp?da?L>7$n1l)CE-LScVGkGD+$2`9%fk1Vz^B$ zl}X$_Q6L<0q$xUl;c<-=&*xNFbMs0%5CwjSeFi&p%=8<+9EEzLS%+tJ#c6pmV}vtA zH&GIf&Md?~_Uk5{{QV8JYfdAEWY;4O!g^6m3(nVED;o0(fd=1M;S<@sULqW(A#$Lb za+|VyfqT=^!^4AU{&H59Pk*OBq@rcumal0FbREEFc#26NUIw$C*kk8r5M6HDTyWNO zkK8tTQM~CN%uwKEX~6u7e(F2L&j#WV$4nOEQYMWu??C@^K?5bf3jCIdhmyr&;m{vn zGFI-1yeq$z3E2#%r?ZxKhX2bX0RIUk9Ggd#v6%j!R7`{~8OyUXJqzKl%xGHs4_h7E z@pQ+h0#iwAg(1&<7s->9!f-O|UvE(C?3}DGSajUy@2j8icxh`yz6-8h-QRrwT1?Lv zKAEUGr#DcDK&_oY<}*}CO}hdK>Cv3$u_QbfkDg24m967f1e9DWvt;DkeJE(+P1<*3 zcR1ji>C%xSC(Jg;ur)~LlmF9^PH-9f*_8ucBpD^+H4U2ihJFmC<5@9O%YOTGYtY<< z>0X*V_EQExFa}LvAx&tB4O4GpopYXRul+a-$z6X=!dA%#sPK|&ceHeE-c~j6iZyjz z<)4pk^3X+r%vxoU9=WW$wD}SUSF6$D9`CnmF)2I@@JuI-IuLkF9785BH$RfHwEnHd z$#N3MTP8ddu7tvOcrsZ`))6tTD$C-~U%;aK>p2};3i)CZh}@+wPC`4cGO5IC;Wby} z_{Yw@onGP;z1e6Zyyxx|x*e#_uI>RGNGS@s^+3sc`|F4ewOR_5_w7QSp#6HZ9ml%O zFYH>)5r+cn$HPxhFO={pw!iwoc>kAmUhFsG=-5fy{A|ly zC%1K5*>>IwS{>xu-!EjfTnqh$$^=#QSn?k=?u6?zJ5H08qoqsXGn;na2_q$v4+J4k zam9G!z`GpEsgREF_X~S$&n^xo2f#VGUU;9b#8R&q-@BRQs2ZHjUm0iy^~1v1cm5Pr zMwH~RgYB|jp)NIf+^S!$+d3_^!sm=}M@U-~o59bCLEh0blluQSlq*)&t1}AH+pjR!c=68*0KNKsP6y3d!!3fq%mrJa;mw6< zDuS=&BlR*agZ@93(6{^x0jw)~v}J-ah}ee@3Y?PLH#I>X=8v(I?>Wa>2GO_cScxZa zCg3K`T_)15|C`uu|FPVajKZ#6`^^3hJZ%#iBwuu}qrC0D86&o|mVO@V(oq6R4tEd2 z;Ft<~1{?R=;bc2%@K0h%pT2@FQ(YV~=^ZPU9#MPxfBsUJFUJPP))qRgjeI^^Uq^yc z?DGUOU3CD@S4b=>&aUSDIWUz}F{D-VkY9g6xX^%LBZCRW#8NdULy|{D1x-5)w3jdh zc~k8p&I}Wv`jkQyqG%-;YH0@FBMp|H7=A_3%N$d*1P3+TZwprorv#qscB*?J(0Nh_ zTYJ6lU?GI7vK{YF+FA`9?@><^7(aWv{(^86QPcJ2iw#3hW2$zLEEL07(fJt1kNahuX2_8P_yszsZd z$Fx2!=-6GpTeANq`g-_JZH;DOp}9)DfI3mM=5H-wh$iDZe-*X&+<1-7%*9pg!7A8h> z-50+azW6Zsrl0&8x@m2s}0YHE~US^VB1^MCn}@}(piPXgkI?65jb_$ zhHsozJWY;coJ4@mi7(4K{wV(R*-3mhEjqk61*BQ>#6Ak(^%MWBp$Lcj$6Q%nQDfmi zcC?9B(@KMmxx{Ce2JoU=XgZRGO6@TDJduH5&-f9DZ-Ur)zB2LcfC+NVh4rD$aX0GQFubfzPJG+J_eG1yW9K4k=m z3Wx9$1qDx^sbJ$~fTZt@2d_tnR<$8zdy5E$eZAfs^}O@N=Jolc3igZ5WeT#7 zAsHIf_qxkYrdfl$B;5{Y)pp!=mhGpkD~w2hG>;)-_fe9rcL-=%pNPer7|hSmuMMe-?=EB1taPV$#4ztI8>QxVe^Y>_g^2C=IsS!|Dj=n0_c>ioiyyReOjZotzoC%T?R23IOyc5ve}~oid^U$*e$m^7NePHu zj@<>S$w~zznWb&NuYu6Mo0TP1E!~-v{!0zjo8 z2D^h1p~36&zO!#*n*kkX!h1{o276FWy&)rWkB>msZrE97vujP9-cR8A80+?sN_JE7 z%82<2tncL7VIm}JJoy)w7Ra#v^}%7a;e<0JBZk8s_)Imopv5oryKM@%f%fylVj^!(qcHw^*SWtlu{`zmmu!kKuk9 zz5dbahxov3q*d+(0JY-ayf*hAb$Yryak&NWtII2}&VE@@OjJ}8i@}Q{*mZGv_^mAhET~ZvN2!2&*TJj3#v4}2GDS0MVu27)2^q``<>*sh4H}3XrY_@ zH@w<#r~^@iN+!kc>dNlQfAx?wlxtP0U^th0Ys)LH z1k4ku`(cvsise61JE3mQlm+Ps@r$_Ka@E^{ucb_q=tKO{b%a#VUPzqM%FI^GIck2``<) zfHrmph6|i6T6i4760~cZ*;nTwOV&9(!rqV`1RNq(swl}r?Y@x`8ttBQ#lm}i?>62D zKYyI1zB7(P@M`?Duhl9cH~!k4w3QH z*7D|Oa%d%w2}|!j|D^QO4tA(E`*ZcYMpe-Oi02{*o<0zcVJ0$gLo=@5IK}q_v1XxxT79f1g^Gp3Ocq5okW7%G5pZvofZF z^I1onISXPWOqVTpk`v5s)E8j{}tts3=E!3@$>cd)hyd)h)u9afZ@0iTy!D#XbnQG0x1pMRf;n8yKW`26+t={33I!K1ZWw` z2`k=8ovacr`Yd{1m2x6I?TsrAYej4)f&A0z8Rl`b8v**IVWIuUZm zNq1bbyS}ObdQ^)0?xiv4T}Cu#yhW$d9X8Rmq#oLiC9zx1-0Z zdMzF|8Dkvl$KtRV(Qol@4ZkRSm1U8iFHV;nU~6)`E%Ncne>4#F5!Y4oP6woWM^7{4 z>cYAYJ$_DvK_Y>2ub2SkumQ7?Bq*68nG7nh`s8FRa64DGk*-rqwWbEhqPHT6uCzE5 zh|7ta>sVHs&1$%k;QZeSHgH#1^qyv*g4UJ2IM?Thv)nZhFWi2$7p;KATk&aS)e_*kA3Y24*8cam@)QY>U&@ZBNQT26x~3tz%6#Uta89>6CS)Y?9A2G5*O zE~cO?MS3_GaQ#I_np=yST?(f115b{6zb3)h_r3CPahC9=&_ywwJ04TmlGSv_-}cLn z;{@pxTTL*b4&d;+REocEs~no0G%aKM8C0``S?)ZFl(J6k_+jw-(71l^^&oAcKo4Q_ zEj>N3s}r$iL3GjHaJK6LuNg_^VD!`qQ!Pu75$eD6TvV=-%anTDvOsSot*?$+V zRQgKiji~?Lj_{XIFxQI1Yiqz(VG?YOtt0q%xQYSjMs0lAWqY5u?HvKvD$dCiq~#a; zK1^i^{*v?sF5Ub34YbIqAV09gq?gRXQ|`onFzGjfh~i2jA26|Xp2QkLRumC3_yeib zL(c1>&3^}8=)0N3=UOjiujD)zMd1teyk9`?&XJlx5F6|mMX8DlkOihbIDAf?pD$D-f4%Gxf_nNf zyRI~&vs*g=2n#=6?+UAV3?rJZMn7g3G>(`=eZGtSxq19^^3?L$-ZdDFcb2J!?fDD# zoWa8{hcV%MD@vjS0&{G4qfAQVQ)G_8srVd_3&*xW$R>SAOi)5W2eXfCCZ)x2bIuXU z+GbQi`=Su*Xbyk5qR>@kvK0^W#l^+NYN;CB>*YQHVCpzdsF?yy@8E1wqs^D|_G00R zgOw^PnK|63R2wf*x&m*8{tWOZeRU{Mc|CdvPMUQ*@SEil1Lu7$s?0+O&1{iJ;hIB3 zbEf4L<&_=OO49T~Okvr!Q!0{ge_L3WCegh!Cw@m=iCkdu+0*O8;?gPaV>$gvo+C=Y zDNP9k#I|t~lu1y;h8cqHZZ6rYL8IHGk(yEFu(hrXE*YI6I80RGpcU9ZK@6&{L$k?d zsnzMn+S=Y27uGQgCEHnOPFX1;n)JSCZo_Wq9 zHMjq6Toa{ndMRGKw1B#$ky+vFd9A&*fiVfm8n-(-b{AGnXM952`%kER_JGR;EF}Ya zMd{$DgU|xGmsds)H07o5Z47Q<@M7>9g>x1WpUIPtBlUD)T-&sL%Ct#ol~Ckpd^(H8 z9?NQK_(;)N4G2Z}8?xs<6(~DXl${5_(^$Ds;4`{Op`EuBn5OMzU{r7ivGFb|0-N}Z z>K}KHdbi=$FX_W6u$B-qk`faA%M_H9CDQV44zC5p;n3&0II&T4QgS1AfgDCM^CODM z4x5I_dEiYn$SXx8rf;2>h0i6s1p9ItzRj>?T=Awj?{AEj#$Nh+U;Ex#bhoo6^f`sz zKJwjzqCfs_pxz%i%23`H?(JTN06+6HW_G1)utD*sZZEZ8gLnIb4AZWMi2E;4Ox6aRpEe4cJ}mM9z<%(^`3 zm-lvB{^k0*c$2*48QW+v8CcHfs%!^Jtz-F_`fjl+ZNIG6zc9bwB8326Oiqr>I$mPf zdfeMR=zctXPG?iGn&Fs!i@rXJ&ynNwWWSz3WnO<6B66kw{}O#WIfF+VG$;BVHfc+0 zFi5TFoP@b8P%ap9ux1As)2wMV|iPWrHR-&^eI>N0=7pfA_SDe599Xr@{e4!w{V*WFEuK@ z-XdpWgLJIS_`0ne@@?|Q^>V`!84HKF>BTQYGLbeS#UDG>j2bk4|6hm(lZQj`p!e>! zX3?y#9!%fnxCw?UaA_7shp@7PfW3Kl7v89p^O$0MGJDnJ;#~$rmWQYk5IAD%ttb@? z$sS+bO_r#29tBJZ+M2y)tTv?)k|9R*gREg`MvURYZ@)(aK8c?6&hL>i(bv!GyeSbZ zV6nQK=If9+e^X4@jkTPUz@O(s6Tf=@>FguUysnMcpV_wq{P{n{EHtf!M0TToP_iC( z$E3+c;kgXK>cn;uG*d9T(X=dCUe$b+gsAhSmabRNZ>pQW9eVV0n*RnZ^u1tHc|UBj z{xm8fYI_UaIVpQ>s>S1&cTe~?^Om5AW#M=A4#)y@G-VyrZWjwfoz;Yn&S@%gFS z`l|V6(57NSa~EQ*i|2aBWDi{;oE@|Q;pth;{-`2R9oJ5R&z=XH*OPsrJce;7?GLrx z$Io&9C71{!n%KrU`k>IbEAhO0j{OiR^ECi6ydq5I3>0>>)wSfgqU=#Z5po6hWbfej zDV3;~MBM!z7k5CRO3u}TW79%ifOqf$JImB?Nu4miB2C)$LDmTi#TVL^fjw$}@{cxrJ}XY5pob&iR~~)7 zOSFa{`kjostMS{mfVIG3;-?w8+-#a02t*deNN>I|S6?J%=KsP3yeE3ylrZPV$Dvod zLxxv71A{mIeyJdgLzVgw0ePZmOV0(_ewPr+YVYU|1(qMh^D7^Q;l7Re>}wL&E`w$0 zwRF`Ct9oWrt*vJ(Oc($pVl92bonaF@)EW@>$SHs2Rm>{FVF~=e$$GbXd4zkRI7IO28fhAAVV@Rt2i+}82qeBl z`wj*u@wB;rFLBYU8^H9w41t}@C7^cFk1+m!1v>#v641|u!hLrI%3;{9x4Ez-S|-dJ z`obU?LxN$MY@8I@4j5WLc@@?3B^Ka}#vGVhzg`8>RbhJs?<{(oSK^6gn8d2iQqZ>z9049bp2;?7@{xTrv#VCXL z_wZ0H>vEJS_Uykm64`el#*UtgvDq0J6>YUCLdZa4g8z$*~@q3p%v*Fo9 zVs8C)1pm^A32n(*^ytvbe}SdS?WT(4cwQ>y(NW#}8HxA7@{N=oyAJ-HNyeubut;Ws zD7r;WDFUhagQ4gs9;?(QzAs5ZF-4M_&0lzo%0U3lx~L=)oVL@-S)74zkh|i_pmve{ z<_{DB%R!cmtC=_Jxa(Z!60~^*5?;7M2fDmQXjiTO>!IatM-c331*5xVg)@a;<%3^iS=-aMXwi9Jb zJKem`ySd>oOQ0RmXRhEn`d7Ay3I$wcg;mgE*HkQ+t(KhC)6sv1DqJNKCixM26IKPM ztDdimNnC!t!&V0>2u|lu&NCvu$fe_GJmn)ux6!=K)4(aRV3g_d1a6#e;i>|H+n91i z{`3h$NK-A%xoz$!`9dL7rt-B&=cq`u3Hw~tEXLLtX2ti!U~FqgbZszw^^eQ9yB{1h zlHaV7?rSv??{BS%$#7V|ghe=Xa#Q#nTWgV@8O=X#h%LPI0>{V>ia2YMl@=47oWkU)4`u9rn&s8pT0d;0JUyq>`I$`ooi)kD?HN1JtVu?WBQ zZtP1Sm#?~gM(U&j=Zz7tnQGw*g_ICZXb)iUj69Xoxuh4QyIMp!mK z;l)-U9~vem;A4j19wu?TL(X|OVF7W3E1%P6WQ~FmvFQ1=riNK87uZSRMApz?LYe*Fy^`ml;-n3a zEwIN&HvB)JZ@mNt3GQunlPRNyM>hUd$44FjwNnwx^Qazt-CH+U|J zRDpcwY$ys(V83V#O!t`+L|31W`FN z3Iq2>PvjI`HQ!Z2ZPiJ+G)`I^piMS|WMtuUy2F=of&|ll=c+Z!19P3)(o4RU7HjnV z2-ufix_!aEnvDA3Md?HFUsaG!%X%_9(tkDeC3zZ#+LdCqk>avz2P2m``PaikE|c`l z?E)JusUZ{Iul0EC`(;#D5h{e2cAycm;75rm&fa$~R@TfEofl78uXtvF;P@icB@@RN z6o?iU%%kp(h^qV~pnt_>sD;_?x(Ox>I2EfbfdagJY9O;)LgTi3HR-p#6c$S42lq;A zx0@z;HOPgBXje>IUeWr1HA0!Xy>skcm<%tTUl#Ju&%O!!X;|2Zl$l7*zNxa=c)ym- zmFUM-W)veADNuQZ%`0i>%xiK48kqP8OY~2nWQ%08A}9Gi+SOegjke|{CsBbOe;Y+; z_I(_Bz0~;dp2b~a6)&O>FRPQbp)r3xo;vWCNQtK3Qjgq?nv@0*W%MT-Zq+VkDe7Yp zceM>iYK>$Syya#3y2VjWf2QoT*tqf5IdwCA{6kPWpUilnx)!E!kvoFsNCR?tvk8jo zB%x7NB3TNuRycYg!FjK5^}~R$+vJaJ;vNhR+XH_MQNA7}o&*}ctMG{y410a&Waqwb z;RHr_85SUr@!v+-avhqA{j&y;T#DTweb~-Yp0s6dXIBj-o0qGBgllb^MeDHvfkYrN z)byWT9lF5&Qf!=|XE!*8yDGj#CgNnZI5^e_V<_wq6YUn3n_5J`bNAVeJsa(7+*e1q zgjgzit*RQYt6BMW&JU!k&8YQhm>ZizvU?*bqi@~goIzAQbJWl$u>yPv;&{U{5fPUP zXZbsv?8V!Gay$(ZLSx!}F zva=9FKqmlBg91!pdvO1y4iuUbjqcXp0Lhm&c4M;@(E!;T#k|B~rY zfXtRir22@GS{l5cx7C?Sl1$p2Q!G%5smQ?R?%)Qtk9HwJWmemKpo$IT9^%E@Kw%2v zY|WwQH#ZMtR{U19j6Smx%}OFc*hMqx*32tfI*C60>PazA zBnTKioyxPdK@Ev9(`{$}Bz|=~+>YJ)>kN`Fq#cPF~YXe;Xk~Yl)+`-KTFu3wPyvk?R@6~QF3X=mY{VT3t!5g zSrqHVdD1Nnejyi^`L<0!&f0V--~Z_Qx)iZ0t3Ptg{OWzF6*n0O-DdcDX%|jNKvdfq zoANX0Gfk-_CPLSF>R9G?Q1nvnIN_W#`bTXi6^n~14D!w{ zLz&}YS!rbj`~zKYNE|TWN9w^{hXwt)R$t-6N$-OHHuMI(ZjOopbmDe*ckM5;(MHXw z46&?TU7NvV1qCA@WyX%%{=Mq%+5~ct67hO9btQ=`ErJGX-lLN62fMmr)i98I&L6M- zz?BB-U7^IO|8iqrPK#YFtz-ZeUEuDb>*K$3Pm_+LZrVx>0iagG=j-WBQQwfVRHjO} zIVyDV?BjYxxZ+wuhlp#47$Sn-6^5X4hOBIx;;u9+5n3d?Ps`x(cjhJ zlf2xyYi*g~0Kyc&;-TaWGy!#_7P^vIrS&H6+Cm+Oy^=IM`B?Ir zS)8=sq9QP(r{HgfmLi{u!5D6CV!VzKW)u~KjsC!->j6NnHz?jYnj@P#fb@WPK1^19bJ z`L&t~;C!sD_$o#wnSK}9r%|isFY#DW-RQlin_D?`DI+;ywUNVme`rPy5k=${7TKL@ znc)Sl;Ahxo?Z7mcVOm?J^efJ28?D?sFx&{ zC3D5bz{ku`+kjy_p$3T{jEXsK=$K~rdqE#~5n@VA-QdvHvd0{p?3R(vO%WkP)n9ddCQj^5IRz9HaF1h9l*GbKR^e-BYiz3GLzojwu$i5tg=-h?1Lvf zN10R@^xgIqVfqeH)V^+18*uI5_G~_g1IY#pfL7peZFoJb|0ret*PMi2R${Nwc_d!` ze*XhJJtz>Sr|lu46s#yXYJWR&h*V^0NvFGvZW!izmC<$+q~R={)D|faUR02y*wd>U zd<_y6)t~Ecv}SZ&Z87MBD_=wHG=4_#=Gj!|ZfVL!&Zq zx+OYG$srf;7CgDtox?<|E))?ytP`|>`1@g~{)96uUxOxv6tc+w6C#9qQ6VcA7grCv zF=LVs*!Rjd8pQtIF9g@R*-fUiWRy z*#+`QEi5J`yWY|`7`{3Toj-@_Et6q9JJOAvG8`m-GO>iMfV$Ht=?W9dC8f6bQ+$cw z1hC@2E|G9G7EH(y=s#?0<-oPwY>^(J^Y(pZ59&=B2USK*rb$~+Y(}ah{4)xbv@KRlUVV%0>8Kk(y{3*u_WNF z*MDKSbWo6HTS!8f6`ZlqPTmz9IEsIX*2wAdwrKCKk-oFGl^`(Tr9^HWBn#ZhAP;VG zfvw=(oEoAYH^Ub>qhNS8fA#;-{RV%w`N0N-8Z1Il()(yk^RL6hM{#3M)>91SS0|_m z#J21af|Yx!xPoB?cszT)=zVhqYWi{9pL|KA2!EL0ml(Tr)r+qwOo4C)KLcq5!~3$F zziA5is|S2bfgsWnb$#1lSa{mZ#Axdlw4qQ$oC%jd@2({zbZvc|!FGeY9kkoeg7y2c z%D;xZl=S@vBDeV{2=<6$yiZXCib~)zsy3tjHy`UntuBC}0!yanHEV%(f;KOC7arSM z8w$dFQOEn<*ML^gRkx#l9#t_gm`w=)mq_yIvrMNIzpA4tE(I29r8t0+&_|6l?ciwB>v zAqCa{FMRAj^q7jbS#}HP#|;|cYIQs!?p7p=R9L4z-O6!nUu#xG`CaI2rqw4Y95f8v z)iPqF%+#>Zek^IOUd~o2m;q}Cbdkt7I-)ZLMxUXWkO=5}wASSowzrRcmc$qpoeoiC z5Eb!3J%q;KrLP-I;yR&Vitxg@3GpC^`ytv8q0Y3Kr|&!grw)UO@{>5&CqoFD^BbvH zvC&}|q~oMU6Oa2-fh=Ac!WBkF#%jkSh4{oq>b_nIe6n_}TA|oe1z2DhnJ*>F$Y*9yCi8dn?@N`o+x-X8tNWxE;g+s( z@$T}GnhM@Ni2VX%wdVl{t>$mqiIJ)71l!Z2;#jY|8_$?uVdhYMmsJD@TL%tiO#Ou%eW#wE~)_)+6faP5PiJn zhaLHp+;QD4WMHG+{AoWsCAs^DuxTva72}k@+7* z?`ot1(6OYIRkdwrMxBh6x{$#QmZ9u=8*jkRJTY~Kv0-#=ugELN4;kTHHsn9a7*oq<2J73RjsCAQQTiHy_kk3E5JmQ^| zou866mIDbFB`qiLXLl~QPIZ;|xx~WrEUFj08Bi zmf^sds;W^qoW30bAG`?u#$?fY!}=2bMoLi1*w408C$Y0Ii6If!XxX$*8ZYEfzv*@T zt>26xXCe!K0~75Yk+9fSR-&_?tN9whU=*%v4(!g+rPl2GdaoW}p8Z3La8f}{d?)a; zawe#Lq6Y|pnme=jpV$kcU^52?1_1q&g^J6|=r4{SGYX$OJ~A#f+sjnkiXQY@RQvcN zTRG5)cI2|#t2#6yGnMZs^(Wy#U?94L<>|)!a$5Vzi(6IB*HB%UJ$}&c8?|6r(WyYO}ayP)NiqtoY)V5#+S>z1DncfHJhXXv3+#9h`0trg|zd=d$jQWyiB zTPg5#MwCEg%6j9ANEl;hjXG;w*6k&tBZpsu>8r*^zgXixyFUcRsFK84RsOL)VcTBP zFR6I!^onM8)w5i;ygrDh1PlnxnxsPpzPqr};ft7z>ARI|y zTlbTH+-Jlu!NOAgSpQlNIqS)kmyBAN{HjITbIW73}qO zGl_CNpgb$}ezd4-cMN?-eecgukiqNL0$o-3d=~i!p~oUP#{9H%RA42uz^NbfX~*D( z$B<6$;1UZNgRtQ>kYbP<5+Y)lJBZ?O0a_I7aRIFag@%mA`~jG#weQq&VLF3{T--eR zoUXMn{c1S2$DH<(GQ0cXOTHg@x*uR3d1buyL zN*pwY&HWmJ=^9|R^c`PIFC{|dFes|VY56C3y2;2fcvbDfG<(ISH7P-m2(i}+Fx}=( zkJEJ5G%W57tg)@1`H-7Ut7iI{T-o)PcHxF?veD?GpGZkY$TDJ-BO4ZGb+08{k9FuZ znz~*w;`i!se&6bBO%I66L%cq4_LY?>QKm>PZAss@fg)j8fJxYKQV8pHk|=1G2Re7ot>nyPpNno5T3&PRVlFxkie_zG~m96G)} z7e0!!-_0#8;Vmj+-9~RU%7j0!x*nbtvHB0Dg0AO23oGL)hKBr1EyNWE@QNHACH7J! zMTXP@sMPxX(RGNG(o^(>;MEt2+Q8@P2W<%XfM>zVk;ez zF$Baf2BTip(OC58$nxe4hE7Z@)U(A;4!}TIc2lL&E7>u{o<=eeSn1>JUKl2y% z%l{d?+uli}-!0yQk^$A-XYDzd;PsJ=jY{gDB;gR!it>-Y{@jUa$Q{XU*x|~sw*&DH z6oGN^0vRsH9ZVu$%76c5DYvv(IRiASFY@CL)p;sohGWG`zjZ3s9eftzjr;5Vw|*z0 z!E&uV?(tX7xDUZh2ik^hY(2vE;)+qvUD$@{yqF9P?s5#c(Pro3ANg+l}&~a^rKm(!W1+eRO~tZpQpK4W8;p zAlRLLjrnLPw`!!@k3!;DSToeNh~yZT3{mJ*B1pv3mE9&zD;}0@-W%>#rtP2r*6wS) z=1gCa-_aZk&(^AvGO3&r&e%L*zGO!0p5u=O_R@8c<2*NgrIv#T(K^)X#GsNP7@3+w zU2}bMZzFcO55FAg0VWJ=#ta6Ju7=<9mKt_p&v|5m9Va-D@$|#md}Y6);rW`%7d9yV z@(|kXXx|>rm^Er;Ufq(KW!v1J7}}fm59k!V$Sv!azqwH; zwHT>LJrxFRS>qFu5@~PBfMqTpR*9(O>%lQP^x6^zj*IYucXdMVXV25klR_Pb=6z1 zVkj0$xt-M%sch9-!MD&+#82Wgc{9*82)MkYppu1H!uHSG&aa&g`NN%$LhJGsK zNEL)iJXeoz9NmhC2N@KkAFi*#zcgL&8wGGX$|UjfY?P^MW0@UAd=T4>G7!726v+~X z)0IyX4(ft=z~4pViR)cZJlcm7w%? z(R~|9WHcPgg-;6rRQ@h*rnuyU-ndmtgP695N#h}0WsQbst&EmJmjZ1#zLxsrej<(K zzta^o{X6Yy!92Zonn@*NNOm@#76G&D=YA>|X}~Owc>LH2qdnu@&w(dOnGVhs*1%tkUF*o_ya$ZtHRM7JPj*CY__mdc(IXeLQb!Y7$+pHSUSiC=>e6OJnyp zr6|2+gpr#j6H8=J$XuJj>$|$~oMf*O!^W?>3E%{aTf~CN*-`~e*D+$#PUZq@kOp}1 zX7|qYM#Fs=6Q+Gh)&0JmLt~r9i*NQ>v_n}|)dM^pg+v*SU=Agm*Xe2gm0y}2V#{5S zi}z@@pl9XkxnVf|!n`L!)B&>SlnFfY3qGeFC{k1-7>(nrI2u3i1q2=%&T8;Jwst*v z0a4CxTdMW2R7z|g8*|5Di9gN*;re!UA+bKCf7?p$dXL2axaVo}pSXdGAnRE8cG)?X zM^dLE>@e0{uFRuHh8jO8sapAI=LXIJw5h<`x6$}k+`l@DwUM>DrY10>17Al-^gA&z z$|Nzd4y34bgz#L}CqD20vIJqwz@tYIuFkvUCB~sVDOTfA!MpqWPiXm04P$Wc)XxN$ zH`!U=n0icjUuen}K2I%uWyUDzDb9SXf+z}V2~>9jZT<7lBvPbH^IM=>8CN{dXbEl< zF}o8+h4_D%dJC?&nzjp*5G1$+cM0x|26wm6xNC4|-09%KA-KD{ySuwP1oz-R{k${Z zTJsNDPSvT}``Y*3)yh@i^s4CINPZgF{p0IEApJz1>IgtQbioz2Re@)ZqIcF}L}mli z!8#izb}c&{Bcxh7_{vlY_BSs0pW+IGBCd5qv2 zwRUUrwhAKBrK^-JGL06fY^!=l0ZhT&kXF?zNNJ&FJn>J3ZH~U68lGwoVj@!FV1-uj z&h{GAW+$wRfQnO4bOws(R8?b`u}hdl&(vPcW5QQx7YQ6uSnS#DlZuIGLs_R1`! z&iFj4p9zp_nJp?tzIgV2Vq9fpH^u9CLo!hwdgR34J8k0fsg_(hd$cb0=%yDjv4A}J zvQUcO;dHy4PZv=j`21Hf<7o+b#yP#I=Yds%A`a)X`=D{;mwYdTdVBD$_5Jl$8{w}z zxx{csY-`mZdyJb}4Q=-Es0nYjVrzuD2ZVMXc*4Yy&p)TiwZsc$MJXBi5jpur-iTf1 zaUTln zcGGo#W-IP|dGzS`Bb^H_QJs)PiRt<7J26t&p^l_Q_47elzXyG7$+kOkOeHTXD}&w9f_9*IQONi?&q|C!i z@fy=W0C&*qhwz) z1U_y17px8`eB+LbP=VzS3=Oi1nGrpJ3!tILfu94iLEcq)Kk@Dqg`STn7s$DFq6njX zilR*hb_<4o^n=kN-*mL)_u{)Pw;OKULC&#IikIXVh06z}>VxVS?(!yJtlildprn8&xX>o}fz>*&V}OPwIOl&$`6`2z5Y z>tY`}eEkKmwSrRT{zk=HwfOC|Wh17^Z8Q^EcAFj%Y2Z&vpuKw&qVG3QerWUcz>G8f z-Wk;4IGQx+gu8zradjoB*aM|t%}N{l*6EAocC@)fy}^~XDovJogEwDg4^_IdE+v6r zo1V}cmCSCID#CYsy|vQr&vfu0KQ948X1{(5?i zMHUL%4oo#+Tb=^3Xj2HJsGF=MbDP4bgW=0Hj&5Ol)FLJj1?cqgR9@*sY zXztjQ%4=&^{~Un}y!c%!<>_zv(co1Dg-;)$B{VO&(wlOpnxnqxPZ%8!onE^KVd?JA zLJh!gYPLjJvIXC^<5ABjX-F_C)H!WtD@h3;_aEVda;@=u&)4y|70m=7oe$Mc)gb|Sl<5Fd^yjMABytl; zFwf6nD07Vxw`R*JCS+o!PX*MRjybNe!9MnSJTlmI_GD#y)MY8w}V7T&tKR$f4C%~cGvh82%(Q=bgG&YB~5aQ zKZG<0XNFC5$=7zg>6Na3fd_SBNTTyvRtiVL#qDAt1e;Cjhq5Yg`DkqVPxP% z0;ebvdRNi|o$P+p@1@X9%m-31*H0m?vv|)+u#X0@Sy(3mdY~ZkU|0*1IR1Uwn?_`X z_2S;*f^{>AX?R7_`W44+LgsRFRoRyZZ2^q?zu$R%TiF(APwVsxri(kH7x0SQpNOuC zVe)G{;L}q*mFX<@at`16Yh@A$ia4`NmFJN@yv>OhTT9*vmk}AA9F6!O{cHIPe7d9i zq=DkOvJVBh{B?@SK7X)s1e*5?jrXz?VpjCBoFll*wyZ28AZP!4$Rj+JZ29u`eAfqw z37W=AW&ZgE^tXap!Yd6{kYDKZc?)hXG|56sSYPNO@q#*a8@8^u#sGdU?NG|&s@UF1 z0Cj_BTE`weYGDZKLx#bH7geyod+)%3W^u6c9io!|+uin!As0%%`fY z-g7mpn?&zQuNbT{ea2fiKNbDU7z)7m6p8V%s*x5s#r@xh1}}2hJlmYlw*&~4~ zLyVs)ynYirXjv+B!8fu5ciM(&o;eVdSqwkEX*Q|>IzQf9TS1LVQD3|tu@=0B&jJF= zKbQ3RK9_1Z2%s)ELsur6%lbUNxt{UT!}>Dd++Y@cTMT3I z-3q~8s|r0q0Gl%7sVOx{23oBhfu{3KClLd04tk^45 z>~?qA@%W?wuf=+DSE`)Iy^BvyZN>}B!KFzhNpg@eP|vr=v2;Lc-Dc1yX68hPw>mCR zD)lphe-u-10ACa6EKvZ^?4B+2vM7ssLXXzzT_!OLMp&K0D5K#HPSlEBj^{XkL$Pal zUCS}EH8#+$1BHTu%^uxO8S#)7e_wv^1SaVGeO+vJ$3r}9#D1t#cgCy#WSRruny{dD zhTDUSq_*JcA)8B#&{@#rH9_qqk<$t~so*v0ZsIc*QQ8bYz9+G}FI@=K^HoL%8jATWHWPwW-$%Z&|# z_}E`RMWu3D8^1nY4<|4*{@KoHqBO0lLhgD^)vdj9%g{b{?_*3zo+|<~mO%D** zmGKy8I3*Xy4>-ZNAM8jwMoRshmuN?Mv-R#{5vk5t;Y$WMRUiM%s8m_(N#fQiKoamZvu<=l^40^;t%7y$}6}_*bWtq4JXgH2(b_xmMTG`|htp@?%#A zI6xrP)q(-9eAQwDOkBAYYgTV9EtZnq?WI{KO+q_!Hu~|VSY5+;`STr>$A@ziXKGYV zq?<0Xx+G8D5s#g#0$UqD`$YTWfUXgO*kh(|5Ffe zLApV*+IY>;>QK1X>Q4{@QWPB>hyj``V zIKS7YkDgQEd$<5PRZ}}m{+MuruS`!=>oq6cJJ#ywzk4=hN8E@+X>FU z!xTSvL8A ztj)gA+}=CW@#1hY%=Z1=#R?%3tdTHHpcaE5Dmi@KO>+crXXjarPze%XJBELoI!~*C zuVxO8oNKl8^`5VIga|YJVjkwG*dN=B%OL!ZGYr9b8>+{pqtd?{6GqJ^Rq<=F zzR&{x^v2$0L0)J8YR-$g2f5vV1DPZOH+C{)6!`Key*TE#hEIt54s)E~Ky3ldGK&c< z&|d5;UQw`LV_jX}uTP(^##p+J2ws|lfS4fd#sSe8{w$(NO`c8u@KkDvIuqnHNB2X? z3Ti7;|0q&>7?fPR7n~*>e4oPIr@F&rZjVyh-P931o>dxZL84adp(&Yzzq3Mw6z1wT zAp=#!tZwIwDm!XiDc^KuSRZ14PYN%IYUZ|E&!~2U(GkXuW{yo`$T!A_25;X3paiEI+rh zd6ArnS`nlsA)hu_D2>c*@zEu~McuZ(S%i9IV+GaAydDB^BUI+uWhFG@vv+~c?zS~J zk`Ph6GHo1{YBCxj`unBuW-ArD;HGvYP%I?Lt|cr7d=`EFQB7htT@t$rr*oMdd$MkI z<;jm6iIwzc{~5eiln~3TM=*`e_fLx>bMW=sH2nuDlkdN~qS%?=?l_U~Js8cTnB+v0 zkck)DrdcG4sK+~hEy9PCGL7EhJXU2t!xGSGvcGFP6Ld`p(AixpOaYFjyLnBDRzn6q zFKz#08WHE?DB=Xr^LAMR*9XB`*e>M`VeztlbI!-JJ!{}KLP#0sV1ZoHbW7cSaE(*O3&$p3*k0d3JN{4455r4xt*_F10r$suhPTL>46i=#NV!8{b{2*T!hY^RSvm z25ZY7znPvYnia7b+2ED08^j6R^ZckLUW*Pw3w%;WQC&E+GsqA$=??ENn z#Qszmi6xK{U_VI>eQGy`s96xnxyAJh%a(WGAX`Yc`b=lT_8=t$a)AU5hmL0Q?tB>y z7_wA;%?%&2C>NY#&TuV=3HjT~nNMOYUGc?i1<}uBzsSM_i6chJ7ka0Kd%0a0zs+Lj zf|H}|eN`(o*4C-04GzfxXgrqv%}$w5FLkxwzZQ}4(#t-4V#iN4wF1!Mim#A4i4@Y| z7a@0GiXNQUu^S3h4#YU!Gyelm{7ybiMUm6!mz8ix|GpW_3Ux|_##)%xzds^nJ04^YrWJg+Vyjvgs1hB$J` zKPjFV-Xql+5}nWO9r2%TW+5v8IPv$xJ&hy*!{022nr412)coxNhOZt2c)6iYM>11v zdhX;zx4i5HK%-F~uTyODI^+sE#nvlLE*LpFMh=m3Q0A2|0W>)27X5FtP%Iw`;G?Uw z&Zxt74@aIpnl|>=_Kg^pBKCiW&Jvxvi86Ty8x3jPWhof6sAzLA$;{ou2~?lCAll2d ztnk>Z=7*GtySbZsr+SMaJq%=%KNybvoS$tzLGMEP^;Eo!cq$)SajxAvN+Bd`d)2ID zrcaQ=WI?70HT-q@{;n=p?fk5|p-#+VT8t=yEtp=joOV>LEPc8%x&7i`gT`V( z3A%qpH*dOj-b4>ssUtGim%wEnkHa{dJfMa(|HHwX@9sRb-g3bigC+AjIK)TC=iRFYcQU_@ZdP|@|`D8jja}rQm~4)JJt%G|L zy;fo?8wr8w5y+jKggfjQFo+0*EPUSQEs2&pCauPUjCZX$V-Nl-!`;vFHRz|9c4KAes3wxSa}*)HXkuC+C!Z4~hnp5#An(By5)ehZN1oN)+yASlTeI$aD*u z2gX2qVusV)Md46CZVnwK-qV?fQ>X&$s*}gz07Q7|4v_xinHSDByY0EH{8ODZ&!;Qf zOUF?SYdx>%340{?Hs{eLdR%$4ZaP0&{{k3=o4;%w?kXgCJg|2*{I{Ew5V zQKZxzGrrqZt62rg+gHsL3%1uDvqJ;w_oh~gSbakIV^V|~N&X%9zIE@;@8t2cDnb83 z-kh2l0b|Ut=xQ`5YNc{Z4R~%@`PD9RnAnZ(>0ZCGSM~|fM@ud^b^Va& zpDWVjaS48GD{JFRbx~FN;Hx&_p3LH>s=SMi12;;gK%JE7cTiDj2-@i239OZ*e8VFs zft|P37zxc1EU|FdcJ4{!`&~T|;EEE~*ZGJ}mJ#=lRij)J}iv{$)vS`-#R9g9{O zs?F^(xULQxwYvV?Th0$yn;G7a!s2PH;N$A=w$DqG(OF#6quA0!`3dkDkiL7 zw#$6YCS1O9SLzPjH>fbQ3fEB38YpD!fCW6>@n1WHN0Yr5nvheM*t$>;QlqVff=Lj_ z>xhl+RmOs{adJd}LKmF;#RlKq$VCJ8d(hF&!jl*RIM*so9(m|q0Ir(Ys`SJksTxSd zWvqc)keeo5{!gdkwuim}BhrA>toiqPbqh{KnJ5Yw`V!-p9X>MkZVNp=md?u}@L;c! z#mnH7P!IyrU;V!?o%=JbikpGzX0fM;jp+;rN#&V}%Umn%jG;S)V@-N}NqdmXgd%}D z@q#Q(bWeiCum4W(@SJKE=~jFb^$$j0QTqvat~tHdoR8L*(MTH^zY*;*;pcmT1zkxW zMdl^B(4w$&7{=$GI|U_ zWC0o4dZ>y~(85&3^xdj%ZrAJ`k&%@@Ex6G*UweP>cztWVJq_XrLsrt`{>*w5qPOhy zO<0%9%bECb-v{{lYV-*Syxbu}(2hl`ja`GyUPL>bARtZ(ed3e*NmHIWKfK$0%;Ho<#&7G2e4&nyFY9x+2-%<&ZuZA$ zk_$Of>pa^Fy6L*g9y6!}Z`3(#C=6w`|I8FSLWT#GcytfUPL=C|izM8MND{u4I4oTR zBW!p{wovFNKXrHvrWU-6J)@?#hCFn|N;+O*Px)K+MHWpCy4hFUutrLUzi408nf@oW zLn|WK+@7rfkI=N~Z_5p4B?bKF2CnU!V{~$vR#klr>@~*mO)}{u6y!${*-Y}-yQWYG z(b!RDQ`z6%UDUws8uZ~K42z7K5!o*QlR}pVW{|Ur(BE*K>)V0Dt3x6L4&;j;n6`u| z+#w4DuIlAKP&y?L>Cm1I^X`q;d}W$bxN332o>M;3sZ>RWb@O_&By&86%yRLT#B~Yr zkt#T#+4)xQ&Z4%=)4S8L|15NQ8&jG-gni(HDtPT@RUN?9Sv}t=wL9!rInIbd^dfT* z1<`mohWvmeuX71F{49}HYS6ugJvLN)On!P=&RD@|p8D#7qRN!OYAh#uAz*op9}&uy z^1=1((ZRCDZ8*+Nx(t;eK2nY-fw^cG?%s&{voodYZ#sk4J85ay^ez(2vbxe) zH2A z(pE7MvXiUQXTkzq>{Q~{(qw-DnX@-GHfnrcT(Rg>zBRsRROt_73V1PAIuQ8Nitoab zkQ3ZX!{Z*w=|o&U^_!(b%67OTQ8ELAjBdg>-LWV#RPZyk+LbG1soYJkRXo@E6ZVdU zApHXu9t3@b&DiT`U-}z4Ptozo8=~=HY|e>@49)G~z2M<sTla)##7ZZFgR!Qv9 z^nMx>v{_;3TGvVNjqn%5cVXjCfKvq)%YdgAzIc=Qoj3F92OG-=naC0a6yk6+DMxyM zmHKXm%?-gRyY`H{KD8LQl`?+MLctnhPrFu^NMd>d!FB_oP9inbsP~q0JtR1?e!dXH z3v#M{XpWAKhEnKgzl|(9sq@Lxg`CrlY`Yep1jr-A7hafFyTBR2S2D< zC;Ju(iRT+$EqtZFic20I_~Jc+eP1n8OoeBEg%zeaTiJgYJ@g}U2S=_%qwp16++=O3 zNv-6jOe{9}Y)Gy*Gjc`}KK^GI6#D7g230&)^-bW>JQF+V^!^Z0F&Po68z2BiD0S(N zLarygqE3pb&VbT{si+xh&4F+5FhVhK+Ae9_J-;nA9JbxFABDCEy`#a&h*q}{|1BG) z^kc~nILQXoa_6s&`h!?4mPzT-1sAqNQC=Sw&_V1aATb?<%htlIY8>&hT;_^SBtbo zcyNF#*Z30I3OU8itbr$0kjtICs57=zhX?lJ&i;!`Cd<2l2nm&89^>Q~6x{r$1 zYzM;4jTbTUg*z?j`*B_`NcbRZD*Z}fJEuL`gG)j_Dc4j4!TdNTYr82n)riHHDzZw* z?$hC_Lgw+2DGZ2Bc(FXhq)*Z=7+?NQ!|G5YpJJ)IK$s`QbqT(=u=qm!ub6KPZ@mD< zv%Y%vfED|{Jv>EFZaRLDX;qr3o9;y%Wk!#%Y5QQoy6TS2oP^Z{_;kvN4wJpj7$mhwF)u z(z}R<0F_Vi$cFW$Nw^00%oQp=HYqGpmwkx>|6YP7!CfA;yhV81@vFIzZ06!ZRzD84 zv_gzO5|R})jaGhkWJspqN5?IrZ-$GmZmp@a57uNFi0LQrA*22;^58g=XfNge!32p; zn32?$JSp)aK>Ac5oA%O3$mL7v*yXqU4DIggHo^VrLc7jDRg+ljRkW2rlf!+Y3Jo}L z=&_Id&DWc;qi26|7@7IiIN&)A9JkOE7rOUyrHNyXYTq2lE5!FVTEM zCe!#8Ug@F@d{s-z?CwPmC`GhKS4|=K;^;`EN!{PwPI%IwK;x$~kKL(6*6RF-$pS(Z z-U!r(_%&ACcA>SNqv_Mn%gd$bc^2Shoq~*8)!`J*fJYK;+*OAK26EHN3+%M2-4KKj zi5fI*T+vI^DrpplDgl?jcu^M#j{Lq7NPBB3Ila^2UfrMNwA0$KUCXxuPm}Ty9LAW5 zV`iv)w;~{B@o0-#_peWQY{r2rYzoSLkOgJ=bj+I`nPQ+GX-hk-w)h1=iU6K<^c^|b z`CSp0HpJJZ`TRZsS1}Mo=vbNEC*Xi?4Xe;2S0DE`ZC#7qxGzhg+=ZdQ6W6|zqP7;_ zM;o_Cig><`6(v|-ed0*%MB-oJ$yO`XgLjGK-u!ZMRwrh}B@JoVLKxsdH@Wg6X-)0* zhN?Jq4SRD1a3Z^h?E8xRq6mgFK8$VSapGL2{mR+tdL<@L#%-Xuxus^2{OcXV5S;C;`OyrJa z43;mT=018*^gx)izOnz4lxwrX z-H@m96=a21z6X!$SE4)UUviPDuismdL3eSH0wB*T(-pSL*m`lH538&|q!*y^Pm_8e z>23&53UpBQ7J*8$RB0mRGg-u;8=9$AWcFSuYIl?+KBXy36t)6Qi}kc-$5m!l*SPg2 zH~bSg+P#9#UlQx~z)QKEDCCK+w-RPsfKCYy}e_J(A9Gb#aJ1H$% z+wAZ_N>i713Jv2d>uIXK7Q?DQ2(miKYh>wC`z6yQ~!tP*;+uq%Io_@$&noD! z6Al~j$;bJmCfr^=sa3YB(Oy;_VN#Xx3-5?=E|JO#Jwg&R`Ej1{>45+1&hf>s2H?bJ z6n<6ey@Z~CokTs}Qr~{i^RAfli|D9j@yXzy0+~kYK0dI%YMH%0K%_yWOHlyw+w7+Ud4Sd#t&j2is)4HfK%8juI`0R;!`D*1QbY+a_VZrzh5Ot)M*8Xi{hz_N5B z+YQZx;5VMTFFz|g$-<)WbrDeLOU$kZs3j-Hom4EmoY1#$t@z@LkPMRpK| z_I09RvSngs41@Cl7L8n%uq^61pE&>U$c{uaM&2PqLblT?R25aLLxN#-KjJjM1D`q2_|bl7BbdP(ZnoTt7?KtAB%afmdls zcH7;-MB4SH*WgM!j3IugOYTCWh*D`<%l(j#K&R?k^S)?+80dMJ?bFZHISMMi_|%*v zQeLBbNd(dNe-aX^Rp=iSi<)heloX(c1Kafu7o<;3cH!|}CJz4^!2+)O@t&#+-hDs# z-LN42);k9x9V#R8`$E7oO|cFg^{T#eYXC}t=pFsAvLp%4XYU+(eRa zRGI4KA$G*bFu`Dr`*JeFl(8ZB`zW0C>W?m@^IVstYo~}Z0etLrD60TQV5;bKhxApY z1f;Za1>NDr>EH zg3*!fvSiysnV+5L6lVFr>Lybr6wHoHY1AQbKAv2y@;R1 z({*~pjs#~>Szf%!{iiDDR{qgqeJ8wu18EmKySwP`qx;G zN|1V_7sW7lO?NB^T;}hj5#X?WE6{^ppk8P-ZBq);=iaeUdQ0hT`+>u4Gh2imjJctM zg~?m7_}k$|ad#>RP!XSfnd%T3JEBJVQaGoP26`-)59MnpCSJBH3k>oD$~DwTMUy1+ zx|EKbeEDUwT92SsmTC~8U8+|eLJ0oJf+3;@NEuy}1dj4H$MiR#!)8i?kEn&b zXXII;H-@FoK>%2og^!#KQ+zTB37RdhcF1yS0Zh0u`4h9jpBe=AtWs6JhCk3GkG=rY z?rtlbmmL)meUc`L{lYv7?u*Hj4>Ta78%;-T@DCCf-Tf!KO+78d%4}27CE-yD9&PZ? z1<&C4zD8VJ7})icAgPp!b23d&FMhoFLP6?62FX&`R@O5Z5z{vjk^7LAX0IkMK4Cq| zCw-4U@lq)Or_*i6cXOd+Td-;r$0YpyG0q8q7&haaYA>EGis3!-NC1Tqo(6UA>z7W= zzHwN}Q-9t(8T<($eFjup{6*8n+V|h)Gqm_|1X4H9sd(SaEg&O#hk#Q0oTa|i$oyA7 zHHkEvwg&^cOG+ccthUrfF*s~z^AQdv;w*O;!{TAU>9x_e@RdUgI&AQ*lAS^*d)a1K zv#%j5OrHM7&rHwdkrV1Kr)?*+CgS$D%blNj@b_2^Iz;sTP9}ktj_&yEwombF7yicz zmU$dkj~z~$O#QUH)hw5%i!U#}_)}qa6@{mZ;iACGk76P<9luSNCz%H~oG_#_Rh`Nx zX9=d2#dr9q^%7yo`LX(sH=A0d z4mbPksq>eRv)3z=xaDB%CXKZYVdq&9DU&J@0;4zvz5% z$;*=->8wTfRe?{c0M!kCe&gjFaEh=Kb%G)NZIj8p@kAwGu6tE5DoBBpzFuCfuV?1R zdJ^VmTt%5k!;?g=%lSUZ;f|dAK6br$Hha zr9P~T#uaZF1DDGqa(~^)Yx{?W#WAs5QF52kY!Tk&Z!KmPc3;-W{#d_8sw_p>HBJcE!c zoUzpQFdalKO!BWPZ4rya?jV##N4>J=oY3)nu4F1i)Ly7lnt5Bb9S!RsvH6^97}@f} z_h1~qT&HQWJRe^KJa>P-X7cav$U*QHpsJ|)ZtS1!($zjsN=?GToJ_SMQ|fs(enWvy zrT-reWMA%oe6y({BV@AhZ2w=4i1hW%oE9 zdcwG>e+sPkx^NtQ0$H`kyEZHHru#Rjg>Y`s{!7#HVz?Bh&K65aD*W2lEvz@=?8^{%7jkReOY71+0?Hed^Io0&Xy*(_BvQ^YuIY%iZBp`y#VM-qm4iNH7bY$qlq}$Wu6qgyaZ0hcaysPgM+G|&!dsFeeqFg zHN3pO5T&k4hI#{nkQoNlf8cM&J0SvBiW78O>ji;K0#m>e8%QpLwjl+8`B{B$6l^;} z#MjX*kSt;xIeh{KuT)^Qaxoc3uHjY0{S#LZ(x%ieQ>9=ie4lD9agb}&?a=^B-vn&F z2eB2K0HB{u;eA^$Xqbn^CV3a zMo|_j^#~a>WMk+$r6UQ7f;(La!0j^m=j@)13=wE+IKC!$I0{*GfBk3$=4;%dVSEl+ z?k@q43FK;Vkhn(S$LZ?h+G2S$=eGQ?NKvB^Y4mdBMo7WTdHGDk4`C7YK+l7DPIHda zY4vh9)ja*CgfFO(Sjgoa;qzZ`Z{9P54`X$4SF^>ShZZznP}7@3-uv8sgOdoGS&q?E2U52-N@etUp_x46V*aueQH?+EsjVyjNKum zzQ3zkQ)0~+hm9W|9)^TIUQH@_$2u~hmslW#WrkgIH-|!@upJ z_d*5tuX9llzS;1_sAZ`ZTu5G&6PeJ;g#9N1f`}ocrPn-&leMBHZDQV5<3Ih7*gvpX zVlz*y*GM&pXHb&vG1ctCOMOD+Q5gO_rz_@qw0A|j-thr*SQ)ZCef+ZQa9jBYBQ7VE zF@*>=nXX$EIz`Z~7fZ(FtILBg5A%j+pwp75@K1VfdbrdMtA|>1uq!5+)hBy|Ld z{C#*B0a$KI$lol{9k9enkb<~0*Tt&6IG%SJQ13dW5Ru^o&HY*5$IoZE7G3b%Mv!Sp zGfPrIDD0S_;Avp|@{V0yZAd2GYwQ>B1dZ9CQ#Zf9q@Qp5c7Zm*x<#3Yz;xp5cS0ON zI4(t|Ahx0LRRH`KaI=dP<1)fxNg!*$Xfj463Eal4JjDk1@4VA8(cYwD;-?k3Yl-E( zp)Ux3O6~#s@8rEC0su?Vf(i!PR%ic6S>>hdtku1>J$JlkdGFwsqs74vJ~xNsGY=zP z?4~SJ+D9Db-??V8e&zpxW&rHFu|P`*w(>l?;>1($q{IkjP462bY#=xl@}XXCGfS9f zrT@{%7?#9fQmd8q+DzDnIue;mzZYos{XxU74d%xTODt6#rMiOEYZkQP$m43Q84|r} z^(KYJ{@b_F{O-sQ*|i2wpbib^=SaE=j5X8^ku1{v;Pet>d3?E2&9{#ghIvi1ZxUAP z!^cwBO5@t#?Ik4!gp{1W$h`2tKcP7^8@~6c;g3dP931Haxu~O9wIC~9fDQkVWEy*s zWd_Iza*Y5&tZKZif}h*Bf1k*_S;g)Aj~(TirX2?irsh+hhQw=_4Z{S1cV7v{eNW#9 z5;YNOqT8^gLJF&pH|sCX4(b6D4LLIZ)BOwl!S{@}8pf?m>0F=VMRv8DoVxT6>@Z$< ziH``Kmxiw92>@)LLkeXR!&(?v49A@UDOSmwGHR#4M^ zapYDg_%3el)K!aopE$e$c>4RvGSbSZ|NVgrkTIGOm z;P~qtzds_m)AaB`Y)n-vPTwyE$60WeP@>s+(L^akXgq`UgNr!fQco!=qw(Ttw>{-K zWgB&%{%n+I5ErbHeCvB2nC7Z9!TXSj1n$Gf|MFj#2R7{uZVd6be8&@ie#rcytk^&U znI;}jR@xI2woNaho{+6hmr^q?-vP=f1gp+sg^`*rupSj*3RCeVoPR;}3JxM<_EU6N zCCliNy7BLor|%?#lE66)ge`(GSwz>pMY+^NwLSSJj~g0i+dwjgPC(5~BX!W|7bo^g zM^pM1-L$R)lm2I;8MGtXv#lHn0awamOV{n_G6lkM=nAdJo7+@0;xFz+9xjmHz^W(3 zrGxK~T#UCuq57R=0t!m02U2h`36PrL+n2A!+vq(MWZBP*v#*B&yB-Ac8%+2FS{t*5 z(lk?=!fIt%vV{!5UgnJNG|$B-qr!g~RF#jyzyD-Kd5=*LRY%B^$l%9Y9zmNoZu7X) zwn>PGF5b+}Jh|#nkD|twe=z5;0&ifFXvvTH-s085(oBv$+4S8Of;8sUJ6&JcR*_>W z@7^Q-?SzvQyt8-HaVlA|Y81#Ozz9%=8^l9%lhFIjr*cJp*rpkpI~+W~B`odY{sf= ztD@aTMfhmUfKKq%8o%jZ-poJRK72T0OX`k$KF(X8(!(IRd+jb%?|(yC^dGF>M9;)B z1;7aKFU}yxY78M_VjD0z@f|cLuZ*>OD#Z-Zh_1L`WVe6GAL8LVL_eJc9uPnJTh|6% zSQ&u70luy?2r0){VGMuOo9~@W-97XL|>f?O}`s{MQ%D`Sa#!ZR2#!7ROMEANYHH%TcF@wSk2jjT#CF9QIU*m+neq~R}7hF)4$j#8D*P_^-C##nxM} z!M}=eEw^K4up95Ae!JhR5b+B6;6$2F>3?a&{II7#vzZ&Hoh;^DtuXuKemMLkE1h}U zdXQrKp4dj0n)}WJ=`q)l*ahX|I|GaH+3nu$s^2B9)ZsyuX8m=;&3vp0PpgI%AhApv zA2wWvIjCihhR}gr@>xo)$Qfb|@wgt-ffqC5NeH%lRZ&sO(w2fce2)*Qs)N1QD{J7?z0%=;LIR1+T8j;RMZk zVZXwLMoOHndR#jkVuIX!_rFwvAAB8F3T1ZjUU8s`TwPruG8sLu>shgzbcKrk)S#IC zXMiqVILC~V;R{G;7Q%8Kl3-u6OgJ;5f9~1}@{uZlyM(BoG3;rnJ!vgEQj+4ooj*bz zNXf1y_0oC02-)4_wmI5#IJD#A3CT@*oa-Z)Cn*N9vgv^rma+vW$zx!w3Muj&XmJ!2 z&)*4r&^6D$oEyAZE`jl*w)#VA(x^P$3?GIl6Rf; z9CTnx8wsr#z@0Jzp9HYze~hnR4ZJ+Je5G*!9g=*HYH`YOos*2q;F~wj5Cr&_n-Pr zSG#VSUo8FKk}?r@6;D7*L`V!ut0TUDpOYn;)ugOn&608K#+wV(?oi*J^r5>J!(DoW zLYKQu`9F%@Od{lwcr1~Gx+s+RByU+@YR_yrc#6la$@21Ljhh?2+!c4Oh3`@Vya3#kk zi32@MjZHR7!?VBosKC|D)_QzLFu^|QIvhC&5cWg)$ADzu&2g z|6sNI?hq6_6`l5E1wZXW05=gP73;uzzBz(B!m>EFwF2Y>e5S>cU^aay@Qd@b^9g+h%!T_(f?gYo?jLB zI99TJUr`KO1-j(zVFGu?6AaIU@PF$KL5sI$$g)yJ$3b<8kEl>3k2mcz_5^LxpAq9T_0z%W)Zzvee_%-Sr=M4n&AKyU#)`aZ?VK+iu`qf&BA}eeo z5U~7I5lUOVOrbyQ=zWtxcnn-)EDs-dO#a~Z6oW5`VV^YBxbngdsdZ!c+IT1d08Awk zp~2hp#xI@}1ssCKn9%TPNx2=^Wg4)YeV7C+2AxFQww-%^@sWd+7VowuCtI?E|vChzT*|4^s6(lI91>{PlF|<;hSA zEsZi!({;WwR*>qP9+y6;txK#GwqP*XX?43256ODW>W6&E_0s>r1PNA4!kzvnsjh{C zDb$i;zAGWDUkB^g!OJTJ0ReiR%WDMz#B*ln1~L}c)qifp+{HN{G|Pc?*kuqkCG$qyX?sOo8f9MGlR)O;bU2*GYZNy& z1WwrZ7VY?pLim?}b%i3R%E0|<<>tkq+fAWdZw1u7?Ub{29oc4G{2QtEWvjo2jKX-a zr22r(F9lK_ot#VYxC(x0i-PZO-72Y{?3*ADPLTb7*m|q5IJ+iTGzkz01a}A$2yVe0 zg1fuBy9a%PySuv#?k*w0-DPlhcR!QwKYL%C=Ug)vGmBomx~saYe$2`gyf`TW#8S#+ z=2#-%6W^e@Z+1zwr_7W3DoEqYc;SDx<=X4I)mO%2^PE%*k7#?p=a)^SD4O}M@u~&2 zJ!FY1nlpG?D8F8>Ql|Q0A?3S)pM8|Hxw_OA3$#K=4+4)M%W*6ceRTv<1*`9LWSi|~ z*_yE?)=g0fw@HQmBiHl-E|Ciz5G6aRTNsHt0FgWDdufxt>!KRTQTC_0@=GmcEO2yi z3zu0sdVDa=Xu+s+Pg%y%&8j-0RMI4#3pv~ns<9w8V*M&$x{|%b{3%H1V_WjR8b2P{ zP@+JmVCdRJtc&AqGY{ry8Y%Z-<98rW(wpP3hta&}htS7a^EoR-^O61qpksu{RXp9& zcX}w1#%TSwZ>tHvazE4Lj^cgaU*)&@&j<`|u-2)|+KV`fXUz)C@!-@5!v|)Ajqy*@ zsHz=ju};Vn4kaupISIY$H0g?k^)nohjX4LdzSN)nGg#|aDxnpycKK&=Osr93P0qg? zet!GgC&XYcIZ?0Q?e~FY6i88c1Jgq+BrVs_p^3Wg-5KC4E%U{1#W99aL-PV_(?@?# zToID0FWo_KS?=@Ek@{y&0(p?O?e_3aSo_2s0$$0Te^ywwnz^edFNT_3 z$A`cMm)IP;2+7U8t*~Y3zoRE4Qw~?Vjsj8TRcE}V^*SW=C^tCNKi?o;JN;Wx-j;-PH1#jI|a6=3PR25&LFiLn3XkD3z7LK?G;cB<0r2d+!mxtQkl? zvC!=Fa<^V;9JOAn&|Rlf??UnVa(`8+{$dYdiOZ6SGVva%fj*V~IDI-3TU)$TJxR>- zAE|#*1JA@@FUQGT27$HG*uORTnD8sj02i>neaSXxXzvVYK zk;%aHC|3w|p|_*vg;T<1i4qaYO8M{0j0CQnq_`)!Cu_SgUYH&2~rqu^F3s&R#Y$a@#kWDO4^%WeY>Xt0_$geZlD9`61Fn9gGh zRrX#mLqa03vSTBe(|o!9&cXR5Lo?#CG17+#UOuS$~b$MpT_>SknmD4Bn#Qr{>Idg*gh3g}Z0uw(-Aws~PsE&4;^ z!|&LG5Cb+=OR1bSt3B?2JDMvCMV^Rt6jGlg4ftT({th52Ew)^r!8>ycpL@Wv=Gi=A zz*U226#N)4qDs!4KT$s8U_0)@Q#%_#yt)HkhWz6==fWQF=?(6Cgz_HWpM>SE| z$FsUp1HPbGLG^7{S>==p9#%9wj(JGcYf&<}rR+FCL|ZN^{ zWMt&vs;a7YGAknmsQnO^zfT;j5$~t>Q)P+Rk0IM<(ihg0y1&sMI&^^8WYaoAOVhfG zNCp}E`IBZ}jp4Da$IR-V*)%snpA6C3zr{!pC*F-083DgNbviD@2SRk(U*VGN0yd9# zPfhTnG{jjYHWY<$~KQ&?LY7nelE#Ei!DfN)2RS~H=J zq|p)G__SY2rV5F4TB`eG6smXg$G<@sKf~u360$Z7?3Qz0EkJ&$3V+z+6F!fegq35Z z=%pxdxh%FUu!h%cu$UUlB$W_8`(7b@(jTcM`x>#zT+9HA&{ql^KF4)Wel&si$n%<{ z9oX0jc%SbYDm9FK^C#kLrXg8nmC0i$qXR7>$-gj`PGC7xNedF{L7o`qjB3x4mrHSz zyNFNM^>p1P@dhu3<}~w+5pH!k2P=)Pu79?NCI>$~jq`Lz z$A2UKAxf9p5Q^y62-!D{Vr?h!Y*3_Q-O7sw76Mnq3W83`^^S6W5KeRH1vOscUT83S zIMYT{zQRB@FG9UzLR((xz&~-0cK^pDS+I!y?STk+h}j|>Q1y2ZAuD@E|1_y)zIxK6 zROpnWhlMMmKmCiC@ z%mm>a7C%cbCJ*+x(^zmqu;~*`;cDp|ffhY3J7E!6a=qT*ZxCe79DCq+AcJ$m5$#Q6 zJ;7-Bthj48Gs@(9ANwjU^8yKA`^hlOSs8e}cJN4r<(JcgCv1e}?G=p#2 zqpR3mq&}5!k;>7lVGL}QdU5c2Z+v>@Jo7UbeYLjOIEg2~t_s{#T}RK=s>CCM_gJ4s zmi#^6KU%=hGmDU1ZI#cnOs`!EJ)~S4k-C=Lb^JG}!;zUUM~czeBDe8$sn(J%Didh+ zhY8*`aCUq1+n=6%eq^CMC!C{=)0`-zP7<4B+BJEvh+q$fOz5c}AUj<`m!4${CwmUh zF;LJ$Z``?4tm$X>5d_bVlv80-euJ7FEpNDC^ajQ+-W_v!s2R7ELPwT^`l-Gl7&%KJ z>?kDD%$P!{P^Dtxez9?YaB8;u8GxQ7_H_?rz6}8+d@8y{9&VKdAMgER;I!M&gSM~<_3vtaEg%L< zGL%^TALN*jJ+Q6cURWa)=>QitbARI$QENHp=+mq%V2X*V8F`#fJ&Q}TQK z#8jp{y+PtoA>^gO@EV4IF`_@pf_tTr@$famS6-Kn(No&DBg{XZb$cER(kpoTWd_;w zZ7|=7Tp*&SsUv=7t1mWg3;g4fe4PBkJd2xE`ZB3xJN>E!)I`KbAzp4BWtk*0%op`# z>dgr}aOuD({qFm#?)fQ0(K5uk+IkVqtjGY=5Rr8wrASN37(dzTWi{mz%H7D^+?h}if*xlXE1~jwzfH)cR&1M5i>>+UQNSf}v_?$ye6+{Pb%%$ORi5vdnKq!co|q9=Ii6K?o<;f|=i1-6D7Hkf5#%q5FsIxh zWjfNg5k6k?P@X`HbERUUOmFnc>~t~0dA!uBqpj2gxT717rvA0QQi8JQa@v*tjL-HN zBAgkVZ?w5EX9_DV=iB7`A_#Q=QR^_6>>DOoQf3{1zPWNh|5pCYsnc`D$AuK;PsIQC z;tKhPeDugfIAl6jsQ+0|$Wq_~`oS&zhvDxZ_nFFEE=*IqnJm;@lxgVrwKDX6>M<#e zBb;F$0B?e$rb^w?f`{RaRoQxrR-!J_TQp+%7rOid<6Ou)RJg(xLbK|fFL<5LI)sOE z&!u>!$r5=Zx=x7F?~jt*euG+quZezUrqV;OA(VS!?Tq~|e4a#0Z*M}_=j$@xdl&2> z3NIqMvVtTldVV0|QjbTqcVeBRX!V0P46dryDSni}P4dA9pQB4w1c?!;!b; zxy|H@!VFI)5kuu?xwU&xHP687Gu-YWRYx;IyU_*F-oIEKS!7y{ror#J{7uNV^v$NT z>gnO6V05XGZnMy#gQ{Ix6LC&BU;u2mdD@u}UX7>jv_+9W|8;22LN&iVqLDnayXljib4sKT$nGGk25EIfNuOK6>x|2kL9!JajT6ZoD z7>*81oFMGVLI}D6MR~4Kn<_+wEbWNtCB;q%-pDIb3zwVkO~XkzzxsWQ>QY|hHpIf@ z=lOZ)P##DCsY4S!@Z#g*Muq@;3@E6$WN$=QZk=P}NWc^*5w?1U+_}056~WOo|GZdB z)Kgm93r~(Te?vbRseiYr;jnEByz-r8p8_|_cp^?BJ%iDpn<^rDFyf)o&b=O#PagU^ zp?lK?JH(%hNjd4Ih>zjm&<;YO75xwDIkGgBq8oS@m}i*G2?cx}vr zJ9ToW?b=h5uE_2F&?7oB!OZ%(n_ zO?WQN(d}waY~5YW)qqa^V?og_HWah6A#9}~Z=R*;=mQYg+}n$f)`RiuFmgiu)3>^_ zGnOB&aunU|$zV`rO8tJsI}==LT-x@xPW1N+ZX_tdW2@MGZhd}N2r@s~*yt#kJSs4u z>(W1Kqg&O^mZ=zcElUs?UGD)=24Hy3Y`e6D8AC$W&{HR-a=p(sKE)1c`^CwRH2ST8 z`2ut7t00gM^`SKVcICrcC7QE7DX;E#r49?>US~kf{;Mgq;NL8x!^^sqhDSdXbvEdg z>wP9Gx;uk9Zx4vP5w@*C<-rfTrY*z(;pKuGdsgr%l__6^JF#SEF z4q2d3D3l5RCrAgY-XDsFc^IHJ#s)TJf= zNrIL0^>uWuMv)ei#oJE*!LqNGFvDEOV916dO#H>d1{rx#vg=f?z2NZq3a8V#N{fRS z0mQ-ZFuq<5<>clU`mccqf^4TuXj4Sw=IYGE&^i*9$+?QtF=GjKd-a0nu5l(Y*a10*5;+zmtkq3w<)*brq?kMQZjk zcPhV#iMHc|s54Nk9{LHAz>p^7kiVa$VJ|?%Kt@sa&#|1HN>yn7m0asXeaBGD@NtV+ zAS(XO{_u}bKALGEyl0+G{&R^cA9vDt8dRDI6W84d)w_*=k2_PX-Ze0LMk8B}CcyBo z#jZIO({w&KxE^rtaP@Nvvu*G~i0QHB1pG2lYB=JsD!h&t?+auP2n6ZllIE2LAA4sO z6waR4L7oflw7+Suw6u_sT|~lw&ncGglvT3P5qAgR$lgi*fQ+?8<|yxBlg}}CWbG!k zvkRzTz9^4DYA3#gABTfK>}|}X0g_lIzD)dwT-Ap!f5iSOc6&Cw7($Kpj4)hRYdl&( ztsGTUu34j^MMrEQfT>3rk`Da`J>veA`Vg657KtqT!}d??y2wJL4lk!hj8w;bgds+I zCg2Fk3EwCx4r9R}*tpdmO8BIK(*p7KC;jH1I zjA3&g)Ni!r3eEh00o^ z@5yda+6k>YJ#4GPY8zRESZY&h!eBnMgIDeP=?F;#-LzJE8*qKKi*xUOqN70!b2yag zi?&ecfquzd-%c5a!+ACEyqUte~jQU9suj4xH!Z zm&V3}Y6k(Q0QDC@7{sgl_pRO=P2N12Mj-p<5H+~tWPxg8Pk-`c)3hkus- zg<1Y>&*7qymFsPli*u?;tU$Zj5xw;4K@c{>bVvjKygfDJ*_p*p!iUc@m1i@1LWxr6 zkdhIvC;(GZbv`(1|&p&`4^LM6r+W**6jk%jwiQ9+9>*#A>T9F?5|=SUFntv zp!6!WKL4PeryoHHjs7~^fHm(L&ZdKf2Ib&?lv62#u>L}B`Pf&~7pm{@rob&gr}?q& z16{L(@PiOxF1f)_Th&=`Fk!<_- z;m84JVoS)1tu7rxZgaMnU|IFD3nWdg7(FyH%OVmG{!bl`Wa;_xwbTxm1+= z{4aO#viXF!Dyuo12$m>hUi)r zzWu=Y;QRKN*&oUteHZ7XcbaZ{t4l)@<961v=e5`AdG|23y2dt&bf7?L_N93dD3Fd_ z9hWQq^I?#I5=DG2Ee%g-NL57{&e%req0bvkyRS_tmSLZ9eHfpzJI3(Fp`-hgG%wj} z?JkNDm5jd8V2h3O2`n!8J>WL8=}T@82*G}khujzeS#jU41CZ>H4&M?zp=i=|F;`S< zYZpN|X4$a5JBg(b>EOb9VRVKCs2V3aZD@onYain3)C2vo``*q$^C7Z19cY2RT{`aO8fAoG> zrjs@Q!>C)dg>|z__S(~e^utkj>`e3g+d0|6{BWeTW9Kj4?}!MA7q zV8kq={X!CM{V>B`h=b`PfVsBbaHl#WQM?ee)U-lc9C1k8umV zN%m8E;5ivup@ci~I2JeC?)$;3loT5$`}~aI+&#UqSIjPQZtG7Ipm0P>)nZPgGRTKI zwZR%1Jrz%iKQZCeY*qbRReO_mX`|Q0mvua2Y#qg)ZPln|2-Ra!#{4&)$v*=QwdH=1fK->6=7 z9vvu9mdao&Q?_k0lhmf8Uqj#c`GI5?>Q>b1^EYa*Gh~Ib%EpFPO*S=Ek*OE8ilq6X z^5i=#;p?WTFU=}QXJ_=}XC0<(w1T}1+XSH(Adbr)lF}DqXc`$5F;Rx8R2ud zo+mriRTAIM?b6VG-iP*J?kb$tk7t!Y(~p$wV1~rD$P_nvu+nOxmrk8yV*A4sFv4jh3)!!avX9SD+^ny`wf(dA^;$3O zm*}z*5IXmKUx#?PNKU6%Hq%rR86NMwvnZR&e99&| zE4NjlPWqR@vxT`PB(aGX%j%98^kM;(ycQ1^IQ)JDEg~Cw9~GNz6;z(C9p& zWf&Q>P1(F{Z2GB3*W>`wRLA}6_U>* z>8Jz(yT?R#Eh0Mh&sz)(32QHOB#ZK1XCNkf`%biCnXFiHHk7GAScPrC)1s3q3a4!1 zM_C3I({C(emP7*t#FkHksU~*D5htq83&0F|XV|!{4}{J7-TiEqy}($+SRmqNp(^={&oUz*L+^@V z<;td}GRSc1DT9@G9H-*hz@cMWqY@?FBuiHyW*~*032qRoz;Iolve7z?Ia$J!Tcq&z z-b(5)wsa{I4>+8gQ|$P=a~Ny%v-9?7deHjI*@8BCHp2?UCUW+Te$UOCG}+rdMcZ)< zh14IzW_qtY86p6a`Zb|ru2>DCe|7zLD{##x67is)&|C8L!XS5X`_H`5)w~J1)oS_T z<;4@~V31QM(-_9NBO{rtj=bb~O3Wj}r@W0Pmgjt`?4&dzwYuK&i{ucL8?6z%E|bZj z5YtjR;lLnj7-pT(M>~uV>iq>(QwHi}&hSI2SWIVYqcHJYf4t%76gD#;GnVr4zU~p9 z+nDloCzt}h3%!Q*sBC8jUzaUiZU9aCX^*3LPl{w-azEqqxn2T?jQQ?$fobTEfzWB= z5m0tu@Y>NH-F;^LLW2l60idLFofnsxXRHl20YoBJf=BaU2c&yR-glT9|6? zd_~WPI9r%=O*?&MSO^I?CKq}V3uBJ)*^S%uEjoX!t?(m6>e48$qFkg6PlEjAyrpd8 zxz1D47mh>)_U6PGPPGaZ#OohugJa*HJ^q?BO?}UL}`;@TbF&>sb?hWX~2bDi{^>@;qa5u=} zIXqr3k=0g={%F}QkB#HLM2gMmquJ$pkJ9Kb*m+KzdDKl|HauO$5T>C|?7{W*I0T+m z0n2kx*{4mI{^t@&n88r7mC0i}A`@^Rst3A-MLe|@SH>d$`y>W8OPINZ-6ELvOI+so zvMzWi;OaJcJQ)xP<4W0|*+~>sE)Pcy<=$P-65Xqp@~IrA@+G)B(UXf~FBV}jvTMKA zf9UHa%~&FrJPWxPPur5i>B#1B+zTDsd*p)@6VaQShN%z=`mD0(37Y>^s*+3C>i^6V z3}>oL8EgnWnF|(qex97qe(lD1u-+}cd0jU90RWsouXCp=)C^H2FZ!D6ibPjm#>;9O zjb&E8N)3Ytz(cCFt)(5-C5}tqHn#m_ZDbg!y(02XZA`jsD+;xWd26lu*%p-*s4z`T z6l-e!6g>CWR&Z;IKg_8rHbP1eyFtdc)oRd12)&(_wWY9FonRUv@Y9a!Fp=VDsBx$i zXh=8NxGYTxY^3M#&hdI0@-H+BX8W{)#mxUKPI$k!ce$80P-pY}@OQhfY`N3~IG^LL zHGcizw5rzW5xL#yL1sJQ4>~bOKgg-`X%Sz;3A!vZOlLB4G6&(I6F6>oWqhy*eemV5 z9VGenysT1}Z_fLloLg*`R2?TK#>mlTl`~HCD3xVwN@G9VMPu`=QFwGORZ1WL2eD>w z%IE~GcWzy)1er=o>KNtPZM_9E^qQ&$r7QH>npF7I%hN}TlLUvkwe6l zBma0a;uMGbwbtV1kan{-`YbG=i6-=a-!AP62H5S?B746v%R@~A0RIAadbUY3$$tMdPVI7 zlbbi1WpfpUR?(;AXbsg;*i^@05iZP`H8>e)tvu~LA0{P9UT8~a?(C}3M3>nU zi?u6}@`2|2E6n58%V~aq{L59Lnt{}yO^poo&~QOsxi*_ECHl7iCawo4QOikM*n$(U zbhg6es&Tzk+eybOH=X>8VVE+R<^FHJ^K@Wvny4X}*HcrxOqFhDw##P_Wr+SZyEr@X z@+NkFzO2*Rf0$|)2lBe-UIO~e7kbZ7=+C(0T^-7NkJg!!aw|adAl-Auo|M9PyN3_D zkCZ|*&t6{ijF*OLt;8<8_P@x6=&u;_=ks9WCzzcN)SMUC*})mxWtT+=W4m zbD%m>3yVnF*%ALseg0_0 zzT-t~I3E9HzFq@zSvnkL3GbVZoy%-DwE@4v*brgtBgKWWf=mI+G!p5TOOu~av-$Z; z%boeErhqQ_RkHFxT%t;C3MDX!sY0L3)?eL>14%U>Zx1MoI6i2GGQzFw>FSYmy-ri? zW*pITPS8SsAK1h!V;9L&bboMq*-=qEjg*ZH`>@5MxHQJ={!9C|Fn6j=%u;beYEET% zhrLT7neT3VEn^qqXooC)C(ll#UZD$8fjx|=AuDXoJjhCI`nH~zzykEpZ$*chbuO2y*Q}y)%d_GR>|nhY1Y>c9?K@w-FHVYcBw#&MrbK{2wQ;L}{QS|mZdwr9=5!@}a&3ig8%Ib4E0`fmwpox4A1@BqG{ zW6lk(1Yj}onM$34oMG&M(xZnq*Au4R(h$G$S+udzn_MhZDIAs)76%8^q;0~zuFf#tzqP3^({^-k`$-Y)b zO}*0#@LG&Pw#K?0doKDp+@wO4%u1e#N?yZ(5k>nxZla1L4Fu9uI_rp5yg1=|npo$z zklW`Rz6Vi&d9hcLQnVpY5v!s+&cups5R5ph*x{YLcusbSx%QdP&5Mc2g7O1qzy`bS z%a+@AeoL&NinV!{^V{NBpp*Z;zZ1U2xt{gfxzYDo4wo!C-s(kCNbh{6mBWcrT=U~= z1EHeR(1^?BLtJF1J$^Milk@pI5^|Eq!ph0qq!DePJ#T3L2?ckkOKO-W+*i~CDp#uD zV{8pd8^&J`D@ozDv#h1)r1+@AX?=tvHtR%Wemd4!bE=qXhchJ8Yl(7+D8kuc3^k6! z3H^rI_IVPf(?hMba?(VQ@zYaw#=4d4YFfMGX|r7^=blg{<0E*z3hzOb6~E4gWtx;U4zhyLpMyvNg8}!z=}%Z zLq%?FjrStXmXKF|AJ|}f>h_=|s+ITjTCxURWQdM=#e@VPpWd~fc z!8F>G#ah|9D`1@@hT5!@20kA(nWYG3RyG=5przg);_sfLk8|lfA`)(UlolOwlP3Q5 zJ?#4SPV-UL-C>jI!C3cOTQH&_wv^~sx#Xi(LLr&(x3)W|RF00G48QD~V{fye^}Hgf z`sUm2c?aC}E=q?(tG?@X)5w2443I-T>2VgjE1A*vl-2&Y3LkIC@1QB6Eyy_6vhNQb zPplk{8xti8SSgq9oK?=%cw6D}5tFd~`Zg5P8JnkkZSWMOa|upRxm;e7x&`s2 zFEu7=JND^6fMH+&%0z4*G!BW*EJB-&;!#Y*eOt7Y^t@Tm)ur%<#xch}mVvVq6s^u@e z1%=9#WB6#|0ETP&&Z`RiY@;>2{h-6=b^%r1|ovRca*Y^rv*mo-Yxm!59= z;&}pQqeGTdX78Yfw+A(ClI!_dmdzPV5OkE%8`=8_rn7{8-LES^W~jW4c;o2ORSvv6 z8w}#qWz|z}j|U)9{%YTU;dqIP2;0xHlP1H*{vR5X&Jzy)Q71sW-DAPD8yna^(^9ux zXqKJKM;bKPvehTq3B9FWq_xE&-k$YvM)L4;%;Uk{6jTL2w{MfDWmzvJVRMqq;C<)B z@G(&KD9LLTc~B&`5d|yBFiE0vG5IvSsI9M(=q4Qp}K` zYNJV>$f2Xss$q#B3bB{f5eZr=?akdBO`+%US{shc`~k+Aj3zs3OgXF|8rQOer$(tc zwCrdFTw)9`{76h1^uD=7ihGc#=|m*3=4ZAt2^L+RVOp_sGe|anJTMh55-bor7Od{P zatM8X8YO#j-UxFF8k%SL^0g*U?W7x}s0(mxZ09mD;l12h5b_*6v*VW~Hbk!>dND}j zscVvR1NO{0&jMaUS+;y+@vsPcdwZE6${}|EpXorXWJaq@&tBc$09b{r)^vyZE6m#L z#8SOTNqLZEvEPTUY16$E79v&kdC%c+v!g2Mcr(@wC-e+1<5aJ?|YS4D!*Yel>XK|JsSKqD|<}dXjDg zPD6yp8ZD_VSIUA1n;9aVeT!BZSO3VXEuXXMZC9cdcW$`y3%p>vmDe5*gl3n=%3&uA z!ZOdpF$vPo%?M`E&#&Wbi@ZLp!6-g&dV#=bi(YxBJuB={vCPpI#p9heI=XSg{V-$Wu37|;fS6lRr+10z7Dwh5hVO8cLf5LyS((-1kHFoRG2&|rxxVQ zH8aBwsTkeKm6VbyG_19`h2_Xto^Y!XktAoc&lEo0L@n036lZw#B9K?Kh$REJm)Ttz zG;PLmilIu2I;2xKII&n2i5xcOea;&jPd>8O&|w@l9qcj z&P=U(C~2q!)gKO47hhUf+y?tXvMz_j8DYd#_yg#TqLq7WzLFgs*`Z8!A;{r=o7Z#B zxjw!W+2D~%iMu7TNzUd~_PGZd{-Omc&n4L;Ds{ao>R>Jn0z@>zdEaKIs?Wt;97=M| zl{Q%%zDcQ8#??-_K+t<33t{f@UPnhqX~t5&4#+7$(hRt=LyJ+WQX$B;G*X^!jdBN{ zO?=d~NfL}8wKN1CwJ{cP$6wqov4;j}q^Qy8a2>~061Ym-{lRh^0Z{#SLX42&mt9Xi zdbwSX<0#(h#9tr&?1`3vHG>=5c5cf)4rrJW9DFe7FbWy+zMM1^_?RoCn-$U4r+1-7 zChIM9>f`swaH<}-J)pL#ML)e)l^jZxJkT0xd+-{QRxqa3^@(Um?yDRE0WOF5XUr}Z zJ&554BGIuNKgVQ!DsYkX@vYY|ug9WqjR4#oAq2@dkk(Dg1R@E-`YSZ4rwW=&5H!0T6kLdcy^jU+ZhvAMqa2Mq)xoy{c- z4`d?C#hU?ZVZy%^n-5|2T*~5B3c`yFHexL|m04xeorAyKY?~lp4?jXw;EW$67uzk? zNNg|Yvz96|C#3_$S^0HH@Ji{NNMPde>Q1zpL=<0!sf1NbLuQ8}F%`Ai&hEHXwd&ON zBoC6bHR{>=HSk-#(|O5ffo*{flZD^(eRm|6S&@KAo+LJHSwf%`4M|tBTJOwXB5<9k zZTsds&dU^qNJPfny(`nvr0BJ5Yd-G#Y6ZuA9ALW)t@u;-scYOLgDnTEfBx&uS|EAb z-YBvf=WwVn_T{&~!G_BF&FCtY#xW6g%3re?s!EdM?7s5e-M?PGSc$PqobeV;$3y<_ zQF1`&bi!D@E-l0}$KlWuFOlO0QR5HA^V4ka<=`?RlS!ZERze$2fnjzQfwZyZH^GMA z&pGc8W8U}4H3BDhhwszenkwEiHaF!njx?)mJpZUiU^Vf-o+DLxbB5j6 zH|tl_enudEWEQ1DX{G2SRmjL!Z%Ab7zw$c&@ZD~3quG7uU=^l7R~2JY2C%1>gpDVw z4&35QY9Zc)2BMC2H9%+&$C-gF$Mb4>#g;-*2+op#NtPa1|7M;aGfSXHMCa|X(}Lug zy`}461$y4xIM_YQM>-~tekM_D7J&#)1hFijyKJD+W=YsaI=_X?~W8#dZwT>W2-w=sERNy6)dhUj;)m&MTpxOW=?U+;;PrEjSs4v+n zY{=ry0_k5kYm2|QY&vv?%G$kQjixgwt!A0O&eYxcIQA`EX}9W~K>#&xq22%G-Gf*c zIAVMjqt}mhxF>GR_xrKDJ7w5kh@ZzKhu^)4gie>YJJnBH{8!4!Cz^LS<@Z=Ce>z|(QCbRq>MMxk#kqmuKHB02CSGuS?X*JbAd z#q8CKYRINu*p;oB74n2tLUydZMhd`2Ac2 zV&&@X!gCc=iE)@T#!7{4Z@>DAW$v2rN*@AYrt(ariVdt6+cl^mv8ZYrGFuvnN&W(? z&GKo*(;Ttyi0?G2PAT4s+orEf<&F{#4p$`7yEl*z)oaaraUQ4S7nrZVn>RHg3})#L zkLD-iZWOCEk>x(qUaYEmizFhGO=m$w%r1YGLhH8ikx?>sJk4X$P-yMN*o?SmJTdOF z#TcSZfP!tYV=|-l_^%5~t8oi<1!%WW;5Z%9KDWQn@;vME+jXB6^j6YM6+H`C)U=6O zwnoMBVoWPY;rQ<9>5(w+Rwg5xCP=zuP?qoaeWf6l`>OC&i4?Uo)39i!|8QYUr_E$= zh+3o8F+NmYr=I8X?6RZB?@0faNSRVCl7OBfn#xgjFLIvkpib}Qm0Q#k6A%i%Ie;B2 z;pSQFIheLf9%y8P+KH!;F3|uAfIpO#V*CGPCk!AB@Ube=%HBSbnzBu@%2DHhnH2T*U(UkI(|)odrjBqI z>ou@&F(G7l<1_W4F$v=>k-RxP^|xut4h8x0?DPsr2 z!^`u(hNBe==$YRMeztK>};&Zko%ki>ElK!CGD6nVrCR|=TVgTanF(^V`vwDnMs5j~Lo}1$kEC4YemAA1pb#7DycaxJ zZU`R+J$->B9Kq_A%!1c&d|8hK5`9#0NJGE?LBLmo!hm0T(1NlV^g6A|nkfM?4MPO;u@ML3xaC5Ke)wFz1i-oge&e%S?rT z%%&U=a5&-fu)Fr+>0&+Q^oi*%QDS%}`YnqFqq>gGFZY~o=`)7J5w8xKTCWQ+GUBPPvSKObnP5itcC!JGSPqtbsGk(q; zOxd011hf_PSp1n_^~rl=h%_n?qx_%?J+%&WEez8*ls4s&tYg0?lYJp6LM`q@9ezcp zEV+ghK$qPVRwh?iP0lULY@AFvCGnrhnHq>t3oyK?Q1VojOvFDvU;A2IKElQhg)You zpE9hqZ{~Qn=JZ&Unij?$?f)SaA}3*P6KH))vf(at7HXi?R3XbA(PB9B(l(rW(>Vct z3uMaF^BlbXeZ)@LRMtVjk4Aerd!pIyE;gMfm2TO6pg@e#TjS`vx$GuN{(mvr=OY?& zuAh(#B_cbXpEK1O$69Oo01sO1{QD^eVu2tbuqQ~hAXS96BEeY7X0ybVNz@}C{?Y4v zcd6ETW3zP^iOV`60?)}fK1~hStd}@v^{RbjkbqW8Mm5;WV@p}(!GNx z9N2NY3jZ(+kwCDN%PqHJ;QCS7Wi32Hp1|QEzy{L~IT#q?;4?HYV2_6VECzx~Y}Xay zn}C;ZF6V;FGNxa+cN$`$K4L&HB$&9hn#h^CQ$}!Ep~-A*QN)^-iI|KH@A}8%c?F;A z8&czuZr&*bb3AN95MDD{F-WlWLEG#!LZjAo*7C|fs3g4MXo3$dv6Y=58;DPfuC$aF z)k~sRr-aBAgjxf)7(-n5=aY{63Suk|OprGd_s>0I$y=PTeZzq~NzD6yS2ef2&RJgK z|GwZ0G!AJA+>9)dvKgv|@ZV*!Y9MO7_GM90lgXV=E)o01r;+kIYrJhw({TCkW~}0g zrT2!Z)ya6({ zgD8WioqbBM{TMDf(5!?mmu#a5nYjOP2_s0HFqW}&|%{D-d;vhlvS2+<%Xvq7nGJ_c{m&+$(E zk%?Xo=<{~v{G|?H9Kpq>2O2wu_|&W6?NMaap<99*(x%Nw>L!~gs&$qUJ>Sm-`@_Ek zahIEvbXwp1$S`a5-3w{8`{aN?T6I+_t)`RG`Q@)qZi#2!-u0o@HUn`o8I{y4v<)!% zg}~VqucY+<878PC`D-`3DStsOgiW~kL^d9mg|6M`@2~oD8{3 zH4%}?-6G}%SObito`anIH^b$zkoHbNTbmZ0TzY`^%NLLQ9smR-?lHgzN1OH5Qm$2} zn#7=K7$(r74xx2r-cy7r#NNu4^2e64tpHm=OpN>{JGBmfKVEs7$#_#05I)_+<;(J{ z3O9T-k<9oQXdK}>14xiGgPke=OR)~hk<;?43S1=xB#`Rd?&rVeDm823-G}I|dU?Jy z9cm@h1mI&B`ef-E9#Ea(P@ayYSNs1#L5d)C^#0usd?&GAAuiWSWlg6EC){pQkYT2{ z`N{?iSINxET!`JE*uTE@a8v%%2HMs)GFg8?#ijSY?#%qGpw}|B^3ND3@T!qqkCeFI zjqP(zrXT~7zCw>8{ty%!K-IS4N`Ncq1|SVjf?FICH5pt$28T|oGe|m%N24#AhzKVG z^5Z@hvSGmb-tp^_)LrRZ)UZ7MoDwqk1|r z!3Rh`RglJ^5;;Aw(vV9qacDAZ;(fqHrBO2_obbrVqJ;d#B?S2Vg-uwq-u_PS88Voz z#BctNU5L;}tvzaYL45WfHw1*(RIhPWkqHOHlf_*-}PSVJY936W7L59~w^8Im5zVg28; zs^Qq|*DrOz8{(FNO~m-eLLx$X^3Jc*=(X=4UzFK6&UqvDD|+tA03P&I^SL;tsANVF zyhVrX0;>EbODOYyW$J8^Q0NcfU;u77O}1OiuxoHia$Xv{wN_n97C#W%9hb<62oVdDSrV~9=eK~9|Ce`8Ym zyZ`9-M|T7t3OZMt*#C#L_Y7-t>B2?yK#G8ff=CTT zAfbjLHPWStB2`6-bWjoLO;G{q2uLsLH^J@R?|061ew|-lhUa-^X03bHta8tc>^C0m zs82G6{a(>aIk?o=bQIAZ0_L02&$|Ry7pY5P@-F$)v32Tvh3W|xk{)$0HuLHT>b-g> z3jsMXA#kzv2_}Jjw@!lfNZjwf+l~*wmB1gA+B_NSYcdO=_Ec2bBmobW|9c{kq@5Gu zbq^7iOn+LKoNM4PIrQ~#WM@x8QAvp0gNglC#^Rf!S8l$XG3(;kJi@OxrArb!A5#0M z`r%B73fTn^qdz%dytf93V06@8Zi0y*n<-7G%ptq|hw=nYCBL4!kKlZ^;o;!H#jbCr zyArR1o2P@D<_~EI+N3?~#W)6Ppr}waTm@lyt~rlDu`u6FA1p0$-cXlR((YXO>ao{r zEj1NFKOdz|<^QVwziC1qgaa9s1%mdJVAKwsd>}ieE}-@*Ugj^>a&wbZ^IM(YWDn7V zae@XD(M|vRv2rvH04cqM=l?&D0FH`z^{%kqzfJFTshc+V$y@A;6dHQ?{0E!---9`n zh$8JOYZV~2?&X{#Yam_V9R88Mb`{r2Bz(AOPe%o!IZas;)m_QJ1J*&b?pEoI{dpDg z_;a8BD_n9LNIi9VKZPQPC>2ctVBiVPd_c6&>=~70lhvo6h{AxcnzoNke^xw~y48J@St%{nzIIubtn+UWObXiQ!=v zJiy&Ssb`yPl%>8nfq8b7v5LkSOYUWJ*}uI65Qv(}*GkN90HauJ~V<;n;8f>Q-kVN8RI(pi5YU z{r}`s4|ZM`j4&38EAQ8Ba7b9{@p$6`uey0#t!7t!yezuBtwFjui0^;>Y%u&I3~{$s zml350D)B8gkNXrR^CN_*SpG$5@x=E?m9t@t!tGA-9Z%;X?MtS?pDDvLPoY#)^cl8v)$>e}frdxvLjV_sw-an>qLvFHvN2 zBN5!H{J=3wu5~`8BZiK)^)AhKxmM@L^{w;opW2~{yKy%nRU+X|NKvXm^ySF`4=S&( zU!h6d1 zBbw+j)xNu8Rwu>sQLw@#>e9tR?q24PC#(3eh)t+{kR5SPRq!6x>K={{O3EB^g*zSV zNy+wS8$`R+d}id@u|8Dllk9&R{Lf4aQ+1PVd`1(WTnjQ;Kfds@SiGCtu{ZpVF-afe zz46nYPT?wOT60!zdc-_3GUzy2XOU4+*PHL3FqfkPcH&c#bHou1fZ8C+O`L4uzis>v za7~Oh)qU*9Vw?#Ak#YC6x;xMB-ejSc8PsZXP^wgIboGe6F0N{^8;Lt z?hqYToF&c_0Uk9V!bBD?+n+hK$20$Hk3q6uXoU~JE$=yBL~JKtE!4GcYiCvkDg8>z5Y8)MCN7v`DzCn>Gp1r?Ony zkUmY)f2-;v=nnXp(eKoGwn&vPxM zL zun#jD=0tibb!}Q++eCzdY|yEP6`xr=Ryp zw!p_M5s`A|YF9f+`zC$~T;$c@uiHuQf4<(8+9Ta7bddfG6&()oOi9-eU;`VhR^DhM5!MQd-e|?&XECe?HCXkRneF| zu88ca0z?$82yu~6L^M@bADD>JYx2EP8AvK;PudE4H>-R0WX$$QtFUK^gDAYe7-MDZ1GlimQpdkGyIebh)yRiV_8v@}275|dxmtqcn4cE-GgYB3le99I( zpAhq`h6i{PtNuCcxI<77fx^h3NM{3`JBI$c&6<&n7vQRDqr%Fq%3HD=#ueaTU&gMDjUqoWY|0+G!QwgN3H zYW!s7xjLT{8HBeF0)s7{AVdbCuEL-tj5s%GQhG_5Tq^3zkzm?ewEi2i^$`ory!AVa zgOv>A&z%5lgFKJ)0J)GYGdPqRO#OhXCBLE=o^4zLE00nAab`-a3S5&j_~gvjgQeL>AYtbe#yH6>zXJ23cPO10Ng`DWp2P5dmN-sg~YDnKI1UIUM?{92c?;_&u7bhB7=o8wFn5RXo{Adz zSeN*(&jo(&CM-+ z%;9Vd+-Pq3c~Q|2?lb|tpGx-fX98Rn=lUan&Xt}4HsEnH-y$+BCys#TiK^hGbk)Qh zE9VCC>q^@bVI5CzY_H>hk;#6^`=P=64N9+Aam`O88wW;d?gVAL*uLK7!t-4+gB9 zb}EN&Zyu-x+mz&G)=ylJo)>{r{_Pvzr4LXs<`cj`$?~8jfrID zx#M2??%BR7!KkC-3{BiJ2PeZ&3%M&ikXp`6&zOGWJnkfMrY9ch3m$Wu%)zbzKRBa^ zG^5D@Ni8vWds|sc*M=G>C zwTt-5_*Hy0H25pTpa`_v_e*m->d`9HT%oYMB6TAO zbFegWH8JY|v(qIDz&Y-4aX-Tu=&+>Kx!_acSQZRPY~GA#EJW72dkRIWz@YXI+nr&d zL$ZhS;t~Y>gK&m|K#)#*O4>QdsRh6x8wv&qP$2`w0a(ZwJ>t3yF$@KxFK#j~%l-4m zY$yO^kw#RePsv4K>yb}}4anajBeFS;B9OMAEvH#|SV0Z@`UIGh53lxx{!fGIWQRdr zP~+93zaO)g09bNZn|2;P8H|8~neRpn=&NDI{rTeItGBQ!0c@uE8|cGE{{BQT`oDiV z9FYqAmPYoUWcnBXI_{#st&nwBK(;z*l1yU^|9$6=816&!YthC~I{RGXfF0el`6i_$_r69KlGAv?26gPdhJ?&B{BU zUh98f8jS{xjh^=#^Tr}nAXSWRL04}W{cQ|r@it^2MN59#SM~2#5F4ON?0dpPl&Al8 z_@Bp%FZ?4l;vUW7$&-{=99f@-qIN=2flLyHV$<{QXa4;YK28NJVe^)Up!o+oFlO>n z5td(*2fYuW97NM~VHVE*MF2oNVvtOucIa$%k^A>o7}n(Ce_?xoZG*{ zjHEc^zZxF9&sZoNY9XHgSE={8DGw{H>dJ!(D%jU_0B)ZSYZ!k!ijX41O==eF_aEG( z$Z%UyZ^4Z#*EbgiotGo5EpdN_kEn(gi6>grZQh9C z%~sNyIyDa;4SSvSYeVqm*Km&MtltNPmL6> zuJ_&91v0&wS_w?w zx&*V5nw!;Zydjj_rQhDm&vNc=J#SoIv}`=SNZQ3NMNNTJy~ol9Kr|R(UnIr3#H_%* zVnCuFXAQO&H5}2MaBuuMJ%}^4c_7tu-YCcP9~3}>L5-yEgq9-JLSlXd`f?WE=60>M zL`YD=tx<2mITF8;BUp!GA7&Oq?=zD1?qHz>@9FNQD=0@liDsA49;0zbXxqZ2)_S&9G9=8wKuEc2NR*vZYIP-bhdoOJI(v$ zbvSiFe!WAl#~7kUhRVL)8R788-#=H5(xu08oqLliVK?olyr0JDzuGkOWp{n{E#+}e zgz~SoxJNdPfww!jyfvTS{AB;0BtNqb_LT2-y9e_A-WzVT?@HhgUphaR9ePpWSUTDo z$7?lZ+PL?iZfnd%L$J`OP;X|0=jYso+aEnT($v9~uwvkzk$d&)dh*|xeHNcQfA?8i zN9S9i^3URf?Z)3Szu))tq}avEYXq)_@+{r4uFKd7Wl$p8{Q8j+p7g2WdQ|TsvNoYj zyf=AhZ)2YK$T3=?V^)Ak!~Un0^uU#o@)n%a=D{RuBN5=Keu6(_ZaiJa<$h8s7$~l} zas0Wv_;K!g*&jXob#MRLogKD{!@dFaC;OpN^V@GlpF{7@f-P^8Tiw^+&1U*NZ5ni0 zY5d*5>9peK_x+RFvd><|mK#CK+)6rv9LyL00SDwS`2qBK<}-9}WqNyYKfU z`1tg>&%3c&%D>mMelPinwx0O?Yr8S*Zf9vr3J>~Lwx#d$XW=Sh(Rc9e;sV9@=}%hnfu>w*2@7?1{1D^bZ?T- z9CeE8VU&2oh~?~e+^dyjaQ^jM&{a3<5@N~a%a?xutoBz?vh7DGA2j)I&1AU0S?l2W z{6&#Q0!lgh%G+Hk9AF@wRYLp<$qU~JN{6Yk$LQGkfb5g+E{}DEv06LrJ-^m+Ox;$J zo--9(D4%W@I>+&ziBDKu{G1XgUNG~Xn$qqx6YsmgUL2M+ZBarHee!AxLjbtT`{DVG z59$sPBja+z5>u%`{AxSI(FkteqNd6_v+r|!>F2HvY(yUD?(a%*P3^N#I@nvKg zj(*-Yc2OJKIPkP8%2GrE69#V{-#W`VYWXe0Egg=1C3uZ@z%NUp~KJ_-0%I*x?CsrsLZ2& zZkFL>>{ka(ZA8Ijm06^F+P!y{#e>?1rptH8+%e5=$#*GQ>OHYA)3-$Ijwp+V?{f7p zb%s5w<*ncoLBX2W-w}&SkIzR9(g|iCOGv_1cLJ0N*86TIv_-MfV8omF*JrvPUwJMJ z!t#}ee{Hy0aF9vvPg{1=QnPD#)m#}Lt?C~Cd*i1%OTt7|y9DMTZftS1aSF$QN-i6_6RURZ~1RaON9#0R#mrY9Vi1=-k_7lZ})fR{C2TF`< z1XVpX&dPD>c;^`G8SxFjmHJ_fpRMjPhnvb5ZU9{eZ?@Scc7u9iJ?tYaeWKx$@8S~& z)}i!IC!PnapL1w`zj=8IC(Rspp6fpFh3>pksDD(mot*xN`~7ofg{%bFvUZZ- zx%c@mR7^Ug#^rMF)}Iu6B4xKfJy^_Uuwdpt=p=<0+EyWoZ29z3-5_v@QYv&$*Gk6%P zk)vGajX+GX$s@%>pmrBX5DW*M zR3o8uj_oeUR2j$)8qFw}`q+n@cddVqRVD zjC{m(TRK^BcREqyHU*ujp*1cy#!Bz5jh0sjLQw00pxU5I@)thp2VDBf0aNTI4XzvmpJ2VX&fa7+c04JiWcXhB+K*Tc|5 z(%UNRE2|z(D^bi}H$BA`pFQ#L>WW9*w9lwtm*vWAe$#5M03G9e$i2(9d7zdT!0Rhh zi-%4{yl%%g^ZTBNI2MEa#h{0lTPhmsG#zf(<*F3J8L9z30Xf5_!UzY6Ms|%DqfIRo z$Ge5Zf$f$7L9NM9os63>N}Xo-3zZw^whq>NIIP}dhSj#@Bb4J>%|v)z=q3Ar_{J*5 zR@p}#>}!378Oq0OA8JrQm3zZA&cqjBVhvY^7z>%}P!A?tzz|&2a&?iC=8ZmdKQG(k z+AQ(?*eI5?>f~Vn621WR zpImS|9>R)BUD!xHBadUle722=D6-segsaTTjj0>I+~}8Uv>U=|qr8(d!3?G9W~211 z$&+hMAY3>_APZ;j+h5_#Bx1&ILV<7$svkOvO(R`cHZUNHlAbv;P3kW`uZXA4A->Cw4)K ztK7zGZWfhB2|arRFKqIUdsztfx6vKbcf-Ov$@?yU+EPEsH1qt*8>@mKQRy#D%V0N=;nq8_PAy&#av4`dqJp)iBg$*BP88fgL(&RyKX}d1vYqD{${; z>Db=W!ymKS_?H)3&&!N``$ik=;^k#Y=tt}gU22S%rr^Q!H^Fl5{Q-<&#V?7%BOs~) zRsg0kX&k_~sb#wh{K@+V*OHrBqGGN6!GinFB7zD_yeqr;smG#|MLJS!iJF#}!5muM z=g%(w_%D~hlFk`N8mngF(1Vz^O6A(w_^-94#^=Z;B=+>GZK{(P{nhN9MW|AR%oao; zs-!Vn1Ln>cv4ZRS02I$`P>z$*CWGS2Rs?#xSnsEc9&7If7fy?d_nciZGa6r)(ufVa zg!GN>EM=2&STbTRDBqe>zBcmZNwO6*TZ*cy+JE=9)HZG+S9yjY?p49DjKdc;0zPD`dbK=j6}}wNE3-+)q{jGM z&G^lzwAiG%`hwZ(+*JA3bJktB#@{Voo7vVhYDV3$54e4p!?y@vajGB#x*VB5+l zXy}Jw=@SHMH>296tbQneWxQE$?OEW#TE|hJAP)CBgAr0i`yP#(L5KuY<68H(2y__6 z;UOy*o+?L&S;!?0fj5$*nCDOxU!@;1dwe@!2s_srb1n}o}Oy?WSA>AyRj56_GC!g;H@o9 zxo-)XwnJEHhbD)XokJ)pW*t$Yl%%74dQ~z`<@?FJDkVu%aEuA{js?$)1R5A3`H-EQM?28$i zc1VjzpxeE=%2oLAZn}z7#nYex%&};y%bl49$D0~n9l#19ov)9+_9!>Gx_pdq!oe}q zr=YkW2JxV_CI`abfUhU9h|LWU7Q+5EcVVRbn0J98n5NR8@(V->2W!9a9cq8ST{w|e z;`lsE641J8^z(pI|FbD}RQz|Lnb-%F50tSOP;gH?@3uaZ^1$FGzLd1O0>9T{+?X4K~BxR~+LX zqMzM)dkT3GDS$N4atwz2&@k9X3WhFl0A)~cN}`<8m>TZj@~2j!L_PZ;YGd! z(IFwrGMv}qP&g_7c0ieRJv$d?Ap0Wqfo!L)e+`I0GF;%*&fN?iH-;l1)i6@iDQHFZ zJ#jWXGbw~3yej5FZ+9wmz(bh6&7#vfqWpt5)g9>4>y)rKTY5zNiB^Njs@^N88A>)) z5@Q#Z+SLqi1f_%08s4b&Ug2iCcRG_C$gtrusGPi1i5y>ax{q|aEZunas!2V5PRgY# z^=<3T<>}0$Ike@`TPGOC%))tF^w=0|I@d2ETC6S^#2B$AZJYwxE$BJ2fZQ8)9j2-P zlQbSwcndPobb0O0BUvvMln(P>2Z*aDE>Jxfx%7sm@;nSPlM}(6F8b-_*3S)`E~(wN z^~5@VLZlPMkdKgz;!o7nMg`$hE8r^DPYiOa5EFG8J2E2vBD#iZjlCYKf}x)%t{j9G ziK5DvWSq(*VvJtd!B*&lPVv|Nl#EdqDOB*2fda9v-hH?eDV zu4)%%I5Gy|xa%Z^G1z`B>ymYQpR-(PkROXuVymF}vJ(B+g3E!ATbq>+1H z^r|>=zT>fpRQdy)SeFmnIj3k7pi8A@yj0QDJ{bRsTl|sHei6r+UY);>dv>LgYGA_C zIi)a!#zXs@?B-ac_N%Ig-|YaaVw-ku6Xb{y?7{orU-c{<@cQc)gb!=>PI9%pVw-vx z^jQ_Nx-?qZ{VH`ErC>fsH&qDRbff!u`mwo-%oDuD)t0Ew)-gt=%8(eZ39BKnXK!K8 zF;8q&y=Xd;K~;h6$AujwoY>5snD=JSDM4R*Oy$%#h6Da-E*5^GXT-7tCe9w_L+O7>yIm-X3kPg`wlBE1abMzD0 z`zbJf#<(OePo7)22`I0C+WK5xT&xypY+#K>yzYY&MTMr?@Hdc9mUAvf4-T>O>Y100 zRGIkE*M^F`b4rQqHEHZ$aLx7!X6m7%4?f`&k;ibtS?fxlN3UGWW!3I;!hr-MO>Iy8 z-eL;5z9x?Xk7vkByShT>hT9Ds;822&Mg6C)XL}*U1Y$Ri7)2b;N3645o9^Jj)y>a< zRJQn+cchT=l%!a%JH09Q?hrgF`Gjc_7N5R)PkfSpW@;qyd)yuOu&m{Jh_f!c^bX_g zI3uvn)IBjaTJQKaRn)O|I_{61TTLyqBJ?||3PI2AHGed}_e`julOf7jWVBV-F7Fv^ zDiEaBEE`jB&Wa!*SJhm`O3n_Sg6<&oe4ekyVv<9)k8n8EF>w1WNvP8%yl-C*SCk{qU1UJrT^;a9^Bb8@2} zr>q8vyFMwe_8hmY+WdHax4G1XuJMZ83~Yx*;m~c4AqO)L>CHb@yO>rMzbTh}(z6GF z1%BzUR68{(KItCB)NnK(J&l|>o^o$zZ;j_5x{Vg8cgrT)u^($B|=_dwoj@RjnYnE*}r{tZBYE8wD{oI5j{SM5gk(6xf_LTOzu z90w1`r9kk>vpd6PMsI+U#o{~XMlk0OlN$(A9SSoByjb97rJ9B;vKVGxqs_cHUKC{?jJe?Rz^fT@YH*Q75dDO|XR3vaQ zp>*U6kc=`zmKD#wBH`j={TzcgR`}gF<@SyQyX48%pKLPsR1IX@yjHD|=64r&Yv&xK zTn2v)C1h6G#}mCD&c(w*KcN}j-q8FMURc$l2D3!)RW>!75o9@T4J(0ymWn?FxE#r) zyt%QuQe_Q7D>9L?lUc-Nifa+S#QB&Z#Q}|L@+;WBB~g!sVTLBHcAnLO1$9q&uhw;Y zl)#g<_m5H$Z2UW16Q?VBi*P$WDf??Z2!YXo))ZT#e)h{AJ~;K-uTwj0>e3$6@yD+n z@9GNaxN?oVg8g&nnP9tsCa2#CMMk--YbVmqG%D%Uo$DUNX?k+*T!~J5P32$dMCa+x zCY$aSe@@b2)$R4CS6c2r+1jtI==;+`%{6ZxIA5U+ZBSF0%JP$={17C7!z0E_LvHbn z1k;MkPE`&Lq;w6X^#>m2GrokY6fhM+zI|0Lr+nuiq$CjRv&w4myVWgLYOP2GZ?tIa zcN~hu+VdK)ngIrh$Ol&oZW`{pQ`gqCkSzy{g~TjO2Fyc?uVgT~gUR^1S`uX^q-(u&{WvydGlDqIcj2qDZd zxPl^8yH7`Xgk`JKkwWg$RGpQ{$R0a*VehaSXBrPn83qm0eUp2tGU`0bQOu47FC(zb zXI`66j&OW+VO84rd?r(mPYi3nLuykqddJ`qDNSL}i(bpexs?1<0NhbWz$ck)8AJM9 zFjH&R>V|myc}@$EY&GawSWW-*Y&}7@xBg})0|5){QnC4pfo+zD~YQJ+?Q?MtVem!16@BR^?#ZOAd2zxV3e zbqO35VF65R@2tnaiF0TX5A6b2{3Cn)uPbJij9TED`Lk%V5SirrRQHuz8|#$`*2vm) zyi2E7nR)JmZhO4pJH|p+=%w-zc8(d$PKB_3hAP_+E!lmMBH3!LL(k)%+NWW#3WB|G zNJ5a2F+jiUE2Q!j_cEl+>eUbqW|pecD%_Dn6Q(36{54-rwZVt3IbrcyAl_&UB}zI9 zyPszoO6cqeuhM?W!iQovI)<%@T=ZufPzD`WEWbt*-`8>1rcJ%y@4=7>6}(hCDZw z6S4lRx$I~#CBq^G(j=L;Dp%EwPxB$-xzX#^AyPw@lKLW_uOp#8gV z&(ZZFV_SMr+*I4>;e<;@e@oB*RJp5*G&s;ZU9EC@1G3L zYCraT7?IN3D)@oIoSJr$nXbmkrtAI76nnZ!wosmqI9&Q)G6cDHT4_8BNs((7IEscGtFPMt_(YARux~v`WFA8 zie5CngjvhBqX7x#)gvMW4bmkU9V2#=S(h~Sn<-5DzV3P6H?M6^t(>|gK>a}I5*}wb zR%1|7jyLN2E<}rstZYvAv$$foS#h695E|igH7L=c_-0Y ztZSz;t+N<`u4ca@8^RaA_~-{GAPw`6`HGTP4plIdq)nKM2UluFIr6nt8QaIC?JHxw z_K=`4*#x9A^4%m`d^iqLWO^`4`*p)K6_y(F%QHS-JBbMs|#fc&Lss z@4M%3gY)J6kL<_Rv|a6GwF+~5cUmx< zJ3;d3?7FnJP&2kKHA|Y*N|Xu z*}%81l8*l&8PHIftCK7yMJ%ESs%p8DPysd4SjlW}@pqQU@$3=LyuIZVy zI_I_u_r`9}Skd8I5VXr@Sm>->K|YamJNK5yi216I7e<&hQ#Hkx>qSQZk&T$6_Fg+ySnv@PcaLXWDgxx%VH7d@OY!xwPsdAFlztaJ*T~8 z1gJXpyrs+k5>>j71MY+fEXF7WAC8gH6P^ndU_18}lWCzo%=}5Oqz|{p55mS6A=F7T zPal~~*ZrCWh294kU0=E%F_UUs=kAv7->CqZe}27rMDgYqEW4%W*VDN=JDe?Pf>@f6 zcv~MWs?$f;LqYgnqjG9+IycIt+zDliVrvyHcEp(7lhH$Zm`AH*RzO`M zcaeHe+J(2ZjdCqBaD6t)v!}^B?-fmeDKQKV8mtW5n=jP8?p1~i4k@S}%jq9 z#Tu4nh5zzac!H}K3t`FVTj$;C7 zs_!7rOVLePD4e2Pn@`vPH35ZdD(9LA31B17IrRTB_m^hYO;|7v*b5)xfTJv^!TEM3q7kb)osFFGaJNlACan_nimz0?cq1zJ&0*zovxC>>y)%61Uh<| z?TSpGdfZEt4CI+9zc%2?9e88vYORQAA8D8+)-_sWw;pV(lPaK(+^+0CFR$tU`4Xf? zw`p4&8Uh3~#OtIgpLfk)E->x6_`az6GAtWa%&&mkY2g_Pwxu~&(Zs4t`mw~nJbp8~ ze6;IT=A72VvONXt;e~j$2_K?P%~`(UUe~_9f_knN5ulIyU9m3ZeODteE+R#3J=$A!)4%axnBc<2(>xn_EVhU-F3R1G!*iGp2_O>7x<;m0f0h z$i)r1p?1Ulevm!E25Ydz=ZoNP4G@&BUpvyP35oU^5jIhQ3k2q!Y0qW6h*T4HUE5nM z)&JxRKU&)PXlLPsWyGzoM40@Z+%4RK-1h3o~7~CNrfMYJi}*F>#{BhZtA) zySF27E+^uh1K0f9gA845JgW1;y96&{V%^HUUkPq1d_2Otnyat}5vu3mFFTH%#xSq& zJ#9M|>CKm3l$`owF#=ZJbuN76J4nOeZb;Y1KS3VlR(r55niWsiv``_f3c zL*+WiwKMnixJ{p3-fMb{1pcAmP@>E``X87?mvX zJ^!xOeMw$vJ>*x|sNjtxln$C$Zn&qlXlp=uB0R5K;($j{==8XHO^()9l+8gdICk=T zLq`TPO0s@XS(p>c&TLR_j8o#L-UL}`8F<=+CYE%iv!xwh;R!2@K3R%KAhjcKi4_dJ z(L)(A>D8&1+#WzL=bp#Io|KeGMwv*Lm|bH01h@JIVlBpAYUCT#k;w;|HZyc?7Bkeg z=^Gf7Awlv)2>OvCN)B)RHPH4NwKHvb_q`|l8NhF-&3CByVq}DaFk)36LcLIo_1?|5 zxu@9;vY5p~>ZTMufB)R3@lAupVImlPZgeT&4JWP;T`>ph7HZsU^!7~M>?=aDMn2+d zZ{Vt!NNLFFcud`qHHovzfl$5?EUT5hEREmxcee>GVxzsnv-pk~@v+bL=Q(e^rgX5| zs(34QCtYmV+XsaMzSMdr&+0_siFE1QhUVW7!*TYvR>h=|kE7t$C~?H&UmnwP~xTU-7-{Sc_o zkFKAXcq!Qx{d3Dzwf%?-P1LvnjrKmJz`~f3Z(oc-XfS}YZXBD}7!H+WIZT*$jbs>| zOWuUetz)yq)9x|t3+PFCz|w{UQB;}{wmHdkZ9$TBjRjkR3S%#dm-&5_qVDA;5&Zcd z3TB$P<}M2^o(FCiONFkBDOslJcaO_tRZhiwbsrC2jg}tlsrTGru%CK%ExKo}@Ls~F zAjf`O8h+;DbI=vQMf!LSHTb!EI#!^3NanJ##K#R0Y_j0&v;BL#r~lJdXU0o{ z*NJo8W=9_-+>&>bqz?8J@we5b!d7Z_^F6o;at!8D`rR?;O^rnLyLsO(NXsX1V9c)Y zq9Ql0+Oy+bFZj`SV{-fPB(?V;nxe8gW(PRm$Ct)s@n_Z9?>ounPM>9|$FRk#T}+Z| z`>xq!AK%sZr0ovMjFXWqRs`bwaDzuwGq>DT`aIlsZUSx|>v?pTmpXPWUhJa1bo?#r zJIkh}92rn$!&_R&Z)5q2OwL$snE-W;bfI%)FQa*VhEb+|9&ks3o>f5Jt+S$Cy=M)X8cBwl9itQ=KM%ikP5KvhdudCoba9uIKiov}Q4YefX8_ z&XXxOtR2-#v+LV)GnqZA2av>tF#Xc_9IhxawhD@T9}U)FZ7%j-WdkITlCg=dK^jtv zC?Q{Kc7)Yowuj$y73bt{tL<3b`x;h|O)K2csd{M+f?^C%@|?SM5jXQL%?>YHW=??h zf#WO3r){jM!6cJx~N?zQ>8HyJP z$D#sJ8OSfK0Y}PXM|1CdRE8BEa51vbxlT}$c%ooyzq<#dECCM}oV@r>S*)~GxJNb9 z(N%J7Le=k~twZ^{2DzPXKLVXXCbsSlu>=ug<7NY?h{pkjDTZ9b*l`<{pzv;pYK&;>QpRUHN@pzO$_& z3h#yxoCJ#NoTfGb)hmH*wc{cl*d(#ulw{&JGfivRq@6&O5dlg1D@`oj_PMu_BxGLw zF}C+!AI?wj>R`?)yv1Z$C^}~L`NL%5uW(+^ch)CvWIbth-kU`fao>M{{>BC|f8)Tyq1&6`YJKn_oqz9V znq#KK(eiuAx6Ze9h&3Mk$j+v>IyXA=7LbZw9wjqB`8*l&XipKzo(r%lUmEZ@K;n*g zR72)kn+FBy3Pzmei|la0oMgPNX(4M6n#!;D+;!B@bSRhZ8JVedL2?9cl?v9K?9V7y%MNkq%q+a ze??R`ZHZ^7W7U1CX~_ozVDBQJkeZq@$N8}TSmU6epe@(Js2Z=PTMejQjN_1d8jI%d zOZwzr2H%XzSHFJ!(ap^3O;W0_$eRSZ)B*o}q|R}`mQ3@8ux{c&fxOodv--#4BeGpG z3j&@SPgObZ%#Q-jJn<2f*r2Q6t**iEmd|n)Z-hFoHM+%);WNle&YzZIiGWoQJ@Z%W z^34;}^evR(3Hi6>OjI)#-di$73Fx`~_QCUjlI`Xm#+b2qr;|eEqxobK^=FKzPfVwl zA%;+g!4dwio?pSr_;E#Sxt-JfA!0jEB)2m02aU<#1*sCHp&I-aV2 zrD1>i^$~_>`8c8#Gix(KPb-b@Q=1FOAwV@zCR)LQwS5KiS^ht|!q2z48swZQtLtOV zi@Z*}i;1-bQSY*H8&)HR{ql-uU(5VCcq+!$VloNEi}`ua4I~r`oDy-0Lty-y5@uiioXxmHF%Rdb*r=vW$?(YJuaHcdDrPf$ogbkl&*o`S&Z20g`Qj+4!2Iuvpuqx zc@j>}HYW^CfQ0IIc_!x@`|d`YNH?T=J>Ue+amOhjKtehEDqQLx&2P1TnAMqNIPo9RNaYSv&z;QTN!wYf>|sZhNr2>+p(XT33>Buo zP+txrsz>8ImCP6RI+S+v4W;xz1aM9_4lZ!}v@+k$t*sk&Z53vO~;jr?9jWZ@$qBswB9gWv4Miu$DQB#0f_8ZV)Q}H&r&id%D5GGX}X`xmT zhqYA=*mxjsy^4LA9B9KIKLYqe@tiMyZjCRJcPP6papaRJa4L5+g1mLfyF3w{vS3w9 z=zNkx*0r#orgR?7{C}#R_fftEHhV~OZsJ_A2x+j>2Xs=uO2fT=(*!WH{T8};?wjlC z#vlhuL9i}=JV0MM46%H(ZcQWcSmVu43eJG8;LON%Ia1nyb2=|hX>9fvvi=pI4}0O_ z1oVWh!=9ebN7Ba+mxjj-TDfUXZ9MdzkN_FJRM^A7{gaFB?%<~j%6sv|0vuoh#AkG( z!LIOGl)dI^-zu6&`eCC**gz-n1-kCC?) ztk3qO5SRqhHMLywsYsrES{fQ($bly=RzMH1f{~%e=oqP$46-8!Xk28m2jt@2Wl(|8 zmYESYDj0|%Od*k4pP#qI?qp;Iwl#ldEW`w=wX(3_SkhY%`C5-J?4LXk&V4`@gwdD= zW016OE*7c9_G-AumQIz<$k)VUGJa0FSqVU*LCz6G7Q(9E>rL&32+Mo zk8GYlOgSe+sMPENA}{9qQ8EWaYr-gJx2BZ5uFjj_)A8p;7)pKb|clp zQ;ps6XEmj%fj6e*f$Y?HC+_h^9+ojUI4ICJz;gPBntHn8QPNnAn@jG6F#LR{F{1F2Bgg5b?fAVi zJ53`+%zq5(H`?k}^XuVy*|AJ4%RPDz71$Es-It&0=a6JH!+JnxN$7Kx`dWxII#igavZLJ7v;1oufOiJrC zERE@sC;u5L*AJt!4i@JUnpjQ$I2)2XH0j^0`e&n*a9}0us}e82L6W6YR=fgIP!*h% zC{e=cgN=Uuqs`Gm#-5s5Un4$LB||;5DUm2sq;fB|tE+4DxF}QyWl13N<;L6f3Ot%T zuTVT>3orCPCa;b4h7K$GZ9z|dH7Dghym6-a3Lq4(gP2Fk&1j$m#M(0!+n+(=Q`Mzx z7B^M~QjMC}zPWf2vl`blVY8z-`;}Qg-&u~k1h&JY(2qoC=m|$6F+SH>mb^Y7`6E+u z4PZqZN9QS^clemVnPHa0j{sHhghByv4%0R>GxKJyH?KRu190I7xe8mIla(o|_Q@+5 zBgD{(^E7{`b~APWcmg1l*RAg?-#_L^`CsPfd*9>z#vVPNS>E6uAVEa` ztbHhWLRxs$2ndy}PCju@lk{E(JyWx@Gb!CL7p-2dZE2t*n=tO@=huSEF}EuNREMvN z{maYCo?c!uTN2xFgi6qBL5Q}Xp37s8y%TR1+^YrCc+~t77Hr&^b{r@dqc*Rbmu0uk zSJ+qUWE)Zv`n8X2$6fn0-!ANdVP;b*o@bpT{*ie< z^~C`CCspPJXq6DcW6aw4$|uZuC8dJ#@o~?90L1~KA{wpP(b0jUyULk;Qsz?LUDpA# zm;@*T1B3dfJ|P0^5zS=w*~3-`#1S3}pH7V>=6}7U@0T#&kcZPSDGSggobt-UjL&ON=?^q$wB-XiorEZ7H zA6$#^f5ry(|7QoW7t&DqlK%WaZZ3G2>JdW(Bh8<|2dRhwgjptxAwS^3qcM;^=|e%i z#*h&@h<>Q~g)a2)WoZP!hYCzLSVa%KK}sJ(9rhhEDLwXdF;Z2N#F94zKkTWKHDXJ` zqu65%=U=2te2oT=d+2@t=kWqzfRgSPr%wKnl{t{y%pBXf;Akqn+-`ia@IN|v5mbNC z<2D!LVUK5kLNXZ2PaOX5@I4{%58DCh-45T*4e|bwj>=V4N*O&?$OihK{{z9|sMe2a z^U(9N{8hds5ZX(=YV~Y5c$VWtzVjbU5TJ*eRfvDhaqRGIC$d6=5$ROHB=Cm3Of~io zS^&w(YWV+5w0VMsuG?B=uuCuOad?ybDCqH)p8>NK8ViA{AJ4f1RqazB?C_{$R-vI5 zSZTm!U~)No(YTCBl68*DY{B4Qh_f6D8LMYLdSayl4$rgP9&^m(lY}8Wkcxn~1@C{G z%szXne2qIa(hf8+WzEs!cu@%DgCgh|_Y^xBFC9oSXJp#RqT*Ly?3vZ>pv<&>{rZ=0 z-stSzyLV}CZ}0v14j0EKpFe+2oK|=4;O`Iro{F&ZU2}fDu=K(I*9V?HO}%yhzW%o0 zT|0MrmY0`jrlzXCefMtJ*|TRCzVGht{_^FE$)DTjEi2^z#6_^LVZO%r`oN6R2OmBd u&0&dAnXX9s8d=bYkDPBAet5itot5lKN231bmSPVon#Qos)}DIqaY zY4b$806bCA#Cah_2_aDt;LV(3BK9wB9RK~Kjh(58k*AaKb5ZXHCK8^;=DsFQ|Gwv? zzo-4b?{W0-aCEgtL2!L3U0~9Jj(Skhmwr0ZPJSYSnl@S}8$udX87>{QxR~^RF8|#B z-w#UO7Zt2!mg#0%Atxhx!4hxPZ^no$V>QCmaN=CKuYJROZ%4Mx}1T_mx z7DRsZEUZ3We(zsTF1UvV5s-v7Y~k4KwOV2#8pIK-i`IJkyN~8|vwa$NHbx8dvi-hx z;O#gU1$?e=*ev<(cYL~CGau|D1_9$jJO{3JZ?3;yG~Zk(4d#9SK3i1S&BmZLMuY0x5!|j&|7zUHt!tQp9?t|Vy|4e zXzU8Z>W|+2<&o-&TR! zRVklq`1rB+tj3;Gu03oHU3DhJyVoV5%3l-%{52MP6NyK@9{(&kL+s@f_|4U9&Vx|d*}wZ;%znb(kCLX{8@9g*>9&=gw2>>-YI3D<9AE8zKe4LW{QTvU zqGIqu#h~I=^^^<0aQb|}R*8G2@A$^ws+W17cZoPmIosRY_QmO&9C%?IIbPbV8Jxbk z2Mk>^UR{hkA5gm9!p)c8=*1mkGJMC)u2SKzCM^AYgD(E+SUNEB;MsHKFcjFkTmIDf z=XvKmC9v{ez3bO{i{_>5Np1wwf$a(*z3YNQmj7?v=FEW2qEg4ftl9b}Dco-L8=rQ7 z=ipP(Cl*Z;4AF+4Z*ZUVi4WE`?9~6zkr;;V0EPbYhd_mPmz&>=mxi@4!PvJ+IIx_h zJJJhpbbtD9mDJ1thiQlUscX6J@mh}Mt6v@cGHdA8pBjaViwMe@y~Q?#X^-YB6O6Nn zTISGgf`d7R&v#Ql$Fb?hzUdV0pH(`z*Ci4>>o*@XODf*CAUW+SF8q$Io;|O$YTP_{ zhJz9~qq>-)fDjN;nH#Uy>+>BrD_#%5t7$hWzX6#w*rHeL{c#?KPee?xmXdG1eD1)u zy*!!miQfWFeu3B$aot?NR$T{;^^C&V3W~8=@LM-qaE=AnqC}Aw_#GsLTz*g4?{dG( z?^kfXM*LsAm-op>RLK>_0-YHG|CH}cSi^lI7`%~)QK6pAHzphjHJ;L+845}!e;BWo zf}9ve@8;UxWF1TY2KM)mlk3b+($TztasDI}L*om~5|3x}E%Z#e=!e8Vp_t@@>W4#={xsg3RA@@S7kh z&jsZOaLw`fQ@_vS+}W>};^Yq=Hg68X#mhSE-q}GO^bg2x3Dk5k1xjD*n4w}st~Wkq z43sn;^v3NSte-K&?`ipqBE~57RSHBrwDzZ@2<98%f&Q!)7JuunW*?sOq^77J!gH`jqR3vWs4#Rug_1?$)I7$;I~ zqj+a#deije9S2KyeI=oR1L;`mGAcA#gCFs3SA%768ifP+*mt_xX4#eI{jjV z&5W5OT}=zJTf-y>aK6T4+IL|`_y~tZ zH|6fLF(bWgLUN`*3glo-h=kvy4Uup)#b(^lqldDrZ;W(hJ~m&&tEb(!Zs{Ea2$i+q z&C#FKtz~V2u2hWC4(ZO9Eti>obNk2PM7HIt14}2wT&XQLs+%~C^mDHdb%fj5suhpN zjNGr!)=p0NlRWR;5?HJZ9?U8gz{>?tIhbYyL!j)Bkj6j9~pp`{KBHBKn zBl)YH(Wg&zE`w?ss6>XWF9BuN#q@R<7arR{?yLwFF`ZnFMi@i}%v~bfTNfyu^;PY||tP685M|Io*SUtIsYkkcyxo02N@}YhJ9zUZPT4hFr15<7OM_eWug>>G?7KAnPr1>am^-hW&t0D|72KQ+ z!e=6wgD1UsuQMu%%1oUc1zI-cl|Wh+YK<9q{!Zk<$dANYgjSLOOQg*C!U ze*yGSoO9zqzpAl+X~hrj4)iHBdG=X0N|^_^$7_~PUVW#_sb8C~rwRhu*w!x(2Tw>Y z0Ztb(PweEwgWbvyU4nPZ#*8WiNyIPxFkV1|5AZ_$cDsu&`Rh6A+KnDA-YDdbYMTy`=;NV}( ze07!zO!A!C{xlpZsLbNAXe^`qG{>kYsud`JI7CYeG{M30+09Z$TWC z-GP_~yr2@tCui}B=iR%W%=cA#&KTKgcry4{MF33cFMR_4Y89C*{im#Lro4-3OUm4~ zjZ;7f4WM;{JC@qgyOxDC?03@3SwqycBhkIz{0xrSrm4%pB;H{s!!|5*d9&_7*j4O0wxc1gImN z7JJ5=rvfS|RK?^_EJ9x3Fo(Xn`jfVq1h`Kw>ijDYGdAv-xSjg{+JN~0MNT`EY z&i2F*mukc_WwuZdHe+t{pNa?&_9AlafF4&)Uhe3_7c;whM$e0v74-L4+zS?q(z@U2 zJKs;{wz}JT<5QL^$Mu8cU5Wj;b>MI4=pT_W%8o^29J7O}Z^Y?o5`2;^t@7u}ERWfU z3oIccyKMSQc=vw1D-e8)`UAB5d@t=vsq*!v)1~MOFUIBX0PmJ*82H2=sjNx-P+HKr z?X&s6{QDQ!sU3kYtW8)2OZvuszfNUe(SDf=q5ew2(mwg|>sviNJzQ|@%Zvn5gt5vM zL}ebfOy+ko>vtia>$+J9wDXtBY4Gc_D?)wOw+JGBxz37czB&ag5fiR%x;*%?^Oi(t z&;RSV`3pg*eu+_7q7N2QyMS`-u!OVtKgy4ODi&NX$>9i;TU8{CZR@N#r$UG%aVpdFH>qniV4`e1;mnJ0wni~dXa zqjYj0ly{H`Cx?akaR>edryeSQ_azhnS^;OIS5@1_;xW_bni=nCa<`km(;io!bX|84 z>rq5ow$Xy)8w>n$Re2)Vrp_g&VI3C@Y;O?)=SAu(WW)!Ig1^8PK_|NKl~#+6r|MmhTM;x3~S zeK!8j0QP@}F(r5i8%Y7cpOP=I6oBdV-h+t-KaZ31t*;GAR~vd8e4p|+wVpL>SNqUd zzb+3v?3bDaaNTMmFnM)pR9CKKYreTT5SSu*4L>dfTwd+M{p5BVD;j|6o*jSc!T37Z zKrhFQJHu7%Wa`D&yH&_AVVXa`(;S&I~k z4-6!Wr2sUYTwm-q&^e;ZUHqR|`abr%xjJdMxm;5!wQdf!9M>Vbe4q>r7oq=~zsG^6 z;hD>`zWFulJ7LMlL9TG5e^S$Y)nC$leg4m&F%9=<{+?Gwbu=n>bqx$lbz7wk1D5`)$vZ^_S>9N_p7A_MvvHvop!v0KHM8Sn z4ANzzGSPz7sey3dVHhT7`yB#J8?`xENo2sh`Tg(Iiw0n#`o3Jb9IrIz_N|ADkwhXF z<2>$$s#bi3MvUs)&dN1`?9z6UEgb(RK2RmUL5${A$MkaI2|mn8@~p=WPES3){|q|l z;dW1V{^a~XtfRzRAfk4$Q2h&ALAOe+u=pJ#mr71q?|fS(fp=2kA(7i0x|t|;TU?%oF`?WX*B_olPo znLEu`?gxy2{97*Ze&6Gjt|xVru8#g0Mqd<{hu=C$~ctv#vA=v1JGlr;*>cTjcuaCUVM(j3nLX%aoGn@sJ@3g zdxp`o1sCYbE%$ri<@U$Y{r8jxC+y!_{-(BkX(0R(+ZmQWwm&?OW|VtXd@>fio*VI+ z=fcb}b2Yo55IgGb2*b~!FAjbP&nleE7!6m@3qLl@7pPlFBBS@5_x>TMxCETzafRaR zi5~##IiKKZmgBk2tu$^nTV!R&)?2`XE;cWMP4I4|!V8BJnZ`$?pNTN3tW=hR@sKNWMREr6^0&Ig@jX1LdH zG-|*pQ3}`e88+c`Gw+OaH&pHOCFfrs);+QE@0bM!tjxyJQxS2~bw2oV;O_Ue-B73f zv$gC7TztaQbEa35Htvy}DeJX&Wmt%-t~Ls?U-#l6-VG{V^!3Xh_PG~izVb$_|6L!> zUp}=CKI_Qz?&Ve7W!~0;?E-9Xx6Nv_GzyN1!Nr}RRS2l0mvTq1$pZaounG`3u7f4J z7Zg`^8-QuG(NQGJ4Po2$BjwWomUm<28@X~tVER>fua#0guyQxkE>7mMYVWz?UJHH@ zNZg+Q60R$^Epa24Hv;sE-@rnNcHL;CM%2nM7cKbYFg?XT037)`qP^hZfdKuV1!(A| zL#D5Zur}+px@s}1k$=Q;{LmA5`^x3OnCsyG^-g2mRf@nvZd$7i!cCK3xRX|7=kD zM1mw}AnDw8rh#qS$GFIP`cQ3Meis4E|G%1r^HMm_Q*y{A&CDjbEm)WOcA^H;J}==z8F*R0K{ zlQgT8n$VqYPLkK{nb3g;0kCi-=UenK#T#}xlI>5F%-ZEVhjC8xM)Tb+SmJIjQ$m1* zbCdO{ba~2u%QO{ZoD-kEk>8A&$Y)ADejQxlz`7{$A}{$X_o9T-cs&XvaVv!Fb^%BN z-dG$?&b*_R_oB3}^LS&ls{~+r!QSZS75$PKN`(7P%dt{_WegykCv$-wCyNox_3y2N ze_V2_k3->Rl7!-I~1g+(8!(lB$Y5?P> ziiX!IEovDYQe)_X+b%@#7ORs`lcXcdKr|q`%UI1r;N-4-)ubgvJwWLOF~BWfnZXqZ zhPbm}7!o~@z9rp6!%EVl#!36t9Br(AFby=7*SZ)SJ-emEf4 zG~@aw>|=>IgL~~Fp|A_v4C^?c#WgZ+Qws+^%;d%2)@c}BBbQkL3y%zqgJ?m{t}ky{ zw=)yiO${S#cVc;>h9cmTQ42jDl}Z--2l;)V@I4i6^$)72q6U0I=ufMd?}Ku?@-={* z2@46kFmlKW18`$3mO*BuhK5a!8uQT*t{k&kw;W6&RGTyHTG2lvHUE0~0KQ4-R6=%F2dR zNc`h%&t>Pyn$+yUx|$a)a#F%CZY>%cNc$gu+PfHg1T&!0g*}xRrK8Y2^e9oIHfxXn z383g;)2|(;jW6$(D}R||g?d>CPoAgCW3n`kvI;q0)d!QR3*x{)*4|>|)_nE%5biM2 zyOPnf2}rtAUd8^kUJPCAP*xKPp?W}tJzoa5pVH^CtleOVlr*!KV_qbeH|ist8Bm~4 zEO&o)bMe*8zRI`}&$U4Exl)8`Oh0}LANvL6f@(u6Zc&@&EPn&_gH~WU80KJ*H{t}^ z=DByO3R5G1lCGp9B|zhqj$?aphBlJqzah7%X>?UUS-DXQLH5?+uIvUE7JZ%}590WNH!cJZX!$0YKJ z1^Uqi!{hp_Wa4nzT>;7FTt$-;j>UIj%#(|1dRAXt!f9Vv)nCfF|63R7G`C3fk0?o5 z(Vn#*^n-%q1FtH&+XH8^>;re6bsm?SPs>%pJHke>!sv+-bxUCe-L6SADNm@UdDY?1 z#V#?Df+)<{cX%5jAi5y-VbM6_s5&{%Z4CqI;ouKEXy+@_j;03Z?EKS;hY}P%{M0RU z?=u!@+f>*|)>ne#23BcRO^vC2Xqrl59?*#k0<0j@y&N!VV2%+9Yf`*j&Q4=?BXZns z*+nZ}TDNi8+L6fix`=gIwli8e)L%^*-3Fz-1kb4;xD?Hi#D5L3SF%O~T535UxnYOI z^wdN0@a4n$XV)0K_VX7DJoFl~b8 zEy?2YxFdM78{+I>bAH5X$YOdbztrevVb{fGyzEc+UENrkY}FRO>I37Lj)lr)$Fex$ z(Z{A|wt9vahEL=(%p%pGVRX?Xp!6eD(_3wVzq|AEs5_yoc=hZk(NIn}({XqEk4)k_ zC}rY;$4W+#O4K$2lvbN7;!AdHYK#ADQYQO1s<2U61L+uN+8VXy6DV}?sHHYy-|=M} zVyG7*I_x>zpX({z!ul4(hi0O^s8Cjd?JeZ+)N?FKaBPZhlrU4&C3B#cz^o~nfVw)j)mFJ(j~GJ5i}bigI0diO)|$bD0Ui9iWb4{;Jecl2 zA*9$d{ZzFs=>V!e$a=%hY>cs5MuY84>#F4QU%xKm{!$LtKFXJ2t^1T5d%^ztG2c_C zOjX2af^0@NLcjeDzYA=G4UtjX}UiK%HPf_BCD0O6$*X&=x!nhI%yiR zALkh;DS?64D$OiFttIq23)gCsXC=Yk)JT>MoTUO9tITS1g7Sl8`v1>)wX%?2l|HA4 z=0SF^tj3ZQfII}uhcqCo^zHzC^op+P$>r8qaWPfFzNf|y$(1jc!}Nh-&q&|#p# zuo}c`_NlPdBq59*jkceP)N6pyJRa;)XRg0@8@$nyK3he9*z^tY%yi%s+Urraz~Ws0 zv}w?K3_CTotji#ks?(@!m=G4rW?H4Z-dyQYlo=9Uj0F7c9PNyXe}>6I@+PXtqVjCb zkNi{&9^QXu>sp02^ID{W+)dhb zr_P`}vdrru!&2D1dI&BX0V-hit=7cDFyL8^CACvaCd&SuwEOB6dl}_3D^O z$f_s7-?{3%(wt0x0S|&eHjCfn$6|~VVvRAYIHe|8B)Cy$1O9$Lwg~Lm6XcASqp)19 z5B|zNhXGxWuc>BLRH6vt9vuQOZI$Gy^_ldX4nuz???1PH8XLemN)0O>rA|J0Fs-m? zw<|Rz;XZp;x8Y)d^serxB6ibD=PZ+_xUjHnbS}$Fo0LW4eQOzFM7Sui+n?JjA>Zqw zjqv=;17}cM+;eSbkEaSdyr5@ygQnzp2Cvoe!=E^7b$qOVAIHmXd2I>_4; zt3GN;!S8y7o>Pyh7>`T1(65f0O4|83y!nOD-<))xQ`j-0Y4aR5Mgg_i0|7Wlfio{t zK<`qN0e<=kqAM70Ay3+1h)=NuIa>N@QBqZKe$2d=Y9b@iFmgy?`DJHSokmos9 zIF(2hCXUjZ$m3yH;}fhjCo-fO*yUK#rB7xm6Ug`Mw$WRc(Itrq5wMMRVjoErvBK1a zDR6n(wzj@$WR0+%98aHE`d8JM}yR zAL3CJASs8!6xi3n0gM0#&3JNH+R{KNtamQr`;E*WoB?smcR17Nf7FoV>B98=NR;~S zx+Bcgd|e3+)WFEwh*g98i(@8}a0tYVC-Poau>4>nzJQYFLu*|*&BB)!mjJD_;9R5< zHZzQGAq+{oiMw4;GZ*mX1k>^(?HzM+mOs=(Wn_JHUq095)6VUJ*&s*BXwQ37%}W^G zB6C39YTfrnk5nJ&%*g;m5fYIvW3i=x1WbT55xk)Ej_3dBJOl7G1xJIbFQSQgp0WkR zBy^NNDZ<)P2@A+Nh1fOXj_5mB3)xaf++FwDX(6~HBZUUl`il}e99o=<68#s|6kij% zOKLr}(l(lt^XTX_Dw;#R(c$qbv|Z17z3vU@IwF;MvHPdRo+M1ASASZ%L9TRJ)<*ws z=!Lgc`o8GzPxk?P5=5vqC8@mp1Hda-a_`uo(zIU2+i4VT*#&ygg-vr1ubz@V&d=^rJYrr~$*f z=C_ua2K2bmzi;sG>}A;fx)3`u8;~_t`Ui~UbBXP^O9=Ct>2~QF?aRbK1&^)gd`}H9 z&W?r7VMc0;A9iD+Fa}g{d7kycX!sOrJd+0JM?;FykeLN%ERV%oSfUmE(OKf(LCnRpi~)!)ck67;J4!}F2{`L|t|OHYt@ zR&bz4?N6!72@QxIM3IXzTZ}|xkCF37dJ}bi^H*wgPkG`#zd@dA92bCtUl{{j7{eCM+FL8** zJ7~!n$wQAlx^%3he~}8V&%;u~iR_cYfTQfX7+lF66bfb~eDT5M84kt$SF7#xX^kjX z<#1`Fsa6)}6t12YoU(iwTLF{|kj^5KOJ0&JwxhIl_bpZnzT;c;uHH&eqgO}v8t2#; zK?GffAO9N4+PUhd$>H0XGMl#7wO}h8(1VpMmBtDkTc8>&BKpzTDL?vM<)%jw1bkjg z9*rk2HFJTLfhv0-S!Bp2(!%}j4@&zCo^Ysj7ToJ86twXp8K%}zm#|hia{QUN0Bz^2 zaJpOA#e1V?ZNG@$njt$94!T5o$^U>&Ee#Kd$JUznxIlCp4hOU;bOkkpqIqFpVZf3I zKIHdqkmT#)ZB#jbVj<0`LljM3Nx9t}m=gQhNw{5zdJpj4jf?NEfW z$qIO@`>gAevH|)1I1Se_vf$LCCHPOr@I7Ui0JFDbnWo)t^Gy>Ca*w*rDDHI;k{)59 zp_-|Bi;;ld z(BY`JXe%U_sx=IE88CUa!UCaUPz^)n)Q_u%kzdFpv6feMUWhE)hr~7NL0!agA?wkQ zE~pbU@W))MNu73K-_=A%`lBLf6={dm@UpX6Oi;bEAB_up#P((>wp*r>vbns)M!jM2 zXID$&o@3Sv!UFl_-{tV>%qDa@phr9e#>J)iWKS*RJ*L~0ng9Pts<7qP zb89dxM=|HW9kI`Bhm+Sti&8(KW^tpod+;~s8E(>koLQ1*uPIVZ>(G>pk!YOVSm_^j zVi-JaN}+MPv(2IJiuOH!m-9)}d9T-$g1hXa|HSL=spq6Gn8vGcMk*ZF>K&z5)AM08 zcx=tg?QmjgPO;h+Z-@HSp)VQ;Q2ix%sL`VI%@fZbJKAcx=O?U(fPrae3ThzT12F@p zUAxc`6C`GlxTDT~tk3}Ekr<6zhq_3-M|6o4P+PprLNO%i!pUhxT0E$4iH}gTfGLSN zNPwK7M9lj*>W~r21W)sGE|Xi2lyizPy!a+ue?HW)eC3r1=utvHuP&#|KqY43cqK2N zMeH2{0&)?7Uwc)b@gn^M z#N3<>eyS3{U9gG1e<0GEMSolqPe#9IqL<5}_?-t3&w1<|M=Oc}f;9fYYMDR%2iS|V z8J}GI-Of;bv`!7UTWZ)3BTMqcB9((cz_&cFqzW_24$l7)rR)dz^V@gsXR_mQa_E1` zbb2%?|2gS@)({PlCNZFagpBjB>YHH2p_0*v$D_Ylfy?<%X>s2DCs_I4c*Q5yH$+aT zB$V}S@qg{X$K+I~dAqwP@H-U~K-^w_1=zS6S)6Ggs?3(kQQfWcligjwa4E^7sd8Vf zSOfBHHNG@}oiMvIDnQe;6vaQ2z^Xa}}&%Do#+W*Hx~%S-}%E70*FLofJ^4R1IX(y1#*61h@C?I`Z-X4^gdgC-%wIBC(H0* z033n`){h&-lXx2iWL)(X@vx5ZQ~1^K79To}UTWa#9KQ9n)MLKM7e7@)VbcU=S<41^ zu-Fw*U) zKt|5GRJz_Lm-=aJRQLFaWz`))gK5qRuKEd*K3dRqnbwDzYe^yWFYUTQGO>-SK zNDRaj9Nhsc@0HwkC2AV*$K-V6(_*p!!{g2_-)7Xh^v&hr1^8mfBFF?;>(?Q>RlMvD zNQ$~8XFyt|7OGkkgz_-}}kk+SSK=#YYz%RRah07JXX&~z{3zWu|ziag` zhqwoVzTAvB*nmxaew=LYP38-2so9rv(|6-8{l?URU=JWQ%QKf=0`6ge6}?AeIrA9m zf@144)4SCe@d3|4rJF_?Pu@f8>jN6U7F?p26h2Dl>+HKFEzjX0H(5@3ku$*et^EZQ z_nKBhdgJZmm8==S48pE$Z7*11znyY6!=q{A`lvwZ?7(YQlRL9=`JVIC2{zAg<^)(F z0X4(w^uFjvK@0VOm)3waZH#~oc_AeA>d&N*&)ZKnDptcXzf;?4PJkn`_FX0`V3T*^ ztF;om22j}R0b{xU=KAVnzQOrZS|<>V(B3(oux5^@bkn<0T0*kV0PY3d7!fetX5|7t z^1w+sHqaxWpe6tEf~!>em+pNE27Fou`FU&%bM>9kxni%6G>~h3#piKP zC|Ooz{c2>KT{bsFW)Nhx1fUPR6Q))N$oMni^zQ4~-D#yBiH(%L*L8rrYB>(y%tS zqTUf;3@_7t5|yU~d^K0=PHap9&RlzfMq0jp`}fIA-~GDm`g@?=;B!DHS6KWQKS4+Q^x|HaSn;UrPNa z0^tTF;D6HOi1JF~z=N-$-lws#b5$d8FUcUWd#o|BmZ>bFdr%9thZxle&ELTG>b%#wTMG-~NL`?DW7yjEjswQ8gbr-08^ z$>!aQK(;6>Ab6r%T0TiQX8NW$zBP^e=w=OVHFHSoh=v2P#elBwe!uK#25ASx0yeGp7};N1HY$M>a~EFWzlIJ3 zg;?XJhM$c;uhh(3D7iL#M)(8MJ~0`|U8JivHRL1eNd_Ojg-~)pOl6@C)Mbksl+Zymw~Y1Qu^DsJZU!y<8BhXdEFp}frw%N8Yyxn=y=zizJOS7H zzk+N*8qF-uPMUAF;|1%>rMm-#g#qND*?4)xJ7yl{Kx6L2dh%bt9RBnN z58C19?~MRc(fB0K^S}lmDCKZtT!aDrlUtLB$-uG)3ZA!~y)8+&@ZW&RIoZPw*{ue= zmJde3{F3%63>{k(Aw7Qp`}`QC$#noqpk*}xg(2;c4i2E(Fn(6BC~Jq0P6e>;`37JXVV;@gtZDc+5avj4Tm0wMLv&MY>V)lp=c!-j`Zno5Jn|uQouc9c^vTW+-1fLD^)n&4j zpjfBnT)F#7WfPJ;BoD}aR;MeOn1KTakXe~}?Qhz48ERJS|7AGY{PHz`ixy9=Ylu4^ zDo`rVNtXGAi8gLf_2N#%wPg_f{5&Mwt-e~s%W)qtPx#n~S= z!{SEe*;DwAzgJ#Kx{Xng+z8Mv!&=xZW?a$N0983va}dzs&;fLt?L&rpUZ|8uoTV{R z8yNx)2bbm2@$4Zo^debE^Qi!6m{BM7QQN8MkJ1;1Ao_@94;w@iR2x|=62a<}y7@Bsqy!T!ZHYgF`UnX~pKBYJ z+3n9gNL|A3ZI^3zxvRSmvbSx);cy|neM-;takyU0NexG`;(?e7K1k(pKA|2h%WD=S z7oAlALzgl>A?!J86qfyvt?Ug%d%O-i?OQ;3O2~JE2_Zt#ajmf*86Wn_a>KuuEOl=Hj9Hnh@q3IqI03SvhdKIv78`+Wa)M28fCT+^0(n}9`PHL)m>C}M3I z@MU;H6VAVhBzBIkeG k?CI-M@nV7Ga<%^#`hmuIiZO)b<7CN7!&>jv_~+%E7}7kIqs$GV*==@Kc+ zPJ8Gv#kHCG#^=`VbJ%eBWr}1Hmopl2ARhspL3kFmr|jb|gV6WDJdpuQ@P@&+{6Ps` z;yz>oAD9dlUw$d6K8Q~5Th6l+EY)O8{krGTc=0T@TTAJA-=Jyu?tOzGX{iMfh_Aj4 z>7WXmThC-_9pxQ{8Rp@4GLbS}Wu`r7L^+e4e4aHA<@{6XfKg~OqKV%3wG1#;32MlF zre+&DA`sv6+AX7r72z2i2S+JwJEH^ z&5%FAWrX$$bSW^1X7PG%n?^pS$10{F1K3u89r6DC2eyq;$@oIy+*!*ep zgT~iDkK;FyK}1GMeBgQZ=H7iuP3;dWQd@^B@|9qR%>kUmRz_6skRq5y*Cs+gUY|Zw z1dy8a2}B>++W;jjS?-;>rVVpyRLD+0c>By`5-<26ht7yJ`-=aa$Xen>!$`qp zMnk8L{8L(PFmG6w6hzI`Z!;vJ-!!8Gc5eH!xZ}Ry*HX2jUvK&Hiaz2jOFz9_X?A0X zpNyi_O6RQ=zY!O2RhoM5RxYOad-2!8)1QywM~}MY47yT6fk<6SKI3B&2oD)9Nnq4% zkKx|(x7`|X@m#j~k&y_mLr9D{ps}z=C4lE^c?0fXjGdZl&AEsze@dBGYx!2`b9jT* z6%6v%*uocWI$UI}8b~MUj>>v_m62d`DAnXEPV`i`1)_g3_x$&$s=7nIuuX_dB*;8J3 zN=ol;o|Uc!nMBeIGG=9JOYiB{+`>H<-<3S4B%wj}!Cptj~0!kvF&L4QcFdF?xMT*|0H$I596%}^*{fp_Yu4*2s%4Wtm7NHad%H}Y< zOrgWCCuZh%B1NF-{GHDQFblVSNDI3Bp0(DQEOBf%{HRDX631%r2#T|qU;{CF1t%Hh z{ze3m6@t)_r^ zEnj=z)K=ZsW$%q0Oh#D0gMh z{wHM-b!k>tkT4C`ZR8$l={mfU{7i=qy?Fe%MzC84cN`+;qJ(btwKemLa$L*|@2 zfcWVNch97Q++Rkr$Pbb5cyX2NwIO7N zdH$xhv`*AgML>lzDR=6J*gM)&3{ho))HjizS~8N=D6e(+h(~;%ahZ3qZ=c4lix?h2 z*}G`JKGAy7h7nzsoto%mJ93ma&QEy-ky^5pv4^p#AT zH;_TE-ZyFFJWSHXOyQu%1=VK|W*6wU!e2t0)gcc-LqHYGM4(@f(Ij%3Tbo!wT*0#Y ze~OKtnCO|^(wJ1`h@@vNhxOY~zonRGiJk|u(t>?~WJhvTfyHYdn$nOx_4OxDP|bkO zbzoe6Mv!;QmX7}~ExtX1hS2OXGvu*6Lcx3v%$3VVc2W)&gHpDOaLKO(vaj4D*}!LD zrqPv}@l?&O$E5}h8B{c8rubE*6A@?=k2+RmKfVFDeOBE+bpd#rHvWiLtXYTJqGdII z*F3akQPg|_q++te#S<6B6vF)TaKKtxpQmfw+Dm9nr5g6wOSOO73LTQN?7KMq3B`xsM*F{`T1?aCN1Hc{#%WtX;9t}X z5U+o1`U~s|$;TXg`vxjFKKiF6IoFtXLaRN^csG$JB4GC2P}GMoWhmZ(;?zko1oBApO6UWlYSW9EACgnwBp{MZNFlLs=tz4P zUGAWdQ@c)yfiD+2>Bs%+CP@$d-<-${X$EX<0RBrAgkGVXm(AH1_23H??p>707Y#Tv znfhDn4Ljbq4bA(H(m4|7BSiLKj7g=TM6@XR16466QT9JfxKVqQz4|4kD}I~^@vMx< z5DrKcn? zDeTvlw)YHowBRJ6I|{G<8ul1fK?3)>#fl+tAYf^e!y zg}f#xIo^Cqu|)=O^%`|)X?@7WNANr?+ufkgv&iUi*r!B5Rb;{7eqz)T-CLsEcB~r~ z@}C{onr{~m(RbhMDqTIY5jWkVXKHC=cctWQKYkEOcs7%1uviJV+O5!PbRwd*OO;^1 zR##|)(EAIQLn2q*sU9nhEiMqcmTF@5#RK2$-s&U$?CIj7KTqC$FK7V=y=d9wu@ zcBNN}DZX6#fJRc8Wwn)SaL@U|R1i}X#Eg>HJ!2}jF&JBx;ONasIX5`~BKjvY(hi*H z16{{rhh6dIY^rar8D@#~k!3Fece(x1-xBXyh5S``@v=S1i^RDrVfWs|TE;+4n8jL5 z##!*8Q0~>)Z#&jRiG45i^+N^ne@qcR_mociDd8xyo`l5n*Zv~l@C@qCOETpe%SQmD^4l#>U zmdBXAi;CK19mI0ADTFVZ`L|Q$>}N!_h7S{Hgzo8Pbv*AFiDDT$9I)LFBc>T7+V!3$ z4cqhNGJuVujOaY>Q&)fq@^;7n;VPyLd;O}Q5aB%DxvC?bCQ5id<<-tdH&&_97D?~or8UXh-an%#uc&r?u`(DCo@*f+XRQ)r?j z20;G*aFtr)fd9wXTgFw@b$g)FE!{|Ws-(2Ebc29^pp>L^E|3n9R7$!9q)WO%$xVrL zN=SEk=l1bA?|JV%AMTg^;|puAS!0Yj{;{#&e_9i&Ddg*tuXibkCoT6v6b+7#FE@aq zmfa7{>5E6-huL}*JaA;eW=W5x8(?u6p&V`=l9y>9BS&xTW#-QLr% zlM=~+^M`Vnxu>cp&8YpsoUL>^s9h7bJ0slj=3~jyMLZO$0wSO4#uIn>AbV|D8e4g& ze9umq!*wDXHYADDH=>iEj=Ym=P=4lxpWbhib?Gtk@Tnz!APPu16 zSD`OOBrjUPD8;>Sujy)~gUy^Hh$$QT_U%=S!$T>`jS8~P5F;N#t~Wug473kb1pwD8 zEKhORR6!)fXKKeU3JTO8w_Hl97B~t3oBgSRsASI?+=Cm@x)nq!k6O=AO=o^C5H;P!)3OugbJ7q#Vn~! zd-Bhc(s-Y!&Ggq8JUfV>eT!&)fB*dlpryK2rG+!qx|)su1WQlZCE6g`*>c*BY-X$v z=&WI+oaglO`qBS11@cdh%VdRWTqw~$*t!JXiAZ|d5BCq)9?YgfWXIa&)TX~f_qqad z>^92?cMa3v05Kw~R5UExzeg#2 zLQOy^?w=`hpyS=UdZ0m%JgceF)ol5^jqwAX3-hPi$D~kQIi!KQ5p?hsz>j_`z<jvIkAg4E!)uB@O_RDK z;k!o|Izf)IIbQd4*q$a}TAbE)*g>#Yg*!5CNvwKtK2r-2WZkQW}A=6!|t1@Lt zbgFc108EBDHvDrx9x%Va$8(U}#qj2YZ%@v#T61?%)rNxL0G421!{jlUG3^N3Cs(4O zav=_-($Rj^SB+jVMLy$2!*mo&b)eDh1mugrdD35pPJ$$+! z-*L!0=N>#+)e=~$PA?fVHq;QZe!_oRZ)0smVfb)PEJ4zEg@)q;Mge;EsQTFm^g5KP z72sr-RBKHp)12(3vG!u!PFjhWxu2Xo(EFE-tu68pBrmQj9s}pY4(vKX%g_jE`M8WZ5 zFfSv(s}d^|SWoeM3sEpZY0HnI12HLS2;67{ML&JtL*Q}NPl^@4<6s5u4JdCLC}0wX zCuIbxhBa$C4nU{N3RA7NG5YJ}fEO?cw*@-2D`QRDNuFGZAW+?YT=QUx^OK|Et;Z!> zwN?p{?K7juW`X9j1!c!$TM#3V{h9jIZ5g`s=Iok3^PB>dqfn zo200;m<{nQ+-u2cr>e#IX)rABy}>|a-s&5c*Oq{;Mm$=e#{Y<@W&W3IQl>D%nvf1I{=b}q zzBtMGjv`=!^4+WP{a@I=S^zFxp1Un>Mvnrz;3DDR|H1R$BcoT?0;83~IGxW-@u2+x zsUt7B070pvo{4XbHxS9r0emB=Y>}UeA5aTKUjGCf0W^Lirkf(T)^~yFupN!YrP=%J z^vmli^B1K8zp7!4w>MW`;AG0LN~Mik#k)Xwd-f&ZYfY+91J;i$eIK-9M*^hinn8C$@6IA4P)^;sfGzySu) zbCww|%!1$Ny%Mw9S}JRJ8{ZB|RR0fM?q6B%tKDe24z<|se)vA^BSmRnkzCh|Z z2M5j69}BErST9>>kIF)sOz1?wvGi?%K+D(O$C9Gk8}XLit1oW6CKikY=XiMj+g(!XK=YG4zcPs z6Ltu?#0k4JiElBO&TPLyuead6A~`F=wtv)p4uVuI)2%yRAQNd8^D-rx($n+)q@wG zg~wH{=Hs#5^3J=?N}Lrz5~pCiZosqzDmaQ3zqEp|vo3)g`V-JFZ@^Lh4f}>Ql8h^7 z;5X&eOXVD82wYLLYId1E7%jtT1!n^spX)2kdmDiqcESz-o_`o0$b`!G1L8#+DIwtI zv=28?+7wY$B2ewmXaulzJ>2W%Wam4Kt7cqt7r5-W0@tq(faP$dxhAyM0t9y1-aw=5 zE8>{3_TF%)-C?mU;NBVBXKM~_Z3G_1Vlw}K(k!06qZSj6{#;|5b=KK=2DlWE3joi* zoSo)nZ~}xodK?2d*VOY&!AW{ols8rbYy~^4K%Tw3H6(Usv=D0gyvH>^)n2#`Sc)~m zQEM~Gj@9~=Xy++o?@~&jN+rcW!=YG(yH!DIyk(EKP-jB?+MD5iJ{d^vzy$2z&2P9I zY*XCm2%NZmYAE&C{BjP?tZ0>N^BtQ862Xlj(IaKJ{JjAX`R1p>uW*1VMqnVw*hl@$ zso&r}Kery5CX9((Dj(slN_S6nhjetGc27z48+$CF{PAmoGf^d!5|-9Jn4F%hie3ub zaM{dx`b7&Zqc5};9qAg{@f&N90Lb=nMrxA4o9<7aTehxHhsk|?))MvHfDktYYTZ}% z0fEat?g{h3)RWHOl|CI&u)gQ77W0O@R{?@{_$VCk6rRKrG;u({Rcw1&!5WA!-AtgH znlFIGF$bskSUXb)#2DCCbk71+_fNM4Uw0rYJo0Quzz=JsYok3psDryKMdDK0RmU!@ zTFiTHxPqNpK&px_0yon8jq527l;B$Kz?trJpDC}(oO~~j4_X;Yn8`OB%G*)xL&z=mPo#6D+ODq_e(%a^ zbr}<$FL!LhRgT>zT}sHpUFiUq9|aCKI^wc-qzv^^rRi+j9U|EB9YuD^14+kC!zD#W zWe7cEr+43Z^u0*bMh}ZaPj!@)dC9;I%?wNNSFsxQ-I)3dMNB=Q{|R@<5=4^5UaJE- z=qWB>C}rOjhVQph2Iw`T&Vo6g9YsZfQCN6%YbU`{eC;eSNFw}!hwlsY^RM5D9)|5v z0&pg!mF0~7^9BY>+M=xL4v>$#!>tE>i8P{HVY;)Sw|y7rV-{)NBab1pi?rsnK!1e{ zOK1Kr*Go0+5>TJ}mKabK;Yp{Q?^Bsc2LJPB@#xp28L8 zJ}}*Y3_pd?$3#fR2EmAR_1ndOfZMpb9m3neQ?W>Mk~;$-=e!k%Qs7%8zf%_0a{>e; zjfq3%lwOu)Ytde|lW1?k5WUk9MFd`K zsyr{ATT72VqFF+T#TgdgvI}A1HnXbc22B?SSwH!DnQ4A$ZRz87&_xF5G9tvYzr^*# zJLx0fbs6``e#@aE6Dehgwg*lOEkhO{Zk3T{O&WXK{c-S-u+*rHxuUaL8Vvv006GnB z2{=xe754)099jUcf5cfXNf4C##R;x_`-NP*p)?+*$cd0Rp1F?h=aA3+Ir|$CYjC;fejc*Dzl#} zlay~u=eq7UPDt_$#L`ESqN~*CzmJ9`AbC$a7{92QC(roh^`dpOWK@_iOqthp7LCUR z`3H!-KfH5}e4HHS*+d;Ibkl!2lXL{1uC)9} zglVJed$cS)4+Ux>(FwdRg_n3I$K=2#0QV-p1=wjF2s?BCj-ucn@Lq>==HhYN#gPD; zFkZc#2{A}2-o5<^*+fXQ-@j<9QAMG->&8798eZwJ_~~{Ugyi`1c0r9>IJsyxeIiIp zbPaDPJLG;KskQd8GGgQuU3&7WAY+M`4SG`$0Rs`e*K+{gU?H)*W1zNo>Wn0;2ysEw zHxlYr!gI3xmh@mHd|+QPYEv=Zzk>tGbDccCtfL5T-h1zt*cbfSm-Ol`h#vk1@s^#L z2zv48U8M-z@wHvSgpC|&lLi7?sk%ZnRCylim75xR@v7a71fqHqqN-dH7GXk9zVD;9 z0EuyYP`4)v;F!7=$0PPALn~`S-O`E95GaR=JBsYKf(p!ij_87n+#c+eIU2nBE)}E| z%~ZhgO~DRtp(}jE-R~VmgE+<~`LvgH9s)n5Bx?u5_b2C`hu&){3@J1i#53xb4M*?o zk<;LPXZ%%%oL+SX_1S^SV7)j!SJryG^1~-}3%KZ&LE$S--^8Q_NFdFPUGxGVbA2k> z-WeZ^eTXx4c}*rHs&ep<+2sD2tZ0Er(x~3Pq@3uQ?~9N-Y8hEv%0f6x^h?!0p6RiW z#N3JW7&ZEF!krxi^CFx)`D-Ma>G}_&sM>YLh@Uv17&(G5jez^Dhs_(-FNP}t5q0#Q zd=;Rsn%{$L?5P8EA2qQZoJwU@;RN7me76dAgt}CD%k-2A#o18$>LLoI=0^(8vV!#( zO7M20;hXC=r)B3@)m~PVW{^{x^xzOwMMqFHR)I(H@*3g7Y=}?EYHwGuXWAiUDkI%| z2P{e@db%*o%lTdtbwxFGCY2$W*S*kQS~Chr6um}3n(t*5jf`8D5^sGa0&WK#NNVZD zVI@Iou+TUGO?G`E$&t4aZV4H4^Y}wg z9;^4`4SO=bH} z4*e!Cuk|0*Gfy!?59V_?$CQOPbMJLC3Uc`}wK$qZVvTNa1}POf4qV}@S!trTX)z;~ zDuaW|QP;A?{r4_(0>ANz8@cM>TM5HY^85Qn0)Ee>nYwVBs_{Jf>>~8#?VlWGnxU(r z=Z2|;iJ)tEgwk;?Z^|k_TpeT~Q-E}bZnDbF*!BK8t_HKfi1P8>2Y7qDho;M=VM%af zAg_1bpjNNW;mIXdeH0*?usS8f*Zn2Fvg$jr8B>EGFc0Xz8_UR@7Wat&S6-ln-VOng z^$l+-iiV{?)s~GjtEgWQ65=K%N6F%_yvMyquXE3GKLW2ss^`%9&dysst}n^%iOvaL zFEwiMvfkH%t9rLDwV^((8O(iAf%P}oDZ9Dk$%cQ#ZzAe!!=e3Xv5Z`ukqy$X*ztAlOt z;p=rdQtOmmq+G;ENjYSoQ0XsZZ;bkT3xvWXAH#_m3etsSAgd19RgcPv^QGZ=3z*X> ze-w@LaE)^(IAF6`73hkLdA5B(%Sc42rX||4oHc5DSLUbFXXECkP{wQ%k`A`D$5gVW z<|~XxZqj(>T6sV1x9B?9reyuwUlFwv;iKUbAKX>blG+^vY#fLs3W9qfSYzrH@}>vd zx=ALg(M^*NsMt07Xu+WUCVubgDyrg?4|T8)u_uk=+G z$Rk;ldik(`vsHZaS3!ie_>-@1!Q&(vfVo^(frRA!XBNpXXW{OzY-=HpndeX%biVUN zq0OM7BgO$>;UnVmVV_&(tre-Y!oCy0uSBAgWMpm(Z>`33Y6zM$1 zSAZLG39AY#0_Hq~=!sFVddgJraOuJ}CIp>gkcH~=BPftfAe144E%j~ehRgn9yZCUW z4D9+Ue3uo@xkvkZ^_N7h1jeSo0i`h=-jw_$^CK6hzzm3i{>i5vz@M&=;h(?3=YP`c zUpd0xHbE$wm1eYQ*8g-3@B*?4Awa0lu8SF9`LE`NiZc8TnL?Hr@$W&WSHBNl2y2p- zJsO=a1rRy}8c|%Je+Nza*8@%Ow}#!n-HKR{^9ABscDWEy;8%G6x7qZd`viYUNkT$X zq?+2=+F2V~(0vF*0v5hhzl*Nvq?M#Ic3Fp=;MKHM3IlCzCdDSvra01{9`|Di)E93a7_8@a|YMRD5?Pg ziEai^m*(flCs1dzPcI`gQ~#W8d!84dj=SU%MX5(2UL1z5&2T?pn@tk(B$O1oS!`_D zE4~Vs^hEzwV=@;EYkK}fXfU;Y_ur{nV^KF*I&NJMI{PZPR!~S$ON}4{i^C{5nGQdd zurIlqxtV%CxY$$DG+p(E6oOX3m5X0+Qf?h2UfKlLHW@)ma$eK23 z&Iz0OC|mQlVS<2P*y?yW=$y@oxJEx>`EY~Tu+Rmx(V-~RZj97IM;_TupBw+ok$>j~%v@=LH8#(C zX`orS8CvwLe!(qx=x(J&drK5hf?aZ`6+G`f*x;mdatfNWcX~!&ADbolhQ1pMa7S!b>J`?E_EMm|tGdkl63!!YvQ%BEzB=2e6hkPYJ6hG`xN?vif2CQ?0`r(*x) zmgty5{N!1I4rue0jva!g&k0na-dshmZnH#`^@JI5P?@$7PhD!Mn);Ed-SR;d<#vl} ztJkn-GI~Nl8#E_0wf8&pCqugG?&S+zE{p;;4Q7mj_@UIp7x$QfliK3fUPYcXi^LT^ zaX;(!`E2$`$vX7wejb)HM*>wX^nzRp%`WA-%Vbp>4a7&>*Az?FVyX~RTCLR{w?++9 z8mgd$&+=oTBY$j^{6)k~Wc)t=wqg6UtH~R^4r^4-SB*hIu$2AHRT9RLJ4*?FOhaD> zaxL)*jyJ}lGlHgZO13%cggT~zunaN*I-jJ_ORB)N_?2;~)QL;_k#FFPqSmDc!AxHW zXJPzF2MkYyxTxVtK}9+fp~HIKc8e*^W=U}G{rFAF+qMn+D9VlaHkcmdkHd4Q#!s}t zy`(Lsfeg6Y4UQ=!(tS?KqQ+!5?sD5Ysw%bp{xQiex4*k|LyKmBZ&hV3iXoBpQUjI9ux6_Yn6%q=AcruT#6N zLjrZ$g?_v>=>s$9AdVpwzPcv3qZAqecl|}cx8g=*B2``RyRs9s8D|xA`8o1!2BZrM zR@W>`7Gir!I5HwilP;{Z7hp^M1N`gTuDerjVPcRS&=)TaH4 zey~DnhQ-Vmcvfv)NPpVrK3gA_o=NraFsGf83HF@a9EM{nWhsSAu3%hGR%Kkh9AE-| zh1fr&Rz6@q-_qoIoQbePx^g)TLAS8C_e6BFF1bcWwfk+s*2P&Tdw77}Qm={!z=y&* zM;j4!!4=i<27z#9>W1aXK}E?-1VY?-^TBg&EOPMPTj(oZm`BWa$fnLdv4BAcS7-O|xcV0>y-$%u>fs?!RhrAu zZfJz#I#GJ@+!JIdgt#Do#n*plgnF&nyx+6ykb3cjf$%|UPM+sQJGyRa z60o+NgH!SM&A@@#ZjTD@#mZTD%^+{Io=+we_``M@Pq6KzsJGNb1;6hteEs3dszz)o zq5E~h{A+Ld4y*<&w6Z7_;7b7vMt}UE)Zg5lgInp;ZuC9qX<^Z;d$Ss4F zfRi~{vBu|D#9;KSF#(z4zF(}P!9aSh;u?I{ZUW2AUvh6L)(j~ zoP3M;^Zi%_15PPAmZPo)z*rn6e0t}t$rifa2X3YS)F>0cL#bpb(rf_3rHFd^-%GFb zUrWDEmv(w{=rmm*CwWfT1qYE1bk?A$KODBjaB^F}^ z#9R;cZ|0`4Sl`f&Eg5@l zKtqDq#@6nryR++Q8wZcqQa`69i=6rFou!{mXAYEp9xZ*EUcQ6iird##6f_)2)vEB* zsNq%oG2~CZOgjG#2`K#$9pZ4`H?dla(jpaP->_S((A7GV3lVQWXlSk#rR8^Q zw6Z2JCH0pbewPrSMJ_ZkY0h!R;C*MLvqyTWJFD6?wY!Vwp<^-E=dU+pacD0VwL8Ah zAr%k^>+Q}kie-kL%c82P96pI7%_GE35^_vQOM{|1+u z+S(*PHYlK~x~|)J(h{D5|5Ee_TsxPQ+8B72nu~Uf*ShbQD-@zUDa7B;qGX)F2!FLv z`$X`;9nW(g5k92>vy7fA&uImv(nCf)B;QfuKD&TFan0J3O6#8|hW_V?*tCAJ0b21s zm8-H(pk)L?G}RiNaNW7HhmP$1@vQE}mhdO0JKT|IYC5h-YhL4KZI(yc(nMaAz*T)u6S&zBC{&8`|9@jz8u%6X+ z@r45hmNRd>&*`dcO(zob-L%?Hh=GD9>uqoFIHi7rEs9a#^?m2|9Q8KM6;~;WK8gaV zCdRth4kS&af+F{bJ0J9sFTDG@vt}9t4tt~{dJT7B31C&Qa%0shH}*l7c8Md47&>e}Wwe6fEv3MJHDvmq7C z9OllxtMCFFf(dGJ2GjnZ-Lq@B2>MrSEl=IaQ}50w77JXX#{d*l0Y zamfaYlH=&^8Hc-R8})ssMZQOm$T2W5k^~*nC+**4Ar*A96OY;F)AQa4R6g9ztj%9@ z4=i{mcpWI*Iro)Nb!e!(rYbnO;o5U*CeRFeajze~eeVCS?Sl)p4^ly8PtmC8+d~z%txcZ-R9^@zSpEkM!%E!Xk`?L{r7 zpaUu01D$Xmo!~{w;ej#iK(7l^Nn8h)z2%6ZmS}Y$NWZhgD8B&HEt^gd9O+T_UiAPN zrQYYI%e7a1{ojb1nQsv}UU8he?qWMYCiPzRoumC2x|5SX8DXP8ercIEsKZZ{>i_Fh z{r^5x-=JK6RojidgmarAF+VcVRfb7 z9ar+H(f9Km8PqR}r3II?%pEz>!&<&#jv@uQ_zG(X6XV~^#wX*1v+r+{??$&n&AyTn z($^mscWsegJ(@E~IyxR5=mMcnCtIhLKLjx?&VDoNnRkpI?@2mKZ+k!f1EkA#STEXX zbSX_P(fS(i9i6A@cP_o3`-v+?qy&Dp6MHX?aJ!GQANr+^G>r&zTD`HgB%}D9+UwBX zgaFvxFX|%q`Y3UKoono_-5&TOK(?Z}Znd>$Ss0>rb{zgNs z+a*Qc`U!@c!}R2Aklw$@0;0~+vvtnqq;if@lFqwJ3{b9edBE!s=w7g>J6Hs=*R{yiS$K9-qK%7zoJb&! z`=4kFl8uK1wWtSPO-)Vyhhpg1hlGTCX6n4jqj6?Av@Vo^bL6SRu=~zgXu?9C2TF-t`6{N%o66m>$~=DSy~?8r9DC zCLH3IYj5Y=-|i0S=Od>pK7W~)r@l^lUzZ(88w)cgBc8*C)l!f291X1<_Ja~rj}**8 zhm>){?a;DFX=`XZKO!9DOl?Es4_6Nu|C9&r(jYLpl+D&W z@sh+nhag`g$agPoc5MzN9Wpr#5|*4hUG}ze0={EDak%pf7b=$gmyAh{9$H^n5llx0#mjq zCTkjkQ9`20-}=YUR!F-x`TB~%l$mG~5sELUq-*qbg1p9V@l3mdoB zW+wCJqMjm152zTxb3R314xNK2_NrVT>^=qV&*v*yuNJjI@=htxNG}Y4Pcc)|<9}BX z`cpF~QwaGw_hVewvLu&|{usP#*qV07+i-<_K+{m~UBVAp1#J#F*|x2Zvzq8#dZrGq z0-pO`j|dJ#2K3&h-&GgVZ&y}5+ne^50jqbVX3}Q;%#KUov%wGj>F{G2dA0Puu_c`T zu+w49YYcTRR{yxo0+P%o<@%=3(vQ$RcwYEAj8?Y0tNclaU7(ci0{k)`s1JO-Ozdp` zJ1Z2+QIe4r@{)p#F=WJr`(pXeS#>D?&sqIb%n|j*BuDjZ{@Njk^0eng_u$(e$M_`f zc}J{c_V{*|C{Y(=g#Pu|SS>_(Z-_(ayR&eV)0`N}@aLv%)bP3lT3z;D^|hqpt?ti! zt|U9#L0P^&Pn}9eBvFt){IXp=Hc|0=b={1ehUrGUpl;H(S>cNo<8r~C8WNm`!aS6M zQ0(TwsjKre{LQQ=YW8ck-$qXC?5~-|XGO&pryk)^&l{`P*S8JLM_1Ut+^&Z}EUjJ< zA6LW$6$OWVf=I(V(ac`3H=8(-3K|cqMWc)US+UN4S8NOkR5?l5j+Xm{Yu}by&odU4_hvKr4$cZP7TAT{nGFLqy!8qHE$Q3*N=y|m>@VUNXzn7X^mD=R}1U60Ik?NkypuP_wW__P~bphV5^OX266w-y!_ z*vcnaE|40o5PO=bxp|KF-y4)Ss+o>X&jJH;7^u>ymVRwuk-EFLXWBe_c8^0cPaCGjco zo^MlJ)4Ijb9@NvdYOFpudmey^{q{t9uWT2*J#2!ccJl1WCHM&zOh4805O8Nv`dYmI zqcY=ZI}>~U@gjrs;%W(=*j}`;BosAv#G=aZ%L0@2SBsdOa9(cz*4A#1A3^!n+6G7c zr>$akqWgp6*Qn}=N>>HHNo^9=)v$Hkc@)pwL%8y;QonX@)bvzQS;O_;GAe1fDua4dCWqi&%lfBcm-b!W>vjoFe0AJ{4L1F`(IgR(mu5; z0H(B2w&>FFK;ZXCA9~k2in5v-^vy7`{0+7Ajzq|rbjDUSlbhJJvZ_wrST#DPjPeH_ zM`DDeQ)aQq&PS?gwJco&qwM#)!^HWT#3XN$K1oISYyDmv+CMl8{Dk&l*Fk0T_6(o$ z8JKucHeoAsGfLch9?I0qerNx=uYSSx)ObQ%yQ|i{?pstpukP^pn|#~Xxw}Z_P!m3E z4#_;!g~YjNb`lwW?5^PEiD0)yoEl+GVtf1Vzc+g{8#rch$__g&kSSmeapUTiUk9l^5Y4<7xq6EnC76 z?03P^`LH)lq5{L=Rn%s}>5UJ~J}~cmUx<3XwYJ?kHt)RqBD)x+wxHl0B>1MIvHbXY zCrX5sja}-oz2Ay(&`>MG=55!A4l$7cNzO8#_R(WnjvLjmM?#O8bNa-s_uYwtgyYTD>$U3gcyJ|yBZae{npy*am=91A& ziD)JZrg(yl9e(n1^A_9z<(60`OWRXH-=jqqEX4<|i-5scvY4t2ALV18AKvW~N2E@N zBeCAxETv=V(9Lp^1snMTVXe?a|slL*7Shr$kdgZFnNE^p8%fpDMA#a-PK5_1#4+T(f@Jj-nQ zbEL&DN{nJ>FKEaw+EM2diiWO6V5&7cV*xQ8)3e}QZQ?iwHjPXIZvGc`FNZGQy*=zI z!Fb--ICm&S@aInNQWo38BR^!ZOrxaA_v7r{&i1h65FW%5bpEKlwErsDrc7OzgSfoq z{XlF56sFHS{_{ra<}C8Ci-8baQ?mSci`+noK_=$tb!{dxezRB6k+?5tZT8BjDW0ZuDNI;4 zLf{IJv&nKmQH*2#yZhzDo88cwyhqF4o;ebb(wVz#W*vk1*OXLp^#|;Kn?W}r+gL(4 zd-FI*a@fSjJFeCE70M1q&6CqAT5Z*Nw;1RuO)lhuWz5;N`3;Pyn-Qp?q1nz>r26`N zQ+PvW-?S06k0=my;xO=R?x~#daB!iR=RL%kK-5iRmtfKRxo@k2K-Z3~&D@UwA-Z9# z^1pY1K$p+wQ=XkwE+ww@NBT2v?@SzAvbG-St*e|;{T?!YRXw|g=x&L0>1T6u%J^o9 zEeE!oUUKLkj+gfE^DbHPSz~>af+=N^>hn4VkLlYrjmO`8{vc+ace=YCFdB%M+j8^z zx4|(e&uvDNRlYpzI1gUMkhnO2aPjb?1i|BuY^luXyDZO(lu!eGY4_$GXDXBoq=TI>PEuF%b>+k6ws7xdssuie!UP@M@Tv9rHsp~+wDfZS{ zC+72~Pq$)|ZI;`LM!eZU5O^D!-E%oeP3>*P}Wsbi49WaoQjsw?k{9V_I} z;D}$EE?4=P)>bd{Kr({p>S@@=WfrZMyT2-1Ru?_hH=v~zLZ@3=imI`;m}~?fUqP3` z8teu`pUGb*%9U|0qep|7{kw43y|01A-Ry~rY5-a=~TN59KG1O}a@AHTaV*mV}S zCc}5}mDTTa=y~v2WWQCK`01(m`%_i7)2Zb0n%J@q_yr*8jHK6|=@l-lx)klm%?(3< zTDdzPiH%my=GFQyi{3lq)Jyj0SnB?Knjfi3Quv{an@jFArPX8VGe6!u{QYtFMhWZO z{1-%Yu{<&pnHh>G6*F;KjGJ%BbEFQgOISVXr?+l-xj~-u<%W01kMi3#`(I$CiMXb_ z@~$m?cXV^b|B+XCitGXM-INCoLOya@?Np_`<>E}Rl7iY3y9%J^$t946369W+BOsJO z1I>60_fJ-{kWmZcG&G72A1;ki_%ybD`a)?Q8liIbxwPn|SJ82(i#B;-iiv;3>!lQ% zmH-57$FAl73lY@Uri%o}v21I0(vlLX{0v8C+9IPz!S!F%MEZ(02=Hl|pfek7SMbnBmjXfV<4wVEi< z$5`f9X3*y$J|S?jD&e`5^)^2x+wA8j5EnbMoPsw^RI)+x6)2m1XzIn`%eq4v+Wm&Qr36#4HZRm&8TXB{3 z^yJbg8Wi@2Kk2i3jFs3LeMddx4%9P}ORwKGX*(!z(-`tVvfo1DfULyMj*L<#WAj!g zF|p6`+qfv}QPF)JaixpTMfTj!MqHldrcw~YC=uu`i-7-Yfq^G9E;1jEZzn3;GX35= z6G?tXa+QrkUCR*7-O}*9{zv=VcT`NYS1Tj99|j)1ZXJZ*c|t)+d!@3Hpr60z=URMV ztVTf|C77{|#ETT$NYD0pn@tfl`(cO;QlNItV_%=goD;D~*K2CE(SK@8 z;TeTxQnTb+=;qVP+vp^Lhe1ymC?XQ5U&7+FpKBtKM?OclRvht`FLXV1>M9p+p?$xV zgwV+Gg4MozuGoy)Bgx;QbzEn6)`y@j)1MEyNBGY>{#G$z%!3GO_+~k(G~ZE{0x<9D5*m8t&1Yl zWEj8q;p@A)wkj+A{4Q&It9(}nczlbRmjL2W1{Bc;__}tzq3U| z`llo;x3UFfv#>an5M=Z7pb9f?(%IVTdNQ^rf{wfg!bl`P9y()T^+>t8xxUo-wOLS= z%CU0~y0;IDb5J)i!4*M6`{uDTs{7?Zkjrl~9elLxxDfDWN0{oln%TxGTHz-CUkX?* z@7_bk-8=o7hu%VNgY$B+TFf|pk%Hm7hn4r5OJ@C%zVO|T4KNEg%(t&zT8G?@&XY~U zC`YsG(T|->FPBKxOTYSAdAGcVP*)MeY()zxAUo5{U4fi4LPxJ(7If5CKaAb1qy(Hi z@aFxVxDz1U^Q^3T{dK%eJ31@H>r1^8SITAnu_?RE#ODIi#?S`3ve5IJ;QR->XA55e zuBYaY-^HV6Phz^h;KuLAOhZNe=AFqFPnK5ol&e;eq_8P-k>u^OB5Ovk))*plA2o;f zyO0{c{tH;uAC!wDUnt~TA-}5DF46PZBg1K_^i=ZT59?N;2NPrFSwjL7ZV@dpz4yI( z*z>UzIpf5Br$#CDqm(rInn}NGj1-(f)k%qdoXLO?orTb)o|j=nESlwS;|;s9E9Kfh zA6Mv^W@0WO`&3-kIc!LH@M}*mlXION@}1F7Ub)%0s-QQBgV(HX72^IdZu})OKCj%L z4VcaTNhu=GLSKqjY~GV9%Z>qq*(y#K&J(w_yq8f-Ue|3|a`~TP{0i~3RHPBu5p`Ek zan0I_KL$FMnwd?%-Wk8{G1ESF$m%J$iXXpob8vV>?8Wv<&(QGeblrFNhsn5*$4JUv z?kgAfV;bhU_NTCZ02vkjV0mWFFzsRGe4r#~)UEa-PLlFXbjqg=REDd|EHyzj=ChTR z=V;){Q)-jw>Joi;LhuLk!_bA9eK^B%R2_)Byf>+ZO5Hkg^>Xa1;p5GN7s%9Q z*H+b|ttR#spp}oAFrjG5Ze3^-hp7!=7PbtQ3rWbKdRrxMvd}NF2^nEozjYwN05yXhN6C;NH}LnO4nLz!^ZsLWp*l&)L_u1(6=#YsYHBqvBv58UVpJGChX_( zn_yg7%ycw_%vPV9d$0C>t_JyaqB00_e8K<5$;FL7OKP1@z%bE0fih%ouT1# zRB7|(E%Lh8xkrw?5hs#nw}GE3wD=9}0*YT%swUJ)2Yb94R?0Nh2S0E>clKps1E3M0??e{{v6GCxR>z+o`==U*dRc zYv__u%t<&iVNm8Dq*kox4^o?r`xb`O%ez0NMvx>j_sq8ZP{N!n)re9q?y>vWm=nt{ z0qE;>AuESGz&r{~^J;2vW}8Kqwl)K(ea$FBIk-!EXg)Z{I5J~dkoK9VlK>tz$q^04C|&fgN5|$2&HthAPHN~t95^- zNHkONH%Wx`$n-NrA~FD3%;QsMa$0?7+=qigayV&zl{=h%vmS|a$#y0xFQT5X*Vc9d8(-4`*4cy92^`A4kb`O$`vBOj!x*HociU(4RC9+s@Qc{-(;r~oN*y+~!x z()pEV%-TGwU=~1DZWg7QCvm>S2ftErGhDpMi#CB*fuzpLja8C&QczbE~*Fq%RIm2QpS(dSoB7rF#KivN!F?kOrR z>z>c4tMD{oA2Ry(_?h9vkO7pGmD9|GdVKoWwi+#8Y~-4jmPZ85aH_;yua*&ClCtMb zni0{eMudo7On4c-`J}+4<7=m-vD@!zq|?*iJI2NckZTPLoFuHxWmAhVZ!J9^ah%H> zBFZWfn-|7KvjsFW5{{&JUR`BbE{Oj^REOE;FYcF#y=^RXJ3URh@7xHn3Y3y9?Azs` zs%o*Zy8KU{lk&wP<-1c+!>y@m?f&8*uvC|sr}hH-!Qqz zZ9j|GUcS6x({J6gKM=_xq_Yi>oM_QV$JU0J4k>SlY-Ge=amr0(W~HPV2Pp>Zk#;bL z?F;zl#&yh&)ZKd>EVbcfQVoL>2qqZ$RC~o+QL5XktM7MS@K>42y&)o)KBBpY_&~f* zw@EP0+W6<#t-~4$XxI=?#*K~DJjMZyj%{mpb$oU&Harno%1tO?Yj4}W7m?0E5E3Cl zu7JF!c?CW-G?2F#x#ClvF8Cr4Tpf3kUe#>}t*_AhZmU$8N^%Gz{<5^Nvbe{DzoHCq z9*NUNL{*0cg^qMyCTyXP2h*bc{#BngxEEKS@8ad?wF;r0AIPClwCFn_4A85}Wiv(Y zEO(GS-%RdE&Kk!hmLntBz{0&!gvMVuhYEE~?#!9^zklj0rmeX4?0(|ducJeC-LV4~ zlTln5N>Z2Y2_&b$6@SL?EMuZ^Fe@GJpYPu-_DCU+Q{QE$|dB-5`vO< z6@QHD+xz2(!NBJ2y@mr#lTUx)!LPv~--MWaN1muTX}+YkubsXg?7DmJ#caJ7jwL~K zR`#|1y?}hbT>69w9i1K1gs3~P&Z%E9dh{h0Z<4O07TJbXneJ)D5zxixgpCHcUVe=G zvNO)dy(Yo%Nqhf!ZO14kB)xo%N4VDRV!o#r4+ox`5PEqM8pW5{xM7oD2k&0BB#&jC zDS0<3__M`MqJJK##rL4V-|0{=On9wE7Oaj)+H3+K4P7K{wi6S8XArdSky^^XiV8cD zHcDX0zx!cL26@2*bmgvRl@W#BCN;*D78r(M`Th1uGi{Bun}*I}7s!ayG$+(<9!l@5 z-LwCF4f;E0$Y`@=7ca2Ag1)%c4^Ilyx^0;|?7cj8>B!1RC4W1)Xyt8)RWJ0tJi%{F z>FA^!sTn(ntQmcyxdBZZ=bfNgdPH6w3~Q$W7k8=6x=dYd*wMY@b`^n63vZ#PD*(2- z`ht;>(R9Aaa~bl54G@E!#FHT&uGLTS^TqSPM`}-cZNIm=qJ^y~2v`qc*EfD)SaZXl zH}F9W7u>sfjf^jxujeOM@Lv9&K7gxDwL#dPPZDh>7LI`v8LvcRtKl z*ymb*G^L_C`A3C415!}G&-KlI+j#$s@&7~DS-(XYb?=_;M!J-clI|`6siC{1yHn}` z1nE$^kp}5*kQk(-yHh%(`#iqy`JU_iaL#`)*Ua9t*IM`IzL&fi0M_1VcKsgq-DKD< z=q*h=gYY8HzdL;=kBVbaeu`1XSs;g~kq*K-w;FrFYG!*-yBpk7Qj%}=PCkA1&(a~S zX(-G*VVefNHBS8l#=7^PasiiC4}gi#-{qSK(?zlLdZ_G@_Eu15820IM?w;^fp&ko3AL}_TcTmk-Q0ftT8w!`gv$fZWaZ&>hV49Oc>z_Zmw3MI=$(x zXY5U6C;ldoe_KMAkC8e50b2&Lfv$%ypjd(%5!J16<^EDB@jLjiMnhwU^Am0C_o1ND zOM2s(dlNuos%7F<%FIvqh+7zvjBn$4`VTmBV`p5~7-Dj|+{n29b3Ecyka9ltkRK9& z)G&JzWX1P}CCaQM%a8|Oa#Eno%Z6XO{Hna>>s;GCeqgVI*3iomgMr7#tJBqOeaNqX8!i z*yKwGmc~>l{ZOYLzdX1@=l9ywFw3|mTxMcs=}*?|`raN5pObIu^M*GdP^BrtmL43v zEYlg9!LNGPdrkD+7QAX15k3(p(x~cU*^9YLpk7?E2&>9xs!z<8x!<279{>X}_PN2CQlZzs zKmYLFi$J;L*YD=f9r}%2gp5wKUQ@o}#z^Un=4k?j-d9@)w1o_(cRV$mM8CrWm5N=L z6-S}FPb43jRf4}o?sk`?sAJ|mG2`s&BD&T2Kn+;R*ri-T1x`xJi9a{w$@2rbW!Wdn zKyj}v$NqCcLV9YR{kY1`rTV@~#wPg0>c&0!e5y%&`K6+L8R<^snx~B|OnjfM8fv}%i+2N#(Z*Nt&k{LII!O4eZxr%&_af=A5-3@KsBCb+}RWsRc zH0HpqM3#w#4U%c4D`JI$3$Urio4~3;?_i^s;?vsIRV>nq;?AB` ziFXwcak}#v6oYUG4xrr|53~P{Xy?Cf(V7QRdOLBc?Nu$^-k8frnL(ZHLbv^M$!(MO z0VhF~?zT&e)xcQe!%O<&_**7V*5Xp)?Za>ig|{}X1yWsN0UQ7s`g2RlmBcztP`uhw zzSD_~qAcy1`xsvWV$Ru_8_iGagRl`$Q1yN03+-TUu>IHlXMw6ln|qv0*Z0rTW9q*U zHBfB+oEjXU5pb8OU3NdbfaR4SYj;yaO*f5tE9W(`4V>-NUo>W78jqF5j$cgWQW6n} zi3D1~9_`kwKwn@?+_}scST7T(5C?I~&#}CuJt*FJn=MPJH?$P^-cu7g^C{NRw+HhQ8tLnOsAd(n@AS?TE$WhlsRnP7q*djBm#6dzo=2u#0qbw-mura z?=N~taGD~k^__;D(NF7t?cn=H2C*$XNnTAZA#9c2mHJ<=%i?^$lx^PLvW)3>O#rghxL46OsK5dWOB-RPW6epZDvLdKXkfAa6ld~NFvWlPAFPOD-0D8@llp(m>Xic`5XPcHTW=yMK#I_ zYXTTYvjc5JJ#vWI&hx)SQC>U_PQ_r%2Cl!3PA%~#NqIozkBN&L0J9{b)3~f6JFx{@ zx&!$rk9A)rE_8L8!+i(hpKgDnXz6s%zhmwy|7s|~_>vjhil$K_A3os=MDW6cOlWm5 z+Rp%pv--UC3%kZIbH$1n*nePPDF_Bi&G55mXl@1}F26bH!;3KY>-j+2q%@4~}H*#?7y47o{#Z{Y z`~fqQbtxH%Kg8tcv`zeZ^w%;YmG5tMUOXYFW{oHuOv2I_=w>rBX4<5`+<)Pm4x#kXTiv_jD zibNR~L^=P2X{CfJ z->msR@?K|c+Wro&0oj*?dYGV=S5%F~sl_o#0`Te&H)k@S9CkgxpoD#neoCJ|$A5fr zruP;`@nipB4&}F_=Quwfv#qeZ#ru|TF;jX2rvN}I=A>lW^*m;bY;q)SM~WZvHa}%#)v3=;6AN&KpZY=r9r{{0wZ6OD+L^a^N5Sb7P4QJF|%58Mm-Z5-Iby-vOfv2Q_2#e0*tX z+U->VmprooNqFTORz+jQ!&)4cck4qf==>i1LBLay@*|9U94`IrswxE=Y05mwIfrO? ztaIG5G3ow3BGgzyzA+q`7-v`I~8c*G?Phe8P&`ylzR*hp0A z7Y2tFFHlEg4Vv;0`gVTKXJ9!GtWkVvwpNx#N;ApUpod zB8HZfb~2NR&rx(b#$D_iEQ@j0B0zXODCBRnt%^W-uvh?RUJ(Z3s)y^yU9FC)LSWiy zbp7skIu|2(fYJRM=~Oglc^3?Dmt`V}^`m6&me88B2XbXiN(_I$xhFZai4_F`5*#E-OPRJtsU%EvKcEe<^* zPxsRRgD%$?Odi|62%zoZ_6=IqR-uti@_bp-$t(2PbLvK-pi&nRVcozgOd2@^IF&(3 znl|bHjp3ukMyTG?6Q@REN}bZiaxr0#K~&)V6H?~4oPBZAxk^J~QG<5BVBYKq!Uy*8 z7+K$0p_5R6<%11_^X+Vc|Jj-Mv0rlENGLB1b0aP94@>4E>`n(+5<-p3@2X-A-_?#| zE~#L``|HTxVE=Uq0aXc&Upt+=pqdl{Q;dv7-kqQ;*;!xy7^ZacXv9p3`FkP=;WbP0zgJA)%y4|_%<$eC-m-sJvwtUfO3-19_uGO4 z$75`8$)VF2KTJLBSR%>M zmYz)H{;5eyUS-1%bB8ix--IZWaUw}RvDgR!|3*VT(WLyNzu9`n>3ORgggM`kJBd!n zetUSYh%SiwhHPPuN@10ldXV42L-6CXAgF!RnsWWo9{c9*hetm3+$5NrGTLD;x`YQDxC{24>DvmOQQorNBF-iu%=)zKQD-6g+wA4AB$(o9UadjRVYXQc4gG5>lRmx!VPxcQ$ICh15}Q3+pwle89G?mGR*u(yzMEE$dAqkb_~b` z{E@XCU)8>_u~wL3gq?kfj1$fFJiDs53dId)q~>mjoqXzgv}gRQFrunqfzBl>22KAp zN>o|5bz&R!)8B7VllXfpybm}p}Y zR)J;n@=Z+Cj9@Jp$NhpxaamwNz^9-sV0@0Q zFj4&3gXwzjq;O#%A!l_lHScBr@SON36@SThey>@}+ z%*JJmAcI24eu|)wF4t?|>hF~wNC);Tx8ryEa-nG!$|IHFDKwOa&{))4`n3XJv(6b+ z{#DyP_Ae8-h!=)AzQ13e@|_TUQCsnPYSixg0s{G)uGG{xH*GhUXIn~*elPSLm5c!^ z_g*fy!W5-Ve{;0%{ezhwH6MS%T^=nY;3{Bz`D6>a_HXvPYHt8^i%#-8m-O*Cx3F}w9esE41Aeu9 z2)}$s@hiXYMFGT0E*b`2%Bova5208Cj6YK6n*oE-(AwM8k!&lg_ZvGcA|VjDo8y1o zdlcws9AV&r0LtKh`w0|UUIFCbCJR~;F$Rph!hsxkdFQVp%f>;dcb z{$I^m?piDEdn}TIb54&&#(vZSyG7M}sfqs$jKj+>)p`I7@ul0MpF7}(zrSmegw!C) zGlzUmLts^J1)Kx%gCEJ)H*}Cgl?aBS&{b2lVJsv9wqP9;+)B&$r&Xed$Xft9!jh5( z3ESAS^UseI9Jx){yNVcQ-DSl2pYyW9oHoE0_YKVh>z=|*u(&;ATHvFw5+XkxuTbIP zKz~1nR+|L*zsjP=YEi8bIw`$b*AXJRbwG?B6e!kFrC&SS3#^U8ysr&arxqt+0oCRB zDqG6K`o_0#DU6=EsX>97fNAk$SExMV#CIO!@Pq$O0rIf&+ir#4bb_BnIr?K*w`ue$ zn?6?YW>gYUe751FH{%LAT#cOA>iP)GCQ&{Dq{|pU%&FiXIQes+3}tsfV?64m`dwYm z!)cfq!fn{QQJ3cZ*DzLq-{C!qXkv5i3NUA6O7)r(P6<_b1_vfcfk z>!Z=WsBW-Vq68+fq4zI?&9ALmQt%7A# z>b@}FKD7i$H42ZR8sClAZLx?6E%`=K* zo3pT1dcbCr6Xtv6Ql&GjUA#j=cv;urUX#45;O1Q4^v@s@g2*t=^Gn(}$?zay-r(#y>%dveR9 zQU2+LdKez@N2cjcp=~rc){2qC^Xc(m=rB{6P*9{hUc8(x2SSPEk3J4)$MP|bnT^?=tSC0q`1*)$-V@qwY#)RM9H?*B^$e%>jX=_{g-PAZn0o#7}SGe}eDL;8} z5B{NQLIQ=al`@KELBMH>qN2RatkiQlR_&obHAjI*QmTENXGGS$RSYc2D|6(NEbCkq z5Va??=3#>>3C=X9*T;Z#3~jFsbit@b3L{H(l>@irB2@F``X&n*vMJ^gKzr*_TJ=HYi^=RX$Z_!9-Rf=kr-kOEl)U zJKdJ%Ck||jI2D)SA`EqUD@6Io56T^Pus1SMm_;Lh(qE65*v%cuX^fsPL9oOt zk?XbvB+>|mm_qBM?m8m|ZJex7$$mhpYqn|QBjw9fHQshsCGS3@41fgZ`}4k6L)V}7 zSEPP1Zxg#{CGXzu*QuhQ+E><S7^LLgIqK`zLB@%HLZRT*_ z)~Rzy1-9{CoDGc>t*$WaSM`_ntShCOfiL}A04+&z1H|c1;>YQ!jQJ|YVe_Ow5sIKv zzc)q9gNV(^Wz#5@johLf0&;BWF#1C!h0z@#f3*DyWh~xiST`gM$CG-tvXF2S^j&jX z9_Z+&o2^)xrTzZ#GZnN#1{}*&xC~AGDn*+=c|o1Ju^Cg+Mut>Xg3c8PiT3#>k z#BHvGlIawQEaY=biFL_M9US@N;mW#)fwi)#ES5gU_FrSbF@9rHR3hBXF9 z7n2*;;PFRc!2+a9@B8?{Nn)<+8Kuv(L}G0hz4}3KqjFa zhjvs|(>rA*>6=w(1rfjDg$W0m-&vDMb#0@Jgb^h?pf3k0dCgaKzE&|>Q9p_C33FuH z0I5tbFZaC= z`T{n9UE46~_xjbT=u(s6A+4M=oC>2+ZlW(7Re}>y!w)tNqE9UgK{^#+&cVC7-JYvQ z(6)2EPln##?>;Rdp-M;C*%4RqIeNbKkSGp5s07Ib!ZecAIMxm)@LZ<-A|7QZfJzSFdP zu6(AXq|72C`GH5%c*PhY8|NSf)w+UFvU3E z5dJf*95v@k4vcAb5-9c?EQ(Q)*}96>gb!dIjC7k#hR`*Z87X0t0dd!G#oP3zVOPgX zDHP)pQs$Bckt+d+y=(2U&nWQ^ zbI!N74?OyuHL3#QJU|t$N})i#rGPXc!#l39+L6pBMYj6)77dm|%`puEB{&3w2`c0t z7+*B@S7#>RJhf)3B}qo?BEe~&g~S_MyJq;CJTxwHNG&pKPkW2d^haAo+;Wx!6B8TM zm)zg>4jZZtRPVp7UglSwIKG<|xC+8~eA2avq|IP*mcJ1{)dfC*_oL)6AX{HVq4u-b zq&vNX7pH&0K2UeUN%-QI9rF@LZ+gCmaE>wBxY`CLY|zl<6DNu!e^U(!anlVpMIy69 zC!}fS*Xy0?M_N6(KD(+mdtmIbM0ux~BDMKP+y!?~;jd`n3;m<{oiB|vMfjA*ry(>& zzylfOmE{@<1pt%GL{7NtQLyr82|2?XXUIUAlc+gcV#h^|Xa|=g>fhHrVHe+ z0<#$)_EC3&mS%S#YoZ?&4uh`f>kK1( zc6MS2V`9x_@|NufMBI14ItsrZrTSPaCCtxYVM{(5)h#L?m;X8=y1Sju2?JMXM{5cH zSM!CnU?XJ!(_7fSsufXK%$|SS>5*??L;jx2Y}d;Uo_DT#&Mj z$%Anz86@f0KA_q79NMGPCvzY((6}J-f6SeYcbPm&GulpyN7c8t-bbq)`r~!BL*0zV z#7yIJxQEFoGz9Nn{@U&GS@CHrrU@y;W6KKHcGlc(mtJup8us#0cLS~$Wjq+aXzOYl zC70JFUKf?(FtaiD8jA@B;-|En-XZ%E{ao9rWUa~S5DD&)!o{OR;v1V4ljX*ad{awO zqSv=OrPum0HjqUUE`NPF4yTjuW^=dt9DuP$m*oK$V7R=p;1iNwrh;k_APTP*LFao` zj;BAiY|&o!xtQe&^gpY-e%;I^?C(F`GQ3i6W11=Y3>8h}`&Ib(cxUa7IWZziDCpFg z1$ss5WfsYlQrTgDXuIiB3G%>48{c+##aGdIzMFWrKVbyyXQW;qZ066qG9)PhcWpEi zY8h=2NT)$H|GZ%ldCo|}`STAZAJUajrkKzoo|Vv@BKqq-R# z@W3r5HlD!df~tbDvTVR}2lrF*eE~Ikoz)oBYt5xKPHA*LP(9O!sO#kn(=5~Hp|zLG zGnuyA#zl@mMz}So<%d-@N$1Or6h(&xX%(B@e99_f<`;?Qs$fhkM@MK$BKl) zRGr^b-GP9qKL;DJa&-bvvhq%y*=44$ZRK0hAUI-Zy_P zn~vlFgH!VJ^Ii7wQie*I^SSllWKe{!ZsxG~S*%aMCIg4tsX^xD;h6LJ0)4N?(ZJn!m>fQl$oh8GF4)y_|eun5ML5L6PL2&V<1yM z-BRqbsZ_wjEPFE2TCxrEN{*@MqVqUa_CAyQO8v%%&e0mRgh>s4UzQXCPitG+VewLT z1k%H45Gk>?%W{A%cBcpeIVi0D>*GvTz)0V+tecTS5hG*RW_Ie$Iz2#EGDx7PohXJv z*SNcm%x$$l5yV39g*yKf3M%`RF6388LUT@%vktKp@~^j2ZPefICro*`J=Z7rcO`Ui zOp*3~VmZwC24SjTF0dm;F@I(1*ZPuG@BS87#c&CAjeHv`en0nW0@ka}PwyZOpoM3k zbn);q6GPRx`fK;FQm{HUv+XDRFe{Om>}Egh7_>{gmQPGz(ZhpF~pR9 zvrG9Z#U)HB|NgEH?vH6qZTRZL33pp`;L#z+LWl~To_xsF~ z*!gqrhCe~-HEf!b`o4cM)XRM7v?v@SA0d z^$)xXp8+-7%w!60Od+kO5ipoQoT~Xc^DU}#nGx+q5HY&n*(~?>6G!c~F@QfxQ@^s# z4wd_9J1M)_CmO#78v_-9o}rp8&9G^&%QP>nAebVhN`-|01z~lYV z9mA)u!6?&V;5&DF!!3Wt7|2zbs!-)X-2o%1q>!;t(wH@#`Lx2@i~Z+;MrUc3@M8(G z>c(hyHGC(+TFkjnX0Q32U^TbtX;yV>b-Wp~jr0iOEmm zVvUjhVTHx12WSJyJSf|W0^3x+q|7r4X{566l$gGB7pK}iJ=DbXs~3$A4F5Lm?aU}A z*gv1x2qVtm=SLCgS;3j@R`Kv6WKHSO9w@|IicnZMmcOAdggWnm0vZ|7gRq4Ipe9>f`O(J2gj^y}F7qZ9lB` zPvrhB@{6gq+o@P!oToAaE-uCcC-G#h-ib5^O~>`WxfFVc(Tt)#_oGkc>=+~~!-(oq zUvn~$EsWr$c*LlNg5jn$*7QT-s8SxK6m>NP1`_?v3q&lHjz>-D92TBnGQU-UO^O*5 z19-gMid%He+6};X7obXS-@z`Fu4$dpvnS-ds_&~iw-}FxCnW3BC-^!?}A z#^R@&SV3iTjh>o#f1#Y0-ZFcprfz|4HRigX{yA-cAGYu4Qa4iyX=SumYZ zdV@=A@}i{n(fR4tboBJ7xw#XAiZ%Gnv)u7t2YnT_dPbd=ZnW95wGzDrGUA{NX|#oXMngBm>DR+kh}QR z9bjq~C&M)@isbpmetR?aM}ih+wIq#cGYhbIVn+|0SDE&N;SMjV*#^Mu4u(Z!SBD;yfdmASIKess`NfVPLt@qX}`-xH2V z`6YYKmB-Zw=IXv8H^`BXaxv-1QGRer74|05Kog_c>&xste13wz zj<~h4!zpZLON|Z;EIYKedR)}WBWYa7V1{-@yra-6w0kq<7}dsm2dJa5Hw>x3fl`N- z4p1k0Z~$r{uX^hj=?O%A&InlDOq`vl{BD$8qJ3%-4BO~QoLB^Yvif?;yfVsOlCmc{ zwq4_P$l)yRhrWANCH#!l^b(Eb(YvTTP;bYo*Y;ufJSz1QNd>gD^^3)rGhg}h`__yS zRwG4jD?!Hbq>i)mH^7m=PgMFTQkx33MNs}`fAg^{(eJKlft_n=Wc-`0=s~fnDbGBE zQqJVnAZuk7rUE*P))+S~D4j{I?{kd_e+Hfojn!6UW~;#LgZYSMqX&M-$;!{bsqT+r z{IVhpsLuD#-_+-u=|h#AB>diF16MXR>IBP1BGNfk=Dr7KfU1GOK;d633L#PnlSMQ7 zi3nyJizgQWB7Lj^YK}Wc&85b-4pwGC>oD|1Iq54Z9`{jAUp|T}9uk~nTn`jKT!2{@ z+Fbf3J&oKcMf=Y+D*9}FEuy1LK(GSHy6L4O%p-oBxS)waqITt?_FBwDC?vVso^<)us92l;;!bmRk$En4Lx+q0jCYL6+P8M) z6c|K!Rrq%D)MR3gn_~x-@6Oed79JEr@0b|!#F7{Q6;1XCY^Lz|;&;fS5+w~p;)ORS z-)4wv%t!lWP~j(a^jobFMhas)>YLABKbgT5yF2t@WpLZz1w17U%ft_XoLnmmMC{@D zotD#1IBeI8mvF-Dgt_buMfcV4^2ToT!0ylA5?u2yzlrE|J<-xqdsGe>?>p}MK||U# z!MjBu;EeG3jta{N55c9k0go)S$L9sh$YgzjMT>{%z4r z9bTN91+U3Xmsm_r)7zScqsLQP_v;NT;(CWFz=fRb+HHaUK3tlYLa~4C*)1`q%UPcG zxlx=8y^BUPH&2PV(b@NFe-&0wv-fD2HU)|DlipR$(y(XN?O(0s4_oHyCF{Hd|N37W zjsV;?qG)G3`Gh0f-?4NR#fTi9*IdJFo1Boey@lu&P8StuteFt0NpL zOLbrfFjG6%ziR#Hu}yc=@6xu)n3Msgn(%dT3s=Z^w;+OE;hZ}gy3U>*O{wa#P>n9n z^GP?ImNfMA5)@5`4uQzSS22iXA<|(U8hKQE7|H;NAqGH8X{11K-|?neQgP z;V8sO!E+Puw$+TO{+#&{poil5TSB}tSDPwo@=n`{vQ5Gy)1%7>UVQfj3_4s=Fl92P z#$H5Grum#WofjMFE6U4p2na%HWMiu@^#(_}c_~fj?%u~}|NBYO4E9UdK-g9V{Sq=SDy4oD88#dQHKeS#+h9OueZSsjs@k+a(vl{l z47%S(-&Flso*IGNkojGw;YF`25{}x;by&_P$#KKHp2W)zg~roAr9g0`0I1b5N(1+g zveE>qYB}@TVusy+*Q#n>Y*`Wt_az||0+GyCE%3YJj<_YIl}H@wcW{~xEPlPZ^vkT< zo0H(ZqJB3|z}g4KJrkGlQg`a@Ahe=F>VU1!UH zK{=+k>IUiKi6%d9w|8I{vx*{Mi?_+)l)=la+5U9B1hz=CS$@c5$pOQG>Q+R^2w3S= z9srb)VjRP}1lHNP5?Y^1eMvzc_seKexxxD?AAwwWkU(R7q3H64Mo3;E_Yflzv+y0;k6)zkwcfCnyz0!x zN)y2lO zP;AkLa*lisX>kBbIr`{jQNZhK1`fy|($)3P8@&%P`IwYon{;2;2ieiZH9eIArmjUP zug@;3!%{L>;M4t=k2g*&u-UYQ_~&&$K6Snthh;PN3#u%3ms->a=V8i}7HqmSl)7GZ zdtx`M51CZd1CxpI`FFNbbn7fPz^$`g1II;ZnNX#jdil1{R@1xUd~Q)&4-b!9n?b&E zibAKjELO$gII1u#=bIPmqj)pmWtQSY+n~j+dx(SlT-V=c6LNuGxv;0p1?%_j6Bzf$ ztIdcSM-lcz%eok6=4&%NJPf}ErC~K2$3|sMBw$^+1aLk#70Mc@Xjve+ajh?yjGB?z zk=Zpjw@Garjii<(J}U!9WNOd)ZMfXL1b$4cOp-=gysmY%s(Na{k$+u*#H3{^TCrYAf?&NZ%ZR{DKjD$CkS~MFJ#g@{7-op|eTz?^ z)Dnjx4DOJ$ItLd5g?pr(T_X{8oi#`oKn5M1&aF0L9olxdPN}+sxD09pO3_^>iO-=O7GPF*id-+7tsQ3J&R(DU_qmqvoXx3JYr#q9I#} zZ!4a0Mo7rMH02~$iYNNCKFhLQI}!a5KN|fm?sI*Z*%>!2Sji1l26HWb-dN3h0|5o} z+3A(K&PGS+ef8RN$pra>5^Rz_Z@&4TNdk&gr90}h_@D}>jR0hKo8}BGtOQ=4RFGw8QI&`gQJQ-daoDyUJg_Z4dLvA8xaHKXqqhWu>h& zIqm*_S~<*JVF%t1-}O*$jyujXsn)Aac(>!cq6vAi@bY5uux6Qh?6=6JWRSA_6wfFL zMd=-Af)Olg9kQ!XS8i$S)uI-rrW|?Y-=ND6$E+#-WT~X2B~e%UgO3tLMYCWDS+=O~ z_)wtgL%v5%SX7;%9+Sg+4Poj$y!iN%G4Z$g7ra#)UzCAW$HEAneBo?P1gE$q)S`>w z^DSh|bIFdpPu-efdMSf#yZe~to*?9-bOjF`2J?$&8qN|JAGgGn`CDu7x^up(K;7+)pVPsO^@Uk?Cov)>NuY7VUkv)=`MzOn-&ou*y9 zq21{^jIS>;&POFVh=hRwIo{?bg7pucqLVX-Syt!rwkY{AEumMat)@x?#9`)q8%d1M zcqj#oT{y2m81^16Yfv5}(#aEeFh+#zSfSVb?R>tst4L8bZXxFeR4ucwtyM|4jH-TA zu>qtC%o5E<<9b$HNzk<~3ipL%$nr1TB%O+nO{O+Zu+x^Z)0EW=4*7F<$!uI-Zv6&- zi-x;!IX|23dw8=3soSdZkhW@ErbRgh+f7&2$}psnzM9!-DW^c^GwiYIQV8Ctx~dGB zc#5`aVthDT*oN0>KL2(*w_T$&QLd$G=LJmIKmB!lg`TBfv=VN0Fv)fM>6%0JW-@0n zPcrZ)<7mq(eu5ktK0a`dA-y-aYzEUJOc$TuLr4tvfv@Vb-L%R4g6J2w1y2SNjn#4A zo4quZXkunmv!>GY=vvXqg2g>|{~gmpo2)$Im#+nG9)F-p_6Dr5O@+gV-&KF?ez^ve zE8huoQaXgmL;C-2es`RbVbGS&`C+MO{|!cs%_yp;|HoHJF-=rqy~1;t_GOBVKZn%f zIKgAum9o^l&!~H(Iz#wdV)iAr3`wdFqPHg4jVDRnxVCN27Ybyrn6`rvgo7#m{>0_2 z4vUHZ&Q9BNv;Jw8Ur7u}ai&VUin7rWSh4+eCafukrRS|P*`k%NwFzCZHbHZ@m!MK8 z8+TXqEQUS_{~<17l~alt4#wOw$#Lq>-qKAVE#_`r?;mGoqcs+{xc^wUD9v$aHkF~3 z&e~ckiNq@G3g^r;W(=-ui3Ar+YhDU6$}I+tyqhu{d+c8%EuP+_ybnqwDVnJU7`Lw} z%8hFc$kn@a@e#Dt=%pXqUIGEY@H}`J%9DQT&;wRFCqFs^MR9h$|D~3WBGnX3$!@0UwZld%D zmP?*4&tHljWdls3Nv*uhp{G#dOw=EXaHWBq33GUOAEUl9i*GrK8e@(82GWlXG1@HG zAEmd(MbwX45FiUtqEz;M=jdv!oek<^dz~^473KH22~To_44)IN)$%Jy%$vUL42}1m z)yrhu{@g}R{O-jU8I8%wNBm%U6=D_e`RAnpMyBgX35iU{6yK_MZ?(d3=s?7}!mSnb zop;K+$W+293T=gF&{uT(tj`#K6~up_O;}HLpg%?u za%}q{s8p@RLa&yvCHNj_iX|m%Fj+PZZc!>@?{IKbh!OoW5ycO*y8*-i#6k_d7wR$2 zI!~vyFhDDFAn1qkB~K}l(9RFb*WqP+M)%gtvBg8ZiRfoNYhn%cOwOc!53uW+_;gWs zqF%cyBrz;$#XPptIMJR`G{`K%m)FcY6J{DmZ_<{wucw<;w;Iis-pGA1Kfi4((O6tp z8g>6X7USVqy|l2ft^p7hKnuO98q7_;rCy@280&tugz!8ZCYxfJd;j|fX6$Ah2+!yO z`-;BX^DRuW+DwE@R$V~%*8qFKOCF=GHeymj|@JhKh!T|hR75dDHoiuqFECrUKYXLyGZf!#{sIOFH!det>z0|GWr zOrKpH!9}s~a5&vERot&A-(&Zs20u%(7#J9C>>VLk5fL@Fw*2Jjx|G71?jOaRer>@3 zdkAenGjnGCQ_r#Uz@1<_)xp({{_59RVz1a@Bz~z|V%CLk_uvF?#d2%^u*+#It^d0E zI1$BzHL|ENDL@wZKQO`bVRz}H{T(=umA1_O{`K=N+r^x5-yh&Z&PG?4b?m+7bPhps zbf|0o#J5v9h2N#ZyW?rTlB8i032)PRbh)05K4GoB_`lEGeEK=VQU0T5o3g?|8*Vna z;EYiGk0DSg_2pdQ95Ivei*3)UhtUFEgM7F}p z7Bd_D5_1#T`oT}?g2ZD3+1<)l-$bj!9(WazMr2%APy* z=N{>p0am8#JL`j5+Zm>M#}&P~@l+;zhxJ!-6a00a)b^D0Tl1J!^(PbRiWo7GP0-^$ zpi*iw#BF#4qQmt){|Dx$EgW7DnXkE0$3l!Jl?pCz8Yp^24-JN0&PK!%$x8Uw> z#odcTDemrY@_y%>zsXD{Gue6Wd#`n^y&+Umuo09ZOEeiL1TKJmCgSPI(j_ZPRvfXD zuKTHf9(8%$uRQplMBr%2C@d$M%>5|*6=mAvzDJVy?~(M2->D-)-mwho+SuyXq4QS4 zQ!*{1mnq|XbuIt>wf2)BHOg+k2Tvh^SqE<|B7Z%z88@{5Af<*CMtesTCb&7bDmf{N zf>Ch?(Tgr=x&bK?xOiJxG2Sw_6yc%ZM5MQuckw-th& zIgp2eXH^u4^#*DuO*k6<0W74A1`AfPMD}9t3mMzWx7$1KZZwARpZ4nvbgu%5tu-Won zX=y9DYc(`enp!2OjdGQ`Mw3qD7~V4ZWmV~}K-*?z-%+^(Q`%dX*ub*mTBvdFaV^YJ zNKOu+@>>s{%V5LIvO*acbSibAh!;zS9PpZ@{Q#UqIT*0KS2{U9-rU{}y4suU>+8c` z6tRITdWbjq=gY`ewO(6IWE)@#nnW>b&AR% ze~y<#&Y+d8LE*3X3 zx&L&j!pBc=MF3q2HKADSGD&VJcMc|J=$mV=TRb}Y=p%33!>|X$IvZFjG`Po6IY~1w zkOmoiS}wPad!Hdp@VT$<()pv~h@zhTuG+0*7Y?X~`G!rkO}U}-t)J{YyF*9)K^%_P znb3xA45(x>`2=vo;Xho$;gB*$lC69>Ds$RNs)x)_=306hT=~zAp&dlUTGo5pxup?V z-QmLA@4ES7Yg7QtoBx0*THP77+hIQHD|OcVuO~jA@3yD7G-R692ppJRr(122sQYG@ zrF5-*_nwkYrKa_puF~UeSWC_eeiMjpK$kuvM~CC+Pu9TPyZMZ zH=9NjfPJP$`Pk-{?t?#ZowiA|uN9jcDcl#--1`oXeX#-r?p%fK{-~w@2rRi$Nl56X z51P1oQ}FD)%@lZ0He%~muj*t)<34UJsInY-N_Tq9tM|lTC5PP!3`Ytr~9r z))TCtBCS23*3-mt9{T7TBi~IGPbJMjAY$19Kvc|Es~LnI_X>1~k!w_sOO3fAel^b4 ztC5L&=la&xtKLCnCZ4#E0afebBVC(W1^nioN?w6q{3mlZ7W-?03)h02j$3iq0ifsr zC=g+oWzJ(K0)6sv6l<2I2;eHI8{idC(V8e7-T{U+@zhg!2|OGDSbXCj{N;fd%s=V8 zZfW%++ZBB7ny^U8uj{1!C}j?~Ro|LF8GTku%34R;4edxKXQ!9kFL1~x z$(rx|F?uWu{Cq$Gop=*8_pH8EL|GBFkJRkpSEY5a*{#!0+JLuLou`~7gcO3M{odPV z-2f8X>fg*4A%kx2^;>!oVMA3$s z{?!_DW9j*)-WgcAO)i0V%`jvRy<2ryoZj1KndKI}Dg0kGyjj1BsUf$okr3x2 zxs{7_nhI%fM?UeEolxwkZO$z$;8M#c{m%H};<(j|fJ(?EbHi`N9E;OkB7QF{5xU-g zS!QWKjWBeyKvx6vXltM(gr>? zTaTPA1$XeeIkI==T7VK8ZAG{jP!7*iWYqiE$&%f(JX$USk#sdv)$qf*vy z>|D+Mbb4w()k$OGk?TjSOGp3={jH-m(=n!OuDw*-HFpA2o(mt%8B!sp860$(rvDJ@ zzD)7^E(?$6S^lODLoL^;+KedK=2#z#iTKq&v*Z$&0cJ8Kdh8TLZFJu?16}&h7M;<+ z7OlqqxS7{#ST~1^?!-QzWV32KF?~F#r;5^@{5to;iCsp*WFO(|I%5z}|Mu|g(@C6q zN7Xj@vvqdSX=fL%o~%RXxy^n@Eajol{lv_so|ZGG0kwRwROO?~KtsLMRsFmb^b)y( zl+Apz3RiSIgTWbN{OBzEKDITf>b8W+l@WEZ89tU&(2O5vwyYdy^@UzzjzpANP<3Df z+bqI6C$fv(YR>jbSL6g3Xr1dP5A7H9k_mSu<#YU{hmBB+MgA-N(^RFFhv$Q~y;$wl zlwG@!eRA|Z6-Uyd-XVrk9qMX7fY;Ps)!bPeJY$9wR0%yhEXkE(ceZ575 z*#1goGaKwrRFuI0brZVQmD!zjLeV-%R#gSI2HuT=SQ8<}RI!E&n58IctE5TM)Hc3l z82=CV2NOiC@oHr1IxXeLjs97S8jCV`iKf%#1NwKqHw%V7?5f5OI4t|f5Q@VnRzTpV zMoBHAL6-rU-60+@38yrRM$r(@s8JfM-{u~Gf>tJp{tYSybRE9nQm_aU2$L%P5fUf* zYB&tNhU6{PsN`nhyY=H^i&#c#-h}JUpp6e+djW7t-@!AMZ!cwx&$WEq(Gk74l$r&0 z)nqBNAP@8Su~S1bCFWC&vpJ$k2Ap1X!wsH0!@T%XMaAQJL0 zr!%J>AFLU!*X|(-KRZ?NH7bYIdfrjrC~*JpgN&{bIiDuj4NZUFYD@^MtzJdAdJnWP zV&Vh$(Z3JL7Rq3yZg`=zhxaIt9zSJjM(0!~nj9FN?a6W&PAMBz*I}8Z#(r)~h<;3J<6#QZQiAdRKHjSGIB5y#U8M`zSp=OSWE) zVZgeLX9usGs^+Jg&sblGH#p~X>&`>>?KerlE7nh)B>&Q`_u)@12Z#{@(cgmPd8sNy z57SgOsM^F16v`Iy4-=hME*wg2&Zd8KY#o~-Z2i?k%vk>O=R-9($Lg#9!*D|3U2ql< z61MKroSFU3IwKw`32;s1qieE$ON9tY-iltK+o@LnG>gpN*vtC85mAVi`tY`hSU78^ zO$QqOHZZYHnlUCUCo2mlLqAf5n?BjPwMrtpU8j5Vp6-yEfPlWQZ$-YEXjMpX^I#i| zm5fZhUgJk}g}1}sAhO$^vl=Y8F^~X&eSfYgd1|Is>Y3*W-kc?o<}^E|BnW*x%k8Al zutfN?XMvyJfX)6WxXr;iRs&rN;PDX3qPmJ!xHVVQR%?v$ZvAu z)?L9A>RR@&nktT2PG`_5=zhA2f`n=wFtZDmS4^^SB8&iu*S(iW zC*|Hk9L4%p3}3M)u|lqN8_?z-nZEkufxX&zp>-(y>_(R4kf2?a#P|O0!4Nu%FSdJQ z9K@fm{rSe#Y&^&s+G`cT6t&C~AKF_o@khm`$j?2SHU{euueFiUqRZ0A>p$LMULi8) zKKsoXqf3%F!+J%I5mM84=>lzy$lZUmY)W_@mUkHMJt_)t^eg44=j<3{8LWPZ>}C%b zpeRM;k;RmT*jLQ&^+?|y4-WUuG!u68Fx5$|=^fYDRTem<34>GlI8-{kblE!ZHI_eS zu{E+2&T|OuX}})B&mxtkNBq}WWv<$yOETp@eE7w^UTe>u`(jlw1Wcf&*g*$@%r&3n z*>vb64roNeHpMj&6t@sIBZOUgz+>H9tFWc4k*P#3}h zaE;=H7_-}&l{jIBD)oOIRU^Aria5Q%c>SF+&BmejE*BtY9`cMm^9&CqqyCM->?jS0u)^ zKg*n_BR?|`WvRRt5P^x4`LkRms?F;NX1Rj}1{y?Qz=179s-*-kUnE67d1K!i&PN+g zUn6WZNzH$S>0k`gi$L?CwXU|FGHBn~`tozU$<^DKXL{6RZ+b}^q>dzrg- zhyY5?q>TQ8FIZFO6X%EfE2^2)Wvktl8|Cy+PiIPS^$h5Gzj7-ZoNl$z@HLVA=B%8# zZ1L}|27TS|KAJfJA2;n_4p=JoThSZuHs5Y}Z1>R)XgR+)H7ZFuhSX@CY*u17A-=)d zdg{_21SLKx1%b@}4#qvcUh z%%I=gFjBe7Jd{$?b*UD$6_{v1g5U4H%nbZ9${4cOty5~w9_e9+n3NwiL;Z-%dyIWZWv-&c!CuERZZKZFm%b4l_##n!iO)#-Z;2;l20Mg>K{rUB6s1^(v zlKRapZa0G&0Y^9n@F$4byRct8CQX&jV1z^;@p{@tPTx!*Mw^o73%)n*4Lrg1fyqkR zO|zfmGQ51%PN9441E3@=<`cMo7Eu*FRNXuiY;-zVfvG(Ls#q>s2M(ZpoF9)ux#S(o zAp))L%A260+;}~pRw#!wRj=~dE}K(7C`)yVxb}Q%1*7mv0FBwo)+#Ec<&d~DlcgsA z`x%I!>aM~zYBr@DG;I3$Ui#xyT8+^eTKh$xk`uD^8t6*6P3(KY`Lh=_7MQ~$AA*i$02eZ?8k|MXOZnnd zyDv}&;=fz0+~IYYM|c)|N#RTCriM{)`J6r2GY#`1g*rLs3Gf?{Eu6)o^8HUJZMgSX zlhSK*{r1Ubv5p8C_ZB2Tb@D=5Rnd2|5|90I3$*t2e-i>J(trN%R_`p{^gmMyh_lkX zfch)J3&KI>dT;5jh)^>H2e?|_6f$O6VEq;yyW#;~JRy8Oul~Fk020<+_r25q{9@$! zFXthmy+^ipsRm&o{f%*t%8OH;Q{eSX=?~mvE}OZ}66{Un^Y`%_Cp!b(kj=Th(JjCW zNjd#Ee9Sfvj4{>4=L4o!!t_uwoXIOUq6Y52N!K`41z#6oz?Q(H z2g%8a1W*h1=;LxwFrmQ~b82Pc!BV*tAzRj= z1Q%>HnBxX|Ea>@-^xR702tCW&PZ*HG@uCPHz zf2a9;8#Y$8v{?Z6^|4%l4aSm1$ut#C=n-N{$eJMxD&0^ZOk3|adQ|e`^J8s1PUSp;)0-tHWWMBgPNXJjqplL1RI*R zmQWpjqb#W)(xOojJeeDbPRR(phrf)U&NYu&wkYa&B4h8#LNet6YZP-Vg8yCSVI9*% z0Keu)QsrJQ_x1{6+{W|4fz8@#6U$u`VYE2Dr*7)Ia!j9 z$2@|yN#OtKl?T;PoUPrX;_+-8c%yq`;_4CwbThy|#~RrRYRkEmf-^PM`jl*T;WR(6Ee zae_%W@%czNOh05~aJ+3Q$;km?3X#7zK`5tL&>S{SgUzBJ#L^yCX=j3D1^B42GeVbg z_&rBO6vlj{HTN`Y2L4jakqWVZzpIO<8adRJwTP$wuP--r2RIU1j@aK0HjnfItL29f ziu-G{lf2^?G7(&q(4W<8s~9MFfwVvBGTi>r`g4l}vs7iswvLJ?r3QA+Y zYXv%~$TgaY#Zn_DpR3b48oZG?fex0ArmBr@2##8*{mZT*rZ)Sw;wPbqzQ_TW=j(j! zYB@Oz({O`v@(p4*=t9^g3?d$xG>6nE)~;tPg%eIZuq&Nf!OwS!!+hg2Lr`Z$=*7?G znWcP%S+Um=RWgXqCK$ky89S`!yOl=z2ne>*46)UiM?M%?EQda{JLu+nwH(VwjYcM| zKqaxh8D=$_-pa1FeE*_=yRZP1m}5kxFWCpPMHsJ-M^#1kWzfQpM;Jj9894ura~@6r zM_zd4J&t&zQUYl`h;x3INI_Jf_87aB3BCwXB<7bXGNA>OW3v z(MS1!B_(JVU>#HVOax{x)uL{nHt1?kU3m5Iwb3W!iPyNo5;kDCO<~PqMd-+^G0_|;P5mm`fFXPV3phZh0jD%1azAYxy-G|NYFHh#r^e$GHdf{`I*8*v>xgDRxVOw#Ylf7OjT;41*|=R66yP=+ z8PlI(cC;b1#q~`IDteLAn{1Smo{zm9qch*AA?0LYM8mH*pDWP)#g13Z%CenImSQDz_^%j2w8Z&K1-LIS2kcd^n+I-6%H@MV<`>%s*q2c zu&I{9xN95#b%;!)I1KOb;mDfwTY{c?@MsrXN^Wb#3?U@M#N;A)91MWm zRJ~zOAS@TNuBLv>#8Bg}R_Cc+apes#y`I->^G!w=|FN!`B4?d-K%VV}ch_-G=}Ae6 zlL41>2gCBL<;^vSMcx;5n88siz|F#$a}zt+Xt*)_aXJPY_1Jr=`7h`Qaj(urz$f$%V_nUvHx z^me>pC6&AS4;&TF)S=9ZC>`j}od4ZTMB!OsEr;fLU8wwfwFGgWZQd?PefmblA0He8 zWq!J74Y<4=;Y^Vqgio()pI^DWg1%Xe6iN!qB%wAF7{%;JQ$Mscg=vX*MFRn)$(vJ^ z9elp(Bc3X=Rxhmo34I1$2h`8cSCgeCsU@&qEMN1$r}+VtQN$HEBd#yyGZeJ1(>u&o znXAQKM$b3jIBndN=h{54%(mM4s(C(E6jF{vt(u86%`y?RyqSJL1ZaGdP5XD7tPP;2 zLUGopM8F%oV_N5#f(7j;Z~^6QVE$l^tvcN|valr_t3Vc~$G;mFdF441xEVRMFbj&n zsAs($&&#Z~;=M#pgO?=>+x^EZsZGqbFzmS4xf4L7TYnzdjs-Abtt*@?g5TuH=17mH zn&Cs;=vf~vqf|}e*cfU+I z=BgILE42X{fPdb12(LQSE7EvZsyy?u!^4#NMQd(6r_sVoarP;aVyk3ANp zwd($)x_A?pig>4Dyz_bjlG$el^)lq_z)qbu>&DePfOz2VO+4v0sdD7P#**)i^hc`= zR%OkNk)5mI7sj)$OVAsl)RB#vR( zaM*nDyFj8ZUhoLOANlKN|A(ukt|3$d)FD?V-;v{%ur(SiO4sLTxYix=9ty4zS-5@V zIsxWNu%WX;E#^Uc&@P+gM95sIa$RO^in~uvodek$)lW6$-NCOgcG=AVV^@ZrzE5y! zNEwX>>j(;qO(?ftt~;!k z#Arr^mt{F@bO|`U7ElGvwu|e2!eC?R%L5)FM!TIXESH876$A59n$i3 ze%$;han73a{zJ~!mX`HoO6#aoYbsku)KrQ$76@xvgFz~Y-}Q2vjv##`NEJ42z#siB zL5gX%Pi}6>hW*Zp-B^-v*Ld7z*e-vGLJ^PPH`h8@UQ9?;Q_O~v2-80z0+FuSk0$`p z!Akp#w{XMdWk$lz^%%W*)t4A2fCP7b@&$rpoy2R-T)gl-;f(0N79mux!l~4Q?ce1u z*%(I=2GSl6(!ak$9FK+l-oIB0{hDrFtd8Pg{Q;tu5ME_k@`$$}Z1ovhfTgIVmk!V= zv9@p?j$r6ME;pp>wD9J8Qy5YQ5x_^6uVo~G+Uy6U9qmvX{e4!XosNhqG1P5476mWMw*s&(r#np3!H8qA+0rHWu?$%On z&`}+Rl@7Uqff}Rd=eJ^uFuoe;-JgyfXixrgyCjwx6OC0Mh69GR4n`vC#X1DkBVZmI zsvP&3#YtRb9r76$Z~<@5-8F zZTXl_dq%DzAFSWslE#ez`0f*D0ngF5p|C}s;1Bm)?`(;ksT}2|=KA`?t9Q#ZH4HXO z*YI$=vZ45^&Qs4EE#&LBCjmyza_I_Rc8zF6ZyfIl?AD`inS>U<5`4{{(qBF02}nog zn(?f0`oT4bMFRxw=l6djSk=Sqp=mVBg)zatJ?J<}?OIc$y!?D%d|~hJ-@rz@mGIhy z=nTY+%ct-ST~rYRJf_q+VR4>ID6`ZZr8?lR%Bl-*&&bW&QX+$E>bF=lt_Xf-XC5#s zTc>O|phmB8511V0nAF9WCf{vV3h}w9I}h8>Kyc&`l2nDHSk9N<8n?TVe$97mE;fFk ztF$L%N@uvhAAto_NV|WM8_I2hjpUAmUw*hdtTS-kG-bK;rLL%%Z?+y}s&>okFPL17 za0hBI0ohKK4B#+k&ibuFyh)dm|bs39}zBHyNUDa@l`t3}>ulA&z129{@oEZd}vsCT7Sd6+2e(I?~IeCK~HS_$n z=(*=?ClL^6-g)*<-|-?J6}B(mOGBavQs`>c1reE)#=Z-{Q2KHmjx#zqeGnDx5V@rf z9eCcOxhm-emC=>(o2OJzY^*YNKMj=Vyd|DB5jDaZVInzJkB0Fs50JBH8oya01^U6O zSatq8I6+dr@D4!5W0hOT$7(n60wgR`rWB|_VBlCCQe%TwaqwCNbdo&9$VY^I+1Blz zry*=|SnVF)v>`YwRKw#bmZOH(C^bwPw<^u#TFtw_&HlBrCuFqj1k)YjPmHF^^PZr{ zD{uzhh4zgeeLByB$L-bXxn;ASt_qLu~>@{=5atD4-)76CdtFq~xjY&MeIF_o<@1a+T z9x|66#T00h^_fG>tJ3@vn8I-?UyA~ zYm(h5-8DKxwj2Fnf{u3q^}}5bPON{HOTC@T)4F8F7zwO*)0dDkN}~c6?(mqj{gVy+ z2r$UZnNs_`hK$eV%kW-bpByUY%{!s|9ki>q5K3vBtiH_ut(5fOwmU^6l zV1er&cxA(KUoE&$*dPTdJrl^y0PQD=A7AxI5qFUbF_wSPnimvaVguqW5R~b!%Jd2=F76X|^vOaHjn9m(* z%Y|7t8uD``rt1o$@h$}&q>4^C&K3qk70#Z}uk`4{ztBhZ*WwW)=+Bp+Xt9G8PCNt(-0mvzPh5b2g z*hf+VR^h%3SH_@PSO9M_0~-Q5c(Ssw2}YIg_L! zzu*Mi3+Ihw!-X+u{vAIKl(~gcTt#`YimF{w-s8CTl#1}b7WsoXIvZ`5 z0=;g^d51OH5UtMkxGB;0YdtOQ zv7H0sB4>dK%7uao&ReEqByY6V&Irh)gslP--y+HVvds7zYQ#_RHls3$2WOb?Vnuq) z;82B5KR?TjQ9c)f9hypdHbLJf)2YXplXV%nVcJ?ep7EJYmDhWAbLCg;7&SGnHL^E^ zO)ybUrhv!5YKzOfJ)FtLWWZH&{$B6Y86`A7ya%B03KFR|MDu)cdgqlf6i2}H^`w`J ztOm9TMi);F7(fqw0pXTkR5d7ymwo4VoFV)tdtHb?8M>EoE(?a0~Bj)k%P`Q;wl zl&&GgZNbos>^Z)9FJC75!G5mUm#VcNKNFHqQP8G^2G0chR=G5IQ)%Iqhm{f=Ko4@U z8a9A7awO>RvZ^uOIj7;f=@vg@HYQYu6}WpgSTj+c><6P?`} z#e85BCAN3t{JHmmukiFwZwLxPkhsl1m?CAVQl|}SG0w@wK?0jM4h%t18y5qG*nSa~ z!cN%&pXWH*6RW(HCac?p_#Q3{toFRghy=jHu=16X4z`t}yL2J+j|7pz26YWTviHj7 z?B|f#$P#4w`Vq@|QIm>@qDcy-f9s%mHN-rH5a(jGG8(*9sEF2 z&r_exvxPrMT3R|cakbgWq+x~8W_>aM1%sJ{Hb=%Vj{PENz*0k5-#}Tu<6x8yRG)(A zVHnM0o=CkX2aHX+M4KF9{hEFm-}f?3m``IrzN#?p?AN{lNP^YX+(VpKOC-B|0^MiR zCjCVGL(*A(L3F9PS%~mRcPqobYy#jMdPQa{`x0trPREhg|0k*AIw?gr8e`Ym4$}(5 zyA(bD`d46jk-2KKPtGiEUK`0_mK`E>T|t*piCPFf{E|NKTK1g|BK=@C&uHdb>025` zubgm~QILbFQ^hX~Z!y`DxcTzc$CemZA^mf-Q7D>Xbp61q$!E`(h!Y^sGt8X&q6IOu z$k~La+8ANZ!9F86l)6?FUWru?xd(c>xb0Pa zS{6_BTEYhZ)Ni0D8So!V)-iv?(Dih$kNT#!yn47?{;87)WUzQ4h1aO=@FFF{rPD!S z=5cMUfoRZCIuXp+r zttqaxnbA0)lAW2OwC&^GICF*Eiqj;Lqnvp1Qk_M<$JzSwW1`Lo9j(retV`=aNeK)E zo0LD3fw18jh24Sj!BJki(0Iz}T4zxDVx?KJzSnKEN!k}srkYbRNRGpT!twBA8*Y;8 zM4dyU!^i}%DSJpOEqvPeSv?r8&bvU~1z%r!Uf)Q(#K6`4H!rxV^3=Y%p{D-WiiiPbfzdwnQQCd9zd1k}~56AXOaP zN-@8Jc3*e>L!_nbxDhh=zkJDst|RFUR&JTEP z#w-OVL`g?a|7q4Uj!I&|`zcjX zZ*xDX{{yD$nYm>ohCmMouB~(wRuvF`9U_%|t5HgjqBGDCX*RJ&1-oEYq&F)xiMZ~< zEM$QNxjH@bS(dwU?7w3BTyQj2CF6&%*4r?<9*s-dBPyi|&9=JPFzM3N!2Rzp5R%;w z&Ck5c+$S*QRDNxy-*+>PQsJQZ2DHRy6|1h}4b#W;Ur{Pu2*zbG4*ygHd>hY&UMp@M z#44uagcvDuiUmgQy}PG>Ur}?uWYk;|cgpwE(2>ay^c(AsxkApHC`NjZ9DsaZTKU> zx!H*~;&(-+!HVfTXmE(AQ_c?+-=!vd#T`smCzQW-{=?@BJ`;zsXfoF&VS`+=?BoMJ zEpXm3a>s>*T}{##y~}9XW0}Ij(Fd;>jv`#2JnYv8YCuhF9ze|RIi}5|$WAu}8`{0P z;rAXG7<5s^_idzudSimDYGL*z zg#+*7r=O*6)X%vynItXIpWmZ0U&#cOuC zblbbeF?KEuoOM9avkUSpt}Mls3vHvQAv;E2z$}4H6`Z{pdx7pau@QQI2rtOAWoSq> zP8^Ta+C;)#V%tbwk|sR4jq-ME|1*zOIi{RcSc9mJ*^_RhUR-03myZ!y8I#JtE1^un zy^ul?D+^B@ld&k7sJb*KZ5}4Up?4%awkb=w6Ce0?d?0{S6ycv17uuAy*!f(GSL1|F z2#YA#ac8Qq#JzXhHBs1DzU6~cTl_}dxG zyB3C#w+*03aVjU&i{Wx2O4o7c8No>b3QYI>h{enWvoRbW1tx+TYPQUkG9rU|CjJ1D zBT~;6Vn;>VgOFu+*A18qKDriD58oPA!S*qm;a$y5Fw-qmO)|MToR`v*8a*89xx$-J zg$Btq_gy*eeIBgU^<5o|GRNW^AS46j^YJLYfF?pVYyZotggY|Kd@YoaY-|o2dK`~D zeg40eM|{|5c6O)#0C%{lMsn5{3|ae(2zELoNh`XFi>F@Dz1upHs?S64E$r09?NI1L z#Oj`4)U0jSBZMe6qu2EfUa#xvBh>i9o3Is#S;suB*9mNET9u7+1DR3MVep>h0P)a+ z0V>NIE$7)gMV{(@Q54sZH&96Y@s=#4-J&n&Hip$muMF;k9(0^E%2|=0#Y0WaEzyKD zp|yYZs{$#*Phf{F$v!p%Uc|ejQ9Dwbkv~Q|N+1_&_WEg2j{Ngsv|))gn)mznM&Vzj z7y_UV{fCja^oS~2lHcLuGk>>$GIkBs+~A;7*SGq|UylVY@d@>M9hgK!j8yQuWakpv z_4W58>vXUa=rO?))+aP*2>J6fp4a=BNnY@wr?{a1>KTwEVL$xEKF~G) zjwHRfO{Q!N};>P!k+=}hcl#=8oM3>xs3BQ1*V!C4RTns7zL z7=iWIq&YACyf^ppPy6UiULuw=JK= z!~7EZW#`95b|2y21Js{sSO_rk8q&WrOll2{;y#>gZ=R$D?v9t{N!`4Q+pVHT>}n#g zV39@Svw1xX4ir9Anl9UA{{6xxTUtITFTVM&+%Gbzk*@ILj14f9#-DYm0DZgn5%l16 zki|7QJEFeU2$ew%;&y#s41ORzNAu#fVDjx;1$zw>@z_o||0>s_37a(d2^V>9t(z8C z`1~TbEje;cK(hLe+Mi)kgQGP2KJ?kv$-N%C3v?=uJ`99TCQ(TYQh$5)`An&Ss3xm~ zLbnS8d9eBQ9XPY=9+sb}`@7NAdKj-Wr`DClF%sp{L0J2Lqes-T_(BRALMOBOJVd*! z&O}%KpfxSVCk(^o(T)%FYj1qBFEOjKE?u)Tt*}{2C9NgjKQM?I&dVRy$5NMaUl%;N zcm$Q)yD{QOM6~vE^s{L+#3NAO7d*t<8OX zbS=Tkcjy-kJ_YvB?GX*|cGY!)=&xYgKOMZr(CY3VGl$KLU7UrSnDR3A=8pEI79 zN7n*6tz8R^A3-lK24n#ht^C5h0{XV9ojN#dLLzm!T*Y*H<#ak8N98(&&NX@Sk)oCL zql`9=0ur!R9?VBb(trNxY}P|9MSM>4Nc$y>c@#tS0OHPbw#D((vI(So38~Lyc(xDu zE)Z?>-HAfeua^R;nvPQk*|xX@ z5|PY+>va3K_M2|S_Q#4u&~~lSRxTct-_z;z`2mx*J6Q$TC$DfTC6Yl>{!q2Q^^p?u zz1BB+73N(Ot1*!#GJX;romke6)DbRNb$x!k3*z&p|C{<3LGWa{)QSER{eF12S{ASg zDM%uZB_t$`sQ&309NbUAML`M;S8qXm?#gvfSY(@$h&^akX_vm92Ii&-n-r^NQ|GJ( z6tz+EjH_E1PFvdC7Kj9IC1JMKjQG*rC<4#bpT8HEO_+AL-U>q1#PF6UAxun4J1H{l zWnIuh?@X%8#d!c1BuF|&jbvsOfUf7V(rL2Sw_RyeY&g?oJtrPBXqM&J4a>B8+`3G; zwgcg^He!6DVx|nD-^qUMG>9FTc^_4#yTHuSscdDd-?;107JjnzqlJKY|BU`oDb(8QIoCQH;qODQZC(ebH~tsF)+050;O}9g^&y*= z8=s@u?HD^NW*XT9$G>Pd=P>TRt}d6W zs*35gr`)e&p!KckHo@nlfs3OWM5EL(Sd~5T&U@ZNAvX4dxc$YXC4FuW#ne+W=4DKD z4)QUC|HT-r!FRo68^vvZtgSvOmbu${8sq12hbWaS-F8j80aG))alo{3~8DT zVlWDXcVd-@N)38Jw#-+=Oo9qg7zCK6cv6C~u6`o;Y9!)NYwR4^N5gL-D z`nK!P{ByF1_>)7_sTKls;DG7;is`Y#Q%?(w$zc&|jw}yk;MW(GCO|?r#mdF8655RZ z-yDprA`tb|l9>Wk%%L)24pBu{SJzVIP{|`ZJNpMz)K57j$#R4>CCG2`-6evEBFZA6 zKgtT!oz3``M5HPhLR1^XM8V8k0UXqVDs(}LY8`h=TcEq{vuVmA@p00TFK7XCX^B1v zDRK}(g9b!24_1Si|KyoQgbYU>ZZ*<3mk26#&Z5&v7=C{!*DJr3 zkVAZK0I05@aW)dFa)|7TB3)(tHD7sl9_`9v_!{-BSjR}K zgp1^qlm=FZfp8Pccgu}!{FWK%{vd0z#ZnCv0r%sf`qQeUqcWY{FKJzl3CTp@gP?eT zV~(-{SDjpuqq-Vq5-+}6gYQ=KWCqL}X-@gka`QYcyel4|!Q_g!EL{ z2SP4~YR!gyHfVnCHi>tVYa<~Nx*xbW4>cKrQ#IEMcowD1(uDUYbRq83A>%_=DdB}3 zHKy&YM%fD&BkC>xNi`=sf}wFmPH8|1V~Pugc`NX*PeQNj>SIyW>R>1K=RZ#WcQ0rgv{7{UUqeGt7sK+0Eb*ZYykW3KQa7v^e7;^(T`8XLOldeQ zHO~*2?9?7-;?oU}T_D`R70VLBf*%A7%HNR}$mqoewRE>;={k2VD-Q zMJDYGNR19e>ABN~^K z0IlcJPV1}GyCCe9{_T~#;6$L77A*EAxY3ki$|*+0MXxS_DDD}2?icdye4EP9UnIv<$RNh_+!d~w%{eeatE{};?`9E4REj+|dk z)RZrJ_Mt+x!3UR&e}LjE>imaiKU=2Q4ZNR<%~~X6%WFNk1TA@6@PA^w$Y* zxy6sj88#8L4x+$@hyoyLO^1w|d_VYx z>3}};oThlxGM+RFbCnFuMaD8dJgbW}2@=xlb=Qs`kY+hU#Tr6`4r_!LR+pgI(Ew0>hGn97u{5Q^=t~ik$+)_2 zRv1&*tAqU~zySOS*?_O6!iYxo;HlI!Gv4XzLdk+;@N%=Hqy)vK@a)UkU(Ivw^Rv-h zbnWEB0i70Y!8Ama6K+5gwrJ@$w>7DrBvx{tAsgBYR zD5^a^pHJ8O|6ziBi;%#{rC!Q>OqD|;C*!W;B6m%bCPvyBE(1>0q+7G&58mM@E#nPEOX8tT5p_Ax zq2kN_`vVHF{L*qsD;J!A0$)NaiK4({V8U$z0JRub3M2$6G5 zq_>=g@rZ8!B=YqHcDl;$+x|t`GzSDS5?dp%5Bl}b2x$epc-Loe7rtE-X%~)XZKi5o zrBmecKaoVEP3A4&u0>QHz}yiqVsCb2#tNI1Ie7Kxtrz-8a%`v4niBR~fjT8^MCImY zB*T**X0|ISvq$8JHITm6xqZ3|S?Z?N{?H&aStuEr1Sa@u>S zdrxdzoiySMLOc+!o=}X)jlBIPY-bx~gyqKYfB5!Q`1NnfUfmCptx=`wkVxXL(_O1IO+-zN;&Aj%7;K`fioY!DjwbR#%jUHT{_d z!QDKDIBKKz6E5`j+rN%V!awzT*G!Yh>^6STY1#zuU&@G@nf)iIN+GJ zv~3L@21^1DgQW>=Sf)R{3zLxoQfGh|Hc3x8c87O=162!VF5r} zKrc6Ze5K~1YV8Q3JA3TyPzykZ)8@*<_YmjticnI3$spdL!^trUm*3($yu7;m`ku;!Y-R=X8`)K6KB3Cyy<9aV z5p+k6TTv8SdmMo9O8%N|emr>R{*Br(mQS!KXezv)1c^7t=#{-+D09{6eB7kmx1@1?E3T7RRM>US2gy znW55b$?Zm0_vVkN2b4?n^tHX4;OKo?i`i4iYM$$@_>@$s8iL|$WqQh}dLwyW6xN_$ zt74@KhCgakLOU+DFpU}W_5_ZkfhH%Tdc!v8(JGb1t0qX-BzzVW^Ue(~>dJI?+J z5X^HpJ9n0ulmlax;ax0Tbxw(~yGECIuTZU`(@{s=SahSXC>R0cl9KKGg34D00y*M~ zBFOYwLQc(svu_JoLe_qUdm%{idkByuaLSTTzq4{$Kymkpit-`u(E)a_AaOwA%Z|#?(S84c?|TFe*lPda=N9+L z#_Pc>mF{vm2h0SP4U7XbI_mtNW>Op?U2FEQIA}$81Uo0(kklU&7|r81k#N-|^=+RF zbFH^=0%zi}mh?b>quWld3)P7PLDEuQhMX#(YGz_TaW}uk)0|qUjERd)%icu-Sy{Eg zBrtE`aD87nJNxo7sTOOFvmspykDUOMGEb}-*vf2a^w_^v{h8mihMdOJ=xKa|YH6(0 z8q02WKliNSYC09ev2B(`@6iYrWfu*)D0j(JMflFy&K5vsMPxB96_`taZ1={#$?&OT zT(yy~=G;pIGW!xZ>I-)v7H#*kCG3xGbW#O0&sazvB6Vk_mxNq~D(V@!!0B##VM<|0 zwphN%POKw)qKcsZ9T~lv#4Qb-w*BN+Fv!iRN#gqg``Redm3q4n+2MPr}f^^HtMq&k2)^mX~gA-H0qo z-ic=?X7RfsfJJScQ>6M*9tn!Wi(H|TI4AcR(LtApbI|#fUS(EmZbUE(SYT9Lro@ug zu|?`9n3U0XVB#iRUo`W&YdFnDE+Aq?;UXC>c49laj}K`^+zBbb91RQsJIsb@(ZSDw zYd78rAyrwG(|G~gpR+_&O07GY{T6Lt$LFDkaPkaj0}^sY`s z(SNO}xjlkB3Nxckn`H=z<7dpV%IOIkn)&`%!3FdFWRxqB_hviD$JlYCs%|9oYo1lE zYNSeYzv$4T`-6_)i*{J1MyT_=|Z_D$dVeUAC_mx0!Q#{g<4D#oZ#Ux@YZ!> z+yueFVeC4XKaa)2dzx43P{T6-EA>^uY81JvarYAO>ORm82_{-+OO_~|5pX(ubteCJ zW1k(%ii7@CN$~=7leJ$8M;EHINmIH_)rKI-Zb`^a7M4Zu{XE@{TWWG(ugK`2zZ)1C zz8*>cEO+JD%-TQG_Rir(H^s2<>9Tjul{;OiH@(U?GGBepqm#iNQGE1N$*z93=Rj^5$u=V1lCf|T_vmJA*KDj-7^1`wUS&FqSH{CKQhe?5 ztOwRzT1*bEgXn-XgWTG8o^?#+vRpju`%}&~ATn8|Bm_HxN7K|Iu}vDn zYgxFjU75hf^y)PcI;%V7otMU|j~3T5=O26fWGJT@26ylx++6MW`>h@X6qmd;HZeYW z%_ak08}5J$>|QK%pPzivv0e0gKg9xGhFMZL$lcPI<5*4vCS+UKKSyRxEyg5u`*6b&C@EQe$|3g?-F-; zI2w`}z4XVp&yw;91BY{RU2PgR9;KE36bVMd@B4b?!{o>{>s$>68Z4}`AA#=TWFgY= zk37lu9nQhuU&Q5!)G-z<7CrjreIeHuF`{XIsa7Pm|M@`ZNa$LShU+T&;G zZ^aGsQPWsd|LhwRc<_6ZH3>cFD$io7=MYf;^mXEK^hWe^vl+Py#WTIQk)qmyKH|6o z#iIl#{GFniay4W`wJZ2F|Lj-8ZkpVvl4o{qlC24-IaXS3ai)W1#Q7esW-*WR zCi@lEpS9TAE&M&zQMJ~pwKdE!QaV7!PSR^`&12(6;1Ho;58i9+`6X!_8XVmyu?=LI zR(lYVXZ;f+2uucJAmWPZgIH`2)bSE8!=; zuWOkQym1{~UGi-8l+vK$1LvYj`4PzU1V#Cc^K2xlX>6}gts+PME)>YWRD|a~kx4!q zeyqUmBhIEJ%%bNWn|pN;QFCcMKmW`HY2OCYQ}EeQSP1=ffsYoEZpyH(i@wvfucv76 z#~1h;P)gn@Hoe2-rhakd>MMCjNkL_#1X|+Iq#?7LOoL74gfwxtJ{8p{O-Vd?8DcZC*J(Ob7Kq9Q9ag0AI&~@Z=vq`!HIqBaGYj~ z$fimoG>wsq2?4OJ#;$x1>DX?C#I7zv> zN{%J7<2@HqGiIL0Y1W!sZ_G^WNEx?*NeAOkAKlvg#$0 zD{@fjNzGWq$G=p`hM00eAp7fGD|0w3_l*U&WB%*nUni#bds%5rbhIiUCq6G&(*eAXiZXfPwYMk$h9rW@t;HD};j?0%Y;rbKL1tG(Fp$ey3h=S(!dhIC^ld@mRsU ztPP_vu{YNC?a6TNu-=?*`w>OU>Z}JHBKu3KK>t(G?g7W^Cyxk_v{TRqn~@RN_A~aB z1`oDSRG*=#x+rBCo?h_w!fs(tjNNB{cQr;>Lip~leoE=KP;I{{eUjQZ6_h_(90P z!Qmi9A7QM(kLUVO!UeA1HkL0=i?*EqJXN;L6Nz5Um-*~CvU9|2Q5o1t~UJImYEczeh7~1km)P#wdcoS?mV_cz31y$1g!#d|_eFKM7-B98%HD z*QzOBJKtBm@S?W3D8)vMIjyEbBuINlAL2QEV}E-tnrkrVk#0j-OkzIDeeHre#i2N~ zC6F@%4@xz+zpg*EA^y{x$eKOQB;r25X0zA9$AAb`(i}3@588DR+23^m0pRQE_tdhq z6a0YK;iX1*ei^yMWY*mfo+36Jb_ZjBP!@`1=^21nIh<}VUG(W+Xxl?Z8^OMCaX{}ev)E#E2*i?l0A4+g^ z6W5>8GV=w8pD2V?cnef>Ue`0j^p^o&cM@}dwh;ax!4;tf?zLVnr8&H%}{GX zSyj^n?XO8M05+@)vdaN8<=aqEYvh9PX-Z;zGA#&(>D1hIY6l-H*#357HMM50Mtq`5 zH6*i*6!keHbxM)G0C=$d=VLd;7&%P3%%3rbg2?S@5jAck4j2Bo0p0u9xY=J5G_Oqt zMpQQt`a1%3Z zaEkfySdwYc^9hpTV)r>!gM*+9%rj&x89a!kXnKyAcq#&xfv2sDeU!S;Bt{?2e<*R3 z`s)KgYjMtRxJMgzCW;S_wp?DPf!bX?oKuh?7)Q$xCfUg#g6eKB=1GcDccc)#LSNGFnuEnQ2&ngFs?jk!g-MUuI8FmLct1(Samn zwl%WMb_F*2fv5QlkI!m>QG>)6pFIOUj(0uL8!mve&f60%%X2f8kp8&1hw);*<}LYs z-?80BhozE)juJwP@F?gqFHlW5f*$!LQ-qNFR^!kfVorBe0oa@`^D&Ro7=fpRw$j2*=WWIx0Cr2aFW@uw=J?@sZ(#` zlIT)6UEw@iexjhKe7_2@A^G(fJ{2db`yKj?G!iaCwLzu?gw0;zLa zZW!}E%RaDoO!K)#gG+Itqp=RG)gD_2B`;HxVLUgX9wt?`+mk)X=y#iw2;&uD%))E2 z#Z|u`Arc66A|b;E+{3F0bBaW&azs>}QrLWo`7fXdUiN!T>2ZaWtYa`IMH1U=Ue}bN zLNdvr@(=KBD%Y>sdX7rJDgt|7WVNkx9|jZZyhjEAZT&%CEsy^}5(M;fGJ5l!kpWA|^`!kc-haM{A}_HRh{(U6yi< zpk*{JD|aVLhc+k4!D^}_Wtt83^{}e;QPITM`@1&S`wQ1yoAuwO3UYe&ABsx_meq6` zo8w*fxW8$;9az_$%*=mU-_2kSQrgY)zCqe~?S$eq3b3)2WS20~gM~%G`UX<>ExIn<8B(g4$?>AkiA{-RaEJ=w^TQg$?YM}c5J&#uvK=u#xCh(!U$H^Tg9z2!otlN zKN~qcDF|@-j($P@&Y|MOF<&JmuVa`?EDG)1+_?+ zkk3(VvD*ZHft)RNQB9WF8g~j?;65_%IRpsw7(JGvN>hm_E2V!1G z{v6RnT&c5^-Cv?JpUWE?U8-orU$QVKZz$CR?03i{p1?$i)ooZiwy&-y83vEOq4!H3 zM8D-a$^hoz*6*4*=;9CWbbkp@W-4_>Nq%v_cc==Qr2LuMgrE|+!D``qsLaFIzcR7O}w%lV(F6obV;O5NJIU z65{THZ?^+WgZCV#*Yz`E_*nDjlu+_}X_&{{cvYbc7rK0j-(%B`=YN$u7al1m)$*9o zjnvUZ?O8iYCX2ls<3cH0Zk%uTU97PM6gYl!Ej!&haN5`(Gia}pnEM!*8g@u=$$v1N zwxmV*pvx6iiUYCV*D0}w&fUhCGv*#5$3>w;T#eEQbLl^0xhZRAabwiSy}7SK$9_v+ z^82uKR-)*mpZ)PyQoTEkzG~GDmR!dmh3vM8@FLdM`f+_DKL4uDYN2x{l{C0`k&Y)N{QY0X8SJhI~O6y6f+?|C5jH z==^Bu1$o)>hZsfo*@N4$;e8-N*JW>f#v|MJc#8j--BcBN3{;0a)vBY(N#>TJSFM`H zd^dI3qwCCN%lGkKj3({-7ZH&OoqbeHyCN}>LrLMr9cn7klOj#4sm&Hk2wrX*WfD(% zy?q+2XGcBqJjc`=3s;Mw^?H}%8o%>c3|f0oiihymNSk|(w9zN^({P-a@pBw?9dFwX<1>%j3&yXLbqFA^IJQ+x(tqjtDzdi*7ZXkhL0vD(sG<%zm5E zRZK{MH7oD;XcEE^FZlWU$1K#gvPUS#f^h>7uF7lYVcVT^^zVRVU}<|RUoXd?w0|3c!)5#z2y&P{yyp9I6 z&TmT5>Uo1+-%ZAlTIDG&w{5+~=934UC(+K9s&$#Hgy{vpDKFo-wQU~NxMkWxpbZLY zT;-V!gJrYGrDRizy}4=Ext43#n3q?nsH2-hgDQj0M4QU%MKsroj@>@z{aMUfNy8QvK-_O$p%_~N{+@c{?pG$mf0Xw}GH|tp5x{4R-irwk#awkhg!9nm@ z7Kk01UL!z|-ol|<;Ti(o)`GMPbBTAcY=d4qFMjZ8wyn>~4t=^f%c>x!28T%5Z-&eiX|S0{Q2iYfS#FUMZbu3S07s8sh^G22aFf%mNHCxE+V!V@J zxuV~iA=kJW+v)Q1u3}=ZKB7jswPY0)xVUI)$5Ka$!>sR>ot+m|9H|byV;{nUqH>~I zWjZXpCU$|^K2diWMjtCYEbVa3c{PJox02}fi~FLb$_!PP|9Vq#o)(r?WN)RznQ}&G zIn&%0G+BTzM;ues;MCcVd(h!M?U~Mh@8gwee?Nd`12UM1*L$UWm#v&;5j6qeo&Y!) zZ*lm_=2itV!t0E=(P4_Wn5-qr;$IG zyMimzp*I{FU{wprlKnnOF00GyIL#R{>N}(R$UV~R60Xnjdg61E;aZ%lLy;6;8rSf>6rR}aY?z$~x-ZDhfaI1pS z>_euZ_Dd#VX+F(1u9S?%JJI~Z7q8+<+<{PqJ= zP|rGkiFyIZV%CK^3z!P(iH#VY^%i{>ByWqQ^TGCa+RdBXW5sM;j}X2JK|c>AC$aSs zEBdNjoloz7ySmA^Qv0E_0!@?2|07xI@_Ow7kpeh4=tFlwDp)qM^T)s z%s5d-DKxT6`4ThPM`hVHa^7Lns1sptmM?HwciY6pyRIAXVp-Su`m4 z3yKPhK))Dk!?@DL4kNZk+G`5Lm5XE^x9_#1gYqkm+9z{gd|5dUq!gR0DwDx3$*#9A zAt}r~44J~rcnfJ}P7_>SD)pJg3r2yEPuHv_GaZSetFm8 zc}N;(hs)N&cqRa~`&x2G3dwGJI)9{h%>^&@RC1#lW79YA&MC;D2UK*~4Fql$pW4*Q zjxG0}!#XPH&8N;cN-O6h$K>n_S5R7(JIQ0fyAda)8b6aV!D)yppOO2(@>C%c#F2Xj zV;!3UjzN}9!F*rSL!M@_&KcQ_=pO8SZLm&$hdgj`n+-Ty)YX_q3|x?zm3<|pTH)YK z*pWi~LVOGhmz??vgMSHYPgOzEZ>&}j2L9^05gsj9p zEaYR7Q*Yra>c!!Yy0#Imsy^CQzGY6x^=oeohl^i%ZeLFnmlr*JHtM|t82TyFmTuOl zMAnT*`T_HkjdIrs0`hvAq1~>8!~0tl<h)rSQpe{+sNgD9K@=wQY>|KSs~_Vnss$or7h5m-j%M~^z`_9IB7Ga zI`156m}jj}z2pNA;Vgg*AecJ+E9c!({h)DN%Y=F_XsN&H|yRYpe-x?X!3 zfkjx4M|=?TzS(k8gO2G^B6u+HVjr-hBWbT0@w7|CHQQj-ws!B@sPD!gu~=?4B<~)o z8<$|2A-_KtcjGC3ie+SpI?bA3F}w*XSoZM`EwI`qmWBJptJ3{5LfQSM0W>{~*LOgQ zgm7WZWo#YD7A@%8cnlpD3HJB4nXq}#1l!`1#g;|FKW0K1t#n<2yY`s^F|!1lEv;sP zyoahS!NN*6Z)g_Wp9@~v^Mk%*fAK;Lr8(ou-A$AI(#?2x{tNXgEWE7Z=Y^C=mU9|% zjrY80ymL3|`(>^UygFyXmtkamoQ)R}uu7{;ALDyr*KfJmRTYcP!KA-k``b=7bU0T8 zO&0GD1?~Mvy`T(n@K5#t5uw&4?uU*b^L(mZ6u#>{8?Wt=Ue1I3CYDU41kT?kxBF;? z2SztqaplkU2v7>~JT@)HXr>2EZJh7e9G#z>6s+d* z*x1KNjnQyYJn#7&XI?w^`lhds&-#Fo_acH0G7!PTdQOG$!lL8;&S*sbO?wAxV3eeH z{J^rRZv98c4B9poAo$FH*C&KIt>N3oXcnYYqwLut3bz2Z+Ag2kuE?F&>5gT&PH2Nc z1j+?qqA#gaTM||NezvbDeztfKe|O5a)aCGfGI^argZxaPn?vKg018dJz#xlk5YB1`7(G%erguRBItTPxS_FGfi1Wl+roNb$!Cx`FZF4 zd^0nBYB$H1;sn^T#-~aa3sc|(a^2L(JRup`8R*9>25=oLgL%cWF{B^_o8_A*)yI z=;9xbTn~HUeK&pYVEN4AmrC1xaz8QIU2z?b4c`&)S9x)hr+2$TB2B>r%wwUhO79Xhc9Q^nL&aaaN989$Y`GYWXH^GRJ4^u(}ugSD0N=y--cNg2&?Xpxe4kj1eSZc6YEk%Q< zWW`?gdG0UO-Evk=k=0wfj5SvQ5$(>%2E#8wz1=7i#(JeQ&?&RyXR8P0&P@PfYHl~` z2hL~VORjpK*nTEi$Jp9OeF>hlzGDMM%1#VhHeN|eb3v?(>W;%s>MO(AIU!3sj9sHz zRZu)$ci%w-_+g}zp6T`Ls3Wgd*7Fxo7@o?{Ww*+Mb<}$5d3pr#H}uPm=LQwr6Rvx> z?b_~4Yp*~LZGTnit36xf2hf>~iuAm>mGjs(O}{wsVhOdHo5?jn()2?eQvw8J@h;&)oJ2aCEpe&_ozSajgi=Na9#Uz=L_Ry@*wPrN#)gw9ENjh)|ve+6gLnSe_JO@nfs_6bTyLKQH=BA;(=SxO5eAyIt{aC-nD2 z03=V6^O*yP4j8XY&7kfH10o5&FLqHb48D%83;05yDqiQ)S1fyia!zCUzIrxX`o->r ztNGfClO;&buXdV(Qs768+VERJeYX{-_NckG?Aw)yZglK-XBt32lq9sP*fFEPS5tlA ziTPN{HXqwEXu@c)7?4@rJkJw36;q-aUcR5t43IT7?r1&lqV{qz*3)-|uJi*Fu4J4X zQ#Zd!saI+Zokz0i;rSjCJR*nzh%$y9mqW5#)8+IC$|&Fl$S{5CmzWw|cOXi9&(p7} z6wX&L*3PlK1Q?LA=vIirIax@^-neKw7OGsDN-1_*zb&tKn8a_{m}Q;o$SN<*kRtYh z+MXvmT`bum<0wpOCz@5{MM=vF$PoepnUNYS^NI zeX!gO#`;Qpyj*S0PbITcA@7#nH2E72N@oig6Ts&I8l<;gzQ#zPuO|E!T2fNdQ;-1r z8ZTuqzHEvxOFHP}6?LtyF#S`V@2_qwRh^6}C+gnTYJq2C{WId$bgQfoSd z?{&U>|5aqD^@D_EQMo>o=T>0%Ft=0* z#{xheA}r-oprRVuLupvLuWvhoig+3Q7E!Sew({|GEyGpa6}|Q1@~_i_9rco=wTve* z>+FAZsM%+|cdrr7EkhHi3Dt8x*Y{9Nwuh2TC*0{1$0P`u@3N)8v#U!iorSfaX~5Fi zlVLp!X!`@pylLyTeIPSc6x(*6x`{yZv;Ij&hD%P?V=&@ zg2mx249AvlqB)W}qd>fQU3c>=*`V&qY02r{2HooinnB01L>O}mH}wTA8}+QVcuf1X3F2zc%oUJm1Z}7v*>Nn52Zj&o+zFBRy z*;Oj&7_S+m+Of9PH5Lt^L%)^+dd_`Wu6;j(Lx=F+`Ypr{8LnaPdjEFDPiDsL^;M3Z z{GwTRa}Bs{FzK`!=8lwSLWYuA(B6L2DA&=7$>QG?n`-x|_b58AX93L&o{l>Tx|DX4 z$~LZIe?u9JneJ%*zNd#Oq~#qF(Mk41Xni-C-~VNWKO`^%eveLk!TDoPpqSb4(atI~ zbi_1Gdun3VvP))L^D||&+M-S?8ut$7jfLK`59xb2h4XX!Mwjb!FihppAN-DkWEG1( zb#u$T6D{?e3Way@J2ffW>|{dmI9)bS(|N3$%JpWe4t-n?t(RLYf_N*7lWOg?dF>Ll zDzP>Ai-7D1(YJM2U{v)QvX#??@{^>)bx~qdoaeSpopU=%obx=tse((reI{3rm{>#n zJ)j8h>36Nh#hh?XIqOy*QdMI{P5EX%nO5hF#g{JBr(;QMiR6LzO%JRLAC6E#5*q> zO1?81Sqj2s`Tzj3Mtex z(CwxxqoFW?E5ViDM>NbC&?Iy-ABnU&Thu zr~>kNtb)F=vyRpb0IJDQC)Tls;u;OH)gbfjB2~AVHH>mLmA`@@V8rN?%q16u59evw z0lQ=lB5_P@uPNs61-afl4w-IVm&)7ox|iKKP^9VV``y&IR|vGA?3Yf;h$)W#=YI0-VmDq)YJ0MvMtJbw;1C zvQNUNZ)KK;bDx4E!4wHzy~l~!?p$%6%ih#Lv-AFr$niiNG+$@7C-i|*J=F#{L8U+i zyL1lXdE{mosi%g*GTP|{{tWyQ?GC^ zPc$pcfT~5_KG^hM{ve!V#rYRm!Ehy!CJmIr3#Bl8A$+H{=V2iCM>p$r$Mo^RJ?*Q{;`I10GBFXvfNy3}V=ssA=T|C!T+>DkFN*hjT<)}qkX zsSVLK*-sX*E3dbyLifR_E`L6$jO!nSLd~2J?Xjmt_0=1BzGb#i#nmP9` zdL)b$rqRZKETZOX208>B09-FRO5s22MSzQUS<)U-%Y&DK5E3Yu52qNd^~W@T2fTYj z*dLZI4u%V93f9&rK^|iHBz_L+;JCkBJR_+8Wv*0N%#hj&NnS_5isDDOBh_g>i zg^A*#V8z;N(>4Thl9^Ux5lQr7(Sx4UMA>S!>E}7tL5H-{l9GEB@Hc4`F8_;rWO+bx zYAVKCeMMwr1U;9m{|Dg#>&!BFrsSPBXPOVr%x>eUM-4ME#3wrjHZ!wtvaORDCZvj3 zpEmCaGlrBWx>U`~jB4vhT9abd=Hr&RE-}{VQ+BKS)6It0IKuHp@DvouZm;H8YPzS0%SQ_8W=yxmK;I;<+@Z^|W$s#2l5(8H|4Wc6 zth%#oOp09q@!5U77OY|fJ>T@MjgySoY4PoD7Yb-vJ%m8JRyg=nyDW97rxo)-=uZ1N zH~^|b;9s+78?`W1_pQ7PVmxC(eB@CT#g>&!yF6$xyTlmgs=A z3n+aFr}H_+$v^&ke!pN2AS=mW$EVL0;y&*9#wiLiFwo+ zGF%Xkjz=S0+z9_59*aAU!Ww03AIfRTS#D zwc1PNw?6`dCdH0RPH?b6^Mb6ElWaw6TMFAx2sCso(FzA0N_6xPS6_l;CX4p)iu-r< zf7GklZ-t33Vma<0a7UUKk%{G4fbY7gruwM(UXd~&(BLQ(OX#SpClUcDg~hou!E6db zU4Uf(8W^?xXQ}iV#{J_7YamcQEb_;L<1{K~9wxL0vTlfENt7fQH&H>90j+U#{Vq#r zk4szG-=Z}5uT_bIT9{S%w|+=K7Nf%gHQ<&e%h9vo9Rg&9!o;^A+^!@`62}~sIe$T} z#aaP4Sac+~70%)r@nrs?<1kf^z<~R=jqnv95}C- zd{0Jl1X;TG`>pC`Z4&R#a(o{mB!d=f$^sYV5-Nm;S%+XXIIt4EEW+&VX(s(-<#G_ml4~PH zd&R+o%OA9P!2NHiAc_7eX&&Zy@WDVM!AH{4ky42Z@c-fnvJA7gyt5e^wUS78&Z>p= znzDmz!K369A(SjuaMSaL9kf@cr`N?Plo5V&MPXO&CBHB#Da99lFkFHr@g2-9KT%?3 zg50$=>>PsJqmUC6BE07$-7E^>`$SuIR|DEgV+4N+RPrTM{ssno32^!!(O3XDjYP^$ zi8$87Dx1LFS0gDAU$9L3g3O@^{^I1La}YB1p8;2$BH^Iy^vJ8-nr1!-V}c0R$TcMI zDqQFV!k`0D$V9!#hYm5nd{Oal!-EgJUBau3DE19I49wrNC)o=&^D}&5V#FUaq=0r(yS48xwjUviW zWUM~YR#jCURr?(crtf>1Q=jS@gOWkTqiwhw# zCV=Eb)#E~Mkp`LU|CVshC$EOh|=W0XO|~&?L|^Ub2Ss;7XAB9`sS&q=NFL&FTN_ zLDZquc94;FXOIFChO8?b2u!4m;Iv&Z!~BpFupjJ}+80DJLl2O914VjAmOc|As3;jB zBuh7LDP%=fsFqh=QX&)8_z+Ck6`>sW16PFnE(rYZpC$K3=N1E82?t`>SdS!gR)bZ` z^N>FTeS2$S1*#Y`=G#81;jcUrh+>9b2!zAA8430!FiB7xN&J0hmb7(V?b?wpWLtS4 z(;G`P1S3C}py&-tU3diYvdw^V67q*=A>Bla6aV7B(cb1l^B?KmzXOWa9_L=yooLLb z^aBJo%fNj!=XK*9?4sl6V^TY_>D9G^C@5PCIfyylt<}fxJE(tk^2mYn;6-S=7}Gs& zYP3mRASrD20!i8R0FwdnL6caq&SA*EKwwk@Cle-=gc5`!^7tent_dDtTX-N=G;I*AWy@IOD7=F7ax6Jg(v%YluA6H z6v_7MYl0|_1%UtjnQ(H5AnNMsR;uy#X+&0fQvb}BP4O?@kOI(DGO&_Y`kU3Fs0 zD!n2&(2$cJ2jf5VEcyU`@yg?j!xcL$&X4g&AF`@mxF0eoui)#8f>6EO&UY8#{~Ewor8NNsJ z)FbQ@*ooplF@eiKJ@4aQR~V#Wo_jMxRVy&Yqc$79u(?;!a!`GBvZ-@_cT074cMh|I z9kd+U8eC5#KP!;tEY~`Arpdq`Q{sQ1flvuz7I5d`b$d3uk7jTwQZfsaCq&XTNng#6 z`I?z$ID|N$zx{g_1t>osv<8(NAuUDvm+js}`A;k99l;9nlnbF~W9^1}b6;KiN!{L8 z>bFrYVsp7yCG#Hl;O<)+z_q_P<&l-Wjg;BzUQ1l7wRh!FeIT`rj2~-!W!rh$S1n~& zmXJ#N^LARy7r^UpcUNNo)S;i0?(}b79l?@n;Yz@#_CctYmZ8cRq?NwcpT*lnmI^9u zUmf`Z*$_?F1 zP*nh($gRclQIMUg#VGzbB*aVn;OO_(z$bZ?>$l^`t27kYqq;IxUoN~HD$-`k?9;$B zv3Vi8I7K|Ty|x`?Hs5?t(wARwTQs}unjw*USKV$&3RZ(V2P3_i(XpE+^V&1gH1Mh0 zZ#@}xy;@J!>F~X^8BAa}IDBU_2L|JNS@-M!czP$n*ONT*+ak1n3Oa=<>w)I6ie$VeQhK2o-vLvagqQKP`IDm%FR7HMw6negu z7t;(J{>TgUS;ft+BER{G1k0SAlfT)k8H3*6F5h!2yMkRPSqw0j5^a2s>rWx$Il`PD zzGJm)W_j)DEMF%PUtFK<>H!s51Ibciw>B>9pAF5*5unoT13GP2K-?F3V$s5T1R1 zl`SWL3Hm%B`i2Gm^^oW0k(BiF)LFpd9Cd+eHG^GPY@F=+yT<=-dPXmEc$dmd%y z-5s2LzpV&Fv=Xca0XJ*p5`tngMni|yLoBW{TITa^?I)xSF`wnL_~r%9zs5BABrm78 z9rqC*9L^Km{!Z?2hF5Pup>@`aOOe(yGc(O67f@?f_>N|Wm3g+0>+N>O{q5oYkilIw z|JjtP>tWjk)Bw1@*5o~GJy{@oV-P)w_ex{#qWyy3>!&}G&2)*nZJFTJfTGRDaO!z4 ztM89}S%I@+#imFd50yuXSe^}Sr_i%j9; zG0y@#3R*_%X7#Ok_o@P;NVq53)Ueex!AlVgt_C%A$-};Oz!wh}mT%$9_w}Nf{I&n5 zsp|}DYU#R&D4{3x-a=Odl@fXfX`w2J7@7qIrAv@vR3IftKh)S~n8d~Tb0RYImVNj*;Cfud#yd)!JID8W4_bP5qFtG_qPM&Tv2bimmz7P zd%t`_83j~F!QsF8ST&$##6s&^k{4;F9ocqGkXv4e++{RT?UTqfOPA(9kf*Y>*~(1@ zUkconYxtFJ+IRS9Fr?#ZiegJyIMb2*+h_)^FXqbM<{F{2ot*auxFxE@V4AMmjr*(1 z=bOYJ_S=L0W>_Pn|J(-0I+!hQX`#ixXi{9ne9cl$Y@w)P^$u~#w=<=t|kBY0)h#v*`O9`dY@2ln7MAnZm8 zYV|485xXwuON{3Ff>ir?Z3Jhbj6vm@PKIpu?}g@KMrMG(zdo%n8;xz;cI)*#jo`Oz zCrO{?#6P~hb7dz>u5q_m06iTsAm2Q~3S+V0rD+3xFFPR%H&0 z8v&VF=j5z07Z|74!gk&RtMlSTL*(rV!=!ex;^&!Va*XI>_?YdRyjqW7W|K zOf8VQM#Mn7p1UBN@HWwt^|KgxMgFrGPe}O1u1sG8#5UJT#5hnTv=MndvjG|`ny2fn zT7Pu7&zIVqz`=KzW+dnnor#~u7GiJ81dC5$YupN&!)S_LRmW)GKO`@{*We9S1hbw; zp|zc&HA#?WAYUU`6&D9aSXEqDz3li+LwY%ol4jY{+bP(msPFUk{PrOV`BO%7Y)F_p z%t%^4LGp#ys~i2kleK+9%nJOT*|Y5>`nFNtGt>+S4sz}9fyby`QN}*Qd zJ4rlKi|l#P@|Dxur23Id$;qLRE} zjI;}J*`}KW>B*X_@BE)>@e?^=Z1BYxzPsK>O%yv!R-l76+8;r=+Lk(Ug!oYJTj;ZZ z$!wBag6hpX*5|hM#{9vNXO#?JOx#H}K5*q}2>+h}ez({)zm62;7ZqU^(MN0i{xx#9 zY5GcL!%&j)D6t(3PxD zxI9rI26g()Vh+$sTfAxW#(;T*f#BajqA7&teO=N4^#eF%_+>TtO!o!PZCe+)yx1n3RGpHqeT4^4k*VSv2ox{>$Qw)q%jna--al^ ztK==<#f8}DI-VEN&1S_b(T%^J$f>aOJmr0><%;7%(miV0UwzM)H?t$q!V4wuUGtpd z7e8@j`O`~2eqEH+@C)+m+b9H+;Ru<{H`>NGoAp>%*xjSwJ6=O_!J2s{1PHE_qa@j| zO2mW>_WiLv)c7((+YQ17xtY~d$IF2Z7k%^=0O{oe$eZ!n5_D3XKVo~A*!+~m6?|WF zA-nJNm@1B=t4SLJvQq5oCs~k;F3Bz2&A}YR)V8^hi=`qH=?L{*14TQ8ctJmiLYH(+ z(cQ|Q)@hi+=$HjNP4lxtE&G@bHC*KJWpq(u0Xl9MUHzg*q}*DAIZn289Kfn>p^3mu z14c(LS>%up$*mk>wUuA#(#aVx@TK(H#s{1+=sbvB00Emqf(nQmMnjz+nhy^#XPBo? zN10w#Hf~PvMx23uLB3yW+;>C`=Eto#8-zTm8rB{kjrDeJ$PPg9IFH$maPN2 z#<=zs__cQ>Ytu?NENs+`q|wXKfDJtgW+LQSPmm7Q#hb&YGPy zUuLI_&AeRJ-?8~*V=&e&K5c*~e>?jVi|)#g4k>BjrL)@B<#GzC-puzropjlo5ryc_ zLiLRS1;PbVw|aOzF!)zHcY0hwsdw5ls=n+K6r_nm&TU0{nPg_&k8jx|52gBWMM?mU)&mRLH@;MTRh>k7mm&g#xNXuG3qbGf-q`wG{o_0_Vtv z8yJ3BOObl*om07FmsvFT?yT~?yW_LGYC@IIE3Up*oqv4E6R=w7s)op*Q;3hYHhSf} z?AV{yA98Em9bdon95_uq$D=b>{_tDrSy)f~qB{5aBymW1( zC9xOzS+{Hm(kg+wtoP^AjNV0>L+&dOdX2ZuA+#r+K;$GZBiakrky|@Vh8xwLg3FDQ ztoLCd65h*{vs>{U`xq zG3%QUN1t|%iiD~eu})4kr9I&k)-lN+`$I)~%Q#}RO*wPMm_pBZ@xY@A!zuDW;6@Cb z<9_82{03axo--({!R1OA{PYn_TI|K$Bs^0*t=ak`hr?6$_3*x8S$M9#lCh?mnUe9m zCQc@Fjyy>Mu>Rvq6p+0Fg2BdISMX5ZXHmCrU}jDH)Ov{fJ`5b~JK2SQTDD$!2^A#+ zjaNYsbtYtr>)!3et)I11cS~vO=F&|QQ*0Wmk3?&w2DlL=Rg3YWd7`4P273eab%xp* zG8>He3DU6eL?#@UKkd}`bKlTygSn*ZFWqZ;f%v13(VR#ar0a(^EVDB7r$<_4pIvpe zTPJTj0x#cuGMk^V#SunMPVlXEB)%R$EOyLw^J!Tq(osCGYYVd{C?#qT%*n7+y%Jld zW6(-fK~~6lbPJKkh;Y-_eO+9N8`+20e0lv@htOC+cWw3+|EJFyK{o_=?kSOm9UCtxeQ`!*5p*NH z-9*hWQ!;WPs7&>Q^^oiQ{oh*EXMxYtZd4zX$DXomR9n-XyDex{!PPk~PXh(i0#`jt zj8g8^yIf{iXdnC8E7vr^bMduQ@tLNtReswlDa`8Y+JP4QzFi_6P0z0d#Q00qkQLc~$2myy8HbU!Qk-YHBgOnaP129AA|gW8&;VZdbF6cv zO)ga~xG1q79D{$px$C9(?PPpk&7$^c11(n;J&~(z)^d3@W5oLy@+-M%dj-aAV{DxH zXXoz%o&0`@BJMSn+M{Aj+$YK}1RDy_9Ib-ppAnAY4DV=1MKth_Uab87{gtA__p_!#LiY@%LyN3uj#JD{nrr_E*>7-sAFCp@30 z$N6mWJrz>#Ks!&TwXq1fz-v|cXU_U{yv$jjaMn}re!0ZC@Xkj_FIsh?HSITSeQ(_&#~UqOYWrU2)(oDan6}aSkDo~8Kx>&xM)+>K-b0!X zw;z~>XGu^?$jz^Qd#?tkvO2+nbO6^pFsPw_hOhCq@0w*7wlbUhxNX%AlSM%J=go5l zbNah_b#o=GO)9AGA(!V2uw6z2g7hjRtEga@UPO$uo|bL?;uPKIn|;{$mda}Lmk_7B zkKmEg1Tj$=;%Tflpd+^=HFM3;ZT55Av2dLjNm&nqSF$&Mn8)OE<)v}Lz@wBaHy;N) z3_fgmC^w3Ge9vKia+)^?Mcq!1F!kKeW^rkw>5N|?rZ4lQY0MpPe z7`+T$gFXtZG51)DaX z&Grm>FMVAx(nC=(HVYH=@b&BsLG2dD67($*{0Y9*v9fitZ~DxhxggiZwROd2uA^oT z28+`G)1Jqf&SyuiL*oMB@)yuAy;>>-(b2?{19mLxu+T}p z=~TY=(w0xUnA1TsJ`JDczbInt9IXbk6r`6-l$iL1{AmAUH)(Bd=4e z^W<2hx3h2Px};nGm^W$R6mvZvnW+5sVP1k%*tdW&m9z&3Nqs4m!XZp9FB-|gao+BZ zzlh1Td=;x=2@*7dl`8R{QiCzBfPAU`bZ@*DI^0TxrQ}i4Db%$IHTCS>o+yU*UYf@O zLt9`p&zH^-_`S8-s};8vHwsbGeU0v1zx$Mg zY+h}Kqc`TdSFiR3r>S3_SA|VgC$^N5NT(jWl9^@|}#Y>)$2TxbxThWLNlkHw{~^ zf-ykf zEYa0>fOuoYPmkt=l{yJ>S#s@o2jAT`w0knY%DGDKCB04yt>6Ax$5YK&gRWAdeOwRY zt$tqdBS`0R2z^=_6j>AIJHPkD_4VM?k4?|iO=@^PAOA5n60@EVY&hX9W;T6F!Rf@C z>2iGzBuu&+2sX*5uY)lspG}HL3hybXtMR+TcwH$1TZj3$FUO^V`+LC)IDn0*;AF^QAM$;fLa0Vote@v#qB1tg&hB z2h)AXk$2yn@lCPP@}Ab_N;b=9UOl12)W;|28UH&9h;6#**Q`~_+$<}o9H<07lip~R zcmQ%VdnTk#x8c1S$qPeTeb$0f#Mha>0`7pmW(Z9&1c$$ZHcEdOxpQ1-2rYE5RS5(T zgo%zJD_cqOr}g31!>LDfq$DhqMyyyal5opj4WqylGTQcV+D&du(xi2fEZW}@wD@?@ z7l6X6M2nGmh!3F?vsXXbCTvh<9669*k2rWprPIkV>hZq5xHmDEby8k6;_|} zB_`73j6D0=pO)}uDenJzktwcDN zY3gzbKDIUNa2r;htY>EvE2eo5w>MDAGRX`KV&7+UNl(ccw+mQg4N2u)KHy-{^%TJYe)+E1PZ;+lmgBh6*~yDPVx7^A91wcQG6wWw2% z=de7ff6FTP9H9m!ws-ED+^M-P6ELrEmlENJ7!^)L+vIIj73@;=by|9w@ox^v*&c~a z@Mg_gRYP!-Wz0yZ4*j4Z{)~GxJ&s&Ru2NT04@oj=m&5>xoEH%W2W?+zQcTsYLN!f< zHeyA(C8Wm3r&EWx^n^$$F(2Y}QoO&|p0Y)>4;eCUG3oJIDJ$2~PU5g1TB@sItzX%^ zK2I2yA6G(qX0IO>%3gWf$Fs)0jZIM4Yc7lB@ZgznB<+wfBNHBJ{EvWf{0uQ%SvuD> zXKJomx*2F4Q&x{qk*KB4<4TSaYz&)i-HqxVA+Z+w@k3fLUy$hPe(b#;q6}BQa z&yZ{Qy`|^5N%nCYXLi;`<+mTDRCFh0w*bqj7dY@x*z6xmwsVScsp<++dseyJ{I&9V zBuK^8=>xt$Th1VAvG)cIOp!jTW3{mgtoyaOPLNL1ML%TKh;Eq8wMbJ4ShDSGVR%8d zmJ;5DAMEe5t#RO=lj;l|S(M~nZ=B^R%3O%H(S%r5k1K0t&k}o$g7y-h6ORE)C4)0d zHoyO7NGUl&UK-bKpCu+gb&>8h9#8I;kgJ1=k&A-`Yc!`FxKnJB;d1O`6*@XeJRM1P z9D2H5P&VG%#0eAq>X@!~8`TceVCPfc2fqBGqAE|_ApvNhM*4O+hfE&pC853_Cm0yL zbg5lt`A~3d-J~DeB+!C)NlHo@3R6;S>9`TYH~#}yaPMgP0T@Qa(RPGbPWRP5e8HA0 z*>;m~tO2rI37eSM3yzyzuh>e$-|SCESRrq*;97Xl8(jYX;sCp3VAVP=9a2~d?<*@WB0Dx;C>^GZd<8F47mIlj;f~Geu-^@7`l8=J0>+jOVR z!Y75Vb|=|BxxnhQl6xCmr0lHD@VQ(rq+bFb z=>Hrxk#yTzpH|0YMcf=8KkMDWz#(UevEJK8m4oPkuqwr9fEC-k;ij!=-R5si1qRFg z*2F=VO{Z9BikA&Z!t`_Trf6$k?_rnB+mnB*8}=I991GkAf>Qx@-v)(2Q0Jj=YuN!j zQ(PeIqInCOqFdzmp}$TRSz|F|P2P>_G1<2HEm$h9C}@$l$jyy@I&TSU(e(ZgGwdXFPmyiUKYufqvkI`^|w=8i2fv#|>njib)3a88z-YN~vf94L;;Xo=Z1^eF-_ zd;fT}R_d3>DU)|jTX&gg!0mXKD1$fM4d(4o7jb|j+C~B%r{xwo>>P>e;_Ga!R&o(Lz@K_h7@LD9;cnRoer2|L#cw2h-} zXiOOqj7C$wCoT!CCZ!soqx|-rw`FWIX1= zVPTEej}#QehM`|tn#Dr{b6ECoZhpvAHvUqymzd<}g`S>PY&HC#++hL%)I@74?Ng3f z?D9pPRhbNV;sP*FKxtf(oslR7hgF9eMZ%HWW;Eg_A3^-0D_zrOkUjZ*hf}r!ub-!ml*R&|9ibk$n>J9BE7uC*>iO0- z`0t!6k=a>#)ZORMpc@Xvm!iJoH+oJj7wr;~L#Dy(U(hz|_D`)sQgue4#$*QmYaCUx zT8d~ieiND%;&MT^gnYrY0F@noJ2nqJ6Ia0+T4h;O&{wIgdy zucE*ogl!;7{dyLyJ@XUm-qZQoc`01VuZsg&{k1EN9#}9Q2b#RtH{SgkHvL9>QL}IO zz>no2=I#ELiy6A{B!jU5ad^D4hb#7Hx9ZinJ!9-&Fb;8L8$?67RlB_Nvq};hE>7Yf}O>#(h5-f|wOK-(;`Qmj%MQ z&K%Ql`UQkYFTQ_Y3MLItcyda$g?CapwSh?*;|vKNB3i6=kwK$l6AZJi`dW$f5Xo3> z<77#i<^_z6&8ws{{fdx=#$HdSM-&Y6tGX&X`7qd;q6{wVTYRq@A+T!M{j3= zp_YV5{_E)U8WDnJ=YD1qlP+9Pe$p9df6O2o*v%M{QF+y4}8jXy1Hbe%ueSJ010{Bjq*q&o6KM zP`#dK+$T#A%0`}kTA!*2(mRUvKA-V3vM(g4qghj7BJkp&U`d8W5zUQ5Nv&-P!2rL_S7&Zl0? zsfRr{bWwi5r^^HI^WUFgeG<^)d6t*xiJA2TdKOl^|8Ah}HY}%mYoXzW23z^dnWFeC zTEXH|b`}1)mjGYi>Y}#y@Y)`a#y4#x96FiiCkdzW8(;9%-@1GXbBn-6y3pP$#!SpS zT%TwTj^2+;k}f_=P}T^U@FLgu$yQbViK{sYmZ;##n#1)Nwz0I*U&8A zyjz(J8_h6Acs=mYa23#%UX#^VQa^;r!cx$*8?b(5VA3kYY`y_26-x^f8HSXhSxL-o z9fbzfde9cl%}0ZEDbdGinf=$q+MGlMc2he$oqPc{QWeOLs$+RYVHK6l)9;^=(?^J3 z%l}1-SKf>cJ>OjA*CmW{6fji598j`cSR*b>NwR#N%;U9hXB*ly7|im;$H5tJ z^N2WKJ~qK)7`b5dM@Y^?UZ8#&v4mF(NcKOjQnJ8sOi`j0PYHE(|4Nm=mqxU%Wpj`ZlQ=)9+P9|7Ptt%X#al>He53{v>lblpzK>J8xdCrYryX+QwR=;tl=j zmzbM~TOyFD>`_`D>*ywLInRHHGYP4yM$;32~@8J^%=wt z-5jWy3*j^UO}#i)Pix%HWX_=V>e%e`el(}O9N*ZHinYpVAfzmtm>O^HpxlsF$hF50R5`s27N-Bm@U zEe!Vg6C>fDNfwR3qcpXL_-myng!|6d)?K=5WLg{aN9w`ZMFAN_2G zLKCCUs6X@<_DnS{i9mP9JbGxMtqn2AhF|0H$*(f={d^Xq*`2L(=R?c7hq@)(uiBrWsYWRWb!un=Yl$nBqr77 zP`K>NjSEwJ2i?JOEdJ^V=*86XNcpfgKk00X|BgSaMt{0!;bKC*-2KM3&1JA~CQIiY zYTZ%KUPn6^B$-VtILZo8KjB1n>%?dSdgB5fLVaTonImQ@hOK2jq$@MCSmUYJz>+a1 zhsLq#Bit+o@!3ONw6SGoC`Vt|-ooZcnpT#2+^=YCOs7TK`w+=cboJP)1s8HTaWMP7zK-%k@gZUNH&>8nt z$IG;7SC?6o z+H?s!(t^7A4P~=EwWFxI9u7ejPL|8+W});6x(i^&e6RHt$H`LFLRD2J3ul^(c!0Dr z<971mJL02U-D7~yBa8dK2L0hZRn^V6>~5ByXzwoo=~PFWqu= zLB`$Y+ar%*Frop9K*d>9=2B0(5l+Qfh73~)PXrM&>8H@LC;0L+FxZ(Oz#uP zINN)MbV%5n5Gufwe?kEK?c8(Ka7n37*?xiDy^N zQcN%Nv-S$z>__m7nf`!7)YSGpni!Ci0FJj9Q#8kXf6$@{)AktTVj|57N^`$)K^nCx&>}6LR#$x zAgR9TB#upRV4T$4#x}x$W9MmEmK+Bwfh@!;k=;s?PfgV|cpD>a7Pve?I9SjNOIVbs zH)f!O;GcLc42GK8YpS>t)kF9E?MCThN*UJ4H@ls3zh3Zb22}SgL-j8uGRQg5rZj=; z_%ZI8P!r2Xqt^y_CNQn~C|LcrF4+AOte|q?2;lwkquVL zDbEGCeJ5M*>VX0m;)?%M$hCBBQy3Ctg}N?2LJw-}AVezb!BFOtI_M1F39N*9&K!+H zA}65(Xt)p`9?Q*ZMmsdh4Vs&<31&QQ*mcD%ZL}mok0k`Cf4$H=n@P+cWWHj$P`$(IZp8R|5xTxxBu#GOP6k4b3pc%bRYh zM+&xuO_ZXVUnzh0F+poKMLktV8mp{-TLZ#sCuhO35PnU_Bsem%|v4 z)f*5PLz&#SG~f=y0lz{%Y@VS0vdO;lyz`Iz!iPTqv~>)nqusxaD?ap|dEW=}(B7R~ zj&*+P(t1*|j0|>po_`}a-3A-GBA(?qLzw0|Y~0LW3lt5if72=$EUt|njm5PjG53ewxaV(;BmAIvV|I!%AY67 zhtfD=CUh6lPUTfN)(_7sJQ?B=J+~a6CGBD8CQC$~t#F>ad^oTe#RP`b7K*jUa=jXV z4A3dHS+8;(<~x>c0Eqs+5(_p;#uyr5!bV|oeG36?>^s^k(LK~!#`qN6*z)DRY_{#_ zWqR`pnQnV74$*yZJ8;fhQ$r0?YNbS_{aBRB?ctX2yuDFI^vMkChydoh*7#WYNaf{4K4~sz zKo4>RN)8-bq(M63A$7o?;DeY^;jkwUX#Sl@iut=WI2`T{{=qXE79mZbdY4pfYXL3_ z4&88>@7NsBOCJnaeu)s;qOyTO>Rlba(*~0=VT>?WF4A30;Vbegbv4G7I=Bm*AGTQcTQb;;oaT_ zMg5qvi+$+rAfk1T3DnLMmeTBMFBasA3tZrFas&|`I40K*j=x+l`g82%%eDW;fLrM!{7G-86gWi96ee0EgERCtUBMC@t zD@k+fHaBSx+9=(7Xn~ktgBm^io;(f8TrQP}s^{AH;`ZX#!7*r72U~r0iv7*)v5Lp< zKQSp!Sjr9UErU=Qq^J~&y8J3VovrBc@RWUY;XbHv>AI>mUfc%;f9IcJME-SAtxXY zl%WDt?z^D5pHYNCwlWze)1nl9UzddObnKHe0+cWYxHUXkkBz|m!w2pXi+Gq0s<;!z zx=QihU$UpUl^NE2;*BH?s)ya@(hVjwj}A7ket1!JryEEYAK3pzQCfhS9{H79s>nYf zbz$m=*U=*;y*|9huD1)xt>ztvkKsWPL+>@fm%IKP2F&@zZ`b<&KHH? znK;Q63h7YLo~(eMfyVWW%r%Yjw2OZNLLtU`s}H<$6kN9C!1YDhXf8oMr8A#@Zb&2ebS~^C zs5oNNs{|uvd-w`+xJ~vFPV4tG^BjflhjLDLDI$_ylF7iwW5-Ws`X~LXXxoK!J&a4a zKB3Vq@eD4LE4Hd;`a3TC5d|OvV!zeE4*mH#(8T|JWK*dG3)#=u{?#;6REj3>LVnzX zx30XEe*={N~A9< zNrwL^nbRltMna032>v&wPGh5gGK3WRg(UdO`T8@w5B|2+_8j=&0scPkdq~>_?Fa5| zm}eFG+Q8ptSxX9EkqDT3SNL!6H6N4=_Q_R)ul{dLz`y)p`=iX2_|32!|G(#!V#mPg z!CHs}rM6%`_P>vNp7xjaqSu`N`zDkNY=lpmt(Isij5083K=de>NBPqTP<>h|nP_icEhSA;m`hC$Qll!BFY)_cygqg7)rj7QIa` z3Z)p@XV}*1zb^hGJZA!x=6{6e|IF&tAnHG>xc|V~BNAjzfadki^9S$0`1g%L;KFvu zUoN)#cOb>Vx(N>5&vDfW+KHg(M+vM`@UNg$UpRoe=DM{}1;gKA07o5c&jBm=>i@Th zL{l~Y(HRdnRaN{ug5VbnD7s0}V@v-3=zss4F%caUh;8EW|J27m6n#0DF<8KeM}*>p z?1NGYw_K$=zR~>nSO{GjiM!~>Q9{&etm>e&50qAeWlMe3ukgoWbDoOd3dl2l;}tT? z_w2F>CFt=J% Date: Thu, 12 Sep 2024 11:47:55 +0900 Subject: [PATCH 207/217] fix(dummy_perception_publisher, tier4_dummy_object_rviz_plugin): separate dummy object msg (#8828) * fix: dummy object rviz plugin dependency Signed-off-by: Taekjin LEE * fix: remove message from dummy perception publisher Signed-off-by: Taekjin LEE * fix: node name Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../dummy_perception_publisher/CMakeLists.txt | 16 --------------- .../dummy_perception_publisher/README.md | 2 +- .../dummy_perception_publisher/node.hpp | 13 ++++++------ .../msg/InitialState.msg | 3 --- .../dummy_perception_publisher/msg/Object.msg | 13 ------------ .../dummy_perception_publisher/package.xml | 5 +---- .../dummy_perception_publisher/src/node.cpp | 20 +++++++++---------- .../tier4_dummy_object_rviz_plugin/README.md | 2 +- .../package.xml | 2 +- .../src/tools/car_pose.cpp | 12 +++++------ .../src/tools/car_pose.hpp | 8 ++++---- .../src/tools/delete_all_objects.cpp | 6 +++--- .../src/tools/delete_all_objects.hpp | 4 ++-- .../src/tools/interactive_object.cpp | 15 +++++++------- .../src/tools/interactive_object.hpp | 9 ++++----- .../src/tools/pedestrian_pose.cpp | 4 ++-- .../src/tools/pedestrian_pose.hpp | 4 ++-- .../src/tools/unknown_pose.cpp | 4 ++-- .../src/tools/unknown_pose.hpp | 4 ++-- 19 files changed, 55 insertions(+), 91 deletions(-) delete mode 100644 simulator/dummy_perception_publisher/msg/InitialState.msg delete mode 100644 simulator/dummy_perception_publisher/msg/Object.msg diff --git a/simulator/dummy_perception_publisher/CMakeLists.txt b/simulator/dummy_perception_publisher/CMakeLists.txt index a27667edf536b..0acf4694d03a6 100644 --- a/simulator/dummy_perception_publisher/CMakeLists.txt +++ b/simulator/dummy_perception_publisher/CMakeLists.txt @@ -4,12 +4,6 @@ project(dummy_perception_publisher) find_package(autoware_cmake REQUIRED) autoware_package() -rosidl_generate_interfaces(${PROJECT_NAME} - "msg/InitialState.msg" - "msg/Object.msg" - DEPENDENCIES autoware_perception_msgs tier4_perception_msgs geometry_msgs std_msgs unique_identifier_msgs -) - # See ndt_omp package for documentation on why PCL is special find_package(PCL REQUIRED COMPONENTS common filters) @@ -46,16 +40,6 @@ target_include_directories(dummy_perception_publisher_node $ $) -# For using message definitions from the same package -if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) - rosidl_target_interfaces(dummy_perception_publisher_node - ${PROJECT_NAME} "rosidl_typesupport_cpp") -else() - rosidl_get_typesupport_target( - cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") - target_link_libraries(dummy_perception_publisher_node "${cpp_typesupport_target}") -endif() - # 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. diff --git a/simulator/dummy_perception_publisher/README.md b/simulator/dummy_perception_publisher/README.md index 5d969dd292832..41bd8091008a6 100644 --- a/simulator/dummy_perception_publisher/README.md +++ b/simulator/dummy_perception_publisher/README.md @@ -13,7 +13,7 @@ This node publishes the result of the dummy detection with the type of perceptio | Name | Type | Description | | -------------- | ----------------------------------------- | ----------------------- | | `/tf` | `tf2_msgs/TFMessage` | TF (self-pose) | -| `input/object` | `dummy_perception_publisher::msg::Object` | dummy detection objects | +| `input/object` | `tier4_simulation_msgs::msg::DummyObject` | dummy detection objects | ### Output diff --git a/simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp b/simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp index c3f7976d3efa1..4d50e547fc759 100644 --- a/simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp +++ b/simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp @@ -15,14 +15,13 @@ #ifndef DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_ #define DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_ -#include "dummy_perception_publisher/msg/object.hpp" - #include #include #include #include #include +#include #include #include @@ -45,7 +44,7 @@ struct ObjectInfo { ObjectInfo( - const dummy_perception_publisher::msg::Object & object, const rclcpp::Time & current_time); + const tier4_simulation_msgs::msg::DummyObject & object, const rclcpp::Time & current_time); double length; double width; double height; @@ -60,7 +59,7 @@ struct ObjectInfo // convert to TrackedObject // (todo) currently need object input to get id and header information, but it should be removed autoware_perception_msgs::msg::TrackedObject toTrackedObject( - const dummy_perception_publisher::msg::Object & object) const; + const tier4_simulation_msgs::msg::DummyObject & object) const; }; class PointCloudCreator @@ -116,11 +115,11 @@ class DummyPerceptionPublisherNode : public rclcpp::Node detected_object_with_feature_pub_; rclcpp::Publisher::SharedPtr ground_truth_objects_pub_; - rclcpp::Subscription::SharedPtr object_sub_; + rclcpp::Subscription::SharedPtr object_sub_; rclcpp::TimerBase::SharedPtr timer_; tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; - std::vector objects_; + std::vector objects_; double visible_range_; double detection_successful_rate_; bool enable_ray_tracing_; @@ -134,7 +133,7 @@ class DummyPerceptionPublisherNode : public rclcpp::Node std::mt19937 random_generator_; void timerCallback(); - void objectCallback(const dummy_perception_publisher::msg::Object::ConstSharedPtr msg); + void objectCallback(const tier4_simulation_msgs::msg::DummyObject::ConstSharedPtr msg); public: DummyPerceptionPublisherNode(); diff --git a/simulator/dummy_perception_publisher/msg/InitialState.msg b/simulator/dummy_perception_publisher/msg/InitialState.msg deleted file mode 100644 index 39948a7f731b8..0000000000000 --- a/simulator/dummy_perception_publisher/msg/InitialState.msg +++ /dev/null @@ -1,3 +0,0 @@ -geometry_msgs/PoseWithCovariance pose_covariance -geometry_msgs/TwistWithCovariance twist_covariance -geometry_msgs/AccelWithCovariance accel_covariance diff --git a/simulator/dummy_perception_publisher/msg/Object.msg b/simulator/dummy_perception_publisher/msg/Object.msg deleted file mode 100644 index 11ac1b3d39daa..0000000000000 --- a/simulator/dummy_perception_publisher/msg/Object.msg +++ /dev/null @@ -1,13 +0,0 @@ -std_msgs/Header header -unique_identifier_msgs/UUID id -dummy_perception_publisher/InitialState initial_state -autoware_perception_msgs/ObjectClassification classification -autoware_perception_msgs/Shape shape -float32 max_velocity -float32 min_velocity - -uint8 ADD=0 -uint8 MODIFY=1 -uint8 DELETE=2 -uint8 DELETEALL=3 -int32 action diff --git a/simulator/dummy_perception_publisher/package.xml b/simulator/dummy_perception_publisher/package.xml index caeb01c6823e5..dda52fd5e8fbb 100644 --- a/simulator/dummy_perception_publisher/package.xml +++ b/simulator/dummy_perception_publisher/package.xml @@ -20,7 +20,6 @@ autoware_perception_msgs autoware_universe_utils - geometry_msgs libpcl-all-dev pcl_conversions rclcpp @@ -30,9 +29,7 @@ tf2_geometry_msgs tf2_ros tier4_perception_msgs - unique_identifier_msgs - - rosidl_interface_packages + tier4_simulation_msgs ament_cmake diff --git a/simulator/dummy_perception_publisher/src/node.cpp b/simulator/dummy_perception_publisher/src/node.cpp index daf61bc33425c..dba230f23f108 100644 --- a/simulator/dummy_perception_publisher/src/node.cpp +++ b/simulator/dummy_perception_publisher/src/node.cpp @@ -37,7 +37,7 @@ using autoware_perception_msgs::msg::TrackedObject; using autoware_perception_msgs::msg::TrackedObjects; ObjectInfo::ObjectInfo( - const dummy_perception_publisher::msg::Object & object, const rclcpp::Time & current_time) + const tier4_simulation_msgs::msg::DummyObject & object, const rclcpp::Time & current_time) : length(object.shape.dimensions.x), width(object.shape.dimensions.y), height(object.shape.dimensions.z), @@ -108,7 +108,7 @@ ObjectInfo::ObjectInfo( } TrackedObject ObjectInfo::toTrackedObject( - const dummy_perception_publisher::msg::Object & object) const + const tier4_simulation_msgs::msg::DummyObject & object) const { TrackedObject tracked_object; tracked_object.kinematics.pose_with_covariance = pose_covariance_; @@ -164,7 +164,7 @@ DummyPerceptionPublisherNode::DummyPerceptionPublisherNode() this->create_publisher( "output/dynamic_object", qos); pointcloud_pub_ = this->create_publisher("output/points_raw", qos); - object_sub_ = this->create_subscription( + object_sub_ = this->create_subscription( "input/object", 100, std::bind(&DummyPerceptionPublisherNode::objectCallback, this, std::placeholders::_1)); @@ -331,10 +331,10 @@ void DummyPerceptionPublisherNode::timerCallback() } void DummyPerceptionPublisherNode::objectCallback( - const dummy_perception_publisher::msg::Object::ConstSharedPtr msg) + const tier4_simulation_msgs::msg::DummyObject::ConstSharedPtr msg) { switch (msg->action) { - case dummy_perception_publisher::msg::Object::ADD: { + case tier4_simulation_msgs::msg::DummyObject::ADD: { tf2::Transform tf_input2map; tf2::Transform tf_input2object_origin; tf2::Transform tf_map2object_origin; @@ -350,7 +350,7 @@ void DummyPerceptionPublisherNode::objectCallback( } tf2::fromMsg(msg->initial_state.pose_covariance.pose, tf_input2object_origin); tf_map2object_origin = tf_input2map.inverse() * tf_input2object_origin; - dummy_perception_publisher::msg::Object object; + tier4_simulation_msgs::msg::DummyObject object; object = *msg; tf2::toMsg(tf_map2object_origin, object.initial_state.pose_covariance.pose); @@ -371,7 +371,7 @@ void DummyPerceptionPublisherNode::objectCallback( objects_.push_back(object); break; } - case dummy_perception_publisher::msg::Object::DELETE: { + case tier4_simulation_msgs::msg::DummyObject::DELETE: { for (size_t i = 0; i < objects_.size(); ++i) { if (objects_.at(i).id.uuid == msg->id.uuid) { objects_.erase(objects_.begin() + i); @@ -380,7 +380,7 @@ void DummyPerceptionPublisherNode::objectCallback( } break; } - case dummy_perception_publisher::msg::Object::MODIFY: { + case tier4_simulation_msgs::msg::DummyObject::MODIFY: { for (size_t i = 0; i < objects_.size(); ++i) { if (objects_.at(i).id.uuid == msg->id.uuid) { tf2::Transform tf_input2map; @@ -398,7 +398,7 @@ void DummyPerceptionPublisherNode::objectCallback( } tf2::fromMsg(msg->initial_state.pose_covariance.pose, tf_input2object_origin); tf_map2object_origin = tf_input2map.inverse() * tf_input2object_origin; - dummy_perception_publisher::msg::Object object; + tier4_simulation_msgs::msg::DummyObject object; objects_.at(i) = *msg; tf2::toMsg(tf_map2object_origin, objects_.at(i).initial_state.pose_covariance.pose); if (use_base_link_z_) { @@ -420,7 +420,7 @@ void DummyPerceptionPublisherNode::objectCallback( } break; } - case dummy_perception_publisher::msg::Object::DELETEALL: { + case tier4_simulation_msgs::msg::DummyObject::DELETEALL: { objects_.clear(); break; } diff --git a/simulator/tier4_dummy_object_rviz_plugin/README.md b/simulator/tier4_dummy_object_rviz_plugin/README.md index 6908b0d9b0bd3..69f91314891c7 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/README.md +++ b/simulator/tier4_dummy_object_rviz_plugin/README.md @@ -17,7 +17,7 @@ The DeleteAllObjectsTool deletes the dummy cars, pedestrians, and obstacles disp | Name | Type | Description | | ---------------------------------------------------- | ----------------------------------------- | ----------------------------------------------- | -| `/simulation/dummy_perception_publisher/object_info` | `dummy_perception_publisher::msg::Object` | The topic on which to publish dummy object info | +| `/simulation/dummy_perception_publisher/object_info` | `tier4_simulation_msgs::msg::DummyObject` | The topic on which to publish dummy object info | ## Parameter diff --git a/simulator/tier4_dummy_object_rviz_plugin/package.xml b/simulator/tier4_dummy_object_rviz_plugin/package.xml index 8264e087bf6a1..ce0ce0dbb84f7 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/package.xml +++ b/simulator/tier4_dummy_object_rviz_plugin/package.xml @@ -10,7 +10,6 @@ ament_cmake autoware_cmake - dummy_perception_publisher libqt5-core libqt5-gui libqt5-widgets @@ -19,6 +18,7 @@ rviz_default_plugins tf2_geometry_msgs tf2_ros + tier4_simulation_msgs ament_lint_auto autoware_lint_common diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.cpp index 49da06aa2478e..ae6e2da6cff37 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.cpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.cpp @@ -112,9 +112,9 @@ void CarInitialPoseTool::onInitialize() updateTopic(); } -Object CarInitialPoseTool::createObjectMsg() const +DummyObject CarInitialPoseTool::createObjectMsg() const { - Object object{}; + DummyObject object{}; std::string fixed_frame = context_->getFixedFrame().toStdString(); // header @@ -205,9 +205,9 @@ void BusInitialPoseTool::onInitialize() updateTopic(); } -Object BusInitialPoseTool::createObjectMsg() const +DummyObject BusInitialPoseTool::createObjectMsg() const { - Object object{}; + DummyObject object{}; std::string fixed_frame = context_->getFixedFrame().toStdString(); // header @@ -302,9 +302,9 @@ void BikeInitialPoseTool::onInitialize() updateTopic(); } -Object BikeInitialPoseTool::createObjectMsg() const +DummyObject BikeInitialPoseTool::createObjectMsg() const { - Object object{}; + DummyObject object{}; std::string fixed_frame = context_->getFixedFrame().toStdString(); // header diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.hpp index 7dbbb65c94560..7a1ebe9db2fe0 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.hpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.hpp @@ -55,14 +55,14 @@ namespace rviz_plugins using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::Shape; -using dummy_perception_publisher::msg::Object; +using tier4_simulation_msgs::msg::DummyObject; class CarInitialPoseTool : public InteractiveObjectTool { public: CarInitialPoseTool(); void onInitialize() override; - [[nodiscard]] Object createObjectMsg() const override; + [[nodiscard]] DummyObject createObjectMsg() const override; }; class BusInitialPoseTool : public InteractiveObjectTool @@ -70,7 +70,7 @@ class BusInitialPoseTool : public InteractiveObjectTool public: BusInitialPoseTool(); void onInitialize() override; - [[nodiscard]] Object createObjectMsg() const override; + [[nodiscard]] DummyObject createObjectMsg() const override; }; class BikeInitialPoseTool : public InteractiveObjectTool @@ -78,7 +78,7 @@ class BikeInitialPoseTool : public InteractiveObjectTool public: BikeInitialPoseTool(); void onInitialize() override; - [[nodiscard]] Object createObjectMsg() const override; + [[nodiscard]] DummyObject createObjectMsg() const override; private: rviz_common::properties::EnumProperty * label_; diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.cpp index 91a1f544c25e8..0857bf85f14c4 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.cpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.cpp @@ -73,7 +73,7 @@ void DeleteAllObjectsTool::onInitialize() void DeleteAllObjectsTool::updateTopic() { rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node(); - dummy_object_info_pub_ = raw_node->create_publisher( + dummy_object_info_pub_ = raw_node->create_publisher( topic_property_->getStdString(), 1); clock_ = raw_node->get_clock(); } @@ -82,7 +82,7 @@ void DeleteAllObjectsTool::updateTopic() void DeleteAllObjectsTool::onPoseSet( [[maybe_unused]] double x, [[maybe_unused]] double y, [[maybe_unused]] double theta) { - dummy_perception_publisher::msg::Object output_msg; + tier4_simulation_msgs::msg::DummyObject output_msg; std::string fixed_frame = context_->getFixedFrame().toStdString(); // header @@ -90,7 +90,7 @@ void DeleteAllObjectsTool::onPoseSet( output_msg.header.stamp = clock_->now(); // action - output_msg.action = dummy_perception_publisher::msg::Object::DELETEALL; + output_msg.action = tier4_simulation_msgs::msg::DummyObject::DELETEALL; dummy_object_info_pub_->publish(output_msg); } diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.hpp index 11b3e569d326c..3895986a87a1c 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.hpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/delete_all_objects.hpp @@ -57,7 +57,7 @@ #include #endif -#include +#include namespace rviz_plugins { @@ -77,7 +77,7 @@ private Q_SLOTS: private: // NOLINT for Qt rclcpp::Clock::SharedPtr clock_; - rclcpp::Publisher::SharedPtr dummy_object_info_pub_; + rclcpp::Publisher::SharedPtr dummy_object_info_pub_; rviz_common::properties::StringProperty * topic_property_; }; diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp index bcd56256bde34..83852d0c85011 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp @@ -252,7 +252,8 @@ void InteractiveObjectTool::onInitialize() void InteractiveObjectTool::updateTopic() { rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node(); - dummy_object_info_pub_ = raw_node->create_publisher(topic_property_->getStdString(), 1); + dummy_object_info_pub_ = + raw_node->create_publisher(topic_property_->getStdString(), 1); clock_ = raw_node->get_clock(); move_tool_.initialize(context_); property_frame_->setFrameManager(context_->getFrameManager()); @@ -280,7 +281,7 @@ void InteractiveObjectTool::onPoseSet(double x, double y, double theta) output_msg.initial_state.accel_covariance.accel.linear.z = 0.0; output_msg.max_velocity = max_velocity_->getFloat(); output_msg.min_velocity = min_velocity_->getFloat(); - output_msg.action = Object::ADD; + output_msg.action = DummyObject::ADD; dummy_object_info_pub_->publish(output_msg); } @@ -292,7 +293,7 @@ void InteractiveObjectTool::publishObjectMsg( output_msg.action = action; output_msg.id.uuid = uuid; - if (action == Object::DELETE) { + if (action == DummyObject::DELETE) { dummy_object_info_pub_->publish(output_msg); return; } @@ -321,10 +322,10 @@ int InteractiveObjectTool::processMouseEvent(rviz_common::ViewportMouseEvent & e if (point) { if (event.shift()) { const auto uuid = objects_.create(point.value()); - publishObjectMsg(uuid.get(), Object::ADD); + publishObjectMsg(uuid.get(), DummyObject::ADD); } else if (event.alt()) { const auto uuid = objects_.remove(point.value()); - publishObjectMsg(uuid.get(), Object::DELETE); + publishObjectMsg(uuid.get(), DummyObject::DELETE); } else { objects_.select(point.value()); } @@ -334,7 +335,7 @@ int InteractiveObjectTool::processMouseEvent(rviz_common::ViewportMouseEvent & e if (event.rightUp()) { const auto uuid = objects_.reset(); - publishObjectMsg(uuid.get(), Object::MODIFY); + publishObjectMsg(uuid.get(), DummyObject::MODIFY); return 0; } @@ -342,7 +343,7 @@ int InteractiveObjectTool::processMouseEvent(rviz_common::ViewportMouseEvent & e const auto point = get_point_from_mouse(event); if (point) { const auto uuid = objects_.update(point.value()); - publishObjectMsg(uuid.get(), Object::MODIFY); + publishObjectMsg(uuid.get(), DummyObject::MODIFY); } return 0; } diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.hpp index c0942d9a6cdd1..fb35ab98da9a3 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.hpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.hpp @@ -61,9 +61,8 @@ #include #endif -#include - #include +#include #include @@ -84,7 +83,7 @@ namespace rviz_plugins using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::Shape; -using dummy_perception_publisher::msg::Object; +using tier4_simulation_msgs::msg::DummyObject; class InteractiveObject { @@ -138,14 +137,14 @@ class InteractiveObjectTool : public rviz_default_plugins::tools::PoseTool int processMouseEvent(rviz_common::ViewportMouseEvent & event) override; int processKeyEvent(QKeyEvent * event, rviz_common::RenderPanel * panel) override; - [[nodiscard]] virtual Object createObjectMsg() const = 0; + [[nodiscard]] virtual DummyObject createObjectMsg() const = 0; protected Q_SLOTS: virtual void updateTopic(); protected: // NOLINT for Qt rclcpp::Clock::SharedPtr clock_; - rclcpp::Publisher::SharedPtr dummy_object_info_pub_; + rclcpp::Publisher::SharedPtr dummy_object_info_pub_; rviz_default_plugins::tools::MoveTool move_tool_; diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.cpp index 52b432661467a..5510d17e06727 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.cpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.cpp @@ -103,9 +103,9 @@ void PedestrianInitialPoseTool::onInitialize() updateTopic(); } -Object PedestrianInitialPoseTool::createObjectMsg() const +DummyObject PedestrianInitialPoseTool::createObjectMsg() const { - Object object{}; + DummyObject object{}; std::string fixed_frame = context_->getFixedFrame().toStdString(); // header diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.hpp index 642159aceaf3d..b9fc38c7a400a 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.hpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/pedestrian_pose.hpp @@ -55,14 +55,14 @@ namespace rviz_plugins using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::Shape; -using dummy_perception_publisher::msg::Object; +using tier4_simulation_msgs::msg::DummyObject; class PedestrianInitialPoseTool : public InteractiveObjectTool { public: PedestrianInitialPoseTool(); void onInitialize() override; - [[nodiscard]] Object createObjectMsg() const override; + [[nodiscard]] DummyObject createObjectMsg() const override; }; } // namespace rviz_plugins diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.cpp index 2060dc1a456e5..59b981b66c0b6 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.cpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.cpp @@ -98,9 +98,9 @@ void UnknownInitialPoseTool::onInitialize() updateTopic(); } -Object UnknownInitialPoseTool::createObjectMsg() const +DummyObject UnknownInitialPoseTool::createObjectMsg() const { - Object object{}; + DummyObject object{}; std::string fixed_frame = context_->getFixedFrame().toStdString(); // header diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.hpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.hpp index 3f1a9b55c30ab..8526a7f995642 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.hpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/unknown_pose.hpp @@ -50,14 +50,14 @@ namespace rviz_plugins using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::Shape; -using dummy_perception_publisher::msg::Object; +using tier4_simulation_msgs::msg::DummyObject; class UnknownInitialPoseTool : public InteractiveObjectTool { public: UnknownInitialPoseTool(); void onInitialize() override; - [[nodiscard]] Object createObjectMsg() const override; + [[nodiscard]] DummyObject createObjectMsg() const override; }; } // namespace rviz_plugins From 08d70f86b9084e79c5d14a0d8d26bc192f1b9603 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 12 Sep 2024 14:53:29 +0900 Subject: [PATCH 208/217] fix(autoware_test_utils): fix unusedFunction (#8857) fix:unusedFunction Signed-off-by: kobayu858 --- common/autoware_test_utils/src/autoware_test_utils.cpp | 2 ++ common/autoware_test_utils/src/mock_data_parser.cpp | 1 + 2 files changed, 3 insertions(+) diff --git a/common/autoware_test_utils/src/autoware_test_utils.cpp b/common/autoware_test_utils/src/autoware_test_utils.cpp index 5bb1fd7633056..a0e0b7518aedc 100644 --- a/common/autoware_test_utils/src/autoware_test_utils.cpp +++ b/common/autoware_test_utils/src/autoware_test_utils.cpp @@ -138,6 +138,7 @@ std::string get_absolute_path_to_lanelet_map( return dir + "/test_map/" + map_filename; } +// cppcheck-suppress unusedFunction std::string get_absolute_path_to_route( const std::string & package_name, const std::string & route_filename) { @@ -228,6 +229,7 @@ Scenario makeScenarioMsg(const std::string & scenario) return scenario_msg; } +// cppcheck-suppress unusedFunction RouteSections combineConsecutiveRouteSections( const RouteSections & route_sections1, const RouteSections & route_sections2) { diff --git a/common/autoware_test_utils/src/mock_data_parser.cpp b/common/autoware_test_utils/src/mock_data_parser.cpp index a8f2a8c6433df..6ad03071a881a 100644 --- a/common/autoware_test_utils/src/mock_data_parser.cpp +++ b/common/autoware_test_utils/src/mock_data_parser.cpp @@ -75,6 +75,7 @@ std::vector parse_segments(const YAML::Node & node) return segments; } +// cppcheck-suppress unusedFunction LaneletRoute parse_lanelet_route_file(const std::string & filename) { LaneletRoute lanelet_route; From aaf5f270408216ab8ba3980bcd1a5a687ddb2307 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 12 Sep 2024 15:27:08 +0900 Subject: [PATCH 209/217] fix(autoware_object_merger): default merger priority within enum range (#8858) fix: default merger priority within enum range Signed-off-by: Taekjin LEE --- .../config/object_association_merger.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_object_merger/config/object_association_merger.param.yaml b/perception/autoware_object_merger/config/object_association_merger.param.yaml index e9b86cd64be29..51e5f2920c5b1 100644 --- a/perception/autoware_object_merger/config/object_association_merger.param.yaml +++ b/perception/autoware_object_merger/config/object_association_merger.param.yaml @@ -5,4 +5,4 @@ recall_threshold_to_judge_overlapped: 0.5 remove_overlapped_unknown_objects: true base_link_frame_id: base_link - priority_mode: 3 # PriorityMode::Confidence + priority_mode: 2 # PriorityMode::Confidence From eaacae4fe8f81af3151b99fc7725c0148ae7aeb1 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 12 Sep 2024 17:35:15 +0900 Subject: [PATCH 210/217] ci: change upload-artifact version from 2 to 4 (#8861) Change upload-artifact version from 2 to 4 Signed-off-by: Shintaro Sakoda --- .github/workflows/cppcheck-differential.yaml | 2 +- .github/workflows/cppcheck-weekly.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/cppcheck-differential.yaml b/.github/workflows/cppcheck-differential.yaml index dc4fed1084bc0..6d466f7c6bc45 100644 --- a/.github/workflows/cppcheck-differential.yaml +++ b/.github/workflows/cppcheck-differential.yaml @@ -85,7 +85,7 @@ jobs: - name: Upload Cppcheck report if: ${{ steps.filter-paths-no-cpp-files.outputs.filtered-full-paths != '' }} - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v4 with: name: cppcheck-report path: cppcheck-report.txt diff --git a/.github/workflows/cppcheck-weekly.yaml b/.github/workflows/cppcheck-weekly.yaml index 2022edcc57e93..c59d663048b9c 100644 --- a/.github/workflows/cppcheck-weekly.yaml +++ b/.github/workflows/cppcheck-weekly.yaml @@ -37,7 +37,7 @@ jobs: shell: bash - name: Upload Cppcheck report - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v4 with: name: cppcheck-report path: cppcheck-report.xml From 19894ae5281a375f98702a52d244b8f7f3d1a50d Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 12 Sep 2024 17:46:58 +0900 Subject: [PATCH 211/217] refactor(ekf_localizer): moved Simple1DFilter from ekf_localizer to ekf_module (#8705) * Moved Simple1DFilter from ekf_localizer to ekf_module Signed-off-by: Shintaro Sakoda * feat(map_loader): visualize BusStopArea Signed-off-by: Mamoru Sobue * feat(map_loader): visualize bicycle_lane Signed-off-by: Mamoru Sobue * add maitainer Signed-off-by: Mamoru Sobue --------- Signed-off-by: Shintaro Sakoda Signed-off-by: Mamoru Sobue Co-authored-by: Mamoru Sobue Co-authored-by: Mamoru Sobue --- .../include/ekf_localizer/ekf_localizer.hpp | 62 ---------------- .../include/ekf_localizer/ekf_module.hpp | 60 ++++++++++++++- .../ekf_localizer/src/ekf_localizer.cpp | 74 +------------------ localization/ekf_localizer/src/ekf_module.cpp | 65 +++++++++++++++- 4 files changed, 123 insertions(+), 138 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 2dc06e50f8eb8..14c8347379af2 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -53,49 +53,6 @@ namespace autoware::ekf_localizer { -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 EKFLocalizer : public rclcpp::Node { public: @@ -156,9 +113,6 @@ class EKFLocalizer : public rclcpp::Node //!< @brief extended kalman filter instance. std::unique_ptr ekf_module_; - Simple1DFilter z_filter_; - Simple1DFilter roll_filter_; - Simple1DFilter pitch_filter_; const HyperParameters params_; @@ -230,17 +184,6 @@ class EKFLocalizer : public rclcpp::Node void publish_callback_return_diagnostics( const std::string & callback_name, const rclcpp::Time & current_time); - /** - * @brief update simple 1d filter - */ - void update_simple_1d_filters( - const geometry_msgs::msg::PoseWithCovarianceStamped & pose, const size_t smoothing_step); - - /** - * @brief initialize simple 1d filter - */ - void init_simple_1d_filters(const geometry_msgs::msg::PoseWithCovarianceStamped & pose); - /** * @brief trigger node */ @@ -250,11 +193,6 @@ class EKFLocalizer : public rclcpp::Node autoware::universe_utils::StopWatch stop_watch_; - /** - * @brief last angular velocity for compensating rph with delay - */ - tf2::Vector3 last_angular_velocity_; - friend class EKFLocalizerTestSuite; // for test code }; diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp index 5cf13dfb309b1..0659e3f73315b 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp @@ -49,6 +49,49 @@ struct EKFDiagnosticInfo 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: @@ -65,8 +108,7 @@ class EKFModule const geometry_msgs::msg::TransformStamped & transform); [[nodiscard]] geometry_msgs::msg::PoseStamped get_current_pose( - const rclcpp::Time & current_time, const double z, const double roll, const double pitch, - bool get_biased_yaw) const; + 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; @@ -87,12 +129,26 @@ class EKFModule 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 diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 7879ddbc55caa..6a3fd2265c637 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -52,8 +52,7 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) params_(this), ekf_dt_(params_.ekf_dt), pose_queue_(params_.pose_smoothing_steps), - twist_queue_(params_.twist_smoothing_steps), - last_angular_velocity_(0.0, 0.0, 0.0) + twist_queue_(params_.twist_smoothing_steps) { is_activated_ = false; @@ -99,10 +98,6 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) ekf_module_ = std::make_unique(warning_, params_); logger_configure_ = std::make_unique(this); - - 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); } /* @@ -182,14 +177,6 @@ void EKFLocalizer::timer_callback() bool is_updated = ekf_module_->measurement_update_pose(*pose, current_time, pose_diag_info_); if (is_updated) { pose_is_updated = true; - - // Update Simple 1D filter with considering change of roll, pitch and height (position z) - // values due to measurement pose delay - const double delay_time = - (current_time - pose->header.stamp).seconds() + params_.pose_additional_delay; - auto pose_with_rph_delay_compensation = - ekf_module_->compensate_rph_with_delay(*pose, last_angular_velocity_, delay_time); - update_simple_1d_filters(pose_with_rph_delay_compensation, params_.pose_smoothing_steps); } } DEBUG_INFO( @@ -220,10 +207,6 @@ void EKFLocalizer::timer_callback() ekf_module_->measurement_update_twist(*twist, current_time, twist_diag_info_); if (is_updated) { twist_is_updated = true; - last_angular_velocity_ = tf2::Vector3( - twist->twist.twist.angular.x, twist->twist.twist.angular.y, twist->twist.twist.angular.z); - } else { - last_angular_velocity_ = tf2::Vector3(0.0, 0.0, 0.0); } } DEBUG_INFO( @@ -232,13 +215,10 @@ void EKFLocalizer::timer_callback() } twist_diag_info_.no_update_count = twist_is_updated ? 0 : (twist_diag_info_.no_update_count + 1); - const double z = z_filter_.get_x(); - const double roll = roll_filter_.get_x(); - const double pitch = pitch_filter_.get_x(); const geometry_msgs::msg::PoseStamped current_ekf_pose = - ekf_module_->get_current_pose(current_time, z, roll, pitch, false); + ekf_module_->get_current_pose(current_time, false); const geometry_msgs::msg::PoseStamped current_biased_ekf_pose = - ekf_module_->get_current_pose(current_time, z, roll, pitch, true); + ekf_module_->get_current_pose(current_time, true); const geometry_msgs::msg::TwistStamped current_ekf_twist = ekf_module_->get_current_twist(current_time); @@ -260,15 +240,11 @@ void EKFLocalizer::timer_tf_callback() return; } - const double z = z_filter_.get_x(); - const double roll = roll_filter_.get_x(); - const double pitch = pitch_filter_.get_x(); - const rclcpp::Time current_time = this->now(); geometry_msgs::msg::TransformStamped transform_stamped; transform_stamped = autoware::universe_utils::pose2transform( - ekf_module_->get_current_pose(current_time, z, roll, pitch, false), "base_link"); + ekf_module_->get_current_pose(current_time, false), "base_link"); transform_stamped.header.stamp = current_time; tf_br_->sendTransform(transform_stamped); } @@ -305,7 +281,6 @@ void EKFLocalizer::callback_initial_pose( params_.pose_frame_id.c_str(), msg->header.frame_id.c_str()); } ekf_module_->initialize(*msg, transform); - init_simple_1d_filters(*msg); } /* @@ -357,12 +332,6 @@ void EKFLocalizer::publish_estimate_result( 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(); - - using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - pose_cov.pose.covariance[COV_IDX::Z_Z] = z_filter_.get_var(); - pose_cov.pose.covariance[COV_IDX::ROLL_ROLL] = roll_filter_.get_var(); - pose_cov.pose.covariance[COV_IDX::PITCH_PITCH] = pitch_filter_.get_var(); - pub_pose_cov_->publish(pose_cov); geometry_msgs::msg::PoseWithCovarianceStamped biased_pose_cov = pose_cov; @@ -469,41 +438,6 @@ void EKFLocalizer::publish_callback_return_diagnostics( pub_diag_->publish(diag_msg); } -void EKFLocalizer::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_); -} - -void EKFLocalizer::init_simple_1d_filters( - const geometry_msgs::msg::PoseWithCovarianceStamped & pose) -{ - 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]; - double roll_var = pose.pose.covariance[COV_IDX::ROLL_ROLL]; - double pitch_var = 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); -} - /** * @brief trigger node */ diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp index d2c29c458572e..f00608e0bb6a4 100644 --- a/localization/ekf_localizer/src/ekf_module.cpp +++ b/localization/ekf_localizer/src/ekf_module.cpp @@ -40,7 +40,8 @@ EKFModule::EKFModule(std::shared_ptr warning, const HyperParameters & p : 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) + 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 @@ -52,6 +53,9 @@ EKFModule::EKFModule(std::shared_ptr warning, const HyperParameters & p 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( @@ -80,12 +84,27 @@ void EKFModule::initialize( 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, const double z, const double roll, const double pitch, - bool get_biased_yaw) const + 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); /* @@ -127,7 +146,15 @@ geometry_msgs::msg::TwistStamped EKFModule::get_current_twist( std::array EKFModule::get_current_pose_covariance() const { - return ekf_covariance_to_pose_message_covariance(kalman_filter_.getLatestP()); + 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 @@ -195,6 +222,7 @@ void EKFModule::predict_with_delay(const double 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( @@ -277,6 +305,12 @@ bool EKFModule::measurement_update_pose( 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()); @@ -328,6 +362,8 @@ bool EKFModule::measurement_update_twist( 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()); @@ -388,6 +424,9 @@ bool EKFModule::measurement_update_twist( 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()); @@ -396,4 +435,22 @@ bool EKFModule::measurement_update_twist( 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 From 9fa11de61b02edf3cedc54663338bdfa290c2821 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 12 Sep 2024 18:06:34 +0900 Subject: [PATCH 212/217] feat(start_planner): add skip_rear_vehicle_check parameter (#8863) Add the skip_rear_vehicle_check parameter to the start planner module configuration. This parameter allows disabling the rear vehicle check during collision detection. By default, the rear vehicle check is enabled. Signed-off-by: Kyoichi Sugahara --- .../README.md | 39 ++++++++++--------- .../config/start_planner.param.yaml | 1 + .../data_structs.hpp | 1 + .../src/manager.cpp | 2 + .../src/start_planner_module.cpp | 20 +++++++++- 5 files changed, 42 insertions(+), 21 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md index 5b68b021f99cb..931b70f8482a5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md @@ -349,25 +349,26 @@ PullOutPath --o PullOutPlannerBase ## General parameters for start_planner -| Name | Unit | Type | Description | Default value | -| :--------------------------------------------------------- | :---- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------------- | -| th_arrived_distance | [m] | double | distance threshold for arrival of path termination | 1.0 | -| th_stopped_velocity | [m/s] | double | velocity threshold for arrival of path termination | 0.01 | -| th_stopped_time | [s] | double | time threshold for arrival of path termination | 1.0 | -| th_distance_to_middle_of_the_road | [m] | double | distance threshold to determine if the vehicle is on the middle of the road | 0.1 | -| collision_check_margins | [m] | double | Obstacle collision check margins list | [2.0, 1.0, 0.5, 0.1] | -| shift_collision_check_distance_from_end | [m] | double | collision check distance from end shift end pose | -10.0 | -| geometric_collision_check_distance_from_end | [m] | double | collision check distance from end geometric end pose | 0.0 | -| collision_check_margin_from_front_object | [m] | double | collision check margin from front object | 5.0 | -| extra_width_margin_for_rear_obstacle | [m] | double | extra width that is added to the perceived rear obstacle's width when deciding if the rear obstacle can overtake the ego vehicle while it is merging to a lane from the shoulder lane. | 0.5 | -| object_types_to_check_for_path_generation.check_car | - | bool | flag to check car for path generation | true | -| object_types_to_check_for_path_generation.check_truck | - | bool | flag to check truck for path generation | true | -| object_types_to_check_for_path_generation.check_bus | - | bool | flag to check bus for path generation | true | -| object_types_to_check_for_path_generation.check_bicycle | - | bool | flag to check bicycle for path generation | true | -| object_types_to_check_for_path_generation.check_motorcycle | - | bool | flag to check motorcycle for path generation | true | -| object_types_to_check_for_path_generation.check_pedestrian | - | bool | flag to check pedestrian for path generation | true | -| object_types_to_check_for_path_generation.check_unknown | - | bool | flag to check unknown for path generation | true | -| center_line_path_interval | [m] | double | reference center line path point interval | 1.0 | +| Name | Unit | Type | Description | Default value | +| :--------------------------------------------------------- | :---- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | :------------------- | +| th_arrived_distance | [m] | double | distance threshold for arrival of path termination | 1.0 | +| th_stopped_velocity | [m/s] | double | velocity threshold for arrival of path termination | 0.01 | +| th_stopped_time | [s] | double | time threshold for arrival of path termination | 1.0 | +| th_distance_to_middle_of_the_road | [m] | double | distance threshold to determine if the vehicle is on the middle of the road | 0.1 | +| collision_check_margins | [m] | double | Obstacle collision check margins list | [2.0, 1.0, 0.5, 0.1] | +| shift_collision_check_distance_from_end | [m] | double | collision check distance from end shift end pose | -10.0 | +| geometric_collision_check_distance_from_end | [m] | double | collision check distance from end geometric end pose | 0.0 | +| collision_check_margin_from_front_object | [m] | double | collision check margin from front object | 5.0 | +| skip_rear_vehicle_check | - | bool | flag to skip rear vehicle check (rear vehicle check is performed to skip safety check and proceed with departure when the ego vehicle is obstructing the progress of a rear vehicle) | false | +| extra_width_margin_for_rear_obstacle | [m] | double | extra width that is added to the perceived rear obstacle's width when deciding if the rear obstacle can overtake the ego vehicle while it is merging to a lane from the shoulder lane | 0.5 | +| object_types_to_check_for_path_generation.check_car | - | bool | flag to check car for path generation | true | +| object_types_to_check_for_path_generation.check_truck | - | bool | flag to check truck for path generation | true | +| object_types_to_check_for_path_generation.check_bus | - | bool | flag to check bus for path generation | true | +| object_types_to_check_for_path_generation.check_bicycle | - | bool | flag to check bicycle for path generation | true | +| object_types_to_check_for_path_generation.check_motorcycle | - | bool | flag to check motorcycle for path generation | true | +| object_types_to_check_for_path_generation.check_pedestrian | - | bool | flag to check pedestrian for path generation | true | +| object_types_to_check_for_path_generation.check_unknown | - | bool | flag to check unknown for path generation | true | +| center_line_path_interval | [m] | double | reference center line path point interval | 1.0 | ### **Ego vehicle's velocity planning** diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml index 443563a7626eb..f93800450a479 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml @@ -7,6 +7,7 @@ th_stopped_time: 1.0 collision_check_margins: [2.0, 1.0, 0.5, 0.1] collision_check_margin_from_front_object: 5.0 + skip_rear_vehicle_check: false extra_width_margin_for_rear_obstacle: 0.5 th_moving_object_velocity: 1.0 object_types_to_check_for_path_generation: 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 5903a691d60e1..9c439e9b3b921 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 @@ -102,6 +102,7 @@ struct StartPlannerParameters double th_stopped_time{0.0}; double prepare_time_before_start{0.0}; double th_distance_to_middle_of_the_road{0.0}; + bool skip_rear_vehicle_check{false}; double extra_width_margin_for_rear_obstacle{0.0}; std::vector collision_check_margins{}; double collision_check_margin_from_front_object{0.0}; 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 193f88d212842..f5739ce322248 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 @@ -40,6 +40,7 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) 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 = @@ -357,6 +358,7 @@ void StartPlannerModuleManager::updateModuleParams( updateParam(parameters, ns + "prepare_time_before_start", p->prepare_time_before_start); updateParam( parameters, ns + "th_distance_to_middle_of_the_road", p->th_distance_to_middle_of_the_road); + updateParam(parameters, ns + "skip_rear_vehicle_check", p->skip_rear_vehicle_check); updateParam( parameters, ns + "extra_width_margin_for_rear_obstacle", p->extra_width_margin_for_rear_obstacle); 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 ec0db1e9c0f4b..4b3a76c8530dd 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 @@ -301,8 +301,24 @@ bool StartPlannerModule::receivedNewRoute() const bool StartPlannerModule::requiresDynamicObjectsCollisionDetection() const { - return parameters_->safety_check_params.enable_safety_check && status_.driving_forward && - !isPreventingRearVehicleFromPassingThrough(); + const auto & safety_params = parameters_->safety_check_params; + const auto & skip_rear_vehicle_check = parameters_->skip_rear_vehicle_check; + + // Return false and do not perform collision detection if any of the following conditions are + // true: + // - Safety check is disabled. + // - The vehicle is not driving forward. + if (!safety_params.enable_safety_check || !status_.driving_forward) { + return false; + } + + // Return true and always perform collision detection if the following condition is true: + // - Rear vehicle check is set to be skipped. + if (skip_rear_vehicle_check) { + return true; + } + + return !isPreventingRearVehicleFromPassingThrough(); } bool StartPlannerModule::noMovingObjectsAround() const From 6daa3fdb3afa6d80020d91be8a53c30b951809e3 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Thu, 12 Sep 2024 18:37:25 +0900 Subject: [PATCH 213/217] feat(autonomous_emergency_braking): add markers showing aeb convex hull polygons for debugging purposes (#8865) * add markers showing aeb convex hull polygons for debugging purposes Signed-off-by: Daniel Sanchez * fix briefs Signed-off-by: Daniel Sanchez * fix typo Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../autonomous_emergency_braking/node.hpp | 25 ++++++-- .../autonomous_emergency_braking/utils.hpp | 19 ++++++ .../src/node.cpp | 64 +++++++++++-------- .../src/utils.cpp | 19 ++++++ .../test/test.cpp | 3 +- 5 files changed, 97 insertions(+), 33 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp index aa3db3d8e92e4..9addc059ad0af 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp @@ -41,6 +41,7 @@ #include #include #include +#include #include #include #include @@ -50,6 +51,7 @@ #include #include #include +#include #include #include namespace autoware::motion::control::autonomous_emergency_braking @@ -72,6 +74,7 @@ using Path = std::vector; using Vector3 = geometry_msgs::msg::Vector3; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; +using colorTuple = std::tuple; /** * @brief Struct to store object data @@ -448,7 +451,7 @@ class AEB : public rclcpp::Node */ void getPointsBelongingToClusterHulls( const PointCloud::Ptr obstacle_points_ptr, - const PointCloud::Ptr points_belonging_to_cluster_hulls); + const PointCloud::Ptr points_belonging_to_cluster_hulls, MarkerArray & debug_markers); /** * @brief Create object data using predicted objects @@ -475,18 +478,26 @@ class AEB : public rclcpp::Node * @param polygons Polygons representing the ego vehicle footprint * @param objects Vector of object data * @param closest_object Optional data of the closest object - * @param color_r Red color component - * @param color_g Green color component - * @param color_b Blue color component - * @param color_a Alpha (transparency) component + * @param debug_colors Tuple of RGBA colors * @param ns Namespace for the marker * @param debug_markers Marker array for debugging */ void addMarker( const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, const std::vector & objects, const std::optional & closest_object, - const double color_r, const double color_g, const double color_b, const double color_a, - const std::string & ns, MarkerArray & debug_markers); + const colorTuple & debug_colors, const std::string & ns, MarkerArray & debug_markers); + + /** + * @brief Add a marker of convex hulls for debugging + * @param current_time Current time + * @param hulls vector of polygons of the convex hulls + * @param debug_colors Tuple of RGBA colors + * @param ns Namespace for the marker + * @param debug_markers Marker array for debugging + */ + void addClusterHullMarkers( + const rclcpp::Time & current_time, const std::vector & hulls, + const colorTuple & debug_colors, const std::string & ns, MarkerArray & debug_markers); /** * @brief Add a collision marker for debugging diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp index 85a20caac9287..5a2dacad2dfc9 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp @@ -26,6 +26,8 @@ #include #include +#include + #ifdef ROS_DISTRO_GALACTIC #include #include @@ -33,6 +35,8 @@ #include #include +#include + #endif namespace autoware::motion::control::autonomous_emergency_braking::utils @@ -83,9 +87,24 @@ Polygon2d convertBoundingBoxObjectToGeometryPolygon( */ Polygon2d convertObjToPolygon(const PredictedObject & obj); +/** + * @brief Get the transform from source to target frame + * @param target_frame target frame + * @param source_frame source frame + * @param tf_buffer buffer of tf transforms + * @param logger node logger + */ std::optional getTransform( const std::string & target_frame, const std::string & source_frame, const tf2_ros::Buffer & tf_buffer, const rclcpp::Logger & logger); + +/** + * @brief Get the predicted object's shape as a geometry polygon + * @param polygons vector of Polygon2d + * @param polygon_marker marker to be filled with polygon points + */ +void fillMarkerFromPolygon( + const std::vector & polygons, visualization_msgs::msg::Marker & polygon_marker); } // namespace autoware::motion::control::autonomous_emergency_braking::utils #endif // AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_ diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 938ed388c9ec9..1f8fd6f4137a2 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -39,7 +39,6 @@ #include #include #include -#include #include #include @@ -411,7 +410,6 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) bool AEB::checkCollision(MarkerArray & debug_markers) { autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - using colorTuple = std::tuple; // step1. check data if (!fetchLatestData()) { @@ -457,10 +455,9 @@ bool AEB::checkCollision(MarkerArray & debug_markers) // Add debug markers if (publish_debug_markers_) { - const auto [color_r, color_g, color_b, color_a] = debug_colors; addMarker( - this->get_clock()->now(), path, ego_polys, objects, collision_data_keeper_.get(), color_r, - color_g, color_b, color_a, debug_ns, debug_markers); + this->get_clock()->now(), path, ego_polys, objects, collision_data_keeper_.get(), + debug_colors, debug_ns, debug_markers); } return objects; }; @@ -529,7 +526,8 @@ bool AEB::checkCollision(MarkerArray & debug_markers) } PointCloud::Ptr points_belonging_to_cluster_hulls = pcl::make_shared(); - getPointsBelongingToClusterHulls(filtered_objects, points_belonging_to_cluster_hulls); + getPointsBelongingToClusterHulls( + filtered_objects, points_belonging_to_cluster_hulls, debug_markers); const auto has_collision_imu_path = [&](const PointCloud::Ptr points_belonging_to_cluster_hulls) -> bool { @@ -770,7 +768,7 @@ void AEB::createObjectDataUsingPredictedObjects( void AEB::getPointsBelongingToClusterHulls( const PointCloud::Ptr obstacle_points_ptr, - const PointCloud::Ptr points_belonging_to_cluster_hulls) + const PointCloud::Ptr points_belonging_to_cluster_hulls, MarkerArray & debug_markers) { autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // eliminate noisy points by only considering points belonging to clusters of at least a certain @@ -789,6 +787,7 @@ void AEB::getPointsBelongingToClusterHulls( ec.extract(cluster_idx); return cluster_idx; }); + std::vector hull_polygons; for (const auto & indices : cluster_indices) { PointCloud::Ptr cluster(new PointCloud); bool cluster_surpasses_threshold_height{false}; @@ -807,9 +806,19 @@ void AEB::getPointsBelongingToClusterHulls( std::vector polygons; PointCloud::Ptr surface_hull(new PointCloud); hull.reconstruct(*surface_hull, polygons); + Polygon2d hull_polygon; for (const auto & p : *surface_hull) { points_belonging_to_cluster_hulls->push_back(p); + if (publish_debug_markers_) { + const auto geom_point = autoware::universe_utils::createPoint(p.x, p.y, p.z); + appendPointToPolygon(hull_polygon, geom_point); + } } + hull_polygons.push_back(hull_polygon); + } + if (publish_debug_markers_ && !hull_polygons.empty()) { + constexpr colorTuple debug_color = {255.0 / 256.0, 51.0 / 256.0, 255.0 / 256.0, 0.999}; + addClusterHullMarkers(now(), hull_polygons, debug_color, "hulls", debug_markers); } } @@ -887,23 +896,39 @@ void AEB::cropPointCloudWithEgoFootprintPath( path_polygon_hull_filter.setHullIndices(polygons); path_polygon_hull_filter.setHullCloud(surface_hull); path_polygon_hull_filter.filter(*filtered_objects); - filtered_objects->header.stamp = full_points_ptr->header.stamp; + filtered_objects->header = full_points_ptr->header; +} + +void AEB::addClusterHullMarkers( + const rclcpp::Time & current_time, const std::vector & hulls, + const colorTuple & debug_colors, const std::string & ns, MarkerArray & debug_markers) +{ + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto [color_r, color_g, color_b, color_a] = debug_colors; + + auto hull_marker = autoware::universe_utils::createDefaultMarker( + "base_link", current_time, ns, 0, Marker::LINE_LIST, + autoware::universe_utils::createMarkerScale(0.03, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); + utils::fillMarkerFromPolygon(hulls, hull_marker); + debug_markers.markers.push_back(hull_marker); } void AEB::addMarker( const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, const std::vector & objects, const std::optional & closest_object, - const double color_r, const double color_g, const double color_b, const double color_a, - const std::string & ns, MarkerArray & debug_markers) + const colorTuple & debug_colors, const std::string & ns, MarkerArray & debug_markers) { autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto [color_r, color_g, color_b, color_a] = debug_colors; + auto path_marker = autoware::universe_utils::createDefaultMarker( "base_link", current_time, ns + "_path", 0L, Marker::LINE_STRIP, autoware::universe_utils::createMarkerScale(0.2, 0.2, 0.2), autoware::universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); - path_marker.points.resize(path.size()); - for (size_t i = 0; i < path.size(); ++i) { - path_marker.points.at(i) = path.at(i).position; + path_marker.points.reserve(path.size()); + for (const auto & p : path) { + path_marker.points.push_back(p.position); } debug_markers.markers.push_back(path_marker); @@ -911,18 +936,7 @@ void AEB::addMarker( "base_link", current_time, ns + "_polygon", 0, Marker::LINE_LIST, autoware::universe_utils::createMarkerScale(0.03, 0.0, 0.0), autoware::universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); - for (const auto & poly : polygons) { - for (size_t dp_idx = 0; dp_idx < poly.outer().size(); ++dp_idx) { - const auto & boost_cp = poly.outer().at(dp_idx); - const auto & boost_np = poly.outer().at((dp_idx + 1) % poly.outer().size()); - const auto curr_point = - autoware::universe_utils::createPoint(boost_cp.x(), boost_cp.y(), 0.0); - const auto next_point = - autoware::universe_utils::createPoint(boost_np.x(), boost_np.y(), 0.0); - polygon_marker.points.push_back(curr_point); - polygon_marker.points.push_back(next_point); - } - } + utils::fillMarkerFromPolygon(polygons, polygon_marker); debug_markers.markers.push_back(polygon_marker); auto object_data_marker = autoware::universe_utils::createDefaultMarker( diff --git a/control/autoware_autonomous_emergency_braking/src/utils.cpp b/control/autoware_autonomous_emergency_braking/src/utils.cpp index 16174bff3b489..9c8bbe388fdc5 100644 --- a/control/autoware_autonomous_emergency_braking/src/utils.cpp +++ b/control/autoware_autonomous_emergency_braking/src/utils.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include @@ -167,4 +168,22 @@ std::optional getTransform( } return std::make_optional(tf_current_pose); } + +void fillMarkerFromPolygon( + const std::vector & polygons, visualization_msgs::msg::Marker & polygon_marker) +{ + for (const auto & poly : polygons) { + for (size_t dp_idx = 0; dp_idx < poly.outer().size(); ++dp_idx) { + const auto & boost_cp = poly.outer().at(dp_idx); + const auto & boost_np = poly.outer().at((dp_idx + 1) % poly.outer().size()); + const auto curr_point = + autoware::universe_utils::createPoint(boost_cp.x(), boost_cp.y(), 0.0); + const auto next_point = + autoware::universe_utils::createPoint(boost_np.x(), boost_np.y(), 0.0); + polygon_marker.points.push_back(curr_point); + polygon_marker.points.push_back(next_point); + } + } +} + } // namespace autoware::motion::control::autonomous_emergency_braking::utils diff --git a/control/autoware_autonomous_emergency_braking/test/test.cpp b/control/autoware_autonomous_emergency_braking/test/test.cpp index 6203e12a78194..11c2fb1ed671d 100644 --- a/control/autoware_autonomous_emergency_braking/test/test.cpp +++ b/control/autoware_autonomous_emergency_braking/test/test.cpp @@ -157,8 +157,9 @@ TEST_F(TestAEB, checkImuPathGeneration) } } PointCloud::Ptr points_belonging_to_cluster_hulls = pcl::make_shared(); + MarkerArray debug_markers; aeb_node_->getPointsBelongingToClusterHulls( - obstacle_points_ptr, points_belonging_to_cluster_hulls); + obstacle_points_ptr, points_belonging_to_cluster_hulls, debug_markers); std::vector objects; aeb_node_->getClosestObjectsOnPath( imu_path, footprint, stamp, points_belonging_to_cluster_hulls, objects); From afcef77c7be04c69b76261212504a7c9c84c4b4f Mon Sep 17 00:00:00 2001 From: Tim Clephas Date: Thu, 12 Sep 2024 11:47:29 +0200 Subject: [PATCH 214/217] fix(autoware_test_utils): missing ament_index_cpp dependency (#8618) Signed-off-by: Tim Clephas --- common/autoware_test_utils/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/common/autoware_test_utils/package.xml b/common/autoware_test_utils/package.xml index afcf44296a75d..0a4152404ab44 100644 --- a/common/autoware_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -15,6 +15,7 @@ ament_cmake_auto autoware_cmake + ament_index_cpp autoware_control_msgs autoware_lanelet2_extension autoware_map_msgs From 9cc5ef1b4e26d31e37cc90a7fcdd6a31c1b65420 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Thu, 12 Sep 2024 19:19:29 +0900 Subject: [PATCH 215/217] feat(rtc_interface, lane_change): check state transition for cooperate status (#8855) * update rtc state transition Signed-off-by: Go Sakayori * remove transition from failuer and succeeded Signed-off-by: Go Sakayori * fix Signed-off-by: Go Sakayori * check initial state for cooperate status Signed-off-by: Go Sakayori * change rtc cooperate status according to module status Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori --- .../src/rtc_interface.cpp | 45 ++++++++++++++++--- .../src/interface.cpp | 3 -- 2 files changed, 38 insertions(+), 10 deletions(-) diff --git a/planning/autoware_rtc_interface/src/rtc_interface.cpp b/planning/autoware_rtc_interface/src/rtc_interface.cpp index 2808a9cc3b8cc..d79741fe66c2e 100644 --- a/planning/autoware_rtc_interface/src/rtc_interface.cpp +++ b/planning/autoware_rtc_interface/src/rtc_interface.cpp @@ -258,20 +258,51 @@ void RTCInterface::updateCooperateStatus( status.module = module_; status.safe = safe; status.command_status.type = Command::DEACTIVATE; - status.state.type = state; + status.state.type = State::WAITING_FOR_EXECUTION; status.start_distance = start_distance; status.finish_distance = finish_distance; status.auto_mode = is_auto_mode_enabled_; registered_status_.statuses.push_back(status); + + if (state != State::WAITING_FOR_EXECUTION) + RCLCPP_WARN_STREAM( + getLogger(), "[updateCooperateStatus] Cannot register " + << state_to_string(state) << " as initial state" << std::endl); + + return; + } + + auto update_status = [&](auto & status) { + status.stamp = stamp; + status.safe = safe; + status.state.type = state; + status.start_distance = start_distance; + status.finish_distance = finish_distance; + }; + + // If the registered status is found, update status by considering the state transition + if ( + itr->state.type == State::WAITING_FOR_EXECUTION && + (state == State::WAITING_FOR_EXECUTION || state == State::RUNNING || state == State::FAILED)) { + update_status(*itr); + return; + } + + if (itr->state.type == State::RUNNING && state != State::WAITING_FOR_EXECUTION) { + update_status(*itr); return; } - // If the registered status is found, update status - itr->stamp = stamp; - itr->safe = safe; - itr->state.type = state; - itr->start_distance = start_distance; - itr->finish_distance = finish_distance; + if (itr->state.type == State::ABORTING && (state == State::ABORTING || state == State::FAILED)) { + update_status(*itr); + return; + } + + RCLCPP_WARN_STREAM( + getLogger(), "[updateCooperateStatus] uuid : " << uuid_to_string(uuid) + << " cannot transit from " + << state_to_string(itr->state.type) << " to " + << state_to_string(state) << std::endl); } void RTCInterface::removeCooperateStatus(const UUID & uuid) 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 982cdcf3e78a0..7f30f34a8f633 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 @@ -160,9 +160,6 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() stop_pose_ = module_type_->getStopPose(); if (!module_type_->isValidPath()) { - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), false, - State::FAILED); path_candidate_ = std::make_shared(); return out; } From 74be2d3da64d992a2fad5678f05024a6aee4436d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mehmet=20Emin=20BA=C5=9EO=C4=9ELU?= Date: Thu, 12 Sep 2024 13:54:50 +0300 Subject: [PATCH 216/217] chore(autoware_component_monitor): add maintainers (#8867) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mehmet Emin BAŞOĞLU --- system/autoware_component_monitor/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/system/autoware_component_monitor/package.xml b/system/autoware_component_monitor/package.xml index 640e1f2dc2517..8c2afc741435b 100644 --- a/system/autoware_component_monitor/package.xml +++ b/system/autoware_component_monitor/package.xml @@ -5,6 +5,8 @@ 0.0.0 A ROS 2 package to monitor system usage of component containers. Mehmet Emin Başoğlu + Barış Zeren + Yavuz Köseoğlu Apache-2.0 ament_cmake_auto From 6860be87eabe14a515010b89e05a7d9c9fa96ecc Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 12 Sep 2024 10:59:45 +0000 Subject: [PATCH 217/217] chore: update CODEOWNERS (#8749) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 0563b9a1b7598..7b1e69db6a9b0 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -17,7 +17,6 @@ common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp common/component_interface_specs/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/component_interface_tools/** isamu.takagi@tier4.jp common/component_interface_utils/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp -common/cuda_utils/** daisuke.nishimatsu@tier4.jp manato.hirabayashi@tier4.jp common/fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp common/glog_component/** takamasa.horibe@tier4.jp @@ -25,7 +24,6 @@ common/goal_distance_calculator/** taiki.tanaka@tier4.jp common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp common/object_recognition_utils/** shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yoshi.ri@tier4.jp common/osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp -common/perception_utils/** shunsuke.miura@tier4.jp yoshi.ri@tier4.jp common/polar_grid/** yukihiro.saito@tier4.jp common/qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp common/signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @@ -61,7 +59,7 @@ control/autoware_vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier 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/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/predicted_path_checker/** berkay@leodrive.ai -evaluator/autoware_control_evaluator/** daniel.sanchez@tier4.jp takayuki.murooka@tier4.jp kosuke.takeuchi@tier4.jp +evaluator/autoware_control_evaluator/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp temkei.kem@tier4.jp evaluator/autoware_evaluator_utils/** daniel.sanchez@tier4.jp takayuki.murooka@tier4.jp evaluator/autoware_planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp evaluator/diagnostic_converter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp @@ -87,13 +85,13 @@ localization/autoware_localization_error_monitor/** anh.nguyen.2@tier4.jp kento. 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 localization/autoware_pose_estimator_arbiter/** 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_initializer/** anh.nguyen.2@tier4.jp isamu.takagi@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_instability_detector/** 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_stop_filter/** 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_twist2accel/** 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/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/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/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_pose_initializer/** anh.nguyen.2@tier4.jp isamu.takagi@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/yabloc/yabloc_common/** 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/yabloc/yabloc_image_processing/** 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/yabloc/yabloc_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 @@ -143,6 +141,7 @@ perception/autoware_traffic_light_map_based_detector/** shunsuke.miura@tier4.jp perception/autoware_traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/autoware_traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/autoware_traffic_light_visualization/** tao.zhong@tier4.jp yukihiro.saito@tier4.jp +perception/perception_utils/** shunsuke.miura@tier4.jp yoshi.ri@tier4.jp planning/autoware_costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp 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 @@ -209,6 +208,7 @@ sensing/autoware_radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.m sensing/autoware_radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp 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/cuda_utils/** daisuke.nishimatsu@tier4.jp manato.hirabayashi@tier4.jp sensing/livox/autoware_livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp simulator/autoware_carla_interface/** maxime.clement@tier4.jp mradityagio@gmail.com @@ -218,7 +218,7 @@ simulator/learning_based_vehicle_model/** maxime.clement@tier4.jp nagy.tomas@tie 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/tier4_dummy_object_rviz_plugin/** yukihiro.saito@tier4.jp simulator/vehicle_door_simulator/** isamu.takagi@tier4.jp -system/autoware_component_monitor/** memin@leodrive.ai +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