From 866bce768ef88449f82fd501861d842ef0af56da Mon Sep 17 00:00:00 2001 From: karishma Date: Tue, 5 Dec 2023 11:55:53 +0530 Subject: [PATCH 001/276] perception/ground_segmentation Signed-off-by: karishma --- .../schema/ground_segmentation.json | 225 ++++++++++++++++++ .../src/ransac_ground_filter_nodelet.cpp | 24 +- .../src/ray_ground_filter_nodelet.cpp | 24 +- .../src/scan_ground_filter_nodelet.cpp | 14 +- 4 files changed, 256 insertions(+), 31 deletions(-) create mode 100644 perception/ground_segmentation/schema/ground_segmentation.json diff --git a/perception/ground_segmentation/schema/ground_segmentation.json b/perception/ground_segmentation/schema/ground_segmentation.json new file mode 100644 index 0000000000000..d96b320dc6fd9 --- /dev/null +++ b/perception/ground_segmentation/schema/ground_segmentation.json @@ -0,0 +1,225 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for ground_segmentation", + "type": "object", + "definitions": { + "velodyne_monitor": { + "type": "object", + "properties": { + "base_frame": { + "type": "string", + "default": "base_link" + }, + "unit_axis": { + "type": "string", + "default": "z" + }, + "max_iterations": { + "type": "number", + "default": 1000 + }, + "min_inliers": { + "type": "number", + "default": 5000 + }, + "min_points": { + "type": "number", + "default": 1000 + }, + "outlier_threshold": { + "type": "number", + "default": 0.01 + }, + "plane_slope_threshold": { + "type": "number", + "default": 10.0 + }, + "voxel_size_x": { + "type": "number", + "default": 0.04 + }, + "voxel_size_y": { + "type": "number", + "default": 0.04 + }, + "voxel_size_z": { + "type": "number", + "default": 0.04 + }, + "height_threshold": { + "type": "number", + "default": 0.01 + }, + "debug": { + "type": "boolean", + "default": "false" + }, + "min_x": { + "type": "number", + "default": -0.01 + }, + "max_x": { + "type": "number", + "default": 0.01 + }, + "min_y": { + "type": "number", + "default": -0.01 + }, + "max_y": { + "type": "number", + "default": 0.01 + }, + "use_vehicle_footprint": { + "type": "boolean", + "default": "false" + }, + "general_max_slope": { + "type": "number", + "default": 8.0 + }, + "local_max_slope": { + "type": "number", + "default": 6.0 + }, + "initial_max_slope": { + "type": "number", + "default": 3.0 + }, + "radial_divider_angle": { + "type": "number", + "default": 1.0 + }, + "min_height_threshold": { + "type": "number", + "default": 0.15 + }, + "concentric_divider_distance": { + "type": "number", + "default": 0.0 + }, + "reclass_distance_threshold": { + "type": "number", + "default": 0.1 + }, + "low_priority_region_x": { + "type": "number", + "default": -20.0 + }, + "detection_range_z_max": { + "type": "number", + "default": 2.5 + }, + "center_pcl_shift": { + "type": "number", + "default": 0.0 + }, + "non_ground_height_threshold": { + "type": "number", + "default": 0.2 + }, + "grid_mode_switch_radius": { + "type": "number", + "default": 20.0 + }, + "grid_size_m": { + "type": "number", + "default": 0.5 + }, + "gnd_grid_buffer_size": { + "type": "number", + "default": 4 + }, + "elevation_grid_mode": { + "type": "boolean", + "default": "true" + }, + "global_slope_max_angle_rad": { + "type": "number", + "default": 8.0 + }, + "local_slope_max_angle_rad": { + "type": "number", + "default": 10.0 + }, + "radial_divider_angle_rad": { + "type": "number", + "default": 1.0 + }, + "split_points_distance_tolerance": { + "type": "number", + "default": 0.2 + }, + "split_height_distance": { + "type": "number", + "default": 0.2 + }, + "use_virtual_ground_point": { + "type": "boolean", + "default": "true" + }, + "use_recheck_ground_cluster": { + "type": "boolean", + "default": "true" + }, + "radial_dividers_num": { + "type": "string" + } + }, + "required": [ + "base_frame", + "unit_axis", + "max_iterations", + "min_inliers", + "min_points", + "outlier_threshold", + "plane_slope_threshold", + "voxel_size_x", + "voxel_size_y", + "voxel_size_z", + "height_threshold", + "debug", + "min_x", + "min_y", + "max_x", + "max_y", + "use_vehicle_footprint", + "general_max_slope", + "local_max_slope", + "initial_max_slope", + "radial_divider_angle", + "min_height_threshold", + "concentric_divider_distance", + "reclass_distance_threshold", + "low_priority_region_x", + "detection_range_z_max", + "center_pcl_shift", + "non_ground_height_threshold", + "grid_mode_switch_radius", + "grid_size_m", + "gnd_grid_buffer_size", + "elevation_grid_mode", + "global_slope_max_angle_rad", + "local_slope_max_angle_rad", + "radial_divider_angle_rad", + "split_points_distance_tolerance", + "split_height_distance", + "use_virtual_ground_point", + "use_recheck_ground_cluster", + "radial_dividers_num" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/ground_segmentation" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp index ebcb02df2c614..c1afdf5ca199d 100644 --- a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp @@ -85,18 +85,18 @@ using pointcloud_preprocessor::get_param; RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptions & options) : Filter("RANSACGroundFilter", options) { - base_frame_ = declare_parameter("base_frame", "base_link"); - unit_axis_ = declare_parameter("unit_axis", "z"); - max_iterations_ = declare_parameter("max_iterations", 1000); - min_inliers_ = declare_parameter("min_trial", 5000); - min_points_ = declare_parameter("min_points", 1000); - outlier_threshold_ = declare_parameter("outlier_threshold", 0.01); - plane_slope_threshold_ = declare_parameter("plane_slope_threshold", 10.0); - voxel_size_x_ = declare_parameter("voxel_size_x", 0.04); - voxel_size_y_ = declare_parameter("voxel_size_y", 0.04); - voxel_size_z_ = declare_parameter("voxel_size_z", 0.04); - height_threshold_ = declare_parameter("height_threshold", 0.01); - debug_ = declare_parameter("debug", false); + base_frame_ = declare_parameter("base_frame"); + unit_axis_ = declare_parameter("unit_axis"); + max_iterations_ = declare_parameter("max_iterations"); + min_inliers_ = declare_parameter("min_trial"); + min_points_ = declare_parameter("min_points"); + outlier_threshold_ = declare_parameter("outlier_threshold"); + plane_slope_threshold_ = declare_parameter("plane_slope_threshold"); + voxel_size_x_ = declare_parameter("voxel_size_x"); + voxel_size_y_ = declare_parameter("voxel_size_y"); + voxel_size_z_ = declare_parameter("voxel_size_z"); + height_threshold_ = declare_parameter("height_threshold"); + debug_ = declare_parameter("debug"); if (unit_axis_ == "x") { unit_vec_ = Eigen::Vector3d::UnitX(); diff --git a/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp index 4b2e81d272e30..4270279ff0162 100644 --- a/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp @@ -48,22 +48,22 @@ RayGroundFilterComponent::RayGroundFilterComponent(const rclcpp::NodeOptions & o grid_precision_ = 0.2; ray_ground_filter::generateColors(colors_, color_num_); - min_x_ = declare_parameter("min_x", -0.01); - max_x_ = declare_parameter("max_x", 0.01); - min_y_ = declare_parameter("min_y", -0.01); - max_y_ = declare_parameter("max_y", 0.01); + min_x_ = declare_parameter("min_x"); + max_x_ = declare_parameter("max_x"); + min_y_ = declare_parameter("min_y"); + max_y_ = declare_parameter("max_y"); setVehicleFootprint(min_x_, max_x_, min_y_, max_y_); - use_vehicle_footprint_ = declare_parameter("use_vehicle_footprint", false); + use_vehicle_footprint_ = declare_parameter("use_vehicle_footprint"); - general_max_slope_ = declare_parameter("general_max_slope", 8.0); - local_max_slope_ = declare_parameter("local_max_slope", 6.0); - initial_max_slope_ = declare_parameter("initial_max_slope", 3.0); - radial_divider_angle_ = declare_parameter("radial_divider_angle", 1.0); - min_height_threshold_ = declare_parameter("min_height_threshold", 0.15); - concentric_divider_distance_ = declare_parameter("concentric_divider_distance", 0.0); - reclass_distance_threshold_ = declare_parameter("reclass_distance_threshold", 0.1); + general_max_slope_ = declare_parameter("general_max_slope"); + local_max_slope_ = declare_parameter("local_max_slope"); + initial_max_slope_ = declare_parameter("initial_max_slope"); + radial_divider_angle_ = declare_parameter("radial_divider_angle"); + min_height_threshold_ = declare_parameter("min_height_threshold"); + concentric_divider_distance_ = declare_parameter("concentric_divider_distance"); + reclass_distance_threshold_ = declare_parameter("reclass_distance_threshold"); } using std::placeholders::_1; diff --git a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp index 953a9feb4d21e..da3c37224ee2a 100644 --- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp @@ -48,13 +48,13 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & grid_size_m_ = static_cast(declare_parameter("grid_size_m", 0.5)); gnd_grid_buffer_size_ = static_cast(declare_parameter("gnd_grid_buffer_size", 4)); elevation_grid_mode_ = static_cast(declare_parameter("elevation_grid_mode", true)); - global_slope_max_angle_rad_ = deg2rad(declare_parameter("global_slope_max_angle_deg", 8.0)); - local_slope_max_angle_rad_ = deg2rad(declare_parameter("local_slope_max_angle_deg", 10.0)); - radial_divider_angle_rad_ = deg2rad(declare_parameter("radial_divider_angle_deg", 1.0)); - split_points_distance_tolerance_ = declare_parameter("split_points_distance_tolerance", 0.2); - split_height_distance_ = declare_parameter("split_height_distance", 0.2); - use_virtual_ground_point_ = declare_parameter("use_virtual_ground_point", true); - use_recheck_ground_cluster_ = declare_parameter("use_recheck_ground_cluster", true); + global_slope_max_angle_rad_ = deg2rad(declare_parameter("global_slope_max_angle_deg")); + local_slope_max_angle_rad_ = deg2rad(declare_parameter("local_slope_max_angle_deg")); + radial_divider_angle_rad_ = deg2rad(declare_parameter("radial_divider_angle_deg")); + split_points_distance_tolerance_ = declare_parameter("split_points_distance_tolerance"); + split_height_distance_ = declare_parameter("split_height_distance"); + use_virtual_ground_point_ = declare_parameter("use_virtual_ground_point"); + use_recheck_ground_cluster_ = declare_parameter("use_recheck_ground_cluster"); radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_); vehicle_info_ = VehicleInfoUtil(*this).getVehicleInfo(); From 306c33c52685916a30aed0c27ebca7377d3fa91f Mon Sep 17 00:00:00 2001 From: karishma Date: Tue, 5 Dec 2023 13:10:52 +0530 Subject: [PATCH 002/276] perception_ground_segmentation Signed-off-by: karishma --- perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp index 4270279ff0162..83e7185f92a15 100644 --- a/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp @@ -56,7 +56,6 @@ RayGroundFilterComponent::RayGroundFilterComponent(const rclcpp::NodeOptions & o setVehicleFootprint(min_x_, max_x_, min_y_, max_y_); use_vehicle_footprint_ = declare_parameter("use_vehicle_footprint"); - general_max_slope_ = declare_parameter("general_max_slope"); local_max_slope_ = declare_parameter("local_max_slope"); initial_max_slope_ = declare_parameter("initial_max_slope"); From c59419f88988213f9464b0608e24bb2e096a4abd Mon Sep 17 00:00:00 2001 From: karishma Date: Wed, 6 Dec 2023 16:48:35 +0530 Subject: [PATCH 003/276] ground-segmentation Signed-off-by: karishma --- perception/ground_segmentation/schema/ground_segmentation.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/ground_segmentation/schema/ground_segmentation.json b/perception/ground_segmentation/schema/ground_segmentation.json index d96b320dc6fd9..9d4331a1179ed 100644 --- a/perception/ground_segmentation/schema/ground_segmentation.json +++ b/perception/ground_segmentation/schema/ground_segmentation.json @@ -3,7 +3,7 @@ "title": "Parameters for ground_segmentation", "type": "object", "definitions": { - "velodyne_monitor": { + "ground_segmentation": { "type": "object", "properties": { "base_frame": { From f7ec95267c5d02c7570ca5aee0742cbf39e92d10 Mon Sep 17 00:00:00 2001 From: karishma Date: Thu, 7 Dec 2023 11:01:47 +0530 Subject: [PATCH 004/276] update-ground-segmentation Signed-off-by: karishma --- .../ground_segmentation/src/ransac_ground_filter_nodelet.cpp | 2 +- .../ground_segmentation/src/ray_ground_filter_nodelet.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp index c1afdf5ca199d..6fed2f5d296a2 100644 --- a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp @@ -91,7 +91,7 @@ RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptio min_inliers_ = declare_parameter("min_trial"); min_points_ = declare_parameter("min_points"); outlier_threshold_ = declare_parameter("outlier_threshold"); - plane_slope_threshold_ = declare_parameter("plane_slope_threshold"); + plane_slope_threshold_ = declare_parameter("plane_slope_threshold"); voxel_size_x_ = declare_parameter("voxel_size_x"); voxel_size_y_ = declare_parameter("voxel_size_y"); voxel_size_z_ = declare_parameter("voxel_size_z"); diff --git a/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp index 83e7185f92a15..6134770b3f4b1 100644 --- a/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp @@ -58,7 +58,7 @@ RayGroundFilterComponent::RayGroundFilterComponent(const rclcpp::NodeOptions & o use_vehicle_footprint_ = declare_parameter("use_vehicle_footprint"); general_max_slope_ = declare_parameter("general_max_slope"); local_max_slope_ = declare_parameter("local_max_slope"); - initial_max_slope_ = declare_parameter("initial_max_slope"); + initial_max_slope_ = declare_parameter("initial_max_slope"); radial_divider_angle_ = declare_parameter("radial_divider_angle"); min_height_threshold_ = declare_parameter("min_height_threshold"); concentric_divider_distance_ = declare_parameter("concentric_divider_distance"); From efed23fcaa45ac8601250d676f933874673f8fe2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 5 Dec 2023 23:46:42 +0900 Subject: [PATCH 005/276] feat(dynamic_avoidance): reintroduce path_generation_method (#5726) * feat(dynamic_avoidance): reintroduce path_generation_method Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * pre-commit Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance.param.yaml | 1 + .../dynamic_avoidance_module.hpp | 23 ++++++++----------- .../dynamic_avoidance_module.cpp | 16 +++++-------- .../dynamic_avoidance/manager.cpp | 20 ++++++++++++++++ 4 files changed, 37 insertions(+), 23 deletions(-) diff --git a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml index 24bc144c40afd..854c29aa89bc5 100644 --- a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml +++ b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml @@ -47,6 +47,7 @@ max_ego_path_lat_cover_ratio: 0.3 # [-] The object will be ignored if the ratio of the object covering the ego's path is higher than this value. drivable_area_generation: + 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/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 49ce760fec4c9..e37ef27d44426 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -46,6 +46,11 @@ struct MinMaxValue double max_value{0.0}; }; +enum class PolygonGenerationMethod { + EGO_PATH_BASE = 0, + OBJECT_PATH_BASE, +}; + struct DynamicAvoidanceParameters { // common @@ -84,6 +89,7 @@ struct DynamicAvoidanceParameters double max_oncoming_crossing_object_angle{0.0}; // drivable area generation + PolygonGenerationMethod polygon_generation_method{}; double min_obj_path_based_lon_polygon_margin{0.0}; double lat_offset_from_obstacle{0.0}; double max_lat_offset_to_avoid{0.0}; @@ -103,10 +109,6 @@ struct DynamicAvoidanceParameters class DynamicAvoidanceModule : public SceneModuleInterface { public: - enum class PolygonGenerationMethod { - EGO_PATH_BASE = 0, - OBJECT_PATH_BASE, - }; struct DynamicAvoidanceObject { DynamicAvoidanceObject( @@ -141,18 +143,15 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::optional lat_offset_to_avoid{std::nullopt}; bool is_collision_left{false}; bool should_be_avoided{false}; - PolygonGenerationMethod polygon_generation_method{PolygonGenerationMethod::OBJECT_PATH_BASE}; void update( const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid, - const bool arg_is_collision_left, const bool arg_should_be_avoided, - const PolygonGenerationMethod & arg_polygon_generation_method) + const bool arg_is_collision_left, const bool arg_should_be_avoided) { lon_offset_to_avoid = arg_lon_offset_to_avoid; lat_offset_to_avoid = arg_lat_offset_to_avoid; is_collision_left = arg_is_collision_left; should_be_avoided = arg_should_be_avoided; - polygon_generation_method = arg_polygon_generation_method; } }; @@ -246,12 +245,11 @@ class DynamicAvoidanceModule : public SceneModuleInterface void updateObject( const std::string & uuid, const MinMaxValue & lon_offset_to_avoid, const MinMaxValue & lat_offset_to_avoid, const bool is_collision_left, - const bool should_be_avoided, const PolygonGenerationMethod & polygon_generation_method) + const bool should_be_avoided) { if (object_map_.count(uuid) != 0) { object_map_.at(uuid).update( - lon_offset_to_avoid, lat_offset_to_avoid, is_collision_left, should_be_avoided, - polygon_generation_method); + lon_offset_to_avoid, lat_offset_to_avoid, is_collision_left, should_be_avoided); } } @@ -311,8 +309,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface void updateTargetObjects(); bool willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, - const double obj_tangent_vel, const LatLonOffset & lat_lon_offset, - PolygonGenerationMethod & polygon_generation_method) const; + const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const; DecisionWithReason willObjectCutOut( const double obj_tangent_vel, const double obj_normal_vel, const bool is_object_left, const std::optional & prev_object) const; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 1310c91d93afe..de76166e068d3 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -319,10 +319,10 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() std::vector obstacles_for_drivable_area; for (const auto & object : target_objects_) { const auto obstacle_poly = [&]() { - if (object.polygon_generation_method == PolygonGenerationMethod::EGO_PATH_BASE) { + if (parameters_->polygon_generation_method == PolygonGenerationMethod::EGO_PATH_BASE) { return calcEgoPathBasedDynamicObstaclePolygon(object); } - if (object.polygon_generation_method == PolygonGenerationMethod::OBJECT_PATH_BASE) { + if (parameters_->polygon_generation_method == PolygonGenerationMethod::OBJECT_PATH_BASE) { return calcObjectPathBasedDynamicObstaclePolygon(object); } throw std::logic_error("The polygon_generation_method's string is invalid."); @@ -492,7 +492,6 @@ void DynamicAvoidanceModule::updateTargetObjects() // 2. Precise filtering of target objects and check if they should be avoided for (const auto & object : target_objects_manager_.getValidObjects()) { - PolygonGenerationMethod polygon_generation_method{PolygonGenerationMethod::EGO_PATH_BASE}; const auto obj_uuid = object.uuid; const auto prev_object = getObstacleFromUuid(prev_objects, obj_uuid); const auto obj_path = *std::max_element( @@ -519,8 +518,8 @@ void DynamicAvoidanceModule::updateTargetObjects() getLateralLongitudinalOffset(input_path->points, object.pose, object.shape); // 2.c. check if object will not cut in - const bool will_object_cut_in = willObjectCutIn( - input_path->points, obj_path, object.vel, lat_lon_offset, polygon_generation_method); + const bool will_object_cut_in = + willObjectCutIn(input_path->points, obj_path, object.vel, lat_lon_offset); if (will_object_cut_in) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, @@ -607,8 +606,7 @@ void DynamicAvoidanceModule::updateTargetObjects() const bool should_be_avoided = true; target_objects_manager_.updateObject( - obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided, - polygon_generation_method); + obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided); } prev_input_ref_path_points = input_ref_path_points; @@ -686,8 +684,7 @@ bool DynamicAvoidanceModule::isObjectFarFromPath( bool DynamicAvoidanceModule::willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, - const double obj_tangent_vel, const LatLonOffset & lat_lon_offset, - PolygonGenerationMethod & polygon_generation_method) const + const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const { // Ignore oncoming object if (obj_tangent_vel < parameters_->min_cut_in_object_vel) { @@ -721,7 +718,6 @@ bool DynamicAvoidanceModule::willObjectCutIn( lon_offset_ego_to_obj < std::max( parameters_->min_lon_offset_ego_to_cut_in_object, relative_velocity * parameters_->min_time_to_start_cut_in)) { - polygon_generation_method = PolygonGenerationMethod::EGO_PATH_BASE; return false; } diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index bf4197c59ffd9..2824a6221591a 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -24,6 +24,18 @@ namespace behavior_path_planner { +namespace +{ +PolygonGenerationMethod convertToPolygonGenerationMethod(const std::string & str) +{ + if (str == "ego_path_base") { + return PolygonGenerationMethod::EGO_PATH_BASE; + } else if (str == "object_path_base") { + return PolygonGenerationMethod::OBJECT_PATH_BASE; + } + throw std::logic_error("The polygon_generation_method's string is invalid."); +} +} // namespace void DynamicAvoidanceModuleManager::init(rclcpp::Node * node) { @@ -91,6 +103,8 @@ void DynamicAvoidanceModuleManager::init(rclcpp::Node * node) { // drivable_area_generation const std::string ns = "dynamic_avoidance.drivable_area_generation."; + p.polygon_generation_method = convertToPolygonGenerationMethod( + node->declare_parameter(ns + "polygon_generation_method")); p.min_obj_path_based_lon_polygon_margin = node->declare_parameter(ns + "object_path_base.min_longitudinal_polygon_margin"); p.lat_offset_from_obstacle = node->declare_parameter(ns + "lat_offset_from_obstacle"); @@ -197,6 +211,12 @@ void DynamicAvoidanceModuleManager::updateModuleParams( { // drivable_area_generation const std::string ns = "dynamic_avoidance.drivable_area_generation."; + std::string polygon_generation_method_str; + if (updateParam( + parameters, ns + "polygon_generation_method", polygon_generation_method_str)) { + p->polygon_generation_method = + convertToPolygonGenerationMethod(polygon_generation_method_str); + } updateParam( parameters, ns + "object_path_base.min_longitudinal_polygon_margin", p->min_obj_path_based_lon_polygon_margin); From 67b0368e43249c38d29d9b91143db4cc1eab8c82 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 5 Dec 2023 23:49:34 +0900 Subject: [PATCH 006/276] feat(mission_planner): print reroute info (#5784) feat(mission_planner): print modified goal reroute Signed-off-by: kosuke55 --- .../mission_planner/src/mission_planner/mission_planner.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 3b5e3217f5beb..2890015ad4788 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -444,6 +444,7 @@ void MissionPlanner::on_set_mrm_route( res->status.success = false; } change_state(RouteState::Message::SET); + RCLCPP_INFO(get_logger(), "Route is successfully changed with the modified goal"); return; } @@ -452,6 +453,7 @@ void MissionPlanner::on_set_mrm_route( change_mrm_route(new_route); change_state(RouteState::Message::SET); res->status.success = true; + RCLCPP_INFO(get_logger(), "MRM route is successfully changed with the modified goal"); return; } @@ -537,6 +539,8 @@ void MissionPlanner::on_clear_mrm_route( void MissionPlanner::on_modified_goal(const ModifiedGoal::Message::ConstSharedPtr msg) { + RCLCPP_INFO(get_logger(), "Received modified goal."); + if (state_.state != RouteState::Message::SET) { RCLCPP_ERROR(get_logger(), "The route hasn't set yet. Cannot reroute."); return; @@ -572,6 +576,7 @@ void MissionPlanner::on_modified_goal(const ModifiedGoal::Message::ConstSharedPt change_mrm_route(new_route); change_state(RouteState::Message::SET); + RCLCPP_INFO(get_logger(), "Changed the MRM route with the modified goal"); return; } @@ -593,6 +598,7 @@ void MissionPlanner::on_modified_goal(const ModifiedGoal::Message::ConstSharedPt change_route(new_route); change_state(RouteState::Message::SET); + RCLCPP_INFO(get_logger(), "Changed the route with the modified goal"); return; } From b6487dc83953e516333e6760d2b5cac225566e87 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 5 Dec 2023 23:49:53 +0900 Subject: [PATCH 007/276] fix(behavior_path_planner): reset previou modified goal (#5785) Signed-off-by: kosuke55 --- .../behavior_path_planner/src/behavior_path_planner_node.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 27a049a5fa56f..3aceedcbde2ba 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -408,7 +408,9 @@ void BehaviorPathPlannerNode::run() // Reset behavior tree when new route is received, // so that the each modules do not have to care about the "route jump". if (!is_first_time && !has_same_route_id) { + RCLCPP_INFO(get_logger(), "New uuid route is received. Resetting modules."); planner_manager_->reset(); + planner_data_->prev_modified_goal.reset(); } } From 803d7a87108b05428e0d3cad936eedec5c36cca0 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 6 Dec 2023 02:23:54 +0900 Subject: [PATCH 008/276] fix(mission_planner): fix reroute chattering when mrm route clear fails (#5788) Signed-off-by: kosuke55 --- .../mission_planner/src/mission_planner/mission_planner.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 2890015ad4788..29e8ae1163938 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -524,9 +524,8 @@ void MissionPlanner::on_clear_mrm_route( // check new route safety if (new_route.segments.empty() || !check_reroute_safety(*mrm_route_, new_route)) { // failed to create a new route - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 5000, "Reroute with normal goal failed."); + RCLCPP_ERROR(get_logger(), "Reroute with normal goal failed."); change_mrm_route(*mrm_route_); - change_route(*normal_route_); change_state(RouteState::Message::SET); res->status.success = false; } else { From 2c6d86fbc6efc378cd2128dcf938a64c38ae5e2c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 6 Dec 2023 02:24:08 +0900 Subject: [PATCH 009/276] feat(mission_planner): judge reroute safe when ego is stopped (#5787) Signed-off-by: kosuke55 --- .../src/mission_planner/mission_planner.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 29e8ae1163938..a1536a1bebfbf 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -734,6 +734,13 @@ bool MissionPlanner::check_reroute_safety( return false; } + const auto current_velocity = odometry_->twist.twist.linear.x; + + // if vehicle is stopped, do not check safety + if (current_velocity < 0.01) { + return true; + } + auto hasSamePrimitives = []( const std::vector & original_primitives, const std::vector & target_primitives) { @@ -878,13 +885,17 @@ bool MissionPlanner::check_reroute_safety( } // check safety - const auto current_velocity = odometry_->twist.twist.linear.x; const double safety_length = std::max(current_velocity * reroute_time_threshold_, minimum_reroute_length_); if (accumulated_length > safety_length) { return true; } + RCLCPP_WARN( + get_logger(), + "Length of lane where original and B target (= %f) is less than safety length (= %f), so " + "reroute is not safe.", + accumulated_length, safety_length); return false; } } // namespace mission_planner From e9530c8d7d0c132c0c382af39182891dd1977960 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 6 Dec 2023 02:25:54 +0900 Subject: [PATCH 010/276] feat(behavior_path_planner): allow reroute when always executable module running or candidate modules is running (#5786) feat(behavior_path_planner): allow reroute when always executable module running or candidate modules Signed-off-by: kosuke55 --- .../behavior_path_planner_node.hpp | 2 +- .../behavior_path_planner/planner_manager.hpp | 7 +++++++ .../src/behavior_path_planner_node.cpp | 14 +++++--------- .../behavior_path_planner/src/planner_manager.cpp | 5 +---- 4 files changed, 14 insertions(+), 14 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 01ad67e45d39d..c47dc70213d1a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -173,7 +173,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node /** * @brief publish reroute availability */ - void publish_reroute_availability(); + void publish_reroute_availability() const; /** * @brief publish steering factor from intersection diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 638dcfe520289..7ceafb6f428de 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -226,6 +226,13 @@ class PlannerManager */ bool hasApprovedModules() const { return !approved_module_ptrs_.empty(); } + bool hasNonAlwaysExecutableApprovedModules() const + { + return std::any_of( + approved_module_ptrs_.begin(), approved_module_ptrs_.end(), + [this](const auto & m) { return !getManager(m)->isAlwaysExecutableModule(); }); + } + /** * @brief check if there are candidate modules. */ diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 3aceedcbde2ba..907c5226c3908 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -551,18 +551,14 @@ void BehaviorPathPlannerNode::publish_steering_factor( steering_factor_interface_ptr_->publishSteeringFactor(get_clock()->now()); } -void BehaviorPathPlannerNode::publish_reroute_availability() +void BehaviorPathPlannerNode::publish_reroute_availability() const { - const bool has_approved_modules = planner_manager_->hasApprovedModules(); - const bool has_candidate_modules = planner_manager_->hasCandidateModules(); - - // In the current behavior path planner, we might get unexpected behavior when rerouting while - // modules other than lane follow are active. Therefore, rerouting will be allowed only when the - // lane follow module is running Note that if there is a approved module or candidate module, it - // means non-lane-following modules are runnning. + // In the current behavior path planner, we might encounter unexpected behavior when rerouting + // while modules other than lane following are active. If non-lane-following module except + // always-executable module is approved and running, rerouting will not be possible. RerouteAvailability is_reroute_available; is_reroute_available.stamp = this->now(); - if (has_approved_modules || has_candidate_modules) { + if (planner_manager_->hasNonAlwaysExecutableApprovedModules()) { is_reroute_available.availability = false; } else { is_reroute_available.availability = true; diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 5c5c675d64b88..c867bffc8e9bd 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -263,10 +263,7 @@ std::vector PlannerManager::getRequestModules( // Condition 1: always executable module can be added regardless of the existence of other // modules, so skip checking the existence of other modules. // in other cases, need to check the existence of other modules and which module can be added. - const bool has_non_always_executable_module = std::any_of( - approved_module_ptrs_.begin(), approved_module_ptrs_.end(), - [this](const auto & m) { return !getManager(m)->isAlwaysExecutableModule(); }); - if (!manager_ptr->isAlwaysExecutableModule() && has_non_always_executable_module) { + if (!manager_ptr->isAlwaysExecutableModule() && hasNonAlwaysExecutableApprovedModules()) { // pairs of find_block_module and is_executable std::vector, std::function>> conditions; From 29f42d29f093af5ee4514591314245d2aff905e3 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> Date: Wed, 6 Dec 2023 15:25:57 +0900 Subject: [PATCH 011/276] fix(ekf_localizer): correct the calculation of delay_step in updateMeasurementPose/Twist (#5691) * Added X_delay_times_ to obtain the accumulated lap times of the timer callback. Added find_closest_index function to easily use the X_delay_times_. Signed-off-by: TaikiYamada4 * Added a concept/variable of accumulated_delay_time_ and store every lap time of timer callback. The delay_step will be calculated from it, and the bug of calculating delay_step should be gone. Besides, removed dt in measurementUpdatePose/Twist since it is not needed. Signed-off-by: TaikiYamada4 * Fixed dt to ekf_dt_ in predictUpdateFrequency() Signed-off-by: TaikiYamada4 * Removed temporary debug stuff Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Fixed code style pointed out from pre-commit.ci Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Fixed typo Signed-off-by: TaikiYamada4 * Removed variable ekf_rate_ which is currently unused. Added warnings when the ekf_dt_ is too large. Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Changed threshold of delay time so that to look the most last (or largest) value of accumulated_delay_times_ Signed-off-by: TaikiYamada4 * Correct the warning messages of diag_info to look up the last (or largest) value of accumulated_delay_times_ Signed-off-by: TaikiYamada4 * style(pre-commit): autofix --------- Signed-off-by: TaikiYamada4 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/ekf_localizer/ekf_localizer.hpp | 1 - .../include/ekf_localizer/ekf_module.hpp | 9 ++- .../include/ekf_localizer/warning_message.hpp | 5 +- .../ekf_localizer/src/ekf_localizer.cpp | 25 +++++--- localization/ekf_localizer/src/ekf_module.cpp | 63 ++++++++++++++++--- .../ekf_localizer/src/warning_message.cpp | 14 ++--- .../test/test_warning_message.cpp | 8 +-- 7 files changed, 91 insertions(+), 34 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index e2ffff2195645..ba18b7dadd599 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -155,7 +155,6 @@ class EKFLocalizer : public rclcpp::Node const HyperParameters params_; - double ekf_rate_; double ekf_dt_; /* process noise variance for discrete model */ diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp index 873060c75fcfc..e88a59ffdfab9 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp @@ -30,6 +30,7 @@ #include #include +#include struct EKFDiagnosticInfo { @@ -76,12 +77,15 @@ class EKFModule std::array getCurrentPoseCovariance() const; std::array getCurrentTwistCovariance() const; + size_t find_closest_delay_time_index(double target_value) const; + void accumulate_delay_time(const double dt); + void predictWithDelay(const double dt); bool measurementUpdatePose( - const PoseWithCovariance & pose, const double dt, const rclcpp::Time & t_curr, + const PoseWithCovariance & pose, const rclcpp::Time & t_curr, EKFDiagnosticInfo & pose_diag_info); bool measurementUpdateTwist( - const TwistWithCovariance & twist, const double dt, const rclcpp::Time & t_curr, + const TwistWithCovariance & twist, const rclcpp::Time & t_curr, EKFDiagnosticInfo & twist_diag_info); geometry_msgs::msg::PoseWithCovarianceStamped compensatePoseWithZDelay( const PoseWithCovariance & pose, const double delay_time); @@ -91,6 +95,7 @@ class EKFModule std::shared_ptr warning_; const int dim_x_; + std::vector accumulated_delay_times_; const HyperParameters params_; }; diff --git a/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp b/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp index f6c664eb26451..e1eafdc6f7948 100644 --- a/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp @@ -17,10 +17,9 @@ #include -std::string poseDelayStepWarningMessage( - const double delay_time, const int extend_state_step, const double ekf_dt); +std::string poseDelayStepWarningMessage(const double delay_time, const double delay_time_threshold); std::string twistDelayStepWarningMessage( - const double delay_time, const int extend_state_step, const double ekf_dt); + const double delay_time, const double delay_time_threshold); std::string poseDelayTimeWarningMessage(const double delay_time); std::string twistDelayTimeWarningMessage(const double delay_time); std::string mahalanobisWarningMessage(const double distance, const double max_distance); diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 5dd78a00f2fbd..a3d2f52a4058c 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -44,7 +44,6 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti : rclcpp::Node(node_name, node_options), warning_(std::make_shared(this)), params_(this), - ekf_rate_(params_.ekf_rate), ekf_dt_(params_.ekf_dt), pose_queue_(params_.pose_smoothing_steps), twist_queue_(params_.twist_smoothing_steps) @@ -109,9 +108,22 @@ void EKFLocalizer::updatePredictFrequency() if (get_clock()->now() < *last_predict_time_) { warning_->warn("Detected jump back in time"); } else { - ekf_rate_ = 1.0 / (get_clock()->now() - *last_predict_time_).seconds(); - DEBUG_INFO(get_logger(), "[EKF] update ekf_rate_ to %f hz", ekf_rate_); - ekf_dt_ = 1.0 / std::max(ekf_rate_, 0.1); + /* Measure dt */ + ekf_dt_ = (get_clock()->now() - *last_predict_time_).seconds(); + DEBUG_INFO( + get_logger(), "[EKF] update ekf_dt_ to %f seconds (= %f hz)", ekf_dt_, 1 / ekf_dt_); + + if (ekf_dt_ > 10.0) { + ekf_dt_ = 10.0; + RCLCPP_WARN( + get_logger(), "Large ekf_dt_ detected!! (%f sec) Capped to 10.0 seconds", ekf_dt_); + } else if (ekf_dt_ > params_.pose_smoothing_steps / params_.ekf_rate) { + RCLCPP_WARN( + get_logger(), "EKF period may be too slow to finish pose smoothing!! (%f sec) ", ekf_dt_); + } + + /* Register dt and accumulate time delay */ + ekf_module_->accumulate_delay_time(ekf_dt_); /* Update discrete proc_cov*/ proc_cov_vx_d_ = std::pow(params_.proc_stddev_vx_c * ekf_dt_, 2.0); @@ -165,7 +177,7 @@ void EKFLocalizer::timerCallback() const size_t n = pose_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto pose = pose_queue_.pop_increment_age(); - bool is_updated = ekf_module_->measurementUpdatePose(*pose, ekf_dt_, t_curr, pose_diag_info_); + bool is_updated = ekf_module_->measurementUpdatePose(*pose, t_curr, pose_diag_info_); if (is_updated) { pose_is_updated = true; @@ -200,8 +212,7 @@ void EKFLocalizer::timerCallback() const size_t n = twist_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto twist = twist_queue_.pop_increment_age(); - bool is_updated = - ekf_module_->measurementUpdateTwist(*twist, ekf_dt_, t_curr, twist_diag_info_); + bool is_updated = ekf_module_->measurementUpdateTwist(*twist, t_curr, twist_diag_info_); if (is_updated) { twist_is_updated = true; } diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp index 0a5e3c98c96c8..10926b04507a0 100644 --- a/localization/ekf_localizer/src/ekf_module.cpp +++ b/localization/ekf_localizer/src/ekf_module.cpp @@ -38,6 +38,7 @@ EKFModule::EKFModule(std::shared_ptr warning, const HyperParameters params) : warning_(std::move(warning)), dim_x_(6), // x, y, yaw, yaw_bias, vx, wz + accumulated_delay_times_(params.extend_state_step, 1.0E15), params_(params) { Eigen::MatrixXd X = Eigen::MatrixXd::Zero(dim_x_, 1); @@ -131,6 +132,48 @@ double EKFModule::getYawBias() const return kalman_filter_.getLatestX()(IDX::YAWB); } +size_t EKFModule::find_closest_delay_time_index(double target_value) const +{ + // If target_value is too large, return last index + 1 + if (target_value > accumulated_delay_times_.back()) { + return accumulated_delay_times_.size(); + } + + auto lower = std::lower_bound( + accumulated_delay_times_.begin(), accumulated_delay_times_.end(), target_value); + + // If the lower bound is the first element, return its index. + // If the lower bound is beyond the last element, return the last index. + // If else, take the closest element. + if (lower == accumulated_delay_times_.begin()) { + return 0; + } else if (lower == accumulated_delay_times_.end()) { + return accumulated_delay_times_.size() - 1; + } else { + // Compare the target with the lower bound and the previous element. + auto prev = lower - 1; + bool is_closer_to_prev = (target_value - *prev) < (*lower - target_value); + + // Return the index of the closer element. + return is_closer_to_prev ? std::distance(accumulated_delay_times_.begin(), prev) + : std::distance(accumulated_delay_times_.begin(), lower); + } +} + +void EKFModule::accumulate_delay_time(const double dt) +{ + // Shift the delay times to the right. + std::copy_backward( + accumulated_delay_times_.begin(), accumulated_delay_times_.end() - 1, + accumulated_delay_times_.end()); + + // Add the new delay time to all elements. + accumulated_delay_times_.front() = 0.0; + for (auto & delay_time : accumulated_delay_times_) { + delay_time += dt; + } +} + void EKFModule::predictWithDelay(const double dt) { const Eigen::MatrixXd X_curr = kalman_filter_.getLatestX(); @@ -147,8 +190,7 @@ void EKFModule::predictWithDelay(const double dt) } bool EKFModule::measurementUpdatePose( - const PoseWithCovariance & pose, const double dt, const rclcpp::Time & t_curr, - EKFDiagnosticInfo & pose_diag_info) + const PoseWithCovariance & pose, const rclcpp::Time & t_curr, EKFDiagnosticInfo & pose_diag_info) { if (pose.header.frame_id != params_.pose_frame_id) { warning_->warnThrottle( @@ -170,14 +212,15 @@ bool EKFModule::measurementUpdatePose( delay_time = std::max(delay_time, 0.0); - const int delay_step = std::roundf(delay_time / dt); + const int delay_step = static_cast(find_closest_delay_time_index(delay_time)); pose_diag_info.delay_time = std::max(delay_time, pose_diag_info.delay_time); - pose_diag_info.delay_time_threshold = params_.extend_state_step * dt; + pose_diag_info.delay_time_threshold = accumulated_delay_times_.back(); if (delay_step >= params_.extend_state_step) { pose_diag_info.is_passed_delay_gate = false; warning_->warnThrottle( - poseDelayStepWarningMessage(delay_time, params_.extend_state_step, dt), 2000); + poseDelayStepWarningMessage(pose_diag_info.delay_time, pose_diag_info.delay_time_threshold), + 2000); return false; } @@ -243,7 +286,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensatePoseWithZDela } bool EKFModule::measurementUpdateTwist( - const TwistWithCovariance & twist, const double dt, const rclcpp::Time & t_curr, + const TwistWithCovariance & twist, const rclcpp::Time & t_curr, EKFDiagnosticInfo & twist_diag_info) { if (twist.header.frame_id != "base_link") { @@ -262,14 +305,16 @@ bool EKFModule::measurementUpdateTwist( } delay_time = std::max(delay_time, 0.0); - const int delay_step = std::roundf(delay_time / dt); + const int delay_step = static_cast(find_closest_delay_time_index(delay_time)); twist_diag_info.delay_time = std::max(delay_time, twist_diag_info.delay_time); - twist_diag_info.delay_time_threshold = params_.extend_state_step * dt; + twist_diag_info.delay_time_threshold = accumulated_delay_times_.back(); if (delay_step >= params_.extend_state_step) { twist_diag_info.is_passed_delay_gate = false; warning_->warnThrottle( - twistDelayStepWarningMessage(delay_time, params_.extend_state_step, dt), 2000); + twistDelayStepWarningMessage( + twist_diag_info.delay_time, twist_diag_info.delay_time_threshold), + 2000); return false; } diff --git a/localization/ekf_localizer/src/warning_message.cpp b/localization/ekf_localizer/src/warning_message.cpp index 9a7bbf47a94eb..c69f30b2d6601 100644 --- a/localization/ekf_localizer/src/warning_message.cpp +++ b/localization/ekf_localizer/src/warning_message.cpp @@ -18,22 +18,20 @@ #include -std::string poseDelayStepWarningMessage( - const double delay_time, const int extend_state_step, const double ekf_dt) +std::string poseDelayStepWarningMessage(const double delay_time, const double delay_time_threshold) { const std::string s = "Pose delay exceeds the compensation limit, ignored. " - "delay: {:.3f}[s], limit = extend_state_step * ekf_dt : {:.3f}[s]"; - return fmt::format(s, delay_time, extend_state_step * ekf_dt); + "delay: {:.3f}[s], limit: {:.3f}[s]"; + return fmt::format(s, delay_time, delay_time_threshold); } -std::string twistDelayStepWarningMessage( - const double delay_time, const int extend_state_step, const double ekf_dt) +std::string twistDelayStepWarningMessage(const double delay_time, const double delay_time_threshold) { const std::string s = "Twist delay exceeds the compensation limit, ignored. " - "delay: {:.3f}[s], limit = extend_state_step * ekf_dt : {:.3f}[s]"; - return fmt::format(s, delay_time, extend_state_step * ekf_dt); + "delay: {:.3f}[s], limit: {:.3f}[s]"; + return fmt::format(s, delay_time, delay_time_threshold); } std::string poseDelayTimeWarningMessage(const double delay_time) diff --git a/localization/ekf_localizer/test/test_warning_message.cpp b/localization/ekf_localizer/test/test_warning_message.cpp index b4a05afa844dc..2069969e0ae5e 100644 --- a/localization/ekf_localizer/test/test_warning_message.cpp +++ b/localization/ekf_localizer/test/test_warning_message.cpp @@ -21,17 +21,17 @@ TEST(PoseDelayStepWarningMessage, SmokeTest) { EXPECT_STREQ( - poseDelayStepWarningMessage(6.0, 2, 2.0).c_str(), + poseDelayStepWarningMessage(6.0, 4.0).c_str(), "Pose delay exceeds the compensation limit, ignored. " - "delay: 6.000[s], limit = extend_state_step * ekf_dt : 4.000[s]"); + "delay: 6.000[s], limit: 4.000[s]"); } TEST(TwistDelayStepWarningMessage, SmokeTest) { EXPECT_STREQ( - twistDelayStepWarningMessage(10.0, 3, 2.0).c_str(), + twistDelayStepWarningMessage(10.0, 6.0).c_str(), "Twist delay exceeds the compensation limit, ignored. " - "delay: 10.000[s], limit = extend_state_step * ekf_dt : 6.000[s]"); + "delay: 10.000[s], limit: 6.000[s]"); } TEST(PoseDelayTimeWarningMessage, SmokeTest) From aa28bb9c448312215d176082b7e12f965d07390d Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 6 Dec 2023 19:45:39 +0900 Subject: [PATCH 012/276] fix(start_planner): check safety only when waiting approval (#5792) 1. The `updateData()` function now sets `status_.is_safe_dynamic_objects` to true when `requiresDynamicObjectsCollisionDetection()` returns false. 2. The `isExecutionReady()` function now checks for dynamic object collisions only if `requiresDynamicObjectsCollisionDetection()` returns true and `isWaitingApproval()` also returns true. This change ensures that dynamic object collision detection is performed only when necessary and approval is pending. Signed-off-by: kyoichi-sugahara --- .../src/scene_module/start_planner/start_planner_module.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 7bbee7fe0a10c..23a981c4920b4 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -146,6 +146,8 @@ void StartPlannerModule::updateData() if (requiresDynamicObjectsCollisionDetection()) { status_.is_safe_dynamic_objects = !hasCollisionWithDynamicObjects(); + } else { + status_.is_safe_dynamic_objects = true; } } @@ -279,7 +281,7 @@ bool StartPlannerModule::isExecutionReady() const is_safe = false; } - if (requiresDynamicObjectsCollisionDetection()) { + if (requiresDynamicObjectsCollisionDetection() && isWaitingApproval()) { is_safe = !hasCollisionWithDynamicObjects(); } From 7914958f667926895a4a7d0a35fc8fc95e810e02 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 7 Dec 2023 01:04:35 +0900 Subject: [PATCH 013/276] feat(start_planner): add surround moving obstacle check (#5782) * feat(start_planner): add surround moving obstacle check This commit introduces a new feature in the start_planner module for checking surrounding moving obstacles. - It adds parameters to specify the search radius and threshold velocity for moving obstacles, along with flags to indicate which types of objects should be checked. - The `noMovingObjectsAround` function has been added to filter dynamic objects within a certain radius based on their velocity. - If no moving objects are detected, the function returns true; otherwise, it returns false. - This feature enhances the safety of the start_planner by ensuring that the path can't be approved while surrond moving obstacles exist. --------- Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner.param.yaml | 14 +++++++++ .../start_planner/start_planner_module.hpp | 11 +++++++ .../start_planner_parameters.hpp | 6 ++++ .../scene_module/start_planner/manager.cpp | 29 +++++++++++++++++ .../start_planner/start_planner_module.cpp | 31 +++++++++++++++---- .../path_safety_checker/objects_filtering.hpp | 13 ++++++++ .../path_safety_checker/objects_filtering.cpp | 21 +++++++++++++ 7 files changed, 119 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml index 4bcb847d1280c..514d61e225ecd 100644 --- a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml +++ b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml @@ -138,6 +138,20 @@ backward_path_length: 30.0 forward_path_length: 100.0 + surround_moving_obstacle_check: + search_radius: 10.0 + th_moving_obstacle_velocity: 1.0 + # ObjectTypesToCheck + object_types_to_check: + check_car: true + check_truck: true + check_bus: true + check_trailer: true + check_bicycle: true + check_motorcycle: true + check_pedestrian: true + check_unknown: false + # debug debug: print_debug_info: false diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index e3249d7ffd311..f70effb7cf186 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -137,6 +137,17 @@ class StartPlannerModule : public SceneModuleInterface void initializeSafetyCheckParameters(); bool requiresDynamicObjectsCollisionDetection() const; + + /** + * @brief Check if there are no moving objects around within a certain radius. + * + * This function filters the dynamic objects within a certain radius and then filters them by + * their velocity. If there are no moving objects around, it returns true. Otherwise, it returns + * false. + * + * @return True if there are no moving objects around. False otherwise. + */ + bool noMovingObjectsAround() const; bool receivedNewRoute() const; bool isModuleRunning() const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp index 46b72cacac651..cbde2b514366d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp @@ -93,6 +93,12 @@ struct StartPlannerParameters utils::path_safety_checker::ObjectsFilteringParams objects_filtering_params{}; utils::path_safety_checker::SafetyCheckParams safety_check_params{}; + // surround moving obstacle check + double search_radius{0.0}; + double th_moving_obstacle_velocity{0.0}; + behavior_path_planner::utils::path_safety_checker::ObjectTypesToCheck + surround_moving_obstacles_type_to_check{}; + bool print_debug_info{false}; }; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp index e379fcfa03a80..14660396062aa 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp @@ -273,6 +273,35 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) node->declare_parameter(rss_ns + "longitudinal_velocity_delta_time"); } + // surround moving obstacle check + std::string surround_moving_obstacle_check_ns = ns + "surround_moving_obstacle_check."; + { + p.search_radius = + node->declare_parameter(surround_moving_obstacle_check_ns + "search_radius"); + p.th_moving_obstacle_velocity = node->declare_parameter( + surround_moving_obstacle_check_ns + "th_moving_obstacle_velocity"); + // ObjectTypesToCheck + std::string obj_types_ns = surround_moving_obstacle_check_ns + "object_types_to_check."; + { + p.surround_moving_obstacles_type_to_check.check_car = + node->declare_parameter(obj_types_ns + "check_car"); + p.surround_moving_obstacles_type_to_check.check_truck = + node->declare_parameter(obj_types_ns + "check_truck"); + p.surround_moving_obstacles_type_to_check.check_bus = + node->declare_parameter(obj_types_ns + "check_bus"); + p.surround_moving_obstacles_type_to_check.check_trailer = + node->declare_parameter(obj_types_ns + "check_trailer"); + p.surround_moving_obstacles_type_to_check.check_unknown = + node->declare_parameter(obj_types_ns + "check_unknown"); + p.surround_moving_obstacles_type_to_check.check_bicycle = + node->declare_parameter(obj_types_ns + "check_bicycle"); + p.surround_moving_obstacles_type_to_check.check_motorcycle = + node->declare_parameter(obj_types_ns + "check_motorcycle"); + p.surround_moving_obstacles_type_to_check.check_pedestrian = + node->declare_parameter(obj_types_ns + "check_pedestrian"); + } + } + // debug std::string debug_ns = ns + "debug."; { diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 23a981c4920b4..7bede9192d35f 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -181,6 +181,21 @@ bool StartPlannerModule::requiresDynamicObjectsCollisionDetection() const return parameters_->safety_check_params.enable_safety_check && status_.driving_forward; } +bool StartPlannerModule::noMovingObjectsAround() const +{ + auto dynamic_objects = *(planner_data_->dynamic_object); + utils::path_safety_checker::filterObjectsWithinRadius( + dynamic_objects, planner_data_->self_odometry->pose.pose.position, parameters_->search_radius); + utils::path_safety_checker::filterObjectsByClass( + dynamic_objects, parameters_->surround_moving_obstacles_type_to_check); + const auto filtered_objects = utils::path_safety_checker::filterObjectsByVelocity( + dynamic_objects, parameters_->th_moving_obstacle_velocity, false); + if (!filtered_objects.objects.empty()) { + DEBUG_PRINT("Moving objects exist in the safety check area"); + } + return filtered_objects.objects.empty(); +} + bool StartPlannerModule::hasCollisionWithDynamicObjects() const { // TODO(Sugahara): update path, params for predicted path and so on in this function to avoid @@ -273,20 +288,24 @@ bool StartPlannerModule::isStopped() bool StartPlannerModule::isExecutionReady() const { bool is_safe = true; - // Evaluate safety. The situation is not safe if any of the following conditions are met: // 1. pull out path has not been found - // 2. waiting for approval and there is a collision with dynamic objects + // 2. there is a moving objects around ego + // 3. waiting for approval and there is a collision with dynamic objects if (!status_.found_pull_out_path) { is_safe = false; + } else if (isWaitingApproval()) { + if (!noMovingObjectsAround()) { + is_safe = false; + } else if (requiresDynamicObjectsCollisionDetection() && hasCollisionWithDynamicObjects()) { + is_safe = false; + } } - if (requiresDynamicObjectsCollisionDetection() && isWaitingApproval()) { - is_safe = !hasCollisionWithDynamicObjects(); + if (!is_safe) { + stop_pose_ = planner_data_->self_odometry->pose.pose; } - if (!is_safe) stop_pose_ = planner_data_->self_odometry->pose.pose; - return is_safe; } diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp index 018e6bd2a3d6e..f66f425f1b7fa 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp @@ -134,6 +134,19 @@ void filterObjectsByPosition( const geometry_msgs::msg::Point & current_pose, const double forward_distance, const double backward_distance); +/** + * @brief Filter objects based on their distance from a reference point. + * + * This function filters out objects that are outside a specified radius from a reference point. + * + * @param objects The predicted objects to filter. + * @param reference_point The reference point (e.g., current pose of the ego vehicle). + * @param search_radius The radius within which to retain objects. + */ +void filterObjectsWithinRadius( + PredictedObjects & objects, const geometry_msgs::msg::Point & reference_point, + const double search_radius); + /** * @brief Filters the provided objects based on their classification. * diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index 84c02b3b325de..188c50993e4ae 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -44,6 +44,15 @@ bool position_filter( return (backward_distance < dist_ego_to_obj && dist_ego_to_obj < forward_distance); } + +bool is_within_circle( + const geometry_msgs::msg::Point & object_pos, const geometry_msgs::msg::Point & reference_point, + const double search_radius) +{ + const double dist = + std::hypot(reference_point.x - object_pos.x, reference_point.y - object_pos.y); + return dist < search_radius; +} } // namespace behavior_path_planner::utils::path_safety_checker::filter namespace behavior_path_planner::utils::path_safety_checker @@ -128,6 +137,18 @@ void filterObjectsByPosition( filterObjects(objects, filter); } +void filterObjectsWithinRadius( + PredictedObjects & objects, const geometry_msgs::msg::Point & reference_point, + const double search_radius) +{ + const auto filter = [&](const auto & object) { + return filter::is_within_circle( + object.kinematics.initial_pose_with_covariance.pose.position, reference_point, search_radius); + }; + + filterObjects(objects, filter); +} + void filterObjectsByClass( PredictedObjects & objects, const ObjectTypesToCheck & target_object_types) { From f43d9c67ad51e50c38d7ade13cfe253215409877 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 7 Dec 2023 10:33:18 +0900 Subject: [PATCH 014/276] refactor(avoidance, avoidance_by_lane_change): separate package (#5790) * refactor(avoidance): separate package Signed-off-by: satoshi-ota * refactor(AbLC): separate package Signed-off-by: satoshi-ota * refactor(bpp): remove separate module Signed-off-by: satoshi-ota * fix(bpp): fix test error Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../CMakeLists.txt | 26 +++ .../config}/avoidance_by_lc.param.yaml | 0 .../data_structs.hpp | 33 ++++ .../interface.hpp | 48 +++++ .../manager.hpp | 52 ++++++ .../scene.hpp} | 10 +- .../package.xml | 36 ++++ .../plugins.xml | 3 + .../src/interface.cpp | 62 ++++++ .../src/manager.cpp | 176 ++++++++++++++++++ .../src/scene.cpp} | 7 +- ...t_behavior_path_planner_node_interface.cpp | 129 +++++++++++++ .../CMakeLists.txt | 29 +++ .../config}/avoidance.param.yaml | 0 .../data_structs.hpp} | 6 +- .../behavior_path_avoidance_module}/debug.hpp | 10 +- .../helper.hpp | 10 +- .../manager.hpp | 10 +- .../behavior_path_avoidance_module/scene.hpp} | 14 +- .../shift_line_generator.hpp | 10 +- .../behavior_path_avoidance_module}/utils.hpp | 10 +- .../package.xml | 53 ++++++ .../plugins.xml | 3 + .../src}/debug.cpp | 2 +- .../src}/manager.cpp | 2 +- .../src/scene.cpp} | 8 +- .../src}/shift_line_generator.cpp | 4 +- .../src}/utils.cpp | 6 +- ...t_behavior_path_planner_node_interface.cpp | 126 +++++++++++++ .../test/test_utils.cpp} | 5 +- planning/behavior_path_planner/CMakeLists.txt | 14 -- .../scene_module/lane_change/interface.hpp | 18 -- .../scene_module/lane_change/manager.hpp | 18 -- .../lane_change/lane_change_module_data.hpp | 11 +- planning/behavior_path_planner/plugins.xml | 2 - .../scene_module/lane_change/interface.cpp | 34 ---- .../src/scene_module/lane_change/manager.cpp | 145 --------------- ...t_behavior_path_planner_node_interface.cpp | 4 - 38 files changed, 832 insertions(+), 304 deletions(-) create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt rename planning/{behavior_path_planner/config/avoidance_by_lc => behavior_path_avoidance_by_lane_change_module/config}/avoidance_by_lc.param.yaml (100%) create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp => behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp} (81%) create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/package.xml create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/plugins.xml create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp rename planning/{behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp => behavior_path_avoidance_by_lane_change_module/src/scene.cpp} (97%) create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp create mode 100644 planning/behavior_path_avoidance_module/CMakeLists.txt rename planning/{behavior_path_planner/config/avoidance => behavior_path_avoidance_module/config}/avoidance.param.yaml (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp => behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp} (98%) rename planning/{behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance => behavior_path_avoidance_module/include/behavior_path_avoidance_module}/debug.hpp (90%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/avoidance => behavior_path_avoidance_module/include/behavior_path_avoidance_module}/helper.hpp (96%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/avoidance => behavior_path_avoidance_module/include/behavior_path_avoidance_module}/manager.hpp (80%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp => behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp} (96%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/avoidance => behavior_path_avoidance_module/include/behavior_path_avoidance_module}/shift_line_generator.hpp (95%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/avoidance => behavior_path_avoidance_module/include/behavior_path_avoidance_module}/utils.hpp (96%) create mode 100644 planning/behavior_path_avoidance_module/package.xml create mode 100644 planning/behavior_path_avoidance_module/plugins.xml rename planning/{behavior_path_planner/src/marker_utils/avoidance => behavior_path_avoidance_module/src}/debug.cpp (99%) rename planning/{behavior_path_planner/src/scene_module/avoidance => behavior_path_avoidance_module/src}/manager.cpp (99%) rename planning/{behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp => behavior_path_avoidance_module/src/scene.cpp} (99%) rename planning/{behavior_path_planner/src/utils/avoidance => behavior_path_avoidance_module/src}/shift_line_generator.cpp (99%) rename planning/{behavior_path_planner/src/utils/avoidance => behavior_path_avoidance_module/src}/utils.cpp (99%) create mode 100644 planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp rename planning/{behavior_path_planner/test/test_avoidance_utils.cpp => behavior_path_avoidance_module/test/test_utils.cpp} (92%) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt b/planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt new file mode 100644 index 0000000000000..bca909c7cef7e --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_avoidance_by_lane_change_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/scene.cpp + src/manager.cpp + src/interface.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_behavior_path_planner_node_interface.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/config/avoidance_by_lc/avoidance_by_lc.param.yaml b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/avoidance_by_lc/avoidance_by_lc.param.yaml rename to planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp new file mode 100644 index 0000000000000..e177244930da6 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp @@ -0,0 +1,33 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ + +#include "behavior_path_avoidance_module/data_structs.hpp" + +#include + +namespace behavior_path_planner +{ +struct AvoidanceByLCParameters : public AvoidanceParameters +{ + // execute only when the target object longitudinal distance is larger than this param. + double execute_object_longitudinal_margin{0.0}; + + // execute only when lane change end point is before the object. + bool execute_only_when_lane_change_finish_before_object{false}; +}; +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp new file mode 100644 index 0000000000000..0bc08ccd400ca --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp @@ -0,0 +1,48 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__INTERFACE_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__INTERFACE_HPP_ + +#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" +#include "behavior_path_avoidance_by_lane_change_module/scene.hpp" +#include "behavior_path_planner/scene_module/lane_change/interface.hpp" + +#include + +#include +#include +#include + +namespace behavior_path_planner +{ +class AvoidanceByLaneChangeInterface : public LaneChangeInterface +{ +public: + AvoidanceByLaneChangeInterface( + const std::string & name, rclcpp::Node & node, + const std::shared_ptr & parameters, + const std::shared_ptr & avoidance_by_lane_change_parameters, + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map); + + bool isExecutionRequested() const override; + +protected: + void updateRTCStatus(const double start_distance, const double finish_distance) override; +}; +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__INTERFACE_HPP_ diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp new file mode 100644 index 0000000000000..b1beae9c6fc03 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp @@ -0,0 +1,52 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__MANAGER_HPP_ + +#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" +#include "behavior_path_avoidance_by_lane_change_module/interface.hpp" +#include "behavior_path_planner/scene_module/lane_change/manager.hpp" + +#include + +#include +#include +#include +#include + +namespace behavior_path_planner +{ +using route_handler::Direction; + +class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager +{ +public: + AvoidanceByLaneChangeModuleManager() + : LaneChangeModuleManager( + "avoidance_by_lc", route_handler::Direction::NONE, + LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) + { + } + + void init(rclcpp::Node * node) override; + + std::unique_ptr createNewSceneModuleInstance() override; + +private: + std::shared_ptr avoidance_parameters_; +}; +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp similarity index 81% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp rename to planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp index 67fd2c1ba0c77..1e667c207c64f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp @@ -12,18 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__AVOIDANCE_BY_LANE_CHANGE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__AVOIDANCE_BY_LANE_CHANGE_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ +#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" #include "behavior_path_planner/scene_module/lane_change/normal.hpp" #include namespace behavior_path_planner { -using autoware_auto_planning_msgs::msg::PathWithLaneId; -using geometry_msgs::msg::Pose; -using geometry_msgs::msg::Twist; using AvoidanceDebugData = DebugData; class AvoidanceByLaneChange : public NormalLaneChange @@ -56,4 +54,4 @@ class AvoidanceByLaneChange : public NormalLaneChange }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__AVOIDANCE_BY_LANE_CHANGE_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_avoidance_by_lane_change_module/package.xml new file mode 100644 index 0000000000000..3bb32bdf76bf0 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/package.xml @@ -0,0 +1,36 @@ + + + + behavior_path_avoidance_by_lane_change_module + 0.1.0 + The behavior_path_avoidance_by_lane_change_module package + + Satoshi Ota + Zulfaqar Azmi + Fumiya Watanabe + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + behavior_path_avoidance_module + behavior_path_planner + behavior_path_planner_common + motion_utils + pluginlib + rclcpp + rtc_interface + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_avoidance_by_lane_change_module/plugins.xml b/planning/behavior_path_avoidance_by_lane_change_module/plugins.xml new file mode 100644 index 0000000000000..092d54c096ae9 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp new file mode 100644 index 0000000000000..2e451461abab7 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -0,0 +1,62 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "behavior_path_avoidance_by_lane_change_module/interface.hpp" + +#include "behavior_path_planner_common/interface/scene_module_interface.hpp" +#include "behavior_path_planner_common/interface/scene_module_visitor.hpp" +#include "behavior_path_planner_common/marker_utils/utils.hpp" + +#include +#include +#include +#include +#include + +namespace behavior_path_planner +{ +AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( + const std::string & name, rclcpp::Node & node, + const std::shared_ptr & parameters, + const std::shared_ptr & avoidance_by_lane_change_parameters, + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map) +: LaneChangeInterface{ + name, + node, + parameters, + rtc_interface_ptr_map, + objects_of_interest_marker_interface_ptr_map, + std::make_unique(parameters, avoidance_by_lane_change_parameters)} +{ +} + +bool AvoidanceByLaneChangeInterface::isExecutionRequested() const +{ + return module_type_->specialRequiredCheck() && module_type_->isLaneChangeRequired(); +} + +void AvoidanceByLaneChangeInterface::updateRTCStatus( + const double start_distance, const double finish_distance) +{ + const auto direction = std::invoke([&]() -> std::string { + const auto dir = module_type_->getDirection(); + return (dir == Direction::LEFT) ? "left" : "right"; + }); + + rtc_interface_ptr_map_.at(direction)->updateCooperateStatus( + uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now()); +} +} // namespace behavior_path_planner diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp new file mode 100644 index 0000000000000..61b0a36ae0fb0 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -0,0 +1,176 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "behavior_path_avoidance_by_lane_change_module/manager.hpp" + +#include "tier4_autoware_utils/ros/parameter.hpp" +#include "tier4_autoware_utils/ros/update_param.hpp" + +#include + +#include +#include +#include + +namespace behavior_path_planner +{ + +void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) +{ + using autoware_auto_perception_msgs::msg::ObjectClassification; + using tier4_autoware_utils::getOrDeclareParameter; + + // init manager interface + initInterface(node, {"left", "right"}); + + // init lane change manager + LaneChangeModuleManager::init(node); + + AvoidanceByLCParameters p{}; + // unique parameters + { + const std::string ns = "avoidance_by_lane_change."; + p.execute_object_longitudinal_margin = + getOrDeclareParameter(*node, ns + "execute_object_longitudinal_margin"); + p.execute_only_when_lane_change_finish_before_object = + getOrDeclareParameter(*node, ns + "execute_only_when_lane_change_finish_before_object"); + } + + // general params + { + const std::string ns = "avoidance."; + p.resample_interval_for_planning = + getOrDeclareParameter(*node, ns + "resample_interval_for_planning"); + p.resample_interval_for_output = + getOrDeclareParameter(*node, ns + "resample_interval_for_output"); + } + + // target object + { + const auto get_object_param = [&](std::string && ns) { + ObjectParameter param{}; + param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); + param.moving_speed_threshold = + getOrDeclareParameter(*node, ns + "moving_speed_threshold"); + param.moving_time_threshold = + getOrDeclareParameter(*node, ns + "moving_time_threshold"); + param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); + param.envelope_buffer_margin = + getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); + param.avoid_margin_lateral = + getOrDeclareParameter(*node, ns + "avoid_margin_lateral"); + param.safety_buffer_lateral = + getOrDeclareParameter(*node, ns + "safety_buffer_lateral"); + return param; + }; + + const std::string ns = "avoidance_by_lane_change.target_object."; + p.object_parameters.emplace( + ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); + p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); + p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); + p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); + p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); + p.object_parameters.emplace( + ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); + p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); + p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); + + p.lower_distance_for_polygon_expansion = + getOrDeclareParameter(*node, ns + "lower_distance_for_polygon_expansion"); + p.upper_distance_for_polygon_expansion = + getOrDeclareParameter(*node, ns + "upper_distance_for_polygon_expansion"); + } + + // target filtering + { + const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { + if (p.object_parameters.count(object_type) == 0) { + return; + } + p.object_parameters.at(object_type).is_avoidance_target = + getOrDeclareParameter(*node, ns); + }; + + const std::string ns = "avoidance.target_filtering."; + set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); + set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); + set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); + set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); + set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); + set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); + set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); + set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); + + p.object_check_goal_distance = + getOrDeclareParameter(*node, ns + "object_check_goal_distance"); + p.threshold_distance_object_is_on_center = + getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); + p.object_check_shiftable_ratio = + getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); + p.object_check_min_road_shoulder_width = + getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); + p.object_last_seen_threshold = + getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); + } + + { + const std::string ns = "avoidance.target_filtering.force_avoidance."; + p.enable_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "enable"); + p.threshold_time_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "time_threshold"); + p.object_ignore_section_traffic_light_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); + p.object_ignore_section_crosswalk_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.front_distance"); + p.object_ignore_section_crosswalk_behind_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); + } + + { + const std::string ns = "avoidance.target_filtering.detection_area."; + p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); + p.object_check_min_forward_distance = + getOrDeclareParameter(*node, ns + "min_forward_distance"); + p.object_check_max_forward_distance = + getOrDeclareParameter(*node, ns + "max_forward_distance"); + p.object_check_backward_distance = + getOrDeclareParameter(*node, ns + "backward_distance"); + } + + // safety check + { + const std::string ns = "avoidance.safety_check."; + p.hysteresis_factor_expand_rate = + getOrDeclareParameter(*node, ns + "hysteresis_factor_expand_rate"); + } + + avoidance_parameters_ = std::make_shared(p); +} + +std::unique_ptr +AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() +{ + return std::make_unique( + name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_); +} + +} // namespace behavior_path_planner + +#include +PLUGINLIB_EXPORT_CLASS( + behavior_path_planner::AvoidanceByLaneChangeModuleManager, + behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp similarity index 97% rename from planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp rename to planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index befd458153e6e..bfa873d9518ef 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -12,15 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp" +#include "behavior_path_avoidance_by_lane_change_module/scene.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" -#include -#include - #include #include diff --git a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..2264669fdcdbe --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,129 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "behavior_path_planner/behavior_path_planner_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::AvoidanceByLaneChangeModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, + {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_planner") + + "/config/lane_change/lane_change.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + + "/config/avoidance.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_avoidance_by_lane_change_module") + + "/config/avoidance_by_lc.param.yaml"}); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} diff --git a/planning/behavior_path_avoidance_module/CMakeLists.txt b/planning/behavior_path_avoidance_module/CMakeLists.txt new file mode 100644 index 0000000000000..c94591f9bbd30 --- /dev/null +++ b/planning/behavior_path_avoidance_module/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_avoidance_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/scene.cpp + src/debug.cpp + src/utils.cpp + src/manager.cpp + src/shift_line_generator.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_utils.cpp + test/test_behavior_path_planner_node_interface.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/avoidance/avoidance.param.yaml rename to planning/behavior_path_avoidance_module/config/avoidance.param.yaml diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp similarity index 98% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index 68c64ff9b7112..8c45230959c6c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -622,4 +622,4 @@ struct DebugData } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp similarity index 90% rename from planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp index 12b54a5031041..2bf3158da9ab6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__MARKER_UTILS__AVOIDANCE__DEBUG_HPP_ -#define BEHAVIOR_PATH_PLANNER__MARKER_UTILS__AVOIDANCE__DEBUG_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__DEBUG_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__DEBUG_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" #include @@ -78,4 +78,4 @@ std::string toStrInfo(const behavior_path_planner::ShiftLine & sp); std::string toStrInfo(const behavior_path_planner::AvoidLine & ap); -#endif // BEHAVIOR_PATH_PLANNER__MARKER_UTILS__AVOIDANCE__DEBUG_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__DEBUG_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 54a38b828e987..6717cefefc9f6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__HELPER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__HELPER_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__HELPER_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__HELPER_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include @@ -331,4 +331,4 @@ class AvoidanceHelper }; } // namespace behavior_path_planner::helper::avoidance -#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__HELPER_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__HELPER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/manager.hpp similarity index 80% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/manager.hpp index 0fe8bd7efa17b..72cfbe6f0a1ed 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/manager.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/avoidance/avoidance_module.hpp" -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/scene.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" #include @@ -51,4 +51,4 @@ class AvoidanceModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp index b01cb62f22372..6a66b485d1c59 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__AVOIDANCE_MODULE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__AVOIDANCE_MODULE_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__SCENE_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/avoidance/helper.hpp" -#include "behavior_path_planner/utils/avoidance/shift_line_generator.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/helper.hpp" +#include "behavior_path_avoidance_module/shift_line_generator.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/interface/scene_module_visitor.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" @@ -450,4 +450,4 @@ class AvoidanceModule : public SceneModuleInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__AVOIDANCE_MODULE_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/shift_line_generator.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/shift_line_generator.hpp similarity index 95% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/shift_line_generator.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/shift_line_generator.hpp index 054a6e15ef6bf..edfe9ab9663ce 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/shift_line_generator.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/shift_line_generator.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__SHIFT_LINE_GENERATOR_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__SHIFT_LINE_GENERATOR_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/avoidance/helper.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/helper.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -248,4 +248,4 @@ class ShiftLineGenerator } // namespace behavior_path_planner::utils::avoidance -#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__SHIFT_LINE_GENERATOR_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp index e7611208962f0..c954ab9022853 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__UTILS_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__UTILS_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -180,4 +180,4 @@ double calcDistanceToAvoidStartLine( const std::shared_ptr & parameters); } // namespace behavior_path_planner::utils::avoidance -#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__UTILS_HPP_ diff --git a/planning/behavior_path_avoidance_module/package.xml b/planning/behavior_path_avoidance_module/package.xml new file mode 100644 index 0000000000000..68cc911e9373d --- /dev/null +++ b/planning/behavior_path_avoidance_module/package.xml @@ -0,0 +1,53 @@ + + + + behavior_path_avoidance_module + 0.1.0 + The behavior_path_avoidance_module package + + Takamasa Horibe + Satoshi Ota + Fumiya Watanabe + Kyoichi Sugahara + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + autoware_auto_perception_msgs + autoware_auto_planning_msgs + autoware_auto_tf2 + autoware_perception_msgs + behavior_path_planner + behavior_path_planner_common + geometry_msgs + lanelet2_extension + libboost-dev + magic_enum + motion_utils + objects_of_interest_marker_interface + pluginlib + rclcpp + route_handler + rtc_interface + sensor_msgs + signal_processing + tf2 + tf2_eigen + tf2_geometry_msgs + tf2_ros + tier4_autoware_utils + tier4_planning_msgs + vehicle_info_util + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_avoidance_module/plugins.xml b/planning/behavior_path_avoidance_module/plugins.xml new file mode 100644 index 0000000000000..f25677dad1e9a --- /dev/null +++ b/planning/behavior_path_avoidance_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp b/planning/behavior_path_avoidance_module/src/debug.cpp similarity index 99% rename from planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp rename to planning/behavior_path_avoidance_module/src/debug.cpp index 7587c3bb3663e..3ae210e0b1d78 100644 --- a/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp +++ b/planning/behavior_path_avoidance_module/src/debug.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/marker_utils/avoidance/debug.hpp" +#include "behavior_path_avoidance_module/debug.hpp" #include "behavior_path_planner_common/utils/utils.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp rename to planning/behavior_path_avoidance_module/src/manager.cpp index e17804f10deaa..f4997d2af12f1 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/avoidance/manager.hpp" +#include "behavior_path_avoidance_module/manager.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp rename to planning/behavior_path_avoidance_module/src/scene.cpp index df93df75410e1..9b0c85f60ba29 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/avoidance/avoidance_module.hpp" +#include "behavior_path_avoidance_module/scene.hpp" -#include "behavior_path_planner/marker_utils/avoidance/debug.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_avoidance_module/debug.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include "behavior_path_planner_common/interface/scene_module_visitor.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" diff --git a/planning/behavior_path_planner/src/utils/avoidance/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/avoidance/shift_line_generator.cpp rename to planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index c7fbaa931737c..48d7e3a4baf8b 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/avoidance/shift_line_generator.hpp" +#include "behavior_path_avoidance_module/shift_line_generator.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" #include diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/avoidance/utils.cpp rename to planning/behavior_path_avoidance_module/src/utils.cpp index 6fd1943369cb9..b469e9070baad 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -14,8 +14,8 @@ #include "behavior_path_planner_common/utils/utils.hpp" -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/traffic_light_utils.hpp" diff --git a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..83514127b0a8e --- /dev/null +++ b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,126 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "behavior_path_planner/behavior_path_planner_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::AvoidanceModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_planner") + + "/config/lane_change/lane_change.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + + "/config/avoidance.param.yaml"}); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} diff --git a/planning/behavior_path_planner/test/test_avoidance_utils.cpp b/planning/behavior_path_avoidance_module/test/test_utils.cpp similarity index 92% rename from planning/behavior_path_planner/test/test_avoidance_utils.cpp rename to planning/behavior_path_avoidance_module/test/test_utils.cpp index fc2bea1a5b288..e5c6fd2e72092 100644 --- a/planning/behavior_path_planner/test/test_avoidance_utils.cpp +++ b/planning/behavior_path_avoidance_module/test/test_utils.cpp @@ -11,8 +11,9 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" + +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include #include diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 2ea43bf5a4ef1..b99bc2a4eb2e4 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -12,8 +12,6 @@ pluginlib_export_plugin_description_file(${PROJECT_NAME} plugins.xml) ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/planner_manager.cpp src/behavior_path_planner_node.cpp - src/scene_module/avoidance/avoidance_module.cpp - src/scene_module/avoidance/manager.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp src/scene_module/dynamic_avoidance/manager.cpp src/scene_module/start_planner/start_planner_module.cpp @@ -25,11 +23,8 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/scene_module/lane_change/interface.cpp src/scene_module/lane_change/normal.cpp src/scene_module/lane_change/external_request.cpp - src/scene_module/lane_change/avoidance_by_lane_change.cpp src/scene_module/lane_change/manager.cpp src/utils/start_goal_planner_common/utils.cpp - src/utils/avoidance/shift_line_generator.cpp - src/utils/avoidance/utils.cpp src/utils/lane_change/utils.cpp src/utils/side_shift/util.cpp src/utils/goal_planner/util.cpp @@ -44,7 +39,6 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/utils/start_planner/freespace_pull_out.cpp src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp - src/marker_utils/avoidance/debug.cpp src/marker_utils/lane_change/debug.cpp ) @@ -71,14 +65,6 @@ if(BUILD_TESTING) ${PROJECT_NAME}_lib ) - ament_add_ros_isolated_gmock(test_${CMAKE_PROJECT_NAME}_avoidance_module - test/test_avoidance_utils.cpp - ) - - target_link_libraries(test_${CMAKE_PROJECT_NAME}_avoidance_module - ${PROJECT_NAME}_lib - ) - ament_add_ros_isolated_gmock(test_${CMAKE_PROJECT_NAME}_lane_change_module test/test_lane_change_utils.cpp ) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp index 2e3cbd992e27f..b7cef007d6d9f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp @@ -15,7 +15,6 @@ #ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ #define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ -#include "behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp" #include "behavior_path_planner/scene_module/lane_change/base_class.hpp" #include "behavior_path_planner/scene_module/lane_change/external_request.hpp" #include "behavior_path_planner/scene_module/lane_change/normal.hpp" @@ -145,23 +144,6 @@ class LaneChangeInterface : public SceneModuleInterface bool is_abort_approval_requested_{false}; }; - -class AvoidanceByLaneChangeInterface : public LaneChangeInterface -{ -public: - AvoidanceByLaneChangeInterface( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters, - const std::shared_ptr & avoidance_by_lane_change_parameters, - const std::unordered_map> & rtc_interface_ptr_map, - std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); - - bool isExecutionRequested() const override; - -protected: - void updateRTCStatus(const double start_distance, const double finish_distance) override; -}; } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp index ed476adcbd834..024c6685b28c4 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp @@ -94,24 +94,6 @@ class ExternalRequestLaneChangeLeftModuleManager : public LaneChangeModuleManage { } }; - -class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager -{ -public: - AvoidanceByLaneChangeModuleManager() - : LaneChangeModuleManager( - "avoidance_by_lc", route_handler::Direction::NONE, - LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) - { - } - - void init(rclcpp::Node * node) override; - - std::unique_ptr createNewSceneModuleInstance() override; - -private: - std::shared_ptr avoidance_parameters_; -}; } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp index f11d48a24c79c..6f34bc79fe5f1 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp @@ -14,8 +14,8 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ #define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" +#include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include @@ -147,15 +147,6 @@ enum class LaneChangeModuleType { EXTERNAL_REQUEST, AVOIDANCE_BY_LANE_CHANGE, }; - -struct AvoidanceByLCParameters : public AvoidanceParameters -{ - // execute only when the target object longitudinal distance is larger than this param. - double execute_object_longitudinal_margin{0.0}; - - // execute only when lane change end point is before the object. - bool execute_only_when_lane_change_finish_before_object{false}; -}; } // namespace behavior_path_planner namespace behavior_path_planner::data::lane_change diff --git a/planning/behavior_path_planner/plugins.xml b/planning/behavior_path_planner/plugins.xml index 561246fcf75e4..5196b20dc5abd 100644 --- a/planning/behavior_path_planner/plugins.xml +++ b/planning/behavior_path_planner/plugins.xml @@ -1,5 +1,4 @@ - @@ -8,5 +7,4 @@ - diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index 413350e3eb23b..26fc423fce02f 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -474,38 +474,4 @@ TurnSignalInfo LaneChangeInterface::getCurrentTurnSignalInfo( // not in the vicinity of the end of the path. return original return original_turn_signal_info; } - -AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters, - const std::shared_ptr & avoidance_by_lane_change_parameters, - const std::unordered_map> & rtc_interface_ptr_map, - std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: LaneChangeInterface{ - name, - node, - parameters, - rtc_interface_ptr_map, - objects_of_interest_marker_interface_ptr_map, - std::make_unique(parameters, avoidance_by_lane_change_parameters)} -{ -} - -bool AvoidanceByLaneChangeInterface::isExecutionRequested() const -{ - return module_type_->specialRequiredCheck() && module_type_->isLaneChangeRequired(); -} - -void AvoidanceByLaneChangeInterface::updateRTCStatus( - const double start_distance, const double finish_distance) -{ - const auto direction = std::invoke([&]() -> std::string { - const auto dir = module_type_->getDirection(); - return (dir == Direction::LEFT) ? "left" : "right"; - }); - - rtc_interface_ptr_map_.at(direction)->updateCooperateStatus( - uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now()); -} } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp index 29b7cad533a66..ed40476723dba 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -246,148 +246,6 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(*node, ns + "execute_object_longitudinal_margin"); - p.execute_only_when_lane_change_finish_before_object = - getOrDeclareParameter(*node, ns + "execute_only_when_lane_change_finish_before_object"); - } - - // general params - { - const std::string ns = "avoidance."; - p.resample_interval_for_planning = - getOrDeclareParameter(*node, ns + "resample_interval_for_planning"); - p.resample_interval_for_output = - getOrDeclareParameter(*node, ns + "resample_interval_for_output"); - } - - // target object - { - const auto get_object_param = [&](std::string && ns) { - ObjectParameter param{}; - param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); - param.moving_speed_threshold = - getOrDeclareParameter(*node, ns + "moving_speed_threshold"); - param.moving_time_threshold = - getOrDeclareParameter(*node, ns + "moving_time_threshold"); - param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); - param.envelope_buffer_margin = - getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); - param.avoid_margin_lateral = - getOrDeclareParameter(*node, ns + "avoid_margin_lateral"); - param.safety_buffer_lateral = - getOrDeclareParameter(*node, ns + "safety_buffer_lateral"); - return param; - }; - - const std::string ns = "avoidance_by_lane_change.target_object."; - p.object_parameters.emplace( - ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); - p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); - p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); - p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); - p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); - p.object_parameters.emplace( - ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); - p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); - p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); - - p.lower_distance_for_polygon_expansion = - getOrDeclareParameter(*node, ns + "lower_distance_for_polygon_expansion"); - p.upper_distance_for_polygon_expansion = - getOrDeclareParameter(*node, ns + "upper_distance_for_polygon_expansion"); - } - - // target filtering - { - const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { - if (p.object_parameters.count(object_type) == 0) { - return; - } - p.object_parameters.at(object_type).is_avoidance_target = - getOrDeclareParameter(*node, ns); - }; - - const std::string ns = "avoidance.target_filtering."; - set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); - set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); - set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); - set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); - set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); - set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); - set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); - set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); - - p.object_check_goal_distance = - getOrDeclareParameter(*node, ns + "object_check_goal_distance"); - p.threshold_distance_object_is_on_center = - getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); - p.object_check_shiftable_ratio = - getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); - p.object_check_min_road_shoulder_width = - getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); - p.object_last_seen_threshold = - getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); - } - - { - const std::string ns = "avoidance.target_filtering.force_avoidance."; - p.enable_force_avoidance_for_stopped_vehicle = - getOrDeclareParameter(*node, ns + "enable"); - p.threshold_time_force_avoidance_for_stopped_vehicle = - getOrDeclareParameter(*node, ns + "time_threshold"); - p.object_ignore_section_traffic_light_in_front_distance = - getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); - p.object_ignore_section_crosswalk_in_front_distance = - getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.front_distance"); - p.object_ignore_section_crosswalk_behind_distance = - getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); - } - - { - const std::string ns = "avoidance.target_filtering.detection_area."; - p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); - p.object_check_min_forward_distance = - getOrDeclareParameter(*node, ns + "min_forward_distance"); - p.object_check_max_forward_distance = - getOrDeclareParameter(*node, ns + "max_forward_distance"); - p.object_check_backward_distance = - getOrDeclareParameter(*node, ns + "backward_distance"); - } - - // safety check - { - const std::string ns = "avoidance.safety_check."; - p.hysteresis_factor_expand_rate = - getOrDeclareParameter(*node, ns + "hysteresis_factor_expand_rate"); - } - - avoidance_parameters_ = std::make_shared(p); -} - -std::unique_ptr -AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() -{ - return std::make_unique( - name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); -} - } // namespace behavior_path_planner #include @@ -403,6 +261,3 @@ PLUGINLIB_EXPORT_CLASS( PLUGINLIB_EXPORT_CLASS( behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager, behavior_path_planner::SceneModuleManagerInterface) -PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::AvoidanceByLaneChangeModuleManager, - behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index 9235e8e8e3de6..c2b115ae98afe 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -49,7 +49,6 @@ std::shared_ptr generateNode() ament_index_cpp::get_package_share_directory("behavior_path_planner"); std::vector module_names; - module_names.emplace_back("behavior_path_planner::AvoidanceModuleManager"); module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); module_names.emplace_back("behavior_path_planner::SideShiftModuleManager"); module_names.emplace_back("behavior_path_planner::StartPlannerModuleManager"); @@ -58,7 +57,6 @@ std::shared_ptr generateNode() module_names.emplace_back("behavior_path_planner::LaneChangeLeftModuleManager"); module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"); - module_names.emplace_back("behavior_path_planner::AvoidanceByLaneChangeModuleManager"); std::vector params; params.emplace_back("launch_modules", module_names); @@ -72,12 +70,10 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - behavior_path_planner_dir + "/config/avoidance/avoidance.param.yaml", behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml", behavior_path_planner_dir + "/config/lane_change/lane_change.param.yaml", behavior_path_planner_dir + "/config/start_planner/start_planner.param.yaml", behavior_path_planner_dir + "/config/goal_planner/goal_planner.param.yaml", - behavior_path_planner_dir + "/config/avoidance_by_lc/avoidance_by_lc.param.yaml", behavior_path_planner_dir + "/config/side_shift/side_shift.param.yaml"}); return std::make_shared(node_options); From 5fe624a38f58584413c0231887179c64262d3281 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 7 Dec 2023 01:42:16 +0000 Subject: [PATCH 015/276] chore: update CODEOWNERS (#5800) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/CODEOWNERS | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 01ccc632b0133..ea86022e7134d 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -154,6 +154,8 @@ perception/traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhon perception/traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp perception/traffic_light_visualization/** yukihiro.saito@tier4.jp +planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner_common/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp From 008da7dfd0fc14db872dc792868efaf9f558dc49 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 7 Dec 2023 11:30:28 +0900 Subject: [PATCH 016/276] refactor(motion_velocity_smoother): boost::optional to std::optional (#5758) * refactor(motion_velocity_smoother): boost::optional to std::optional Signed-off-by: Zulfaqar Azmi * style(pre-commit): autofix --------- Signed-off-by: Zulfaqar Azmi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../trajectory_utils.hpp | 22 +++++++------------ planning/motion_velocity_smoother/package.xml | 1 - .../src/trajectory_utils.cpp | 10 ++++----- 3 files changed, 12 insertions(+), 21 deletions(-) diff --git a/planning/motion_velocity_smoother/include/motion_velocity_smoother/trajectory_utils.hpp b/planning/motion_velocity_smoother/include/motion_velocity_smoother/trajectory_utils.hpp index ec8a89c5a3e9c..35e8ab53dd75d 100644 --- a/planning/motion_velocity_smoother/include/motion_velocity_smoother/trajectory_utils.hpp +++ b/planning/motion_velocity_smoother/include/motion_velocity_smoother/trajectory_utils.hpp @@ -15,20 +15,15 @@ #ifndef MOTION_VELOCITY_SMOOTHER__TRAJECTORY_UTILS_HPP_ #define MOTION_VELOCITY_SMOOTHER__TRAJECTORY_UTILS_HPP_ -#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" -#include "geometry_msgs/msg/pose.hpp" +#include "autoware_auto_planning_msgs/msg/detail/trajectory_point__struct.hpp" +#include "geometry_msgs/msg/detail/pose__struct.hpp" -#include "boost/optional.hpp" - -#include #include -#include +#include #include #include -namespace motion_velocity_smoother -{ -namespace trajectory_utils +namespace motion_velocity_smoother::trajectory_utils { using autoware_auto_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; @@ -57,7 +52,7 @@ double getMaxAbsVelocity(const TrajectoryPoints & trajectory); void applyMaximumVelocityLimit( const size_t from, const size_t to, const double max_vel, TrajectoryPoints & trajectory); -boost::optional searchZeroVelocityIdx(const TrajectoryPoints & trajectory); +std::optional searchZeroVelocityIdx(const TrajectoryPoints & trajectory); bool calcStopDistWithJerkConstraints( const double v0, const double a0, const double jerk_acc, const double jerk_dec, @@ -68,12 +63,12 @@ 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); -boost::optional applyDecelFilterWithJerkConstraint( +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); -boost::optional> updateStateWithJerkConstraint( +std::optional> updateStateWithJerkConstraint( const double v0, const double a0, const std::map & jerk_profile, const double t); std::vector calcVelocityProfileWithConstantJerkAndAccelerationLimit( @@ -82,7 +77,6 @@ std::vector calcVelocityProfileWithConstantJerkAndAccelerationLimit( double calcStopDistance(const TrajectoryPoints & trajectory, const size_t closest); -} // namespace trajectory_utils -} // namespace motion_velocity_smoother +} // namespace motion_velocity_smoother::trajectory_utils #endif // MOTION_VELOCITY_SMOOTHER__TRAJECTORY_UTILS_HPP_ diff --git a/planning/motion_velocity_smoother/package.xml b/planning/motion_velocity_smoother/package.xml index 54c60c938970a..4bb0d8a2883dd 100644 --- a/planning/motion_velocity_smoother/package.xml +++ b/planning/motion_velocity_smoother/package.xml @@ -22,7 +22,6 @@ autoware_auto_planning_msgs geometry_msgs interpolation - libboost-dev motion_utils nav_msgs osqp_interface diff --git a/planning/motion_velocity_smoother/src/trajectory_utils.cpp b/planning/motion_velocity_smoother/src/trajectory_utils.cpp index dd361696a5dad..acc3673d66925 100644 --- a/planning/motion_velocity_smoother/src/trajectory_utils.cpp +++ b/planning/motion_velocity_smoother/src/trajectory_utils.cpp @@ -15,7 +15,6 @@ #include "motion_velocity_smoother/trajectory_utils.hpp" #include "interpolation/linear_interpolation.hpp" -#include "interpolation/spline_interpolation.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -430,7 +429,7 @@ bool isValidStopDist( return true; } -boost::optional applyDecelFilterWithJerkConstraint( +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) @@ -536,7 +535,7 @@ boost::optional applyDecelFilterWithJerkConstraint( return output_trajectory; } -boost::optional> updateStateWithJerkConstraint( +std::optional> updateStateWithJerkConstraint( const double v0, const double a0, const std::map & jerk_profile, const double t) { // constexpr double eps = 1.0E-05; @@ -558,15 +557,14 @@ boost::optional> updateStateWithJerkC x = integ_x(x, v, a, j, dt); v = integ_v(v, a, j, dt); a = integ_a(a, j, dt); - const auto state = std::make_tuple(x, v, a, j); - return boost::optional>(state); + return std::make_tuple(x, v, a, j); } } RCLCPP_WARN_STREAM( rclcpp::get_logger("motion_velocity_smoother").get_child("trajectory_utils"), "Invalid jerk profile"); - return {}; + return std::nullopt; } std::vector calcVelocityProfileWithConstantJerkAndAccelerationLimit( From 29458b36c67c1422995d59ecfac62fb2aabd4832 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 7 Dec 2023 18:05:27 +0900 Subject: [PATCH 017/276] refactor(start_planner, goal_planner): separate package (#5802) * separate packages Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../CMakeLists.txt | 19 +++++ .../config}/goal_planner.param.yaml | 0 .../default_fixed_goal_planner.hpp | 8 +- .../fixed_goal_planner_base.hpp | 6 +- .../freespace_pull_over.hpp | 8 +- .../geometric_pull_over.hpp | 10 +-- .../goal_planner_module.hpp | 39 ++++++--- .../goal_planner_parameters.hpp | 8 +- .../goal_searcher.hpp | 8 +- .../goal_searcher_base.hpp | 8 +- .../manager.hpp | 8 +- .../pull_over_planner_base.hpp | 8 +- .../shift_pull_over.hpp | 8 +- .../util.hpp | 8 +- .../package.xml | 35 ++++++++ .../plugins.xml | 3 + .../src}/default_fixed_goal_planner.cpp | 4 +- .../src}/freespace_pull_over.cpp | 8 +- .../src}/geometric_pull_over.cpp | 4 +- .../src}/goal_planner_module.cpp | 56 ++++++++----- .../src}/goal_searcher.cpp | 4 +- .../src}/manager.cpp | 4 +- .../src}/shift_pull_over.cpp | 4 +- .../src}/util.cpp | 2 +- planning/behavior_path_planner/CMakeLists.txt | 16 ---- planning/behavior_path_planner/plugins.xml | 2 - ...t_behavior_path_planner_node_interface.cpp | 4 - .../CMakeLists.txt | 2 + .../parking_departure}/common_module_data.hpp | 6 +- .../geometric_parallel_parking.hpp | 6 +- .../utils/parking_departure}/utils.hpp | 48 ++++------- .../geometric_parallel_parking.cpp | 6 +- .../src/utils/parking_departure}/utils.cpp | 80 +++++++------------ .../CMakeLists.txt | 17 ++++ .../config}/start_planner.param.yaml | 0 .../freespace_pull_out.hpp | 8 +- .../geometric_pull_out.hpp | 12 +-- .../manager.hpp | 8 +- .../pull_out_path.hpp | 6 +- .../pull_out_planner_base.hpp | 10 +-- .../shift_pull_out.hpp | 10 +-- .../start_planner_module.hpp | 34 +++++--- .../start_planner_parameters.hpp | 8 +- .../util.hpp | 13 +-- .../package.xml | 35 ++++++++ .../plugins.xml | 3 + .../src}/freespace_pull_out.cpp | 9 ++- .../src}/geometric_pull_out.cpp | 4 +- .../src}/manager.cpp | 2 +- .../src}/shift_pull_out.cpp | 10 +-- .../src}/start_planner_module.cpp | 48 ++++++++--- .../src}/util.cpp | 23 +----- 52 files changed, 395 insertions(+), 305 deletions(-) create mode 100644 planning/behavior_path_goal_planner_module/CMakeLists.txt rename planning/{behavior_path_planner/config/goal_planner => behavior_path_goal_planner_module/config}/goal_planner.param.yaml (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/default_fixed_goal_planner.hpp (80%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/fixed_goal_planner_base.hpp (86%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/freespace_pull_over.hpp (83%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/geometric_pull_over.hpp (86%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/goal_planner_module.hpp (92%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/goal_planner_parameters.hpp (92%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/goal_searcher.hpp (88%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/goal_searcher_base.hpp (86%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/manager.hpp (84%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/pull_over_planner_base.hpp (92%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/shift_pull_over.hpp (88%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/util.hpp (91%) create mode 100644 planning/behavior_path_goal_planner_module/package.xml create mode 100644 planning/behavior_path_goal_planner_module/plugins.xml rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/default_fixed_goal_planner.cpp (96%) rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/freespace_pull_over.cpp (94%) rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/geometric_pull_over.cpp (95%) rename planning/{behavior_path_planner/src/scene_module/goal_planner => behavior_path_goal_planner_module/src}/goal_planner_module.cpp (97%) rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/goal_searcher.cpp (99%) rename planning/{behavior_path_planner/src/scene_module/goal_planner => behavior_path_goal_planner_module/src}/manager.cpp (99%) rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/shift_pull_over.cpp (98%) rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/util.cpp (99%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common => behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure}/common_module_data.hpp (84%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking => behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure}/geometric_parallel_parking.hpp (95%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common => behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure}/utils.hpp (63%) rename planning/{behavior_path_planner/src/utils/geometric_parallel_parking => behavior_path_planner_common/src/utils/parking_departure}/geometric_parallel_parking.cpp (98%) rename planning/{behavior_path_planner/src/utils/start_goal_planner_common => behavior_path_planner_common/src/utils/parking_departure}/utils.cpp (72%) create mode 100644 planning/behavior_path_start_planner_module/CMakeLists.txt rename planning/{behavior_path_planner/config/start_planner => behavior_path_start_planner_module/config}/start_planner.param.yaml (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/freespace_pull_out.hpp (83%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/geometric_pull_out.hpp (70%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/manager.hpp (83%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/pull_out_path.hpp (84%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/pull_out_planner_base.hpp (83%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/shift_pull_out.hpp (84%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/start_planner_module.hpp (88%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/start_planner_parameters.hpp (91%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/util.hpp (81%) create mode 100644 planning/behavior_path_start_planner_module/package.xml create mode 100644 planning/behavior_path_start_planner_module/plugins.xml rename planning/{behavior_path_planner/src/utils/start_planner => behavior_path_start_planner_module/src}/freespace_pull_out.cpp (93%) rename planning/{behavior_path_planner/src/utils/start_planner => behavior_path_start_planner_module/src}/geometric_pull_out.cpp (97%) rename planning/{behavior_path_planner/src/scene_module/start_planner => behavior_path_start_planner_module/src}/manager.cpp (99%) rename planning/{behavior_path_planner/src/utils/start_planner => behavior_path_start_planner_module/src}/shift_pull_out.cpp (97%) rename planning/{behavior_path_planner/src/scene_module/start_planner => behavior_path_start_planner_module/src}/start_planner_module.cpp (96%) rename planning/{behavior_path_planner/src/utils/start_planner => behavior_path_start_planner_module/src}/util.cpp (83%) diff --git a/planning/behavior_path_goal_planner_module/CMakeLists.txt b/planning/behavior_path_goal_planner_module/CMakeLists.txt new file mode 100644 index 0000000000000..c91289bf29e2c --- /dev/null +++ b/planning/behavior_path_goal_planner_module/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_goal_planner_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + 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 +) + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml b/planning/behavior_path_goal_planner_module/config/goal_planner.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml rename to planning/behavior_path_goal_planner_module/config/goal_planner.param.yaml diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/default_fixed_goal_planner.hpp similarity index 80% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/default_fixed_goal_planner.hpp index 1595503a225f8..4da625a7a9087 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/default_fixed_goal_planner.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__DEFAULT_FIXED_GOAL_PLANNER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__DEFAULT_FIXED_GOAL_PLANNER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__DEFAULT_FIXED_GOAL_PLANNER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__DEFAULT_FIXED_GOAL_PLANNER_HPP_ -#include "behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp" +#include "behavior_path_goal_planner_module/fixed_goal_planner_base.hpp" #include @@ -42,4 +42,4 @@ class DefaultFixedGoalPlanner : public FixedGoalPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__DEFAULT_FIXED_GOAL_PLANNER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__DEFAULT_FIXED_GOAL_PLANNER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp similarity index 86% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp index 5fe3427749844..0926d1010b5c3 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FIXED_GOAL_PLANNER_BASE_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FIXED_GOAL_PLANNER_BASE_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FIXED_GOAL_PLANNER_BASE_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FIXED_GOAL_PLANNER_BASE_HPP_ #include "behavior_path_planner_common/data_manager.hpp" @@ -50,4 +50,4 @@ class FixedGoalPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FIXED_GOAL_PLANNER_BASE_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FIXED_GOAL_PLANNER_BASE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp similarity index 83% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp index bb5d7b7555cfc..5ce6d83795069 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FREESPACE_PULL_OVER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FREESPACE_PULL_OVER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FREESPACE_PULL_OVER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FREESPACE_PULL_OVER_HPP_ -#include "behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp" +#include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" #include #include @@ -51,4 +51,4 @@ class FreespacePullOver : public PullOverPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FREESPACE_PULL_OVER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FREESPACE_PULL_OVER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp similarity index 86% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp index d96b01582a2d1..c5ba04ba7f52e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GEOMETRIC_PULL_OVER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GEOMETRIC_PULL_OVER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" -#include "behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp" +#include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" #include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include @@ -69,4 +69,4 @@ class GeometricPullOver : public PullOverPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GEOMETRIC_PULL_OVER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp similarity index 92% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index a9bc31983ac6c..7b5b9b1a68102 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -12,19 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__GOAL_PLANNER_MODULE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__GOAL_PLANNER_MODULE_HPP_ - -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" -#include "behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp" -#include "behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp" -#include "behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp" -#include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" -#include "behavior_path_planner/utils/goal_planner/goal_searcher.hpp" -#include "behavior_path_planner/utils/goal_planner/shift_pull_over.hpp" +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_MODULE_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_MODULE_HPP_ + +#include "behavior_path_goal_planner_module/default_fixed_goal_planner.hpp" +#include "behavior_path_goal_planner_module/freespace_pull_over.hpp" +#include "behavior_path_goal_planner_module/geometric_pull_over.hpp" +#include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" +#include "behavior_path_goal_planner_module/goal_searcher.hpp" +#include "behavior_path_goal_planner_module/shift_pull_over.hpp" #include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" +#include "behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/utils.hpp" @@ -282,6 +282,19 @@ class GoalPlannerModule : public SceneModuleInterface bool isExecutionReady() const override; void processOnExit() override; void updateData() override; + + void updateEgoPredictedPathParams( + std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & goal_planner_params); + + void updateSafetyCheckParams( + std::shared_ptr & safety_check_params, + const std::shared_ptr & goal_planner_params); + + void updateObjectsFilteringParams( + std::shared_ptr & objects_filtering_params, + const std::shared_ptr & goal_planner_params); + void postProcess() override; void setParameters(const std::shared_ptr & parameters); void acceptVisitor( @@ -291,7 +304,7 @@ class GoalPlannerModule : public SceneModuleInterface CandidateOutput planCandidate() const override { return CandidateOutput{}; } private: - /*  + /* * state transitions and plan function used in each state * * +--------------------------+ @@ -494,4 +507,4 @@ class GoalPlannerModule : public SceneModuleInterface }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__GOAL_PLANNER_MODULE_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_MODULE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_parameters.hpp similarity index 92% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_parameters.hpp index c5adf3a2ad652..21eb22046bff6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_parameters.hpp @@ -13,10 +13,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_PLANNER_PARAMETERS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_PLANNER_PARAMETERS_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_PARAMETERS_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_PARAMETERS_HPP_ -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include @@ -124,4 +124,4 @@ struct GoalPlannerParameters }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_PLANNER_PARAMETERS_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_PARAMETERS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp similarity index 88% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp index 2fc0acf1c5086..2d9e2c6cf3700 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_HPP_ -#include "behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp" +#include "behavior_path_goal_planner_module/goal_searcher_base.hpp" #include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include @@ -55,4 +55,4 @@ class GoalSearcher : public GoalSearcherBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp similarity index 86% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp index 7d1c99a69b1d5..93472ab6c0703 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_BASE_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_BASE_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_BASE_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_BASE_HPP_ -#include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" +#include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include @@ -69,4 +69,4 @@ class GoalSearcherBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_BASE_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_BASE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/manager.hpp similarity index 84% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/manager.hpp index a166a677c7388..aefd4cac3ee35 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/manager.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp" +#include "behavior_path_goal_planner_module/goal_planner_module.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" #include @@ -55,4 +55,4 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp similarity index 92% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp index a0bfd8e883d80..ddd7c93998654 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__PULL_OVER_PLANNER_BASE_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__PULL_OVER_PLANNER_BASE_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER_BASE_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER_BASE_HPP_ -#include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" +#include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" @@ -135,4 +135,4 @@ class PullOverPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__PULL_OVER_PLANNER_BASE_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER_BASE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/shift_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp similarity index 88% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/shift_pull_over.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp index 9247ec566fbd8..cc8686f4a9fef 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/shift_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__SHIFT_PULL_OVER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__SHIFT_PULL_OVER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ -#include "behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp" +#include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" #include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include @@ -61,4 +61,4 @@ class ShiftPullOver : public PullOverPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__SHIFT_PULL_OVER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp similarity index 91% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp index 25c0551d896b3..791c35f3afca6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__UTIL_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__UTIL_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ -#include "behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp" +#include "behavior_path_goal_planner_module/goal_searcher_base.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/utils.hpp" @@ -71,4 +71,4 @@ MarkerArray createNumObjectsToAvoidTextsMarkerArray( } // namespace goal_planner_utils } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__UTIL_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ diff --git a/planning/behavior_path_goal_planner_module/package.xml b/planning/behavior_path_goal_planner_module/package.xml new file mode 100644 index 0000000000000..d29f6c6124750 --- /dev/null +++ b/planning/behavior_path_goal_planner_module/package.xml @@ -0,0 +1,35 @@ + + + + behavior_path_goal_planner_module + 0.1.0 + The behavior_path_goal_planner_module package + + Kosuke Takeuchi + Kyoichi Sugahara + Satoshi OTA + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + behavior_path_planner + behavior_path_planner_common + motion_utils + pluginlib + rclcpp + rtc_interface + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_goal_planner_module/plugins.xml b/planning/behavior_path_goal_planner_module/plugins.xml new file mode 100644 index 0000000000000..6c3b557e35e7a --- /dev/null +++ b/planning/behavior_path_goal_planner_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp b/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp similarity index 96% rename from planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp rename to planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp index 9ae50def1d358..f028b8aff8b98 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp +++ b/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp" +#include "behavior_path_goal_planner_module/default_fixed_goal_planner.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" diff --git a/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp similarity index 94% rename from planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp rename to planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp index d5252028f880b..c9af9ee369bd5 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp" +#include "behavior_path_goal_planner_module/freespace_pull_over.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" +#include "behavior_path_goal_planner_module/util.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include @@ -116,7 +116,7 @@ std::optional FreespacePullOver::plan(const Pose & goal_pose) std::vector> pairs_terminal_velocity_and_accel{}; pairs_terminal_velocity_and_accel.resize(partial_paths.size()); - utils::start_goal_planner_common::modifyVelocityByDirection( + utils::parking_departure::modifyVelocityByDirection( partial_paths, pairs_terminal_velocity_and_accel, velocity_, 0); // Check if driving forward for each path, return empty if not diff --git a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp similarity index 95% rename from planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp rename to planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp index 55d8bc6cfda3f..31c1d3ef77b0e 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp" +#include "behavior_path_goal_planner_module/geometric_pull_over.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include #include diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp similarity index 97% rename from planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp rename to planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index e8905f64e9617..19c60d77b3d67 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp" +#include "behavior_path_goal_planner_module/goal_planner_module.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -39,7 +39,7 @@ #include #include -using behavior_path_planner::utils::start_goal_planner_common::calcFeasibleDecelDistance; +using behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance; using motion_utils::calcLongitudinalOffsetPose; using motion_utils::calcSignedArcLength; using motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; @@ -120,8 +120,7 @@ GoalPlannerModule::GoalPlannerModule( // Initialize safety checker if (parameters_->safety_check_params.enable_safety_check) { initializeSafetyCheckParameters(); - utils::start_goal_planner_common::initializeCollisionCheckDebugMap( - goal_planner_data_.collision_check); + utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); } prev_data_.reset(); @@ -242,6 +241,30 @@ void GoalPlannerModule::onFreespaceParkingTimer() } } +void GoalPlannerModule::updateEgoPredictedPathParams( + std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & goal_planner_params) +{ + ego_predicted_path_params = + std::make_shared(goal_planner_params->ego_predicted_path_params); +} + +void GoalPlannerModule::updateSafetyCheckParams( + std::shared_ptr & safety_check_params, + const std::shared_ptr & goal_planner_params) +{ + safety_check_params = + std::make_shared(goal_planner_params->safety_check_params); +} + +void GoalPlannerModule::updateObjectsFilteringParams( + std::shared_ptr & objects_filtering_params, + const std::shared_ptr & goal_planner_params) +{ + objects_filtering_params = + std::make_shared(goal_planner_params->objects_filtering_params); +} + void GoalPlannerModule::updateData() { if (getCurrentStatus() == ModuleStatus::IDLE && !isExecutionRequested()) { @@ -303,11 +326,9 @@ void GoalPlannerModule::initializeOccupancyGridMap() void GoalPlannerModule::initializeSafetyCheckParameters() { - utils::start_goal_planner_common::updateEgoPredictedPathParams( - ego_predicted_path_params_, parameters_); - utils::start_goal_planner_common::updateSafetyCheckParams(safety_check_params_, parameters_); - utils::start_goal_planner_common::updateObjectsFilteringParams( - objects_filtering_params_, parameters_); + updateEgoPredictedPathParams(ego_predicted_path_params_, parameters_); + updateSafetyCheckParams(safety_check_params_, parameters_); + updateObjectsFilteringParams(objects_filtering_params_, parameters_); } void GoalPlannerModule::processOnExit() @@ -775,7 +796,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output if (prev_data_.safety_status.is_safe || !prev_data_.stop_path_after_approval) { auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto stop_path = - behavior_path_planner::utils::start_goal_planner_common::generateFeasibleStopPath( + behavior_path_planner::utils::parking_departure::generateFeasibleStopPath( current_path, planner_data_, *stop_pose_, parameters_->maximum_deceleration_for_stop, parameters_->maximum_jerk_for_stop); if (stop_path) { @@ -1761,13 +1782,13 @@ std::pair GoalPlannerModule::isSafePath() const parameters_->forward_goal_search_length); const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_over_path.points); const std::pair terminal_velocity_and_accel = - utils::start_goal_planner_common::getPairsTerminalVelocityAndAccel( + utils::parking_departure::getPairsTerminalVelocityAndAccel( thread_safe_data_.get_pull_over_path()->pairs_terminal_velocity_and_accel, thread_safe_data_.get_pull_over_path()->path_idx); RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for goal_planner: %f, %f", terminal_velocity_and_accel.first, terminal_velocity_and_accel.second); - utils::start_goal_planner_common::updatePathProperty( + utils::parking_departure::updatePathProperty( ego_predicted_path_params_, terminal_velocity_and_accel); // TODO(Sugahara): shoule judge is_object_front properly const bool is_object_front = true; @@ -1786,7 +1807,7 @@ std::pair GoalPlannerModule::isSafePath() const const auto target_objects_on_lane = utils::path_safety_checker::createTargetObjectsOnLane( pull_over_lanes, route_handler, filtered_objects, objects_filtering_params_); - utils::start_goal_planner_common::updateSafetyCheckTargetObjectsData( + utils::parking_departure::updateSafetyCheckTargetObjectsData( goal_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); const double hysteresis_factor = @@ -1812,7 +1833,7 @@ std::pair GoalPlannerModule::isSafePath() const throw std::domain_error("[pull_over] invalid safety check method"); }); - /*   + /* *   ==== is_safe *   ---- current_is_safe *   is_safe @@ -1937,8 +1958,7 @@ void GoalPlannerModule::setDebugData() } add(showPredictedPath(goal_planner_data_.collision_check, "ego_predicted_path")); add(showPolygon(goal_planner_data_.collision_check, "ego_and_target_polygon_relation")); - utils::start_goal_planner_common::initializeCollisionCheckDebugMap( - goal_planner_data_.collision_check); + utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); // visualize safety status maker { diff --git a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp rename to planning/behavior_path_goal_planner_module/src/goal_searcher.cpp index ee8dae231f587..b087827a9c539 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/goal_searcher.hpp" +#include "behavior_path_goal_planner_module/goal_searcher.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "lanelet2_extension/regulatory_elements/no_parking_area.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp b/planning/behavior_path_goal_planner_module/src/manager.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp rename to planning/behavior_path_goal_planner_module/src/manager.cpp index 0916b5e8ebaef..3079361253c31 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp +++ b/planning/behavior_path_goal_planner_module/src/manager.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/goal_planner/manager.hpp" +#include "behavior_path_goal_planner_module/manager.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" #include diff --git a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp similarity index 98% rename from planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp rename to planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp index 9ff452b131efa..712da5aa03a4e 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/shift_pull_over.hpp" +#include "behavior_path_goal_planner_module/shift_pull_over.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" diff --git a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp b/planning/behavior_path_goal_planner_module/src/util.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/goal_planner/util.cpp rename to planning/behavior_path_goal_planner_module/src/util.cpp index 1cd985d566f73..a01f5680dcc13 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp +++ b/planning/behavior_path_goal_planner_module/src/util.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include #include diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index b99bc2a4eb2e4..75f9e7f7af187 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -14,30 +14,14 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/behavior_path_planner_node.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp src/scene_module/dynamic_avoidance/manager.cpp - src/scene_module/start_planner/start_planner_module.cpp - src/scene_module/start_planner/manager.cpp - src/scene_module/goal_planner/goal_planner_module.cpp - src/scene_module/goal_planner/manager.cpp src/scene_module/side_shift/side_shift_module.cpp src/scene_module/side_shift/manager.cpp src/scene_module/lane_change/interface.cpp src/scene_module/lane_change/normal.cpp src/scene_module/lane_change/external_request.cpp src/scene_module/lane_change/manager.cpp - src/utils/start_goal_planner_common/utils.cpp src/utils/lane_change/utils.cpp src/utils/side_shift/util.cpp - src/utils/goal_planner/util.cpp - src/utils/goal_planner/shift_pull_over.cpp - src/utils/goal_planner/geometric_pull_over.cpp - src/utils/goal_planner/freespace_pull_over.cpp - src/utils/goal_planner/goal_searcher.cpp - src/utils/goal_planner/default_fixed_goal_planner.cpp - src/utils/start_planner/util.cpp - src/utils/start_planner/shift_pull_out.cpp - src/utils/start_planner/geometric_pull_out.cpp - src/utils/start_planner/freespace_pull_out.cpp - src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp src/marker_utils/lane_change/debug.cpp ) diff --git a/planning/behavior_path_planner/plugins.xml b/planning/behavior_path_planner/plugins.xml index 5196b20dc5abd..fed2e1c9af3c3 100644 --- a/planning/behavior_path_planner/plugins.xml +++ b/planning/behavior_path_planner/plugins.xml @@ -1,6 +1,4 @@ - - diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index c2b115ae98afe..0e253c0c73985 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -51,8 +51,6 @@ std::shared_ptr generateNode() std::vector module_names; module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); module_names.emplace_back("behavior_path_planner::SideShiftModuleManager"); - module_names.emplace_back("behavior_path_planner::StartPlannerModuleManager"); - module_names.emplace_back("behavior_path_planner::GoalPlannerModuleManager"); module_names.emplace_back("behavior_path_planner::LaneChangeRightModuleManager"); module_names.emplace_back("behavior_path_planner::LaneChangeLeftModuleManager"); module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); @@ -72,8 +70,6 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml", behavior_path_planner_dir + "/config/lane_change/lane_change.param.yaml", - behavior_path_planner_dir + "/config/start_planner/start_planner.param.yaml", - behavior_path_planner_dir + "/config/goal_planner/goal_planner.param.yaml", behavior_path_planner_dir + "/config/side_shift/side_shift.param.yaml"}); return std::make_shared(node_options); diff --git a/planning/behavior_path_planner_common/CMakeLists.txt b/planning/behavior_path_planner_common/CMakeLists.txt index 5567f04d5726b..5dbf81280f9b1 100644 --- a/planning/behavior_path_planner_common/CMakeLists.txt +++ b/planning/behavior_path_planner_common/CMakeLists.txt @@ -21,6 +21,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/utils/drivable_area_expansion/drivable_area_expansion.cpp src/utils/drivable_area_expansion/map_utils.cpp src/utils/drivable_area_expansion/footprints.cpp + src/utils/parking_departure/geometric_parallel_parking.cpp + src/utils/parking_departure/utils.cpp src/marker_utils/utils.cpp ) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp similarity index 84% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp rename to planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp index 84d84e0628cad..c270a1500431c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__COMMON_MODULE_DATA_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__COMMON_MODULE_DATA_HPP_ +#ifndef BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__COMMON_MODULE_DATA_HPP_ +#define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__COMMON_MODULE_DATA_HPP_ #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -44,4 +44,4 @@ struct StartGoalPlannerData } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__COMMON_MODULE_DATA_HPP_ +#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__COMMON_MODULE_DATA_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp similarity index 95% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp rename to planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp index 7f5eee7a12aaa..4d1f1fdb959c0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GEOMETRIC_PARALLEL_PARKING__GEOMETRIC_PARALLEL_PARKING_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GEOMETRIC_PARALLEL_PARKING__GEOMETRIC_PARALLEL_PARKING_HPP_ +#ifndef BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__GEOMETRIC_PARALLEL_PARKING_HPP_ +#define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__GEOMETRIC_PARALLEL_PARKING_HPP_ #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/parameters.hpp" @@ -150,4 +150,4 @@ class GeometricParallelParking }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GEOMETRIC_PARALLEL_PARKING__GEOMETRIC_PARALLEL_PARKING_HPP_ +#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__GEOMETRIC_PARALLEL_PARKING_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp similarity index 63% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/utils.hpp rename to planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp index 16be48b5acc6d..1d4245bfec0e4 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp @@ -12,14 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__UTILS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__UTILS_HPP_ +#ifndef BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__UTILS_HPP_ +#define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__UTILS_HPP_ -#include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" -#include "behavior_path_planner/utils/start_planner/start_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" +#include "behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include @@ -28,10 +25,9 @@ #include #include -namespace behavior_path_planner::utils::start_goal_planner_common +namespace behavior_path_planner::utils::parking_departure { -using behavior_path_planner::StartPlannerParameters; using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebugMap; using behavior_path_planner::utils::path_safety_checker::EgoPredictedPathParams; using behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams; @@ -59,30 +55,6 @@ void modifyVelocityByDirection( std::vector> & terminal_vel_acc_pairs, const double target_velocity, const double acceleration); -void updateEgoPredictedPathParams( - std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & start_planner_params); - -void updateEgoPredictedPathParams( - std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & goal_planner_params); - -void updateSafetyCheckParams( - std::shared_ptr & safety_check_params, - const std::shared_ptr & start_planner_params); - -void updateSafetyCheckParams( - std::shared_ptr & safety_check_params, - const std::shared_ptr & goal_planner_params); - -void updateObjectsFilteringParams( - std::shared_ptr & objects_filtering_params, - const std::shared_ptr & start_planner_params); - -void updateObjectsFilteringParams( - std::shared_ptr & objects_filtering_params, - const std::shared_ptr & goal_planner_params); - void updatePathProperty( std::shared_ptr & ego_predicted_path_params, const std::pair & pairs_terminal_velocity_and_accel); @@ -103,6 +75,14 @@ std::optional generateFeasibleStopPath( geometry_msgs::msg::Pose & stop_pose, const double maximum_deceleration, const double maximum_jerk); -} // namespace behavior_path_planner::utils::start_goal_planner_common +/** + * @brief calculate end arc length to generate reference path considering the goal position + * @return a pair of s_end and terminal_is_goal + */ +std::pair calcEndArcLength( + const double s_start, const double forward_path_length, const lanelet::ConstLanelets & road_lanes, + const Pose & goal_pose); + +} // namespace behavior_path_planner::utils::parking_departure -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__UTILS_HPP_ +#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__UTILS_HPP_ diff --git a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp b/planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp similarity index 98% rename from planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp rename to planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp index e6dbd2679db3c..7ba4f114328a7 100644 --- a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" -#include "behavior_path_planner/utils/start_planner/util.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -281,7 +281,7 @@ bool GeometricParallelParking::planPullOut( // get road center line path from pull_out end to goal, and combine after the second arc path const double s_start = getArcCoordinates(road_lanes, *end_pose).length; - const auto path_end_info = start_planner_utils::calcEndArcLength( + const auto path_end_info = utils::parking_departure::calcEndArcLength( s_start, planner_data_->parameters.forward_path_length, road_lanes, goal_pose); const double s_end = path_end_info.first; const bool path_terminal_is_goal = path_end_info.second; diff --git a/planning/behavior_path_planner/src/utils/start_goal_planner_common/utils.cpp b/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp similarity index 72% rename from planning/behavior_path_planner/src/utils/start_goal_planner_common/utils.cpp rename to planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp index cbc6d6a4a0b8d..58fd392988ad9 100644 --- a/planning/behavior_path_planner/src/utils/start_goal_planner_common/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp @@ -12,9 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" -namespace behavior_path_planner::utils::start_goal_planner_common +#include "behavior_path_planner_common/utils/utils.hpp" + +#include + +namespace behavior_path_planner::utils::parking_departure { using motion_utils::calcDecelDistWithJerkAndAccConstraints; @@ -80,53 +84,6 @@ void modifyVelocityByDirection( } } -void updateEgoPredictedPathParams( - std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & start_planner_params) -{ - ego_predicted_path_params = - std::make_shared(start_planner_params->ego_predicted_path_params); -} -void updateEgoPredictedPathParams( - std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & goal_planner_params) -{ - ego_predicted_path_params = - std::make_shared(goal_planner_params->ego_predicted_path_params); -} - -void updateSafetyCheckParams( - std::shared_ptr & safety_check_params, - const std::shared_ptr & start_planner_params) -{ - safety_check_params = - std::make_shared(start_planner_params->safety_check_params); -} - -void updateSafetyCheckParams( - std::shared_ptr & safety_check_params, - const std::shared_ptr & goal_planner_params) -{ - safety_check_params = - std::make_shared(goal_planner_params->safety_check_params); -} - -void updateObjectsFilteringParams( - std::shared_ptr & objects_filtering_params, - const std::shared_ptr & start_planner_params) -{ - objects_filtering_params = - std::make_shared(start_planner_params->objects_filtering_params); -} - -void updateObjectsFilteringParams( - std::shared_ptr & objects_filtering_params, - const std::shared_ptr & goal_planner_params) -{ - objects_filtering_params = - std::make_shared(goal_planner_params->objects_filtering_params); -} - void updatePathProperty( std::shared_ptr & ego_predicted_path_params, const std::pair & pairs_terminal_velocity_and_accel) @@ -178,7 +135,7 @@ std::optional generateFeasibleStopPath( // try to insert stop point in current_path after approval // but if can't stop with constraints(maximum deceleration, maximum jerk), don't insert stop point const auto min_stop_distance = - behavior_path_planner::utils::start_goal_planner_common::calcFeasibleDecelDistance( + behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance( planner_data, maximum_deceleration, maximum_jerk, 0.0); if (!min_stop_distance) { @@ -198,4 +155,25 @@ std::optional generateFeasibleStopPath( return current_path; } -} // namespace behavior_path_planner::utils::start_goal_planner_common +std::pair calcEndArcLength( + const double s_start, const double forward_path_length, const lanelet::ConstLanelets & road_lanes, + const Pose & goal_pose) +{ + const double s_forward_length = s_start + forward_path_length; + // use forward length if the goal pose is not in the lanelets + if (!utils::isInLanelets(goal_pose, road_lanes)) { + return {s_forward_length, false}; + } + + const double s_goal = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; + + // If the goal is behind the start or beyond the forward length, use forward length. + if (s_goal < s_start || s_goal >= s_forward_length) { + return {s_forward_length, false}; + } + + // path end is goal + return {s_goal, true}; +} + +} // namespace behavior_path_planner::utils::parking_departure diff --git a/planning/behavior_path_start_planner_module/CMakeLists.txt b/planning/behavior_path_start_planner_module/CMakeLists.txt new file mode 100644 index 0000000000000..6bb2f76cb9842 --- /dev/null +++ b/planning/behavior_path_start_planner_module/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_start_planner_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/start_planner_module.cpp + src/manager.cpp + src/freespace_pull_out.cpp + src/geometric_pull_out.cpp + src/shift_pull_out.cpp + src/util.cpp +) + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/start_planner/start_planner.param.yaml rename to planning/behavior_path_start_planner_module/config/start_planner.param.yaml diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/freespace_pull_out.hpp similarity index 83% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/freespace_pull_out.hpp index 3a154dfd83353..f38279d172009 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/freespace_pull_out.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ -#include "behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp" +#include "behavior_path_start_planner_module/pull_out_planner_base.hpp" #include #include @@ -49,4 +49,4 @@ class FreespacePullOut : public PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/geometric_pull_out.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/geometric_pull_out.hpp similarity index 70% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/geometric_pull_out.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/geometric_pull_out.hpp index 4f46350d6c2b1..164868b47535e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/geometric_pull_out.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/geometric_pull_out.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__GEOMETRIC_PULL_OUT_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__GEOMETRIC_PULL_OUT_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" +#include "behavior_path_start_planner_module/pull_out_path.hpp" +#include "behavior_path_start_planner_module/pull_out_planner_base.hpp" #include @@ -36,4 +36,4 @@ class GeometricPullOut : public PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__GEOMETRIC_PULL_OUT_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/manager.hpp similarity index 83% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/manager.hpp index 10fcbf81f8d45..3fb64baaa2bba 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/manager.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/start_planner/start_planner_module.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" +#include "behavior_path_start_planner_module/start_planner_module.hpp" #include @@ -53,4 +53,4 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_path.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_path.hpp similarity index 84% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_path.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_path.hpp index 9c9c6fe83e288..68fcb25cac88e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_path.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_path.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PATH_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PATH_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -34,4 +34,4 @@ struct PullOutPath Pose end_pose{}; }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PATH_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp similarity index 83% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp index 60cd2731eb92f..de3d376fa4b3d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PLANNER_BASE_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PLANNER_BASE_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" -#include "behavior_path_planner/utils/start_planner/start_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" +#include "behavior_path_start_planner_module/pull_out_path.hpp" +#include "behavior_path_start_planner_module/start_planner_parameters.hpp" #include #include @@ -66,4 +66,4 @@ class PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PLANNER_BASE_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp similarity index 84% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp index 7a868e6c2a234..9012504ed2e7a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__SHIFT_PULL_OUT_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__SHIFT_PULL_OUT_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp" +#include "behavior_path_start_planner_module/pull_out_path.hpp" +#include "behavior_path_start_planner_module/pull_out_planner_base.hpp" #include @@ -57,4 +57,4 @@ class ShiftPullOut : public PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__SHIFT_PULL_OUT_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp similarity index 88% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index f70effb7cf186..a143f34ead649 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -12,20 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__START_PLANNER_MODULE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__START_PLANNER_MODULE_HPP_ - -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp" -#include "behavior_path_planner/utils/start_planner/freespace_pull_out.hpp" -#include "behavior_path_planner/utils/start_planner/geometric_pull_out.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" -#include "behavior_path_planner/utils/start_planner/shift_pull_out.hpp" -#include "behavior_path_planner/utils/start_planner/start_planner_parameters.hpp" +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ + #include "behavior_path_planner_common/interface/scene_module_interface.hpp" +#include "behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_start_planner_module/freespace_pull_out.hpp" +#include "behavior_path_start_planner_module/geometric_pull_out.hpp" +#include "behavior_path_start_planner_module/pull_out_path.hpp" +#include "behavior_path_start_planner_module/shift_pull_out.hpp" +#include "behavior_path_start_planner_module/start_planner_parameters.hpp" #include #include @@ -100,6 +100,18 @@ class StartPlannerModule : public SceneModuleInterface void processOnExit() override; void updateData() override; + void updateEgoPredictedPathParams( + std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & start_planner_params); + + void updateSafetyCheckParams( + std::shared_ptr & safety_check_params, + const std::shared_ptr & start_planner_params); + + void updateObjectsFilteringParams( + std::shared_ptr & objects_filtering_params, + const std::shared_ptr & start_planner_params); + void setParameters(const std::shared_ptr & parameters) { parameters_ = parameters; @@ -244,4 +256,4 @@ class StartPlannerModule : public SceneModuleInterface }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__START_PLANNER_MODULE_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp similarity index 91% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp index cbde2b514366d..783aace0983ca 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp @@ -13,10 +13,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__START_PLANNER_PARAMETERS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__START_PLANNER_PARAMETERS_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_ -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include @@ -104,4 +104,4 @@ struct StartPlannerParameters } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__START_PLANNER_PARAMETERS_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp similarity index 81% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp index 5fcb5fd5668b1..147632329d926 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__UTIL_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__UTIL_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" @@ -50,13 +50,6 @@ lanelet::ConstLanelets getPullOutLanes( const std::shared_ptr & planner_data, const double backward_length); Pose getBackedPose( const Pose & current_pose, const double & yaw_shoulder_lane, const double & back_distance); -/** - * @brief calculate end arc length to generate reference path considering the goal position - * @return a pair of s_end and terminal_is_goal - */ -std::pair calcEndArcLength( - const double s_start, const double forward_path_length, const lanelet::ConstLanelets & road_lanes, - const Pose & goal_pose); } // namespace behavior_path_planner::start_planner_utils -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__UTIL_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ diff --git a/planning/behavior_path_start_planner_module/package.xml b/planning/behavior_path_start_planner_module/package.xml new file mode 100644 index 0000000000000..393c1d46fa789 --- /dev/null +++ b/planning/behavior_path_start_planner_module/package.xml @@ -0,0 +1,35 @@ + + + + behavior_path_start_planner_module + 0.1.0 + The behavior_path_start_planner_module package + + Kyoichi Sugahara + Kosuke Takeuchi + Satoshi OTA + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + behavior_path_planner + behavior_path_planner_common + motion_utils + pluginlib + rclcpp + rtc_interface + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_start_planner_module/plugins.xml b/planning/behavior_path_start_planner_module/plugins.xml new file mode 100644 index 0000000000000..fde8b673be5bc --- /dev/null +++ b/planning/behavior_path_start_planner_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_planner/src/utils/start_planner/freespace_pull_out.cpp b/planning/behavior_path_start_planner_module/src/freespace_pull_out.cpp similarity index 93% rename from planning/behavior_path_planner/src/utils/start_planner/freespace_pull_out.cpp rename to planning/behavior_path_start_planner_module/src/freespace_pull_out.cpp index 32a36e1d70509..dd068c3c26cf8 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/freespace_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/freespace_pull_out.cpp @@ -12,11 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/start_planner/freespace_pull_out.hpp" +#include "behavior_path_start_planner_module/freespace_pull_out.hpp" -#include "behavior_path_planner/utils/start_planner/util.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_start_planner_module/util.hpp" #include @@ -90,8 +91,8 @@ std::optional FreespacePullOut::plan(const Pose & start_pose, const constexpr double offset_from_end_pose = 1.0; const auto arc_position_end = lanelet::utils::getArcCoordinates(road_lanes, end_pose); const double s_start = std::max(arc_position_end.length + offset_from_end_pose, 0.0); - const auto path_end_info = - start_planner_utils::calcEndArcLength(s_start, forward_path_length, road_lanes, goal_pose); + const auto path_end_info = behavior_path_planner::utils::parking_departure::calcEndArcLength( + s_start, forward_path_length, road_lanes, goal_pose); const double s_end = path_end_info.first; const bool path_terminal_is_goal = path_end_info.second; diff --git a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp b/planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp similarity index 97% rename from planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp rename to planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp index fefa6b440c096..7d6dd60398e8e 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/start_planner/geometric_pull_out.hpp" +#include "behavior_path_start_planner_module/geometric_pull_out.hpp" -#include "behavior_path_planner/utils/start_planner/util.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_start_planner_module/util.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_start_planner_module/src/manager.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp rename to planning/behavior_path_start_planner_module/src/manager.cpp index 14660396062aa..58d0fbee7921b 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_start_planner_module/src/manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/start_planner/manager.hpp" +#include "behavior_path_start_planner_module/manager.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp similarity index 97% rename from planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp rename to planning/behavior_path_start_planner_module/src/shift_pull_out.cpp index dd1d3d3c4cca4..73952ca02f558 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/start_planner/shift_pull_out.hpp" +#include "behavior_path_start_planner_module/shift_pull_out.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" -#include "behavior_path_planner/utils/start_planner/util.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_start_planner_module/util.hpp" #include "motion_utils/trajectory/path_with_lane_id.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" @@ -187,8 +187,8 @@ std::vector ShiftPullOut::calcPullOutPaths( // generate road lane reference path const auto arc_position_start = getArcCoordinates(road_lanes, start_pose); const double s_start = std::max(arc_position_start.length - backward_path_length, 0.0); - const auto path_end_info = - start_planner_utils::calcEndArcLength(s_start, forward_path_length, road_lanes, goal_pose); + const auto path_end_info = behavior_path_planner::utils::parking_departure::calcEndArcLength( + s_start, forward_path_length, road_lanes, goal_pose); const double s_end = path_end_info.first; const bool path_terminal_is_goal = path_end_info.second; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp similarity index 96% rename from planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp rename to planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 7bede9192d35f..ca84795cb77b3 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/start_planner/start_planner_module.hpp" +#include "behavior_path_start_planner_module/start_planner_module.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" -#include "behavior_path_planner/utils/start_planner/util.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" +#include "behavior_path_start_planner_module/util.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include @@ -36,7 +36,7 @@ #include #include -using behavior_path_planner::utils::start_goal_planner_common::initializeCollisionCheckDebugMap; +using behavior_path_planner::utils::parking_departure::initializeCollisionCheckDebugMap; using motion_utils::calcLongitudinalOffsetPose; using tier4_autoware_utils::calcOffsetPose; @@ -130,6 +130,30 @@ void StartPlannerModule::initVariables() initializeCollisionCheckDebugMap(start_planner_data_.collision_check); } +void StartPlannerModule::updateEgoPredictedPathParams( + std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & start_planner_params) +{ + ego_predicted_path_params = + std::make_shared(start_planner_params->ego_predicted_path_params); +} + +void StartPlannerModule::updateSafetyCheckParams( + std::shared_ptr & safety_check_params, + const std::shared_ptr & start_planner_params) +{ + safety_check_params = + std::make_shared(start_planner_params->safety_check_params); +} + +void StartPlannerModule::updateObjectsFilteringParams( + std::shared_ptr & objects_filtering_params, + const std::shared_ptr & start_planner_params) +{ + objects_filtering_params = + std::make_shared(start_planner_params->objects_filtering_params); +} + void StartPlannerModule::updateData() { if (receivedNewRoute()) { @@ -350,7 +374,7 @@ BehaviorModuleOutput StartPlannerModule::plan() if (!status_.is_safe_dynamic_objects && !isWaitingApproval() && !status_.has_stop_point) { auto current_path = getCurrentPath(); const auto stop_path = - behavior_path_planner::utils::start_goal_planner_common::generateFeasibleStopPath( + behavior_path_planner::utils::parking_departure::generateFeasibleStopPath( current_path, planner_data_, *stop_pose_, parameters_->maximum_deceleration_for_stop, parameters_->maximum_jerk_for_stop); @@ -431,11 +455,9 @@ CandidateOutput StartPlannerModule::planCandidate() const void StartPlannerModule::initializeSafetyCheckParameters() { - utils::start_goal_planner_common::updateEgoPredictedPathParams( - ego_predicted_path_params_, parameters_); - utils::start_goal_planner_common::updateSafetyCheckParams(safety_check_params_, parameters_); - utils::start_goal_planner_common::updateObjectsFilteringParams( - objects_filtering_params_, parameters_); + updateEgoPredictedPathParams(ego_predicted_path_params_, parameters_); + updateSafetyCheckParams(safety_check_params_, parameters_); + updateObjectsFilteringParams(objects_filtering_params_, parameters_); } PathWithLaneId StartPlannerModule::getFullPath() const @@ -1095,13 +1117,13 @@ bool StartPlannerModule::isSafePath() const // for ego predicted path const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_out_path.points); const std::pair terminal_velocity_and_accel = - utils::start_goal_planner_common::getPairsTerminalVelocityAndAccel( + utils::parking_departure::getPairsTerminalVelocityAndAccel( status_.pull_out_path.pairs_terminal_velocity_and_accel, status_.current_path_idx); RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for start_planner: %f, %f", terminal_velocity_and_accel.first, terminal_velocity_and_accel.second); RCLCPP_DEBUG(getLogger(), "current_path_idx %ld", status_.current_path_idx); - utils::start_goal_planner_common::updatePathProperty( + utils::parking_departure::updatePathProperty( ego_predicted_path_params_, terminal_velocity_and_accel); // TODO(Sugahara): shoule judge is_object_front properly const bool is_object_front = true; @@ -1122,7 +1144,7 @@ bool StartPlannerModule::isSafePath() const const double hysteresis_factor = status_.is_safe_dynamic_objects ? 1.0 : safety_check_params_->hysteresis_factor_expand_rate; - utils::start_goal_planner_common::updateSafetyCheckTargetObjectsData( + utils::parking_departure::updateSafetyCheckTargetObjectsData( start_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS( diff --git a/planning/behavior_path_planner/src/utils/start_planner/util.cpp b/planning/behavior_path_start_planner_module/src/util.cpp similarity index 83% rename from planning/behavior_path_planner/src/utils/start_planner/util.cpp rename to planning/behavior_path_start_planner_module/src/util.cpp index 0b26c793155f7..9a9466936c422 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/util.cpp +++ b/planning/behavior_path_start_planner_module/src/util.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/start_planner/util.hpp" +#include "behavior_path_start_planner_module/util.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -106,25 +106,4 @@ lanelet::ConstLanelets getPullOutLanes( /*forward_only_in_route*/ true); } -std::pair calcEndArcLength( - const double s_start, const double forward_path_length, const lanelet::ConstLanelets & road_lanes, - const Pose & goal_pose) -{ - const double s_forward_length = s_start + forward_path_length; - // use forward length if the goal pose is not in the lanelets - if (!utils::isInLanelets(goal_pose, road_lanes)) { - return {s_forward_length, false}; - } - - const double s_goal = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; - - // If the goal is behind the start or beyond the forward length, use forward length. - if (s_goal < s_start || s_goal >= s_forward_length) { - return {s_forward_length, false}; - } - - // path end is goal - return {s_goal, true}; -} - } // namespace behavior_path_planner::start_planner_utils From c227db0c97fce83672023eb61a3fff3e619da80c Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 7 Dec 2023 18:26:14 +0900 Subject: [PATCH 018/276] fix(avoidance): fix invalid optional access (#5804) Signed-off-by: satoshi-ota --- .../src/shift_line_generator.cpp | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index 48d7e3a4baf8b..108412876d47f 100644 --- a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -966,6 +966,7 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( AvoidLineArray ret = shift_lines; constexpr double ep = 1.0e-3; + constexpr double RETURN_SHIFT_THRESHOLD = 0.1; const bool has_candidate_point = !ret.empty(); const bool has_registered_point = last_.has_value(); @@ -977,14 +978,15 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( return ret; } - // If the return-to-center shift points are already registered, do nothing. - if (!has_registered_point && std::fabs(base_offset_) < ep) { - return ret; - } - - constexpr double RETURN_SHIFT_THRESHOLD = 0.1; - if (std::abs(last_.value().end_shift_length) < RETURN_SHIFT_THRESHOLD) { - return ret; + if (last_.has_value()) { + if (std::abs(last_.value().end_shift_length) < RETURN_SHIFT_THRESHOLD) { + return ret; + } + } else { + // If the return-to-center shift points are already registered, do nothing. + if (std::abs(base_offset_) < ep) { + return ret; + } } // From here, the return-to-center is not registered. But perhaps the candidate is From 53a4ec6bc4f7901069e77bb685ef4b504777bfe5 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 7 Dec 2023 21:47:20 +0900 Subject: [PATCH 019/276] refactor(behavior_path_planner): delete unnecessary TODO (#5806) delete unnecessary TODO Signed-off-by: kyoichi-sugahara --- .../src/goal_planner_module.cpp | 1 - .../src/scene_module/lane_change/interface.cpp | 1 - .../src/start_planner_module.cpp | 2 -- 3 files changed, 4 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 19c60d77b3d67..98f5664153bfd 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -873,7 +873,6 @@ void GoalPlannerModule::updateSteeringFactor( return SteeringFactor::STRAIGHT; }); - // TODO(tkhmy) add handle status TRYING steering_factor_interface_ptr_->updateSteeringFactor( pose, distance, PlanningBehavior::GOAL_PLANNER, steering_factor_direction, type, ""); } diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index 26fc423fce02f..cec9d5013d929 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -372,7 +372,6 @@ void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & o const auto finish_distance = motion_utils::calcSignedArcLength( output.path->points, current_position, status.lane_change_path.info.shift_line.end.position); - // TODO(tkhmy) add handle status TRYING steering_factor_interface_ptr_->updateSteeringFactor( {status.lane_change_path.info.shift_line.start, status.lane_change_path.info.shift_line.end}, {start_distance, finish_distance}, PlanningBehavior::LANE_CHANGE, steering_factor_direction, diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index ca84795cb77b3..0d3892cde8023 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -427,7 +427,6 @@ BehaviorModuleOutput StartPlannerModule::plan() path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.end_pose.position); updateRTCStatus(start_distance, finish_distance); - // TODO(tkhmy) add handle status TRYING steering_factor_interface_ptr_->updateSteeringFactor( {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {start_distance, finish_distance}, PlanningBehavior::START_PLANNER, steering_factor_direction, @@ -437,7 +436,6 @@ BehaviorModuleOutput StartPlannerModule::plan() path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); updateRTCStatus(0.0, distance); - // TODO(tkhmy) add handle status TRYING steering_factor_interface_ptr_->updateSteeringFactor( {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance}, PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, ""); From 5690d8c0b446534f00e4011bad1cc75d4faef729 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 8 Dec 2023 09:35:08 +0900 Subject: [PATCH 020/276] chore(bpp): update maintainer (#5809) Signed-off-by: satoshi-ota --- .../package.xml | 3 +++ .../package.xml | 3 +++ .../package.xml | 3 +++ planning/behavior_path_planner/package.xml | 21 ++++++------------- .../package.xml | 5 ++++- 5 files changed, 19 insertions(+), 16 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_avoidance_by_lane_change_module/package.xml index 3bb32bdf76bf0..da51dd9f235dc 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/package.xml +++ b/planning/behavior_path_avoidance_by_lane_change_module/package.xml @@ -8,6 +8,9 @@ Satoshi Ota Zulfaqar Azmi Fumiya Watanabe + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando Apache License 2.0 diff --git a/planning/behavior_path_avoidance_module/package.xml b/planning/behavior_path_avoidance_module/package.xml index 68cc911e9373d..642f83497acfb 100644 --- a/planning/behavior_path_avoidance_module/package.xml +++ b/planning/behavior_path_avoidance_module/package.xml @@ -9,6 +9,9 @@ Satoshi Ota Fumiya Watanabe Kyoichi Sugahara + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando Apache License 2.0 diff --git a/planning/behavior_path_goal_planner_module/package.xml b/planning/behavior_path_goal_planner_module/package.xml index d29f6c6124750..213c0093b08d9 100644 --- a/planning/behavior_path_goal_planner_module/package.xml +++ b/planning/behavior_path_goal_planner_module/package.xml @@ -8,6 +8,9 @@ Kosuke Takeuchi Kyoichi Sugahara Satoshi OTA + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando Apache License 2.0 diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 5ca86ee5a47b6..0ca7badd0b3f4 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -7,28 +7,19 @@ Zulfaqar Azmi - - Kosuke Takeuchi - - Kosuke Takeuchi Fumiya Watanabe Kyoichi Sugahara - - Takamasa Horibe - Satoshi Ota - - Zulfaqar Azmi - Satoshi Ota - Mamoru Sobue - - - Takayuki Murooka - Taiki Tanaka Tomoya Kimura Shumpei Wakabayashi + Tomohito Ando + Takamasa Horibe + Satoshi Ota + Kosuke Takeuchi + Kyoichi Sugahara + Takayuki Murooka Apache License 2.0 diff --git a/planning/behavior_path_start_planner_module/package.xml b/planning/behavior_path_start_planner_module/package.xml index 393c1d46fa789..cbfdba0d07a57 100644 --- a/planning/behavior_path_start_planner_module/package.xml +++ b/planning/behavior_path_start_planner_module/package.xml @@ -5,9 +5,12 @@ 0.1.0 The behavior_path_start_planner_module package - Kyoichi Sugahara Kosuke Takeuchi + Kyoichi Sugahara Satoshi OTA + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando Apache License 2.0 From 0e97ab61c4f09a30c3a92f172d7eea488bb320ea Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Fri, 8 Dec 2023 10:20:39 +0900 Subject: [PATCH 021/276] fix(crosswalk_traffic_light_estimator): add operation to remove traffic signals with duplicated ids (#5653) * fix: add operation to remove traffic signals with duplicated ids Signed-off-by: ktro2828 * feat: move operation into `crosswalk_traffic_light_estimator` Signed-off-by: ktro2828 --------- Signed-off-by: ktro2828 --- .../crosswalk_traffic_light_estimator/node.hpp | 2 ++ .../src/node.cpp | 17 +++++++++++++++++ 2 files changed, 19 insertions(+) diff --git a/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp b/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp index e38b747a6ce67..848293f6334bb 100644 --- a/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp +++ b/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp @@ -92,6 +92,8 @@ class CrosswalkTrafficLightEstimatorNode : public rclcpp::Node boost::optional getHighestConfidenceTrafficSignal( const lanelet::Id & id, const TrafficLightIdMap & traffic_light_id_map) const; + void removeDuplicateIds(TrafficSignalArray & signal_array) const; + // Node param bool use_last_detect_color_; double last_detect_color_hold_time_; diff --git a/perception/crosswalk_traffic_light_estimator/src/node.cpp b/perception/crosswalk_traffic_light_estimator/src/node.cpp index 870b8bc7c13f5..6527f0662bcbf 100644 --- a/perception/crosswalk_traffic_light_estimator/src/node.cpp +++ b/perception/crosswalk_traffic_light_estimator/src/node.cpp @@ -174,6 +174,8 @@ void CrosswalkTrafficLightEstimatorNode::onTrafficLightArray( setCrosswalkTrafficSignal(crosswalk, crosswalk_tl_color, output); } + removeDuplicateIds(output); + updateLastDetectedSignal(traffic_light_id_map); pub_traffic_light_array_->publish(output); @@ -383,6 +385,21 @@ boost::optional CrosswalkTrafficLightEstimatorNode::getHighestConfidenc return ret; } + +void CrosswalkTrafficLightEstimatorNode::removeDuplicateIds(TrafficSignalArray & signal_array) const +{ + auto & signals = signal_array.signals; + std::sort(signals.begin(), signals.end(), [](const auto & s1, const auto & s2) { + return s1.traffic_signal_id < s2.traffic_signal_id; + }); + + signals.erase( + std::unique( + signals.begin(), signals.end(), + [](const auto & s1, const auto s2) { return s1.traffic_signal_id == s2.traffic_signal_id; }), + signals.end()); +} + } // namespace traffic_light #include From 7730e88f764e4240bc58f989ae3facc3416df57d Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 8 Dec 2023 10:24:27 +0900 Subject: [PATCH 022/276] refactor(multi_object_tracker): put node parameters to yaml file (#5769) * rework multi object tracker parameters Signed-off-by: yoshiri * update README Signed-off-by: yoshiri * rework radar tracker parameter too Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../tracking/tracking.launch.xml | 10 ++----- .../launch/perception.launch.xml | 1 + perception/multi_object_tracker/README.md | 30 ++++++++++++------- ...l => multi_object_tracker_node.param.yaml} | 6 ++++ .../launch/multi_object_tracker.launch.xml | 8 +---- .../src/multi_object_tracker_core.cpp | 6 ++-- .../launch/radar_object_tracker.launch.xml | 6 ---- 7 files changed, 33 insertions(+), 34 deletions(-) rename perception/multi_object_tracker/config/{default_tracker.param.yaml => multi_object_tracker_node.param.yaml} (68%) diff --git a/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml index 07b53fb671732..85c6e87c0fd19 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -1,8 +1,6 @@ - - @@ -19,8 +17,7 @@ - - + @@ -29,15 +26,12 @@ - - + - - diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 96ad80131e4e7..da393b1efff59 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -14,6 +14,7 @@ + diff --git a/perception/multi_object_tracker/README.md b/perception/multi_object_tracker/README.md index 0cc8f1708e334..311fe7b6da716 100644 --- a/perception/multi_object_tracker/README.md +++ b/perception/multi_object_tracker/README.md @@ -70,16 +70,26 @@ Example: ### Core Parameters -| Name | Type | Description | -| --------------------------- | ------ | -------------------------------------------------------------- | -| `can_assign_matrix` | double | Assignment table for data association | -| `max_dist_matrix` | double | Maximum distance table for data association | -| `max_area_matrix` | double | Maximum area table for data association | -| `min_area_matrix` | double | Minimum area table for data association | -| `max_rad_matrix` | double | Maximum angle table for data association | -| `world_frame_id` | double | tracking frame | -| `enable_delay_compensation` | bool | Estimate obstacles at current time considering detection delay | -| `publish_rate` | double | if enable_delay_compensation is true, how many hertz to output | +Node parameters are defined in [multi_object_tracker.param.yaml](config/multi_object_tracker.param.yaml) and association parameters are defined in [data_association.param.yaml](config/data_association.param.yaml). + +#### Node parameters + +| Name | Type | Description | +| --------------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------- | +| `***_tracker` | string | EKF tracker name for each class | +| `world_frame_id` | double | object kinematics definition frame | +| `enable_delay_compensation` | bool | if True, tracker use timers to schedule publishers and use prediction step to extrapolate object state at desired timestamp | +| `publish_rate` | double | Timer frequency to output with delay compensation | + +#### Association parameters + +| Name | Type | Description | +| ------------------- | ------ | ------------------------------------------- | +| `can_assign_matrix` | double | Assignment table for data association | +| `max_dist_matrix` | double | Maximum distance table for data association | +| `max_area_matrix` | double | Maximum area table for data association | +| `min_area_matrix` | double | Minimum area table for data association | +| `max_rad_matrix` | double | Maximum angle table for data association | ## Assumptions / Known limits diff --git a/perception/multi_object_tracker/config/default_tracker.param.yaml b/perception/multi_object_tracker/config/multi_object_tracker_node.param.yaml similarity index 68% rename from perception/multi_object_tracker/config/default_tracker.param.yaml rename to perception/multi_object_tracker/config/multi_object_tracker_node.param.yaml index 23e88d8274172..9552b35b65bed 100644 --- a/perception/multi_object_tracker/config/default_tracker.param.yaml +++ b/perception/multi_object_tracker/config/multi_object_tracker_node.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + # default tracker models for each class car_tracker: "multi_vehicle_tracker" truck_tracker: "multi_vehicle_tracker" bus_tracker: "multi_vehicle_tracker" @@ -7,3 +8,8 @@ pedestrian_tracker: "pedestrian_and_bicycle_tracker" bicycle_tracker: "pedestrian_and_bicycle_tracker" motorcycle_tracker: "pedestrian_and_bicycle_tracker" + + # default tracker node parameters + publish_rate: 10.0 + world_frame_id: map + enable_delay_compensation: false diff --git a/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml b/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml index 21a2ce67d552d..dcd080b851c20 100644 --- a/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml +++ b/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml @@ -2,18 +2,12 @@ - - - - + - - - diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index d302b04d733cd..e42ff748c503e 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -78,9 +78,9 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) create_publisher("output", rclcpp::QoS{1}); // Parameters - double publish_rate = declare_parameter("publish_rate", 30.0); - world_frame_id_ = declare_parameter("world_frame_id", "world"); - bool enable_delay_compensation{declare_parameter("enable_delay_compensation", false)}; + double publish_rate = declare_parameter("publish_rate"); + world_frame_id_ = declare_parameter("world_frame_id"); + bool enable_delay_compensation{declare_parameter("enable_delay_compensation")}; auto cti = std::make_shared( this->get_node_base_interface(), this->get_node_timers_interface()); diff --git a/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml b/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml index 6e6813d3e40ff..60ed2efb5767b 100644 --- a/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml +++ b/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml @@ -2,9 +2,6 @@ - - - @@ -19,8 +16,5 @@ - - - From 6dd31109fc96187e94bf19627292f2684f8dc911 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 8 Dec 2023 14:26:53 +0900 Subject: [PATCH 023/276] chore(crosswalk): update comments (#5813) * fix typo * update comments Signed-off-by: Yuki Takagi --- .../config/crosswalk.param.yaml | 36 +++++++++---------- .../src/manager.cpp | 8 ++--- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index 762639950b2c5..6559f39278fdc 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -9,7 +9,7 @@ # param for stop position stop_position: - stop_position_threshold: 1.0 # [m] threshold to check whether the vehicle stops in front of crosswalk for yielding + stop_position_threshold: 1.0 # [m] If the ego vehicle has stopped near the stop line than this value, this module assumes itself to have achieved yielding. # For the Lanelet2 map with no explicit stop lines stop_distance_from_crosswalk: 3.5 # [m] make stop line away from crosswalk @@ -18,24 +18,24 @@ # For the case where the stop position is determined according to the object position. stop_distance_from_object: 2.0 # [m] the vehicle decelerates to be able to stop in front of object with margin - # param for ego's slow down velocity + # params for ego's slow down velocity. These params are not used for the case of "enable_rtc: false". slow_down: min_slow_down_velocity: 2.78 # [m/s] target vehicle velocity when module receive slow down command from FOA (2.78 m/s = 10.0 kmph) max_slow_down_jerk: -1.5 # [m/sss] minimum jerk deceleration for safe brake max_slow_down_accel: -2.5 # [m/ss] minimum accel deceleration for safe brake no_relax_velocity: 2.78 # [m/s] if the current velocity is less than X m/s, ego always stops at the stop position(not relax deceleration constraints 2.78 m/s = 10 kmph) - # param for stuck vehicles + # params to prevent stopping on crosswalks due to another vehicle ahead stuck_vehicle: enable_stuck_check_in_intersection: false # [-] flag to enable stuck vehicle checking for crosswalk which is in intersection - stuck_vehicle_velocity: 1.0 # [m/s] maximum velocity threshold whether the vehicle is stuck - max_stuck_vehicle_lateral_offset: 2.0 # [m] maximum lateral offset for stuck vehicle position should be looked - stuck_vehicle_attention_range: 10.0 # [m] the detection area is defined as X meters behind the crosswalk - min_acc: -1.0 # min acceleration [m/ss] - min_jerk: -1.0 # min jerk [m/sss] - max_jerk: 1.0 # max jerk [m/sss] + stuck_vehicle_velocity: 1.0 # [m/s] threshold velocity whether other vehicles are assumed to be stuck or not. + max_stuck_vehicle_lateral_offset: 2.0 # [m] The feature does not handle the vehicles farther than this value to the ego's path. + stuck_vehicle_attention_range: 10.0 # [m] Ego does not enter the crosswalk area if a stuck vehicle exists within this distance from the end of the crosswalk on the ego's path. + min_acc: -1.0 # min acceleration [m/ss] + min_jerk: -1.0 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] - # param for pass judge logic + # 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: [6.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) @@ -44,21 +44,21 @@ ego_pass_later_margin_y: [10.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering - no_stop_decision: + no_stop_decision: # parameters to determine if it is safe to attempt stopping before the crosswalk max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk. - min_acc: -1.0 # min acceleration [m/ss] - min_jerk: -1.0 # min jerk [m/sss] - max_jerk: 1.0 # max jerk [m/sss] + min_acc: -1.0 # min acceleration [m/ss] + min_jerk: -1.0 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph) ## param for yielding - disable_stop_for_yield_cancel: true # for the crosswalk where there is a traffic signal - disable_yield_for_new_stopped_object: true # for the crosswalk where there is a traffic signal - # if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first. + disable_stop_for_yield_cancel: true # for the crosswalks with traffic signal + disable_yield_for_new_stopped_object: true # for the crosswalks with traffic signal + # If the pedestrian does not move for X seconds after the ego has stopped in front the crosswalk, the module judge that the pedestrian has no intention to walk and allows the ego to proceed. distance_map_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order timeout_map_for_no_intention_to_walk: [3.0, 0.0] # [s] - timeout_ego_stop_for_yield: 3.0 # [s] the amount of time which ego should be stopping to query whether it yields or not + timeout_ego_stop_for_yield: 3.0 # [s] If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough. # param for target object filtering object_filtering: diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index c743d440bee85..cb0311ffe8ebb 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -152,10 +152,10 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path) path.header.stamp); }; - const auto crosswalk_leg_elem_map = planning_utils::getRegElemMapOnPath( + const auto crosswalk_reg_elem_map = planning_utils::getRegElemMapOnPath( path, rh->getLaneletMapPtr(), planner_data_->current_odometry->pose); - for (const auto & crosswalk : crosswalk_leg_elem_map) { + for (const auto & crosswalk : crosswalk_reg_elem_map) { // NOTE: The former id is a lane id, and the latter one is a regulatory element's id. launch(crosswalk.second.id(), crosswalk.first->crosswalkLanelet().id(), crosswalk.first->id()); } @@ -178,10 +178,10 @@ CrosswalkModuleManager::getModuleExpiredFunction(const PathWithLaneId & path) crosswalk_id_set = getCrosswalkIdSetOnPath( planner_data_->current_odometry->pose, path, rh->getLaneletMapPtr(), rh->getOverallGraphPtr()); - const auto crosswalk_leg_elem_map = planning_utils::getRegElemMapOnPath( + const auto crosswalk_reg_elem_map = planning_utils::getRegElemMapOnPath( path, rh->getLaneletMapPtr(), planner_data_->current_odometry->pose); - for (const auto & crosswalk : crosswalk_leg_elem_map) { + for (const auto & crosswalk : crosswalk_reg_elem_map) { crosswalk_id_set.insert(crosswalk.first->crosswalkLanelet().id()); } From 68f821a3f3bfdb2ea412f2638b4515b158f13a57 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 8 Dec 2023 15:00:57 +0900 Subject: [PATCH 024/276] refactor(motion_utils): stop using CAPACITY from Trajectory message (#5755) Signed-off-by: Maxime CLEMENT --- common/motion_utils/src/trajectory/tmp_conversion.cpp | 7 +------ .../test/src/trajectory/test_trajectory.cpp | 11 ----------- 2 files changed, 1 insertion(+), 17 deletions(-) diff --git a/common/motion_utils/src/trajectory/tmp_conversion.cpp b/common/motion_utils/src/trajectory/tmp_conversion.cpp index 5c907a5926046..18705637a8387 100644 --- a/common/motion_utils/src/trajectory/tmp_conversion.cpp +++ b/common/motion_utils/src/trajectory/tmp_conversion.cpp @@ -36,12 +36,7 @@ autoware_auto_planning_msgs::msg::Trajectory convertToTrajectory( const std::vector & trajectory) { autoware_auto_planning_msgs::msg::Trajectory output{}; - for (const auto & pt : trajectory) { - output.points.push_back(pt); - if (output.points.size() >= output.CAPACITY) { - break; - } - } + for (const auto & pt : trajectory) output.points.push_back(pt); return output; } diff --git a/common/motion_utils/test/src/trajectory/test_trajectory.cpp b/common/motion_utils/test/src/trajectory/test_trajectory.cpp index 1786586ec39a8..22567b569d0ad 100644 --- a/common/motion_utils/test/src/trajectory/test_trajectory.cpp +++ b/common/motion_utils/test/src/trajectory/test_trajectory.cpp @@ -803,17 +803,6 @@ TEST(trajectory, convertToTrajectory) const auto traj = convertToTrajectory(traj_input); EXPECT_EQ(traj.points.size(), traj_input.size()); } - - // Clipping check - { - const auto traj_input = generateTestTrajectoryPointArray(10000, 1.0); - const auto traj = convertToTrajectory(traj_input); - EXPECT_EQ(traj.points.size(), traj.CAPACITY); - // Value check - for (size_t i = 0; i < traj.points.size(); ++i) { - EXPECT_EQ(traj.points.at(i), traj_input.at(i)); - } - } } TEST(trajectory, convertToTrajectoryPointArray) From a5e4b2924f01c713d8bf701b3f229db957687ef6 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Fri, 8 Dec 2023 15:18:53 +0900 Subject: [PATCH 025/276] fix: add missing param on perception launch: (#5812) detection_by_tracker_param_path was missing Signed-off-by: Taekjin LEE --- .../launch/object_recognition/detection/detection.launch.xml | 2 ++ launch/tier4_perception_launch/launch/perception.launch.xml | 1 + 2 files changed, 3 insertions(+) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml index 0d03e3c8cdcd9..0649d8c5d5116 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -104,6 +104,7 @@ + @@ -132,6 +133,7 @@ + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index da393b1efff59..7f5f9d61c4bf0 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -178,6 +178,7 @@ + From 28346444fbe2b413dbeb54391a0db405600131ba Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 8 Dec 2023 17:18:51 +0900 Subject: [PATCH 026/276] refactor(lane_change): move lane change param (#5807) * refactor(lane_change): move lane change params Signed-off-by: satoshi-ota * fix(avoidance): remove unnecessary param path Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- ...t_behavior_path_planner_node_interface.cpp | 2 - .../lane_change/lane_change_module_data.hpp | 53 ++++++++++ .../utils/lane_change/utils.hpp | 15 ++- .../src/behavior_path_planner_node.cpp | 37 ------- .../scene_module/lane_change/interface.cpp | 7 +- .../src/scene_module/lane_change/manager.cpp | 43 +++++++++ .../src/scene_module/lane_change/normal.cpp | 96 +++++++++---------- .../src/utils/lane_change/utils.cpp | 65 +++++++++---- .../test/test_lane_change_utils.cpp | 3 +- .../parameters.hpp | 51 ---------- .../utils/utils.hpp | 4 - .../src/utils/utils.cpp | 25 ----- 12 files changed, 205 insertions(+), 196 deletions(-) diff --git a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 83514127b0a8e..58bf36d978cea 100644 --- a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -62,8 +62,6 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - ament_index_cpp::get_package_share_directory("behavior_path_planner") + - "/config/lane_change/lane_change.param.yaml", ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + "/config/avoidance.param.yaml"}); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp index 6f34bc79fe5f1..debeef5ec573f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp @@ -17,12 +17,55 @@ #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" +#include + #include +#include #include namespace behavior_path_planner { +struct LateralAccelerationMap +{ + std::vector base_vel; + std::vector base_min_acc; + std::vector base_max_acc; + + void add(const double velocity, const double min_acc, const double max_acc) + { + if (base_vel.size() != base_min_acc.size() || base_vel.size() != base_max_acc.size()) { + return; + } + + size_t idx = 0; + for (size_t i = 0; i < base_vel.size(); ++i) { + if (velocity < base_vel.at(i)) { + break; + } + idx = i + 1; + } + + base_vel.insert(base_vel.begin() + idx, velocity); + base_min_acc.insert(base_min_acc.begin() + idx, min_acc); + base_max_acc.insert(base_max_acc.begin() + idx, max_acc); + } + + std::pair find(const double velocity) const + { + if (!base_vel.empty() && velocity < base_vel.front()) { + return std::make_pair(base_min_acc.front(), base_max_acc.front()); + } + if (!base_vel.empty() && velocity > base_vel.back()) { + return std::make_pair(base_min_acc.back(), base_max_acc.back()); + } + + const double min_acc = interpolation::lerp(base_vel, base_min_acc, velocity); + const double max_acc = interpolation::lerp(base_vel, base_max_acc, velocity); + + return std::make_pair(min_acc, max_acc); + } +}; struct LaneChangeCancelParameters { @@ -33,6 +76,7 @@ struct LaneChangeCancelParameters double max_lateral_jerk{10.0}; double overhang_tolerance{0.0}; }; + struct LaneChangeParameters { // trajectory generation @@ -41,6 +85,15 @@ struct LaneChangeParameters int longitudinal_acc_sampling_num{10}; int lateral_acc_sampling_num{10}; + // lane change parameters + double backward_length_buffer_for_end_of_lane; + double backward_length_buffer_for_blocking_object; + double lane_changing_lateral_jerk{0.5}; + double minimum_lane_changing_velocity{5.6}; + double lane_change_prepare_duration{4.0}; + double lane_change_finish_judge_buffer{3.0}; + LateralAccelerationMap lane_change_lat_acc_map; + // parked vehicle double object_check_min_road_shoulder_width{0.5}; double object_shiftable_ratio_threshold{0.6}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp index 12e6da00b2f36..f99ed043eb5dd 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp @@ -54,17 +54,21 @@ using tier4_autoware_utils::Polygon2d; double calcLaneChangeResampleInterval( const double lane_changing_length, const double lane_changing_velocity); +double calcMinimumLaneChangeLength( + const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals, + const double length_to_intersection = 0.0); + double calcMaximumLaneChangeLength( - const double current_velocity, const BehaviorPathPlannerParameters & common_param, + const double current_velocity, const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals, const double max_acc); double calcMinimumAcceleration( const double current_velocity, const double min_longitudinal_acc, - const BehaviorPathPlannerParameters & params); + const LaneChangeParameters & lane_change_parameters); double calcMaximumAcceleration( const double current_velocity, const double current_max_velocity, - const double max_longitudinal_acc, const BehaviorPathPlannerParameters & params); + const double max_longitudinal_acc, const LaneChangeParameters & lane_change_parameters); double calcLaneChangingAcceleration( const double initial_lane_changing_velocity, const double max_path_velocity, @@ -130,7 +134,7 @@ double getLateralShift(const LaneChangePath & path); bool hasEnoughLengthToLaneChangeAfterAbort( const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const Pose & curent_pose, const double abort_return_dist, - const BehaviorPathPlannerParameters & common_param, const Direction direction); + const LaneChangeParameters & lane_change_parameters, const Direction direction); lanelet::ConstLanelets getBackwardLanelets( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, @@ -150,7 +154,8 @@ std::optional getLaneChangeTargetLane( std::vector convertToPredictedPath( const LaneChangePath & lane_change_path, const Twist & vehicle_twist, const Pose & pose, - const BehaviorPathPlannerParameters & common_parameters, const double resolution); + const BehaviorPathPlannerParameters & common_parameters, + const LaneChangeParameters & lane_change_parameters, const double resolution); bool isParkedObject( const PathWithLaneId & path, const RouteHandler & route_handler, diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 907c5226c3908..46057031afd8a 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -238,39 +238,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.min_acc = declare_parameter("normal.min_acc"); p.max_acc = declare_parameter("normal.max_acc"); - // lane change parameters - p.backward_length_buffer_for_end_of_lane = - declare_parameter("lane_change.backward_length_buffer_for_end_of_lane"); - p.backward_length_buffer_for_blocking_object = - declare_parameter("lane_change.backward_length_buffer_for_blocking_object"); - p.lane_changing_lateral_jerk = - declare_parameter("lane_change.lane_changing_lateral_jerk"); - p.lane_change_prepare_duration = declare_parameter("lane_change.prepare_duration"); - p.minimum_lane_changing_velocity = - declare_parameter("lane_change.minimum_lane_changing_velocity"); - p.minimum_lane_changing_velocity = - std::min(p.minimum_lane_changing_velocity, p.max_acc * p.lane_change_prepare_duration); - p.lane_change_finish_judge_buffer = - declare_parameter("lane_change.lane_change_finish_judge_buffer"); - - // lateral acceleration map for lane change - const auto lateral_acc_velocity = - declare_parameter>("lane_change.lateral_acceleration.velocity"); - const auto min_lateral_acc = - declare_parameter>("lane_change.lateral_acceleration.min_values"); - const auto max_lateral_acc = - declare_parameter>("lane_change.lateral_acceleration.max_values"); - if ( - lateral_acc_velocity.size() != min_lateral_acc.size() || - lateral_acc_velocity.size() != max_lateral_acc.size()) { - RCLCPP_ERROR(get_logger(), "Lane change lateral acceleration map has invalid size."); - exit(EXIT_FAILURE); - } - for (size_t i = 0; i < lateral_acc_velocity.size(); ++i) { - p.lane_change_lat_acc_map.add( - lateral_acc_velocity.at(i), min_lateral_acc.at(i), max_lateral_acc.at(i)); - } - 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 = @@ -297,10 +264,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.ego_nearest_dist_threshold = declare_parameter("ego_nearest_dist_threshold"); p.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); - if (p.backward_length_buffer_for_end_of_lane < 1.0) { - RCLCPP_WARN_STREAM( - get_logger(), "Lane change buffer must be more than 1 meter. Modifying the buffer."); - } return p; } diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index cec9d5013d929..101dd43919361 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -148,8 +148,7 @@ ModuleStatus LaneChangeInterface::updateState() return ModuleStatus::RUNNING; } - const auto & common_parameters = module_type_->getCommonParam(); - const auto threshold = common_parameters.backward_length_buffer_for_end_of_lane; + const auto threshold = module_type_->getLaneChangeParam().backward_length_buffer_for_end_of_lane; const auto status = module_type_->getLaneChangeStatus(); if (module_type_->isNearEndOfCurrentLanes(status.current_lanes, status.target_lanes, threshold)) { log_warn_throttled("Lane change path is unsafe but near end of lane. Continue lane change."); @@ -432,8 +431,8 @@ TurnSignalInfo LaneChangeInterface::getCurrentTurnSignalInfo( const auto & common_parameter = module_type_->getCommonParam(); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const double next_lane_change_buffer = utils::calcMinimumLaneChangeLength( - common_parameter, shift_intervals, common_parameter.backward_length_buffer_for_end_of_lane); + const double next_lane_change_buffer = + utils::lane_change::calcMinimumLaneChangeLength(lane_change_param, shift_intervals); const double & nearest_dist_threshold = common_parameter.ego_nearest_dist_threshold; const double & nearest_yaw_threshold = common_parameter.ego_nearest_yaw_threshold; const double & base_to_front = common_parameter.base_link2front; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp index ed40476723dba..658ffb06c25fe 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -141,6 +141,49 @@ void LaneChangeModuleManager::init(rclcpp::Node * node) p.rss_params_for_stuck.lateral_distance_max_threshold = getOrDeclareParameter( *node, parameter("safety_check.stuck.lateral_distance_max_threshold")); + // lane change parameters + const auto max_acc = getOrDeclareParameter(*node, "normal.max_acc"); + p.backward_length_buffer_for_end_of_lane = + getOrDeclareParameter(*node, parameter("backward_length_buffer_for_end_of_lane")); + p.backward_length_buffer_for_blocking_object = + getOrDeclareParameter(*node, parameter("backward_length_buffer_for_blocking_object")); + p.lane_changing_lateral_jerk = + getOrDeclareParameter(*node, parameter("lane_changing_lateral_jerk")); + p.lane_change_prepare_duration = + getOrDeclareParameter(*node, parameter("prepare_duration")); + p.minimum_lane_changing_velocity = + getOrDeclareParameter(*node, parameter("minimum_lane_changing_velocity")); + p.minimum_lane_changing_velocity = + std::min(p.minimum_lane_changing_velocity, max_acc * p.lane_change_prepare_duration); + p.lane_change_finish_judge_buffer = + getOrDeclareParameter(*node, parameter("lane_change_finish_judge_buffer")); + + if (p.backward_length_buffer_for_end_of_lane < 1.0) { + RCLCPP_WARN_STREAM( + node->get_logger().get_child(name()), + "Lane change buffer must be more than 1 meter. Modifying the buffer."); + } + + // lateral acceleration map for lane change + const auto lateral_acc_velocity = + getOrDeclareParameter>(*node, parameter("lateral_acceleration.velocity")); + const auto min_lateral_acc = + getOrDeclareParameter>(*node, parameter("lateral_acceleration.min_values")); + const auto max_lateral_acc = + getOrDeclareParameter>(*node, parameter("lateral_acceleration.max_values")); + if ( + lateral_acc_velocity.size() != min_lateral_acc.size() || + lateral_acc_velocity.size() != max_lateral_acc.size()) { + RCLCPP_ERROR( + node->get_logger().get_child(name()), + "Lane change lateral acceleration map has invalid size."); + exit(EXIT_FAILURE); + } + for (size_t i = 0; i < lateral_acc_velocity.size(); ++i) { + p.lane_change_lat_acc_map.add( + lateral_acc_velocity.at(i), min_lateral_acc.at(i), max_lateral_acc.at(i)); + } + // target object { const std::string ns = "lane_change.target_object."; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 423ffc48dd6cd..ebb41ae63dcbe 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -215,9 +215,8 @@ void NormalLaneChange::insertStopPoint( } const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(lanelets.back()); - const double lane_change_buffer = utils::calcMinimumLaneChangeLength( - getCommonParam(), shift_intervals, getCommonParam().backward_length_buffer_for_end_of_lane, - 0.0); + const double lane_change_buffer = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals, 0.0); const auto getDistanceAlongLanelet = [&](const geometry_msgs::msg::Pose & target) { return utils::getSignedDistance(path.points.front().point.pose, target, lanelets); @@ -233,7 +232,7 @@ void NormalLaneChange::insertStopPoint( distance_to_terminal = utils::getDistanceToEndOfLane(path.points.front().point.pose, lanelets); } - const double stop_point_buffer = getCommonParam().backward_length_buffer_for_end_of_lane; + const double stop_point_buffer = lane_change_parameters_->backward_length_buffer_for_end_of_lane; const auto target_objects = getTargetObjects(status_.current_lanes, status_.target_lanes); double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer; @@ -294,15 +293,14 @@ void NormalLaneChange::insertStopPoint( if (distance_to_ego_lane_obj < distance_to_terminal) { // consider rss distance when the LC need to avoid obstacles const auto rss_dist = calcRssDistance( - 0.0, planner_data_->parameters.minimum_lane_changing_velocity, + 0.0, lane_change_parameters_->minimum_lane_changing_velocity, lane_change_parameters_->rss_params); - const double lane_change_buffer_for_blocking_object = utils::calcMinimumLaneChangeLength( - getCommonParam(), shift_intervals, - getCommonParam().backward_length_buffer_for_blocking_object, 0.0); + const double lane_change_buffer_for_blocking_object = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); const auto stopping_distance_for_obj = distance_to_ego_lane_obj - lane_change_buffer_for_blocking_object - - getCommonParam().backward_length_buffer_for_blocking_object - rss_dist - + lane_change_parameters_->backward_length_buffer_for_blocking_object - rss_dist - getCommonParam().base_link2front; // If the target lane in the lane change section is blocked by a stationary obstacle, there @@ -498,9 +496,8 @@ bool NormalLaneChange::isNearEndOfCurrentLanes( const auto & current_pose = getEgoPose(); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const auto lane_change_buffer = utils::calcMinimumLaneChangeLength( - planner_data_->parameters, shift_intervals, - getCommonParam().backward_length_buffer_for_end_of_lane); + const auto lane_change_buffer = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); auto distance_to_end = utils::getDistanceToEndOfLane(current_pose, current_lanes); @@ -519,7 +516,7 @@ bool NormalLaneChange::hasFinishedLaneChange() const const auto & lane_change_end = status_.lane_change_path.info.shift_line.end; const double dist_to_lane_change_end = utils::getSignedDistance( current_pose, lane_change_end, status_.lane_change_path.info.target_lanes); - double finish_judge_buffer = planner_data_->parameters.lane_change_finish_judge_buffer; + double finish_judge_buffer = lane_change_parameters_->lane_change_finish_judge_buffer; // If ego velocity is low, relax finish judge buffer const double ego_velocity = getEgoVelocity(); @@ -560,7 +557,7 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const planner_data_->parameters.ego_nearest_yaw_threshold); const double ego_velocity = - std::max(getEgoVelocity(), planner_data_->parameters.minimum_lane_changing_velocity); + std::max(getEgoVelocity(), lane_change_parameters_->minimum_lane_changing_velocity); const double estimated_travel_dist = ego_velocity * lane_change_parameters_->cancel.delta_time; double dist = 0.0; @@ -664,10 +661,10 @@ std::pair NormalLaneChange::calcCurrentMinMaxAcceleration() cons prev_module_path_.points.at(ego_seg_idx).point.longitudinal_velocity_mps; // calculate minimum and maximum acceleration - const auto min_acc = - utils::lane_change::calcMinimumAcceleration(getEgoVelocity(), vehicle_min_acc, p); + const auto min_acc = utils::lane_change::calcMinimumAcceleration( + getEgoVelocity(), vehicle_min_acc, *lane_change_parameters_); const auto max_acc = utils::lane_change::calcMaximumAcceleration( - getEgoVelocity(), max_path_velocity, vehicle_max_acc, p); + getEgoVelocity(), max_path_velocity, vehicle_max_acc, *lane_change_parameters_); return {min_acc, max_acc}; } @@ -678,8 +675,8 @@ double NormalLaneChange::calcMaximumLaneChangeLength( const auto shift_intervals = getRouteHandler()->getLateralIntervalsToPreferredLane(current_terminal_lanelet); return utils::lane_change::calcMaximumLaneChangeLength( - std::max(getCommonParam().minimum_lane_changing_velocity, getEgoVelocity()), getCommonParam(), - shift_intervals, max_acc); + std::max(lane_change_parameters_->minimum_lane_changing_velocity, getEgoVelocity()), + *lane_change_parameters_, shift_intervals, max_acc); } std::vector NormalLaneChange::sampleLongitudinalAccValues( @@ -746,7 +743,6 @@ std::vector NormalLaneChange::sampleLongitudinalAccValues( std::vector NormalLaneChange::calcPrepareDuration( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const { - const auto & common_parameters = planner_data_->parameters; const auto base_link2front = planner_data_->parameters.base_link2front; const auto threshold = lane_change_parameters_->min_length_for_turn_signal_activation + base_link2front; @@ -754,7 +750,7 @@ std::vector NormalLaneChange::calcPrepareDuration( std::vector prepare_durations; constexpr double step = 0.5; - for (double duration = common_parameters.lane_change_prepare_duration; duration >= 0.0; + for (double duration = lane_change_parameters_->lane_change_prepare_duration; duration >= 0.0; duration -= step) { prepare_durations.push_back(duration); if (!isNearEndOfCurrentLanes(current_lanes, target_lanes, threshold)) { @@ -1024,12 +1020,11 @@ bool NormalLaneChange::hasEnoughLength( const auto current_pose = getEgoPose(); const auto & route_handler = *getRouteHandler(); const auto overall_graphs_ptr = route_handler.getOverallGraphPtr(); - const auto & common_parameters = planner_data_->parameters; const double lane_change_length = path.info.length.sum(); const auto shift_intervals = route_handler.getLateralIntervalsToPreferredLane(target_lanes.back(), direction); - double minimum_lane_change_length_to_preferred_lane = utils::calcMinimumLaneChangeLength( - common_parameters, shift_intervals, common_parameters.backward_length_buffer_for_end_of_lane); + double minimum_lane_change_length_to_preferred_lane = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); if (lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) { return false; @@ -1125,7 +1120,8 @@ bool NormalLaneChange::getLaneChangePaths( const auto backward_path_length = common_parameters.backward_path_length; const auto forward_path_length = common_parameters.forward_path_length; - const auto minimum_lane_changing_velocity = common_parameters.minimum_lane_changing_velocity; + const auto minimum_lane_changing_velocity = + lane_change_parameters_->minimum_lane_changing_velocity; const auto lateral_acc_sampling_num = lane_change_parameters_->lateral_acc_sampling_num; // get velocity @@ -1137,12 +1133,12 @@ bool NormalLaneChange::getLaneChangePaths( const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanes.back()); - const double lane_change_buffer = utils::calcMinimumLaneChangeLength( - common_parameters, route_handler.getLateralIntervalsToPreferredLane(current_lanes.back()), - common_parameters.backward_length_buffer_for_end_of_lane); - const double next_lane_change_buffer = utils::calcMinimumLaneChangeLength( - common_parameters, route_handler.getLateralIntervalsToPreferredLane(target_lanes.back()), - common_parameters.backward_length_buffer_for_end_of_lane); + const double lane_change_buffer = utils::lane_change::calcMinimumLaneChangeLength( + *lane_change_parameters_, + route_handler.getLateralIntervalsToPreferredLane(current_lanes.back())); + const double next_lane_change_buffer = utils::lane_change::calcMinimumLaneChangeLength( + *lane_change_parameters_, + route_handler.getLateralIntervalsToPreferredLane(target_lanes.back())); const auto dist_to_end_of_current_lanes = utils::getDistanceToEndOfLane(getEgoPose(), current_lanes); @@ -1219,7 +1215,7 @@ bool NormalLaneChange::getLaneChangePaths( // get lateral acceleration range const auto [min_lateral_acc, max_lateral_acc] = - common_parameters.lane_change_lat_acc_map.find(initial_lane_changing_velocity); + lane_change_parameters_->lane_change_lat_acc_map.find(initial_lane_changing_velocity); const auto lateral_acc_resolution = std::abs(max_lateral_acc - min_lateral_acc) / lateral_acc_sampling_num; @@ -1238,7 +1234,7 @@ bool NormalLaneChange::getLaneChangePaths( }; const auto lane_changing_time = PathShifter::calcShiftTimeFromJerk( - shift_length, common_parameters.lane_changing_lateral_jerk, lateral_acc); + shift_length, lane_change_parameters_->lane_changing_lateral_jerk, lateral_acc); const double longitudinal_acc_on_lane_changing = utils::lane_change::calcLaneChangingAcceleration( initial_lane_changing_velocity, max_path_velocity, lane_changing_time, @@ -1264,8 +1260,9 @@ bool NormalLaneChange::getLaneChangePaths( const auto num = std::abs(route_handler.getNumLaneToPreferredLane(target_lanes.back(), direction)); const double backward_buffer = - num == 0 ? 0.0 : common_parameters.backward_length_buffer_for_end_of_lane; - const double finish_judge_buffer = common_parameters.lane_change_finish_judge_buffer; + num == 0 ? 0.0 : lane_change_parameters_->backward_length_buffer_for_end_of_lane; + const double finish_judge_buffer = + lane_change_parameters_->lane_change_finish_judge_buffer; if ( s_start + lane_changing_length + finish_judge_buffer + backward_buffer + next_lane_change_buffer > @@ -1536,7 +1533,7 @@ bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const bool NormalLaneChange::isRequiredStop(const bool is_object_coming_from_rear) const { - const auto threshold = planner_data_->parameters.backward_length_buffer_for_end_of_lane; + const auto threshold = lane_change_parameters_->backward_length_buffer_for_end_of_lane; return isNearEndOfCurrentLanes(status_.current_lanes, status_.target_lanes, threshold) && isAbleToStopSafely() && is_object_coming_from_rear; } @@ -1546,7 +1543,7 @@ bool NormalLaneChange::calcAbortPath() const auto & route_handler = getRouteHandler(); const auto & common_param = getCommonParam(); const auto current_velocity = - std::max(common_param.minimum_lane_changing_velocity, getEgoVelocity()); + std::max(lane_change_parameters_->minimum_lane_changing_velocity, getEgoVelocity()); const auto current_pose = getEgoPose(); const auto & selected_path = status_.lane_change_path; const auto reference_lanelets = selected_path.info.current_lanes; @@ -1557,8 +1554,8 @@ bool NormalLaneChange::calcAbortPath() const auto direction = getDirection(); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane( selected_path.info.current_lanes.back(), direction); - const double minimum_lane_change_length = utils::calcMinimumLaneChangeLength( - common_param, shift_intervals, common_param.backward_length_buffer_for_end_of_lane); + const double minimum_lane_change_length = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); const auto & lane_changing_path = selected_path.path; const auto lane_changing_end_pose_idx = std::invoke([&]() { @@ -1605,8 +1602,8 @@ bool NormalLaneChange::calcAbortPath() } if (!utils::lane_change::hasEnoughLengthToLaneChangeAfterAbort( - *route_handler, reference_lanelets, current_pose, abort_return_dist, common_param, - direction)) { + *route_handler, reference_lanelets, current_pose, abort_return_dist, + *lane_change_parameters_, direction)) { RCLCPP_ERROR(logger_, "insufficient distance to abort."); return false; } @@ -1629,7 +1626,8 @@ bool NormalLaneChange::calcAbortPath() const auto lateral_jerk = behavior_path_planner::PathShifter::calcJerkFromLatLonDistance( shift_line.end_shift_length, abort_start_dist, current_velocity); path_shifter.setVelocity(current_velocity); - const auto lateral_acc_range = common_param.lane_change_lat_acc_map.find(current_velocity); + const auto lateral_acc_range = + lane_change_parameters_->lane_change_lat_acc_map.find(current_velocity); const double & max_lateral_acc = lateral_acc_range.second; path_shifter.setLateralAccelerationLimit(max_lateral_acc); @@ -1662,7 +1660,7 @@ bool NormalLaneChange::calcAbortPath() PathWithLaneId ref = route_handler->getCenterLinePath(reference_lanelets, s_start, s_end, true); ref.points.back().point.longitudinal_velocity_mps = std::min( ref.points.back().point.longitudinal_velocity_mps, - static_cast(common_param.minimum_lane_changing_velocity)); + static_cast(lane_change_parameters_->minimum_lane_changing_velocity)); return ref; }); @@ -1707,7 +1705,8 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( const double & time_resolution = lane_change_parameters_->prediction_time_resolution; const auto ego_predicted_path = utils::lane_change::convertToPredictedPath( - lane_change_path, current_twist, current_pose, common_parameters, time_resolution); + lane_change_path, current_twist, current_pose, common_parameters, *lane_change_parameters_, + time_resolution); const auto debug_predicted_path = utils::path_safety_checker::convertToPredictedPath(ego_predicted_path, time_resolution); @@ -1818,10 +1817,9 @@ bool NormalLaneChange::isVehicleStuck( : utils::getDistanceToEndOfLane(getEgoPose(), current_lanes); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const double lane_change_buffer = utils::calcMinimumLaneChangeLength( - getCommonParam(), shift_intervals, getCommonParam().backward_length_buffer_for_end_of_lane, - 0.0); - const double stop_point_buffer = getCommonParam().backward_length_buffer_for_end_of_lane; + const double lane_change_buffer = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals, 0.0); + const double stop_point_buffer = lane_change_parameters_->backward_length_buffer_for_end_of_lane; const double terminal_judge_buffer = lane_change_buffer + stop_point_buffer + 1.0; if (distance_to_terminal < terminal_judge_buffer) { return true; @@ -1844,7 +1842,7 @@ bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lan const auto [min_acc, max_acc] = calcCurrentMinMaxAcceleration(); const auto max_lane_change_length = calcMaximumLaneChangeLength(current_lanes.back(), max_acc); const auto rss_dist = calcRssDistance( - 0.0, planner_data_->parameters.minimum_lane_changing_velocity, + 0.0, lane_change_parameters_->minimum_lane_changing_velocity, lane_change_parameters_->rss_params); // It is difficult to define the detection range. If it is too short, the stuck will not be diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp index 66182454ecf85..8ba820231d7cc 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -67,17 +67,43 @@ double calcLaneChangeResampleInterval( lane_changing_length / min_resampling_points, lane_changing_velocity * resampling_dt); } +double calcMinimumLaneChangeLength( + const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals, + const double length_to_intersection) +{ + if (shift_intervals.empty()) { + return 0.0; + } + + const double & vel = lane_change_parameters.minimum_lane_changing_velocity; + const auto lat_acc = lane_change_parameters.lane_change_lat_acc_map.find(vel); + const double & max_lateral_acc = lat_acc.second; + const double & lateral_jerk = lane_change_parameters.lane_changing_lateral_jerk; + const double & finish_judge_buffer = lane_change_parameters.lane_change_finish_judge_buffer; + const double & backward_buffer = lane_change_parameters.backward_length_buffer_for_end_of_lane; + + double accumulated_length = length_to_intersection; + for (const auto & shift_interval : shift_intervals) { + const double t = + PathShifter::calcShiftTimeFromJerk(shift_interval, lateral_jerk, max_lateral_acc); + accumulated_length += vel * t + finish_judge_buffer; + } + accumulated_length += backward_buffer * (shift_intervals.size() - 1.0); + + return accumulated_length; +} + double calcMaximumLaneChangeLength( - const double current_velocity, const BehaviorPathPlannerParameters & common_param, + const double current_velocity, const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals, const double max_acc) { if (shift_intervals.empty()) { return 0.0; } - const double & finish_judge_buffer = common_param.lane_change_finish_judge_buffer; - const double & lateral_jerk = common_param.lane_changing_lateral_jerk; - const double & t_prepare = common_param.lane_change_prepare_duration; + const double & finish_judge_buffer = lane_change_parameters.lane_change_finish_judge_buffer; + const double & lateral_jerk = lane_change_parameters.lane_changing_lateral_jerk; + const double & t_prepare = lane_change_parameters.lane_change_prepare_duration; double vel = current_velocity; double accumulated_length = 0.0; @@ -87,7 +113,7 @@ double calcMaximumLaneChangeLength( vel = vel + max_acc * t_prepare; // lane changing section - const auto lat_acc = common_param.lane_change_lat_acc_map.find(vel); + const auto lat_acc = lane_change_parameters.lane_change_lat_acc_map.find(vel); const double t_lane_changing = PathShifter::calcShiftTimeFromJerk(shift_interval, lateral_jerk, lat_acc.second); const double lane_changing_length = @@ -97,26 +123,26 @@ double calcMaximumLaneChangeLength( vel = vel + max_acc * t_lane_changing; } accumulated_length += - common_param.backward_length_buffer_for_end_of_lane * (shift_intervals.size() - 1.0); + lane_change_parameters.backward_length_buffer_for_end_of_lane * (shift_intervals.size() - 1.0); return accumulated_length; } double calcMinimumAcceleration( const double current_velocity, const double min_longitudinal_acc, - const BehaviorPathPlannerParameters & params) + const LaneChangeParameters & lane_change_parameters) { - const double min_lane_changing_velocity = params.minimum_lane_changing_velocity; - const double prepare_duration = params.lane_change_prepare_duration; + const double min_lane_changing_velocity = lane_change_parameters.minimum_lane_changing_velocity; + const double prepare_duration = lane_change_parameters.lane_change_prepare_duration; const double acc = (min_lane_changing_velocity - current_velocity) / prepare_duration; return std::clamp(acc, -std::abs(min_longitudinal_acc), -std::numeric_limits::epsilon()); } double calcMaximumAcceleration( const double current_velocity, const double current_max_velocity, - const double max_longitudinal_acc, const BehaviorPathPlannerParameters & params) + const double max_longitudinal_acc, const LaneChangeParameters & lane_change_parameters) { - const double prepare_duration = params.lane_change_prepare_duration; + const double prepare_duration = lane_change_parameters.lane_change_prepare_duration; const double acc = (current_max_velocity - current_velocity) / prepare_duration; return std::clamp(acc, 0.0, max_longitudinal_acc); } @@ -601,12 +627,12 @@ double getLateralShift(const LaneChangePath & path) bool hasEnoughLengthToLaneChangeAfterAbort( const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const Pose & current_pose, const double abort_return_dist, - const BehaviorPathPlannerParameters & common_param, const Direction direction) + const LaneChangeParameters & lane_change_parameters, const Direction direction) { const auto shift_intervals = route_handler.getLateralIntervalsToPreferredLane(current_lanes.back(), direction); - const double minimum_lane_change_length = utils::calcMinimumLaneChangeLength( - common_param, shift_intervals, common_param.backward_length_buffer_for_end_of_lane); + const double minimum_lane_change_length = + calcMinimumLaneChangeLength(lane_change_parameters, shift_intervals); const auto abort_plus_lane_change_length = abort_return_dist + minimum_lane_change_length; if (abort_plus_lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) { return false; @@ -765,7 +791,8 @@ std::optional getLaneChangeTargetLane( std::vector convertToPredictedPath( const LaneChangePath & lane_change_path, const Twist & vehicle_twist, const Pose & vehicle_pose, - const BehaviorPathPlannerParameters & common_parameters, const double resolution) + const BehaviorPathPlannerParameters & common_parameters, + const LaneChangeParameters & lane_change_parameters, const double resolution) { if (lane_change_path.path.points.empty()) { return {}; @@ -776,7 +803,8 @@ std::vector convertToPredictedPath( const auto lane_changing_acc = lane_change_path.info.longitudinal_acceleration.lane_changing; const auto duration = lane_change_path.info.duration.sum(); const auto prepare_time = lane_change_path.info.duration.prepare; - const auto & minimum_lane_changing_velocity = common_parameters.minimum_lane_changing_velocity; + const auto & minimum_lane_changing_velocity = + lane_change_parameters.minimum_lane_changing_velocity; const auto nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, vehicle_pose, common_parameters.ego_nearest_dist_threshold, @@ -1065,7 +1093,8 @@ std::optional createPolygon( } ExtendedPredictedObject transform( - const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters, + const PredictedObject & object, + [[maybe_unused]] const BehaviorPathPlannerParameters & common_parameters, const LaneChangeParameters & lane_change_parameters) { ExtendedPredictedObject extended_object; @@ -1078,7 +1107,7 @@ ExtendedPredictedObject transform( const auto & time_resolution = lane_change_parameters.prediction_time_resolution; const auto & check_at_prepare_phase = lane_change_parameters.enable_prepare_segment_collision_check; - const auto & prepare_duration = common_parameters.lane_change_prepare_duration; + const auto & prepare_duration = lane_change_parameters.lane_change_prepare_duration; const auto & velocity_threshold = lane_change_parameters.prepare_segment_ignore_object_velocity_thresh; const auto start_time = check_at_prepare_phase ? 0.0 : prepare_duration; diff --git a/planning/behavior_path_planner/test/test_lane_change_utils.cpp b/planning/behavior_path_planner/test/test_lane_change_utils.cpp index 3268bd7ec468e..477af32893b0b 100644 --- a/planning/behavior_path_planner/test/test_lane_change_utils.cpp +++ b/planning/behavior_path_planner/test/test_lane_change_utils.cpp @@ -11,6 +11,7 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. +#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" #include @@ -41,7 +42,7 @@ TEST(BehaviorPathPlanningLaneChangeUtilsTest, projectCurrentPoseToTarget) TEST(BehaviorPathPlanningLaneChangeUtilsTest, TESTLateralAccelerationMap) { - LateralAccelerationMap lat_acc_map; + behavior_path_planner::LateralAccelerationMap lat_acc_map; lat_acc_map.add(0.0, 0.2, 0.315); lat_acc_map.add(3.0, 0.2, 0.315); lat_acc_map.add(5.0, 0.2, 0.315); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp index 7832dd4e53cfc..5bdd0a2f3f88d 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp @@ -15,7 +15,6 @@ #ifndef BEHAVIOR_PATH_PLANNER_COMMON__PARAMETERS_HPP_ #define BEHAVIOR_PATH_PLANNER_COMMON__PARAMETERS_HPP_ -#include #include #include @@ -32,47 +31,6 @@ struct ModuleConfigParameters uint8_t max_module_size{0}; }; -struct LateralAccelerationMap -{ - std::vector base_vel; - std::vector base_min_acc; - std::vector base_max_acc; - - void add(const double velocity, const double min_acc, const double max_acc) - { - if (base_vel.size() != base_min_acc.size() || base_vel.size() != base_max_acc.size()) { - return; - } - - size_t idx = 0; - for (size_t i = 0; i < base_vel.size(); ++i) { - if (velocity < base_vel.at(i)) { - break; - } - idx = i + 1; - } - - base_vel.insert(base_vel.begin() + idx, velocity); - base_min_acc.insert(base_min_acc.begin() + idx, min_acc); - base_max_acc.insert(base_max_acc.begin() + idx, max_acc); - } - - std::pair find(const double velocity) const - { - if (!base_vel.empty() && velocity < base_vel.front()) { - return std::make_pair(base_min_acc.front(), base_max_acc.front()); - } - if (!base_vel.empty() && velocity > base_vel.back()) { - return std::make_pair(base_min_acc.back(), base_max_acc.back()); - } - - const double min_acc = interpolation::lerp(base_vel, base_min_acc, velocity); - const double max_acc = interpolation::lerp(base_vel, base_max_acc, velocity); - - return std::make_pair(min_acc, max_acc); - } -}; - struct BehaviorPathPlannerParameters { bool verbose; @@ -81,8 +39,6 @@ struct BehaviorPathPlannerParameters double backward_path_length; double forward_path_length; - double backward_length_buffer_for_end_of_lane; - double backward_length_buffer_for_blocking_object; double backward_length_buffer_for_end_of_pull_over; double backward_length_buffer_for_end_of_pull_out; @@ -90,13 +46,6 @@ struct BehaviorPathPlannerParameters double min_acc; double max_acc; - // lane change parameters - double lane_changing_lateral_jerk{0.5}; - double minimum_lane_changing_velocity{5.6}; - double lane_change_prepare_duration{4.0}; - double lane_change_finish_judge_buffer{3.0}; - LateralAccelerationMap lane_change_lat_acc_map; - double minimum_pull_over_length; double minimum_pull_out_length; double drivable_area_resolution; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp index 3a7d346849e16..e2c9fd1e332a2 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp @@ -333,10 +333,6 @@ lanelet::ConstLanelets calcLaneAroundPose( bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_threshold); -double calcMinimumLaneChangeLength( - const BehaviorPathPlannerParameters & common_param, const std::vector & shift_intervals, - const double backward_buffer, const double length_to_intersection = 0.0); - lanelet::ConstLanelets getLaneletsFromPath( const PathWithLaneId & path, const std::shared_ptr & route_handler); diff --git a/planning/behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner_common/src/utils/utils.cpp index 88c7532b0ad72..7c3a5883989fb 100644 --- a/planning/behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/utils.cpp @@ -1515,31 +1515,6 @@ bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_thre return true; } -double calcMinimumLaneChangeLength( - const BehaviorPathPlannerParameters & common_param, const std::vector & shift_intervals, - const double backward_buffer, const double length_to_intersection) -{ - if (shift_intervals.empty()) { - return 0.0; - } - - const double & vel = common_param.minimum_lane_changing_velocity; - const auto lat_acc = common_param.lane_change_lat_acc_map.find(vel); - const double & max_lateral_acc = lat_acc.second; - const double & lateral_jerk = common_param.lane_changing_lateral_jerk; - const double & finish_judge_buffer = common_param.lane_change_finish_judge_buffer; - - double accumulated_length = length_to_intersection; - for (const auto & shift_interval : shift_intervals) { - const double t = - PathShifter::calcShiftTimeFromJerk(shift_interval, lateral_jerk, max_lateral_acc); - accumulated_length += vel * t + finish_judge_buffer; - } - accumulated_length += backward_buffer * (shift_intervals.size() - 1.0); - - return accumulated_length; -} - lanelet::ConstLanelets getLaneletsFromPath( const PathWithLaneId & path, const std::shared_ptr & route_handler) { From dfedb9c82dc9f2ce6f7380c7d2928c21de53fff7 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> Date: Fri, 8 Dec 2023 19:16:52 +0900 Subject: [PATCH 027/276] fix(ekf_localizer): correct the initialization of accumulated_delay_times to obtain accurate computation of delay_time (#5821) Correct accumulated_delay_times in ekf_localizer so that the delay_step is computed accurately. Signed-off-by: TaikiYamada4 --- localization/ekf_localizer/src/ekf_module.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp index 10926b04507a0..573472fe2dabf 100644 --- a/localization/ekf_localizer/src/ekf_module.cpp +++ b/localization/ekf_localizer/src/ekf_module.cpp @@ -167,10 +167,10 @@ void EKFModule::accumulate_delay_time(const double dt) accumulated_delay_times_.begin(), accumulated_delay_times_.end() - 1, accumulated_delay_times_.end()); - // Add the new delay time to all elements. + // Add a new element (=0) and, and add delay time to the previous elements. accumulated_delay_times_.front() = 0.0; - for (auto & delay_time : accumulated_delay_times_) { - delay_time += dt; + for (size_t i = 1; i < accumulated_delay_times_.size(); ++i) { + accumulated_delay_times_[i] += dt; } } From c9b91e4d7d3a6f1e4655c044c7cfb64f97150faa Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 8 Dec 2023 21:25:04 +0900 Subject: [PATCH 028/276] feat(system_diagnostic_graph): support config override and add tests (#5816) Signed-off-by: Takagi, Isamu --- system/system_diagnostic_graph/CMakeLists.txt | 11 +- .../config/default.param.yaml | 4 +- .../example/example_0.yaml | 6 +- .../src/core/config.cpp | 125 +++++++++++---- .../src/core/config.hpp | 19 +++ .../src/core/debug.cpp | 27 +++- .../src/core/debug.hpp | 2 +- .../src/core/error.hpp | 5 + .../src/core/graph.cpp | 36 +++-- .../src/core/graph.hpp | 7 +- .../src/core/modes.cpp | 6 +- .../src/core/units.cpp | 33 +++- .../src/core/units.hpp | 17 +++ system/system_diagnostic_graph/src/main.cpp | 13 +- system/system_diagnostic_graph/src/main.hpp | 2 + .../system_diagnostic_graph/src/tool/main.cpp | 140 +++++++++++++++++ .../files/{ => test1}/field-not-found.yaml | 0 .../files/{ => test1}/file-not-found.yaml | 0 .../files/{ => test1}/graph-circulation.yaml | 0 .../files/{ => test1}/invalid-dict-type.yaml | 0 .../files/{ => test1}/invalid-list-type.yaml | 0 .../test/files/{ => test1}/path-conflict.yaml | 0 .../files/{ => test1}/path-not-found.yaml | 0 .../files/{ => test1}/unknown-node-type.yaml | 0 .../{ => test1}/unknown-substitution.yaml | 0 .../test/files/test2/and.yaml | 10 ++ .../test/files/test2/or.yaml | 10 ++ .../test/files/test2/warn-to-error.yaml | 7 + .../test/files/test2/warn-to-ok.yaml | 7 + .../test/src/{test.cpp => test1.cpp} | 29 ++-- .../test/src/test2.cpp | 143 ++++++++++++++++++ .../test/src/utils.cpp | 20 +++ .../test/src/utils.hpp | 23 +++ 33 files changed, 605 insertions(+), 97 deletions(-) create mode 100644 system/system_diagnostic_graph/src/tool/main.cpp rename system/system_diagnostic_graph/test/files/{ => test1}/field-not-found.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/file-not-found.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/graph-circulation.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/invalid-dict-type.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/invalid-list-type.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/path-conflict.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/path-not-found.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/unknown-node-type.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/unknown-substitution.yaml (100%) create mode 100644 system/system_diagnostic_graph/test/files/test2/and.yaml create mode 100644 system/system_diagnostic_graph/test/files/test2/or.yaml create mode 100644 system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml create mode 100644 system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml rename system/system_diagnostic_graph/test/src/{test.cpp => test1.cpp} (57%) create mode 100644 system/system_diagnostic_graph/test/src/test2.cpp create mode 100644 system/system_diagnostic_graph/test/src/utils.cpp create mode 100644 system/system_diagnostic_graph/test/src/utils.hpp diff --git a/system/system_diagnostic_graph/CMakeLists.txt b/system/system_diagnostic_graph/CMakeLists.txt index 142aa94eeef69..be0fc19188a0b 100644 --- a/system/system_diagnostic_graph/CMakeLists.txt +++ b/system/system_diagnostic_graph/CMakeLists.txt @@ -20,9 +20,18 @@ ament_auto_add_executable(converter src/tool.cpp ) +ament_auto_add_executable(tool + src/tool/main.cpp +) +target_include_directories(tool PRIVATE src/core) + if(BUILD_TESTING) get_filename_component(RESOURCE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/test/files ABSOLUTE) - ament_auto_add_gtest(gtest_${PROJECT_NAME} test/src/test.cpp) + ament_auto_add_gtest(gtest_${PROJECT_NAME} + test/src/test1.cpp + test/src/test2.cpp + test/src/utils.cpp + ) target_compile_definitions(gtest_${PROJECT_NAME} PRIVATE TEST_RESOURCE_PATH="${RESOURCE_PATH}") target_include_directories(gtest_${PROJECT_NAME} PRIVATE src) endif() diff --git a/system/system_diagnostic_graph/config/default.param.yaml b/system/system_diagnostic_graph/config/default.param.yaml index 9fd572c7926fa..e91664c5b82d8 100644 --- a/system/system_diagnostic_graph/config/default.param.yaml +++ b/system/system_diagnostic_graph/config/default.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - mode_availability: true - mode: psim + use_operation_mode_availability: true + use_debug_mode: false rate: 1.0 input_qos_depth: 1000 graph_qos_depth: 1 diff --git a/system/system_diagnostic_graph/example/example_0.yaml b/system/system_diagnostic_graph/example/example_0.yaml index fc4436bba1595..ed92259b50721 100644 --- a/system/system_diagnostic_graph/example/example_0.yaml +++ b/system/system_diagnostic_graph/example/example_0.yaml @@ -22,15 +22,15 @@ nodes: list: - { type: link, link: /external/remote_command } - - path: /autoware/modes/emergency-stop + - path: /autoware/modes/emergency_stop type: ok - - path: /autoware/modes/comfortable-stop + - path: /autoware/modes/comfortable_stop type: and list: - { type: link, link: /functions/obstacle_detection } - - path: /autoware/modes/pull-over + - path: /autoware/modes/pull_over type: and list: - { type: link, link: /functions/pose_estimation } diff --git a/system/system_diagnostic_graph/src/core/config.cpp b/system/system_diagnostic_graph/src/core/config.cpp index 2339e96f3951f..4a32398a1b08f 100644 --- a/system/system_diagnostic_graph/src/core/config.cpp +++ b/system/system_diagnostic_graph/src/core/config.cpp @@ -22,6 +22,8 @@ #include #include #include +#include +#include #include #include @@ -66,15 +68,24 @@ ConfigData ConfigData::load(YAML::Node yaml) ConfigData ConfigData::type(const std::string & name) const { ConfigData data(file); - data.mark = name; + data.mark = mark.empty() ? name : mark + "-" + name; return data; } ConfigData ConfigData::node(const size_t index) const { - ConfigData data(file); - data.mark = mark + "-" + std::to_string(index); - return data; + return type(std::to_string(index)); +} + +std::optional ConfigData::take_yaml(const std::string & name) +{ + if (!object.count(name)) { + return std::nullopt; + } + + const auto yaml = object.at(name); + object.erase(name); + return yaml; } std::string ConfigData::take_text(const std::string & name) @@ -114,50 +125,82 @@ std::vector ConfigData::take_list(const std::string & name) return std::vector(yaml.begin(), yaml.end()); } -void check_config_nodes(const std::vector & nodes) +void resolve_link_nodes(RootConfig & root) { - std::unordered_map path_count; - for (const auto & node : nodes) { - path_count[node->path] += 1; + std::unordered_map paths; + for (const auto & node : root.nodes) { + if (node->path.empty()) { + continue; + } + if (paths.count(node->path)) { + throw error("object path is not unique", node->path); + } + paths[node->path] = node; } - path_count.erase(""); - for (const auto & [path, count] : path_count) { - if (1 < count) { - throw error("object path is not unique", path); + std::vector nodes; + std::vector links; + for (const auto & node : root.nodes) { + if (node->type == "link") { + links.push_back(node); + } else { + nodes.push_back(node); } } + + std::unordered_map targets; + for (const auto & node : nodes) { + targets[node] = node; + } + for (const auto & node : links) { + const auto path = node->data.take_text("link"); + if (!paths.count(path)) { + throw error("link path is not found", path, node->data); + } + const auto link = paths.at(path); + if (link->type == "link") { + throw error("link target is link type", path, node->data); + } + targets[node] = link; + } + for (const auto & node : nodes) { + for (auto & child : node->children) { + child = targets.at(child); + } + } + root.nodes = nodes; } -void resolve_link_nodes(std::vector & nodes) +void resolve_remove_edits(RootConfig & root) { - std::vector filtered; - std::unordered_map links; std::unordered_map paths; - - for (const auto & node : nodes) { - links[node] = node; + for (const auto & node : root.nodes) { paths[node->path] = node; } - for (const auto & node : nodes) { - if (node->type == "link" && node->path == "") { - const auto link = node->data.take_text("link"); - if (!paths.count(link)) { - throw error("link path is not found", link, node->data); + std::unordered_set removes; + for (const auto & edit : root.edits) { + if (edit->type == "remove") { + if (!paths.count(edit->path)) { + throw error("remove path is not found", edit->path, edit->data); } - links[node] = paths.at(link); - } else { - filtered.push_back(node); + removes.insert(paths.at(edit->path)); } } - nodes = filtered; - for (const auto & node : nodes) { - for (auto & child : node->children) { - child = links.at(child); + const auto filter = [removes](const std::vector & nodes) { + std::vector result; + for (const auto & node : nodes) { + if (!removes.count(node)) { + result.push_back(node); + } } + return result; + }; + for (const auto & node : root.nodes) { + node->children = filter(node->children); } + root.nodes = filter(root.nodes); } std::string complement_node_type(ConfigData & data) @@ -224,13 +267,23 @@ UnitConfig::SharedPtr parse_node_config(const ConfigData & data) return node; } +EditConfig::SharedPtr parse_edit_config(const ConfigData & data) +{ + const auto edit = std::make_shared(data); + edit->path = edit->data.take_text("path", ""); + edit->type = edit->data.take_text("type", ""); + return edit; +} + FileConfig::SharedPtr parse_file_config(const ConfigData & data) { const auto file = std::make_shared(data); const auto path_data = data.type("file"); const auto node_data = data.type("node"); + const auto edit_data = data.type("edit"); const auto paths = file->data.take_list("files"); const auto nodes = file->data.take_list("nodes"); + const auto edits = file->data.take_list("edits"); for (const auto & [index, yaml] : enumerate(paths)) { const auto path = path_data.node(index).load(yaml); @@ -240,6 +293,10 @@ FileConfig::SharedPtr parse_file_config(const ConfigData & data) const auto node = node_data.node(index).load(yaml); file->nodes.push_back(parse_node_config(node)); } + for (const auto & [index, yaml] : enumerate(edits)) { + const auto edit = edit_data.node(index).load(yaml); + file->edits.push_back(parse_edit_config(edit)); + } return file; } @@ -267,20 +324,22 @@ RootConfig load_root_config(const PathConfig::SharedPtr root) } std::vector nodes; + std::vector edits; for (const auto & file : files) { extend(nodes, file->nodes); + extend(edits, file->edits); } for (size_t i = 0; i < nodes.size(); ++i) { const auto node = nodes[i]; extend(nodes, node->children); } - check_config_nodes(nodes); - resolve_link_nodes(nodes); - RootConfig config; config.files = files; config.nodes = nodes; + config.edits = edits; + resolve_link_nodes(config); + resolve_remove_edits(config); return config; } diff --git a/system/system_diagnostic_graph/src/core/config.hpp b/system/system_diagnostic_graph/src/core/config.hpp index d959f5b6be8aa..d7cdd0ec3c5f7 100644 --- a/system/system_diagnostic_graph/src/core/config.hpp +++ b/system/system_diagnostic_graph/src/core/config.hpp @@ -18,6 +18,7 @@ #include #include +#include #include #include #include @@ -32,6 +33,14 @@ struct ConfigData ConfigData type(const std::string & name) const; ConfigData node(const size_t index) const; + template + T take(const std::string & name, const T & fail) + { + const auto yaml = take_yaml(name); + return yaml ? yaml.value().as() : fail; + } + + std::optional take_yaml(const std::string & name); std::string take_text(const std::string & name); std::string take_text(const std::string & name, const std::string & fail); std::vector take_list(const std::string & name); @@ -64,18 +73,28 @@ struct UnitConfig : public BaseConfig std::vector children; }; +struct EditConfig : public BaseConfig +{ + using SharedPtr = std::shared_ptr; + using BaseConfig::BaseConfig; + std::string type; + std::string path; +}; + struct FileConfig : public BaseConfig { using SharedPtr = std::shared_ptr; using BaseConfig::BaseConfig; std::vector paths; std::vector nodes; + std::vector edits; }; struct RootConfig { std::vector files; std::vector nodes; + std::vector edits; }; template diff --git a/system/system_diagnostic_graph/src/core/debug.cpp b/system/system_diagnostic_graph/src/core/debug.cpp index f14177f4571ad..e2771f08f9f1e 100644 --- a/system/system_diagnostic_graph/src/core/debug.cpp +++ b/system/system_diagnostic_graph/src/core/debug.cpp @@ -26,19 +26,32 @@ namespace system_diagnostic_graph { -const std::unordered_map level_names = { - {DiagnosticStatus::OK, "OK"}, - {DiagnosticStatus::WARN, "WARN"}, - {DiagnosticStatus::ERROR, "ERROR"}, - {DiagnosticStatus::STALE, "STALE"}}; +std::string get_level_text(DiagnosticLevel level) +{ + switch (level) { + case DiagnosticStatus::OK: + return "OK"; + case DiagnosticStatus::WARN: + return "WARN"; + case DiagnosticStatus::ERROR: + return "ERROR"; + case DiagnosticStatus::STALE: + return "STALE"; + } + return "UNKNOWN"; +} void Graph::debug() { std::vector lines; for (const auto & node : nodes_) { - const auto level_name = level_names.at(node->level()); + const auto level_name = get_level_text(node->level()); const auto index_name = std::to_string(node->index()); - lines.push_back({"unit", index_name, level_name, node->path(), "-----"}); + lines.push_back({index_name, level_name, node->path(), node->type()}); + } + for (const auto & [name, level] : unknowns_) { + const auto level_name = get_level_text(level); + lines.push_back({"*", level_name, name, "unknown"}); } std::array widths = {}; diff --git a/system/system_diagnostic_graph/src/core/debug.hpp b/system/system_diagnostic_graph/src/core/debug.hpp index bb1bbc6f14230..297356cd36bab 100644 --- a/system/system_diagnostic_graph/src/core/debug.hpp +++ b/system/system_diagnostic_graph/src/core/debug.hpp @@ -21,7 +21,7 @@ namespace system_diagnostic_graph { -constexpr size_t diag_debug_size = 5; +constexpr size_t diag_debug_size = 4; using DiagDebugData = std::array; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/error.hpp b/system/system_diagnostic_graph/src/core/error.hpp index 2c10d659f2df4..7e110654bf475 100644 --- a/system/system_diagnostic_graph/src/core/error.hpp +++ b/system/system_diagnostic_graph/src/core/error.hpp @@ -40,6 +40,11 @@ class InvalidType : public Exception using Exception::Exception; }; +class InvalidValue : public Exception +{ + using Exception::Exception; +}; + class FieldNotFound : public Exception { using Exception::Exception; diff --git a/system/system_diagnostic_graph/src/core/graph.cpp b/system/system_diagnostic_graph/src/core/graph.cpp index 96e9bcff5bfd9..5ad7df09de1d1 100644 --- a/system/system_diagnostic_graph/src/core/graph.cpp +++ b/system/system_diagnostic_graph/src/core/graph.cpp @@ -103,6 +103,12 @@ BaseUnit::UniquePtr make_node(const UnitConfig::SharedPtr & config) if (config->type == "or") { return std::make_unique(config->path); } + if (config->type == "warn-to-ok") { + return std::make_unique(config->path, DiagnosticStatus::OK); + } + if (config->type == "warn-to-error") { + return std::make_unique(config->path, DiagnosticStatus::ERROR); + } if (config->type == "ok") { return std::make_unique(config->path, DiagnosticStatus::OK); } @@ -128,10 +134,8 @@ Graph::~Graph() // for unique_ptr } -void Graph::init(const std::string & file, const std::string & mode) +void Graph::init(const std::string & file) { - (void)mode; // TODO(Takagi, Isamu) - BaseUnit::UniquePtrList nodes; BaseUnit::NodeDict dict; @@ -149,17 +153,26 @@ void Graph::init(const std::string & file, const std::string & mode) // Sort units in topological order for update dependencies. nodes = topological_sort(std::move(nodes)); - for (size_t index = 0; index < nodes.size(); ++index) { - nodes[index]->set_index(index); - } - + // List diag nodes that have diag name. for (const auto & node : nodes) { const auto diag = dynamic_cast(node.get()); if (diag) { diags_[diag->name()] = diag; - std::cout << diag->name() << std::endl; } } + + // List unit nodes that have path name. + for (const auto & node : nodes) { + if (!node->path().empty()) { + units_.push_back(node.get()); + } + } + + // Set unit index. + for (size_t index = 0; index < units_.size(); ++index) { + units_[index]->set_index(index); + } + nodes_ = std::move(nodes); } @@ -170,8 +183,7 @@ void Graph::callback(const rclcpp::Time & stamp, const DiagnosticArray & array) if (iter != diags_.end()) { iter->second->callback(stamp, status); } else { - // TODO(Takagi, Isamu) - std::cout << "unknown diag: " << status.name << std::endl; + unknowns_[status.name] = status.level; } } } @@ -184,8 +196,8 @@ DiagnosticGraph Graph::report(const rclcpp::Time & stamp) DiagnosticGraph message; message.stamp = stamp; - message.nodes.reserve(nodes_.size()); - for (const auto & node : nodes_) { + message.nodes.reserve(units_.size()); + for (const auto & node : units_) { const auto report = node->report(); DiagnosticNode temp; temp.status.name = node->path(); diff --git a/system/system_diagnostic_graph/src/core/graph.hpp b/system/system_diagnostic_graph/src/core/graph.hpp index 366f6b457e272..7b0a5bf563106 100644 --- a/system/system_diagnostic_graph/src/core/graph.hpp +++ b/system/system_diagnostic_graph/src/core/graph.hpp @@ -34,16 +34,17 @@ class Graph final Graph(); ~Graph(); - void init(const std::string & file, const std::string & mode = ""); + void init(const std::string & file); void callback(const rclcpp::Time & stamp, const DiagnosticArray & array); + void debug(); DiagnosticGraph report(const rclcpp::Time & stamp); std::vector nodes() const; - void debug(); - private: std::vector> nodes_; + std::vector units_; std::unordered_map diags_; + std::unordered_map unknowns_; }; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/modes.cpp b/system/system_diagnostic_graph/src/core/modes.cpp index 96944bd50f81a..1488387811d67 100644 --- a/system/system_diagnostic_graph/src/core/modes.cpp +++ b/system/system_diagnostic_graph/src/core/modes.cpp @@ -48,9 +48,9 @@ OperationModes::OperationModes(rclcpp::Node & node, const std::vector #include #include @@ -40,13 +42,6 @@ auto resolve(const BaseUnit::NodeDict & dict, const std::vector result; - result.push_back(dict.paths.at(path)); - return result; -} - BaseUnit::BaseUnit(const std::string & path) : path_(path) { index_ = 0; @@ -69,8 +64,8 @@ BaseUnit::NodeData BaseUnit::report() const void DiagUnit::init(const UnitConfig::SharedPtr & config, const NodeDict &) { - timeout_ = 3.0; // TODO(Takagi, Isamu): parameterize name_ = config->data.take_text("diag"); + timeout_ = config->data.take("timeout", 1.0); } void DiagUnit::update(const rclcpp::Time & stamp) @@ -148,6 +143,28 @@ void OrUnit::update(const rclcpp::Time &) level_ = std::min(level_, DiagnosticStatus::ERROR); } +RemapUnit::RemapUnit(const std::string & path, DiagnosticLevel remap_warn) : BaseUnit(path) +{ + remap_warn_ = remap_warn; +} + +void RemapUnit::init(const UnitConfig::SharedPtr & config, const NodeDict & dict) +{ + if (config->children.size() != 1) { + throw error("list size must be 1", config->data); + } + children_ = resolve(dict, config->children); +} + +void RemapUnit::update(const rclcpp::Time &) +{ + const auto status = children_.front()->status(); + level_ = status.level; + links_ = status.links; + + if (level_ == DiagnosticStatus::WARN) level_ = remap_warn_; +} + DebugUnit::DebugUnit(const std::string & path, DiagnosticLevel level) : BaseUnit(path) { level_ = level; // overwrite diff --git a/system/system_diagnostic_graph/src/core/units.hpp b/system/system_diagnostic_graph/src/core/units.hpp index ad5fa4c4bc090..2b94b5f83a216 100644 --- a/system/system_diagnostic_graph/src/core/units.hpp +++ b/system/system_diagnostic_graph/src/core/units.hpp @@ -50,6 +50,7 @@ class BaseUnit virtual ~BaseUnit() = default; virtual void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) = 0; virtual void update(const rclcpp::Time & stamp) = 0; + virtual std::string type() const = 0; NodeData status() const; NodeData report() const; @@ -77,6 +78,7 @@ class DiagUnit : public BaseUnit using BaseUnit::BaseUnit; void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; void update(const rclcpp::Time & stamp) override; + std::string type() const override { return "diag"; } std::string name() const { return name_; } void callback(const rclcpp::Time & stamp, const DiagnosticStatus & status); @@ -93,6 +95,7 @@ class AndUnit : public BaseUnit AndUnit(const std::string & path, bool short_circuit); void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; void update(const rclcpp::Time & stamp) override; + std::string type() const override { return short_circuit_ ? "short-circuit-and" : "and"; } private: bool short_circuit_; @@ -104,6 +107,19 @@ class OrUnit : public BaseUnit using BaseUnit::BaseUnit; void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; void update(const rclcpp::Time & stamp) override; + std::string type() const override { return "or"; } +}; + +class RemapUnit : public BaseUnit +{ +public: + RemapUnit(const std::string & path, DiagnosticLevel remap_warn); + void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; + void update(const rclcpp::Time & stamp) override; + std::string type() const override { return "remap"; } + +private: + DiagnosticLevel remap_warn_; }; class DebugUnit : public BaseUnit @@ -112,6 +128,7 @@ class DebugUnit : public BaseUnit DebugUnit(const std::string & path, DiagnosticLevel level); void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; void update(const rclcpp::Time & stamp) override; + std::string type() const override { return "const"; } }; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/main.cpp b/system/system_diagnostic_graph/src/main.cpp index 7db35d1fd2551..7393d9fb086f6 100644 --- a/system/system_diagnostic_graph/src/main.cpp +++ b/system/system_diagnostic_graph/src/main.cpp @@ -25,13 +25,11 @@ MainNode::MainNode() : Node("system_diagnostic_graph_aggregator") // Init diagnostics graph. { const auto file = declare_parameter("graph_file"); - const auto mode = declare_parameter("mode"); - graph_.init(file, mode); - graph_.debug(); + graph_.init(file); } - // Init plugins - if (declare_parameter("mode_availability")) { + // Init plugins. + if (declare_parameter("use_operation_mode_availability")) { modes_ = std::make_unique(*this, graph_.nodes()); } @@ -48,6 +46,9 @@ MainNode::MainNode() : Node("system_diagnostic_graph_aggregator") const auto rate = rclcpp::Rate(declare_parameter("rate")); timer_ = rclcpp::create_timer(this, get_clock(), rate.period(), [this]() { on_timer(); }); } + + // Init debug mode. + debug_ = declare_parameter("use_debug_mode"); } MainNode::~MainNode() @@ -59,7 +60,7 @@ void MainNode::on_timer() { const auto stamp = now(); pub_graph_->publish(graph_.report(stamp)); - graph_.debug(); + if (debug_) graph_.debug(); if (modes_) modes_->update(stamp); } diff --git a/system/system_diagnostic_graph/src/main.hpp b/system/system_diagnostic_graph/src/main.hpp index 6deb0518cd9d0..495c51218cabc 100644 --- a/system/system_diagnostic_graph/src/main.hpp +++ b/system/system_diagnostic_graph/src/main.hpp @@ -40,6 +40,8 @@ class MainNode : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_graph_; void on_timer(); void on_diag(const DiagnosticArray::ConstSharedPtr msg); + + bool debug_; }; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/tool/main.cpp b/system/system_diagnostic_graph/src/tool/main.cpp new file mode 100644 index 0000000000000..6efb911d8e2d3 --- /dev/null +++ b/system/system_diagnostic_graph/src/tool/main.cpp @@ -0,0 +1,140 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "graph.hpp" +#include "types.hpp" +#include "units.hpp" + +#include +#include +#include + +namespace system_diagnostic_graph +{ + +struct GraphNode +{ + using UniquePtr = std::unique_ptr; + std::string type; + std::string path; + std::vector children; + std::vector parents; +}; + +struct GraphRoot +{ + std::vector owner; + std::vector nodes; +}; + +GraphRoot load_graph_nodes(const std::string & path) +{ + GraphRoot result; + { + std::unordered_map mapping; + Graph graph; + graph.init(path); + + for (const auto & node : graph.nodes()) { + auto data = std::make_unique(); + data->path = node->path(); + data->type = node->type(); + mapping[node] = std::move(data); + } + + for (const auto & [node, data] : mapping) { + for (const auto & link : node->children()) { + const auto parent = data.get(); + const auto child = mapping.at(link).get(); + child->parents.push_back(parent); + parent->children.push_back(child); + } + } + + for (auto & [node, data] : mapping) { + result.owner.push_back(std::move(data)); + } + for (const auto & node : result.owner) { + result.nodes.push_back(node.get()); + } + } + return result; +} + +void dump_plantuml_path(const std::string & path) +{ + const auto graph = load_graph_nodes(path); + const auto color = "#FFFFFF"; + + for (const auto & node : graph.nodes) { + std::cout << "card " << node << " " << color << " [" << std::endl; + std::cout << node->path << std::endl; + std::cout << "]" << std::endl; + } + + for (const auto & node : graph.nodes) { + for (const auto & child : node->children) { + std::cout << node << " --> " << child << std::endl; + } + } +} + +void dump_tree_node(const GraphNode * node, const std::string & indent = "", bool root = true) +{ + const auto path = node->path.empty() ? "" : node->path + " "; + const auto type = "(" + node->type + ")"; + std::cout << indent << "- " << path << type << std::endl; + + if (root || node->parents.size() == 1) { + for (const auto child : node->children) { + dump_tree_node(child, indent + " ", false); + } + } +} + +void dump_tree_path(const std::string & path) +{ + const auto graph = load_graph_nodes(path); + + std::cout << "===== root nodes =================================" << std::endl; + for (const auto & node : graph.nodes) { + if (node->parents.size() == 0 && node->children.size() != 0) { + dump_tree_node(node); + } + } + std::cout << "===== intermediate nodes =========================" << std::endl; + for (const auto & node : graph.nodes) { + if (node->parents.size() >= 2) { + dump_tree_node(node); + } + } + + std::cout << "===== isolated nodes =============================" << std::endl; + for (const auto & node : graph.nodes) { + if (node->parents.size() == 0 && node->children.size() == 0) { + dump_tree_node(node); + } + } +} + +} // namespace system_diagnostic_graph + +int main(int argc, char ** argv) +{ + if (argc != 2) { + std::cerr << "usage: " << argv[0] << " " << std::endl; + return 1; + } + system_diagnostic_graph::dump_tree_path(argv[1]); +} diff --git a/system/system_diagnostic_graph/test/files/field-not-found.yaml b/system/system_diagnostic_graph/test/files/test1/field-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/field-not-found.yaml rename to system/system_diagnostic_graph/test/files/test1/field-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/file-not-found.yaml b/system/system_diagnostic_graph/test/files/test1/file-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/file-not-found.yaml rename to system/system_diagnostic_graph/test/files/test1/file-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/graph-circulation.yaml b/system/system_diagnostic_graph/test/files/test1/graph-circulation.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/graph-circulation.yaml rename to system/system_diagnostic_graph/test/files/test1/graph-circulation.yaml diff --git a/system/system_diagnostic_graph/test/files/invalid-dict-type.yaml b/system/system_diagnostic_graph/test/files/test1/invalid-dict-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/invalid-dict-type.yaml rename to system/system_diagnostic_graph/test/files/test1/invalid-dict-type.yaml diff --git a/system/system_diagnostic_graph/test/files/invalid-list-type.yaml b/system/system_diagnostic_graph/test/files/test1/invalid-list-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/invalid-list-type.yaml rename to system/system_diagnostic_graph/test/files/test1/invalid-list-type.yaml diff --git a/system/system_diagnostic_graph/test/files/path-conflict.yaml b/system/system_diagnostic_graph/test/files/test1/path-conflict.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/path-conflict.yaml rename to system/system_diagnostic_graph/test/files/test1/path-conflict.yaml diff --git a/system/system_diagnostic_graph/test/files/path-not-found.yaml b/system/system_diagnostic_graph/test/files/test1/path-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/path-not-found.yaml rename to system/system_diagnostic_graph/test/files/test1/path-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/unknown-node-type.yaml b/system/system_diagnostic_graph/test/files/test1/unknown-node-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/unknown-node-type.yaml rename to system/system_diagnostic_graph/test/files/test1/unknown-node-type.yaml diff --git a/system/system_diagnostic_graph/test/files/unknown-substitution.yaml b/system/system_diagnostic_graph/test/files/test1/unknown-substitution.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/unknown-substitution.yaml rename to system/system_diagnostic_graph/test/files/test1/unknown-substitution.yaml diff --git a/system/system_diagnostic_graph/test/files/test2/and.yaml b/system/system_diagnostic_graph/test/files/test2/and.yaml new file mode 100644 index 0000000000000..0c9b651f89b2e --- /dev/null +++ b/system/system_diagnostic_graph/test/files/test2/and.yaml @@ -0,0 +1,10 @@ +nodes: + - path: output + type: and + list: + - path: input-0 + type: diag + diag: "test: input-0" + - path: input-1 + type: diag + diag: "test: input-1" diff --git a/system/system_diagnostic_graph/test/files/test2/or.yaml b/system/system_diagnostic_graph/test/files/test2/or.yaml new file mode 100644 index 0000000000000..c7f37a6c32064 --- /dev/null +++ b/system/system_diagnostic_graph/test/files/test2/or.yaml @@ -0,0 +1,10 @@ +nodes: + - path: output + type: or + list: + - path: input-0 + type: diag + diag: "test: input-0" + - path: input-1 + type: diag + diag: "test: input-1" diff --git a/system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml b/system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml new file mode 100644 index 0000000000000..816bf4fd6e1bf --- /dev/null +++ b/system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml @@ -0,0 +1,7 @@ +nodes: + - path: output + type: warn-to-error + list: + - path: input-0 + type: diag + diag: "test: input-0" diff --git a/system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml b/system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml new file mode 100644 index 0000000000000..1f5cf18978e3c --- /dev/null +++ b/system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml @@ -0,0 +1,7 @@ +nodes: + - path: output + type: warn-to-ok + list: + - path: input-0 + type: diag + diag: "test: input-0" diff --git a/system/system_diagnostic_graph/test/src/test.cpp b/system/system_diagnostic_graph/test/src/test1.cpp similarity index 57% rename from system/system_diagnostic_graph/test/src/test.cpp rename to system/system_diagnostic_graph/test/src/test1.cpp index b763179be0791..d01822e93c2eb 100644 --- a/system/system_diagnostic_graph/test/src/test.cpp +++ b/system/system_diagnostic_graph/test/src/test1.cpp @@ -14,75 +14,68 @@ #include "core/error.hpp" #include "core/graph.hpp" +#include "utils.hpp" #include -#include -#include - using namespace system_diagnostic_graph; // NOLINT(build/namespaces) -std::filesystem::path resource(const std::string & path) -{ - return std::filesystem::path(TEST_RESOURCE_PATH) / path; -} - TEST(ConfigFile, RootNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("fake-file-name.yaml")), FileNotFound); + EXPECT_THROW(graph.init(resource("test1/fake-file-name.yaml")), FileNotFound); } TEST(ConfigFile, FileNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("file-not-found.yaml")), FileNotFound); + EXPECT_THROW(graph.init(resource("test1/file-not-found.yaml")), FileNotFound); } TEST(ConfigFile, UnknownSubstitution) { Graph graph; - EXPECT_THROW(graph.init(resource("unknown-substitution.yaml")), UnknownType); + EXPECT_THROW(graph.init(resource("test1/unknown-substitution.yaml")), UnknownType); } TEST(ConfigFile, UnknownNodeType) { Graph graph; - EXPECT_THROW(graph.init(resource("unknown-node-type.yaml")), UnknownType); + EXPECT_THROW(graph.init(resource("test1/unknown-node-type.yaml")), UnknownType); } TEST(ConfigFile, InvalidDictType) { Graph graph; - EXPECT_THROW(graph.init(resource("invalid-dict-type.yaml")), InvalidType); + EXPECT_THROW(graph.init(resource("test1/invalid-dict-type.yaml")), InvalidType); } TEST(ConfigFile, InvalidListType) { Graph graph; - EXPECT_THROW(graph.init(resource("invalid-list-type.yaml")), InvalidType); + EXPECT_THROW(graph.init(resource("test1/invalid-list-type.yaml")), InvalidType); } TEST(ConfigFile, FieldNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("field-not-found.yaml")), FieldNotFound); + EXPECT_THROW(graph.init(resource("test1/field-not-found.yaml")), FieldNotFound); } TEST(ConfigFile, PathConflict) { Graph graph; - EXPECT_THROW(graph.init(resource("path-conflict.yaml")), PathConflict); + EXPECT_THROW(graph.init(resource("test1/path-conflict.yaml")), PathConflict); } TEST(ConfigFile, PathNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("path-not-found.yaml")), PathNotFound); + EXPECT_THROW(graph.init(resource("test1/path-not-found.yaml")), PathNotFound); } TEST(ConfigFile, GraphCirculation) { Graph graph; - EXPECT_THROW(graph.init(resource("graph-circulation.yaml")), GraphStructure); + EXPECT_THROW(graph.init(resource("test1/graph-circulation.yaml")), GraphStructure); } diff --git a/system/system_diagnostic_graph/test/src/test2.cpp b/system/system_diagnostic_graph/test/src/test2.cpp new file mode 100644 index 0000000000000..3e4c946f73fb7 --- /dev/null +++ b/system/system_diagnostic_graph/test/src/test2.cpp @@ -0,0 +1,143 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "core/error.hpp" +#include "core/graph.hpp" +#include "utils.hpp" + +#include +#include +#include + +#include + +using namespace system_diagnostic_graph; // NOLINT(build/namespaces) + +using diagnostic_msgs::msg::DiagnosticArray; +using diagnostic_msgs::msg::DiagnosticStatus; +using tier4_system_msgs::msg::DiagnosticGraph; + +constexpr auto OK = DiagnosticStatus::OK; +constexpr auto WARN = DiagnosticStatus::WARN; +constexpr auto ERROR = DiagnosticStatus::ERROR; +constexpr auto STALE = DiagnosticStatus::STALE; + +struct GraphTestParam +{ + std::string config; + std::vector inputs; + uint8_t result; +}; + +class GraphTest : public testing::TestWithParam +{ +}; + +DiagnosticArray create_input(const std::vector & levels) +{ + DiagnosticArray array; + for (size_t i = 0; i < levels.size(); ++i) { + DiagnosticStatus status; + status.level = levels[i]; + status.name = "test: input-" + std::to_string(i); + array.status.push_back(status); + } + return array; +}; + +uint8_t get_output(const DiagnosticGraph & graph) +{ + for (const auto & node : graph.nodes) { + if (node.status.name == "output") { + return node.status.level; + } + } + throw std::runtime_error("output node is not found"); +} + +TEST_P(GraphTest, Aggregation) +{ + const auto param = GetParam(); + const auto stamp = rclcpp::Clock().now(); + Graph graph; + graph.init(resource(param.config)); + graph.callback(stamp, create_input(param.inputs)); + + const auto output = get_output(graph.report(stamp)); + EXPECT_EQ(output, param.result); +} + +// clang-format off + +INSTANTIATE_TEST_SUITE_P(And, GraphTest, + testing::Values( + GraphTestParam{"test2/and.yaml", {OK, OK }, OK }, + GraphTestParam{"test2/and.yaml", {OK, WARN }, WARN }, + GraphTestParam{"test2/and.yaml", {OK, ERROR}, ERROR}, + GraphTestParam{"test2/and.yaml", {OK, STALE}, ERROR}, + GraphTestParam{"test2/and.yaml", {WARN, OK }, WARN }, + GraphTestParam{"test2/and.yaml", {WARN, WARN }, WARN }, + GraphTestParam{"test2/and.yaml", {WARN, ERROR}, ERROR}, + GraphTestParam{"test2/and.yaml", {WARN, STALE}, ERROR}, + GraphTestParam{"test2/and.yaml", {ERROR, OK }, ERROR}, + GraphTestParam{"test2/and.yaml", {ERROR, WARN }, ERROR}, + GraphTestParam{"test2/and.yaml", {ERROR, ERROR}, ERROR}, + GraphTestParam{"test2/and.yaml", {ERROR, STALE}, ERROR}, + GraphTestParam{"test2/and.yaml", {STALE, OK }, ERROR}, + GraphTestParam{"test2/and.yaml", {STALE, WARN }, ERROR}, + GraphTestParam{"test2/and.yaml", {STALE, ERROR}, ERROR}, + GraphTestParam{"test2/and.yaml", {STALE, STALE}, ERROR} + ) +); + +INSTANTIATE_TEST_SUITE_P(Or, GraphTest, + testing::Values( + GraphTestParam{"test2/or.yaml", {OK, OK }, OK }, + GraphTestParam{"test2/or.yaml", {OK, WARN }, OK }, + GraphTestParam{"test2/or.yaml", {OK, ERROR}, OK }, + GraphTestParam{"test2/or.yaml", {OK, STALE}, OK }, + GraphTestParam{"test2/or.yaml", {WARN, OK }, OK }, + GraphTestParam{"test2/or.yaml", {WARN, WARN }, WARN }, + GraphTestParam{"test2/or.yaml", {WARN, ERROR}, WARN }, + GraphTestParam{"test2/or.yaml", {WARN, STALE}, WARN }, + GraphTestParam{"test2/or.yaml", {ERROR, OK }, OK }, + GraphTestParam{"test2/or.yaml", {ERROR, WARN }, WARN }, + GraphTestParam{"test2/or.yaml", {ERROR, ERROR}, ERROR}, + GraphTestParam{"test2/or.yaml", {ERROR, STALE}, ERROR}, + GraphTestParam{"test2/or.yaml", {STALE, OK }, OK }, + GraphTestParam{"test2/or.yaml", {STALE, WARN }, WARN }, + GraphTestParam{"test2/or.yaml", {STALE, ERROR}, ERROR}, + GraphTestParam{"test2/or.yaml", {STALE, STALE}, ERROR} + ) +); + +INSTANTIATE_TEST_SUITE_P(WarnToOk, GraphTest, + testing::Values( + GraphTestParam{"test2/warn-to-ok.yaml", {OK }, OK }, + GraphTestParam{"test2/warn-to-ok.yaml", {WARN }, OK}, + GraphTestParam{"test2/warn-to-ok.yaml", {ERROR}, ERROR}, + GraphTestParam{"test2/warn-to-ok.yaml", {STALE}, STALE} + ) +); + +INSTANTIATE_TEST_SUITE_P(WarnToError, GraphTest, + testing::Values( + GraphTestParam{"test2/warn-to-error.yaml", {OK }, OK }, + GraphTestParam{"test2/warn-to-error.yaml", {WARN }, ERROR}, + GraphTestParam{"test2/warn-to-error.yaml", {ERROR}, ERROR}, + GraphTestParam{"test2/warn-to-error.yaml", {STALE}, STALE} + ) +); + +// clang-format on diff --git a/system/system_diagnostic_graph/test/src/utils.cpp b/system/system_diagnostic_graph/test/src/utils.cpp new file mode 100644 index 0000000000000..c64812afa649a --- /dev/null +++ b/system/system_diagnostic_graph/test/src/utils.cpp @@ -0,0 +1,20 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "utils.hpp" + +std::filesystem::path resource(const std::string & path) +{ + return std::filesystem::path(TEST_RESOURCE_PATH) / path; +} diff --git a/system/system_diagnostic_graph/test/src/utils.hpp b/system/system_diagnostic_graph/test/src/utils.hpp new file mode 100644 index 0000000000000..27f0b293d72dc --- /dev/null +++ b/system/system_diagnostic_graph/test/src/utils.hpp @@ -0,0 +1,23 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef UTILS_HPP_ +#define UTILS_HPP_ + +#include +#include + +std::filesystem::path resource(const std::string & path); + +#endif // UTILS_HPP_ From 6c2506ad80e55db6e1c448e5d3f278bb96aa97aa Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Sat, 9 Dec 2023 00:51:12 +0900 Subject: [PATCH 029/276] fix(autoware_auto_msgs_adapter): fix predicted path test (#5744) Signed-off-by: Takagi, Isamu --- .../test/test_msg_predicted_objects.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/system/autoware_auto_msgs_adapter/test/test_msg_predicted_objects.cpp b/system/autoware_auto_msgs_adapter/test/test_msg_predicted_objects.cpp index 9f7f0ce8056f5..a84985770059d 100644 --- a/system/autoware_auto_msgs_adapter/test/test_msg_predicted_objects.cpp +++ b/system/autoware_auto_msgs_adapter/test/test_msg_predicted_objects.cpp @@ -65,7 +65,10 @@ autoware_perception_msgs::msg::PredictedObjects generate_perception_msg() kin.initial_acceleration_with_covariance.accel.angular.y = 0; kin.initial_acceleration_with_covariance.accel.angular.z = 0; - for (size_t i = 0; i < 10; i++) { + constexpr size_t path_size = 10; + kin.predicted_paths.resize(1); + kin.predicted_paths[0].path.resize(path_size); + for (size_t i = 0; i < path_size; i++) { kin.predicted_paths[0].path[i].position.x = i; kin.predicted_paths[0].path[i].position.y = 0; kin.predicted_paths[0].path[i].position.z = 0; From 60889706f5096fec199a2c98adc1d4d96d7deb8a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Sat, 9 Dec 2023 17:55:35 +0900 Subject: [PATCH 030/276] refactor(side_shift): separate side shift module (#5820) * refactor(side_shift): separate side shift module Signed-off-by: satoshi-ota * refactor(bpp): remove side shift module Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- planning/behavior_path_planner/CMakeLists.txt | 3 - planning/behavior_path_planner/plugins.xml | 1 - ...t_behavior_path_planner_node_interface.cpp | 4 +- .../CMakeLists.txt | 26 ++++ .../config}/side_shift.param.yaml | 0 .../data_structs.hpp} | 6 +- .../manager.hpp | 8 +- .../scene.hpp} | 10 +- .../utils.hpp} | 8 +- .../package.xml | 38 ++++++ .../plugins.xml | 3 + .../src}/manager.cpp | 2 +- .../src/scene.cpp} | 6 +- .../src/utils.cpp} | 4 +- ...t_behavior_path_planner_node_interface.cpp | 124 ++++++++++++++++++ 15 files changed, 214 insertions(+), 29 deletions(-) create mode 100644 planning/behavior_path_side_shift_module/CMakeLists.txt rename planning/{behavior_path_planner/config/side_shift => behavior_path_side_shift_module/config}/side_shift.param.yaml (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/side_shift/side_shift_parameters.hpp => behavior_path_side_shift_module/include/behavior_path_side_shift_module/data_structs.hpp} (86%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/side_shift => behavior_path_side_shift_module/include/behavior_path_side_shift_module}/manager.hpp (83%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp => behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp} (92%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp => behavior_path_side_shift_module/include/behavior_path_side_shift_module/utils.hpp} (86%) create mode 100644 planning/behavior_path_side_shift_module/package.xml create mode 100644 planning/behavior_path_side_shift_module/plugins.xml rename planning/{behavior_path_planner/src/scene_module/side_shift => behavior_path_side_shift_module/src}/manager.cpp (97%) rename planning/{behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp => behavior_path_side_shift_module/src/scene.cpp} (99%) rename planning/{behavior_path_planner/src/utils/side_shift/util.cpp => behavior_path_side_shift_module/src/utils.cpp} (97%) create mode 100644 planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 75f9e7f7af187..56456b08aac1e 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -14,14 +14,11 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/behavior_path_planner_node.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp src/scene_module/dynamic_avoidance/manager.cpp - src/scene_module/side_shift/side_shift_module.cpp - src/scene_module/side_shift/manager.cpp src/scene_module/lane_change/interface.cpp src/scene_module/lane_change/normal.cpp src/scene_module/lane_change/external_request.cpp src/scene_module/lane_change/manager.cpp src/utils/lane_change/utils.cpp - src/utils/side_shift/util.cpp src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp src/marker_utils/lane_change/debug.cpp ) diff --git a/planning/behavior_path_planner/plugins.xml b/planning/behavior_path_planner/plugins.xml index fed2e1c9af3c3..2028b0d571e68 100644 --- a/planning/behavior_path_planner/plugins.xml +++ b/planning/behavior_path_planner/plugins.xml @@ -1,5 +1,4 @@ - diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index 0e253c0c73985..bab77f9141a00 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -50,7 +50,6 @@ std::shared_ptr generateNode() std::vector module_names; module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); - module_names.emplace_back("behavior_path_planner::SideShiftModuleManager"); module_names.emplace_back("behavior_path_planner::LaneChangeRightModuleManager"); module_names.emplace_back("behavior_path_planner::LaneChangeLeftModuleManager"); module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); @@ -69,8 +68,7 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml", - behavior_path_planner_dir + "/config/lane_change/lane_change.param.yaml", - behavior_path_planner_dir + "/config/side_shift/side_shift.param.yaml"}); + behavior_path_planner_dir + "/config/lane_change/lane_change.param.yaml"}); return std::make_shared(node_options); } diff --git a/planning/behavior_path_side_shift_module/CMakeLists.txt b/planning/behavior_path_side_shift_module/CMakeLists.txt new file mode 100644 index 0000000000000..28009e48a4cc4 --- /dev/null +++ b/planning/behavior_path_side_shift_module/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_side_shift_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/scene.cpp + src/utils.cpp + src/manager.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_behavior_path_planner_node_interface.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/config/side_shift/side_shift.param.yaml b/planning/behavior_path_side_shift_module/config/side_shift.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/side_shift/side_shift.param.yaml rename to planning/behavior_path_side_shift_module/config/side_shift.param.yaml diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/side_shift_parameters.hpp b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/data_structs.hpp similarity index 86% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/side_shift_parameters.hpp rename to planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/data_structs.hpp index 6475661f72ac4..c9edd3d6bf6a6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/side_shift_parameters.hpp +++ b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/data_structs.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__SIDE_SHIFT_PARAMETERS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__SIDE_SHIFT_PARAMETERS_HPP_ +#ifndef BEHAVIOR_PATH_SIDE_SHIFT_MODULE__DATA_STRUCTS_HPP_ +#define BEHAVIOR_PATH_SIDE_SHIFT_MODULE__DATA_STRUCTS_HPP_ #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -51,4 +51,4 @@ struct SideShiftDebugData }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__SIDE_SHIFT_PARAMETERS_HPP_ +#endif // BEHAVIOR_PATH_SIDE_SHIFT_MODULE__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/manager.hpp similarity index 83% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp rename to planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/manager.hpp index 53bac3914ce86..ef8a48bc29760 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp +++ b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/manager.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_SIDE_SHIFT_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_SIDE_SHIFT_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/side_shift/side_shift_module.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" +#include "behavior_path_side_shift_module/scene.hpp" #include @@ -50,4 +50,4 @@ class SideShiftModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_SIDE_SHIFT_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp similarity index 92% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp rename to planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp index 014a0f403f9ec..7d72afebfb359 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp +++ b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__SIDE_SHIFT_MODULE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__SIDE_SHIFT_MODULE_HPP_ +#ifndef BEHAVIOR_PATH_SIDE_SHIFT_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_SIDE_SHIFT_MODULE__SCENE_HPP_ -#include "behavior_path_planner/utils/side_shift/side_shift_parameters.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" +#include "behavior_path_side_shift_module/data_structs.hpp" #include @@ -134,4 +134,4 @@ class SideShiftModule : public SceneModuleInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__SIDE_SHIFT_MODULE_HPP_ +#endif // BEHAVIOR_PATH_SIDE_SHIFT_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/utils.hpp similarity index 86% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp rename to planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/utils.hpp index 6cdfd84d79075..210dd4e8a8d2a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp +++ b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/utils.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__UTIL_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__UTIL_HPP_ +#ifndef BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_ +#define BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_ #include #include @@ -41,4 +41,4 @@ Point transformToGrid( } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__UTIL_HPP_ +#endif // BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_ diff --git a/planning/behavior_path_side_shift_module/package.xml b/planning/behavior_path_side_shift_module/package.xml new file mode 100644 index 0000000000000..5c421b04c0e39 --- /dev/null +++ b/planning/behavior_path_side_shift_module/package.xml @@ -0,0 +1,38 @@ + + + + behavior_path_side_shift_module + 0.1.0 + The behavior_path_side_shift_module package + + Satoshi Ota + Fumiya Watanabe + Kyoichi Sugahara + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + autoware_auto_planning_msgs + behavior_path_planner + behavior_path_planner_common + geometry_msgs + motion_utils + pluginlib + rclcpp + tier4_autoware_utils + tier4_planning_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_side_shift_module/plugins.xml b/planning/behavior_path_side_shift_module/plugins.xml new file mode 100644 index 0000000000000..2688e3a17c2b6 --- /dev/null +++ b/planning/behavior_path_side_shift_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp b/planning/behavior_path_side_shift_module/src/manager.cpp similarity index 97% rename from planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp rename to planning/behavior_path_side_shift_module/src/manager.cpp index b20712ef19179..fa8d579da3d09 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp +++ b/planning/behavior_path_side_shift_module/src/manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/side_shift/manager.hpp" +#include "behavior_path_side_shift_module/manager.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp b/planning/behavior_path_side_shift_module/src/scene.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp rename to planning/behavior_path_side_shift_module/src/scene.cpp index 9f77288e608cf..69df77672cd96 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp +++ b/planning/behavior_path_side_shift_module/src/scene.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/side_shift/side_shift_module.hpp" +#include "behavior_path_side_shift_module/scene.hpp" -#include "behavior_path_planner/utils/side_shift/util.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_side_shift_module/utils.hpp" #include diff --git a/planning/behavior_path_planner/src/utils/side_shift/util.cpp b/planning/behavior_path_side_shift_module/src/utils.cpp similarity index 97% rename from planning/behavior_path_planner/src/utils/side_shift/util.cpp rename to planning/behavior_path_side_shift_module/src/utils.cpp index af733722562f8..a674d57597bc7 100644 --- a/planning/behavior_path_planner/src/utils/side_shift/util.cpp +++ b/planning/behavior_path_side_shift_module/src/utils.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/side_shift/util.hpp" +#include "behavior_path_side_shift_module/utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" diff --git a/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..94be083bdebcd --- /dev/null +++ b/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,124 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ament_index_cpp/get_package_share_directory.hpp" +#include "behavior_path_planner/behavior_path_planner_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::SideShiftModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_side_shift_module") + + "/config/side_shift.param.yaml"}); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} From c63e704e5355cb059bfec17063ac046782dffe2d Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Sun, 10 Dec 2023 17:02:30 +0900 Subject: [PATCH 031/276] fix(avoidance): output invalid avoidance path with unsafe state (#5689) fix(avoidance): output invalid avoidance path Signed-off-by: satoshi-ota --- .../src/scene.cpp | 18 +++--------------- 1 file changed, 3 insertions(+), 15 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 9b0c85f60ba29..67316dbc763f2 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -137,7 +137,7 @@ bool AvoidanceModule::isExecutionRequested() const bool AvoidanceModule::isExecutionReady() const { DEBUG_PRINT("AVOIDANCE isExecutionReady"); - return avoid_data_.safe && avoid_data_.comfortable; + return avoid_data_.safe && avoid_data_.comfortable && avoid_data_.valid; } bool AvoidanceModule::canTransitSuccessState() @@ -450,15 +450,14 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de * STEP1: Create candidate shift lines. * Merge rough shift lines, and extract new shift lines. */ - const auto processed_shift_lines = generator_.generate(data, debug); + data.new_shift_line = generator_.generate(data, debug); /** * Step2: Validate new shift lines. * Output new shift lines only when the avoidance path which is generated from them doesn't have * huge offset from ego. */ - data.valid = isValidShiftLine(processed_shift_lines, path_shifter); - data.new_shift_line = data.valid ? processed_shift_lines : AvoidLineArray{}; + data.valid = isValidShiftLine(data.new_shift_line, path_shifter); const auto found_new_sl = data.new_shift_line.size() > 0; const auto registered = path_shifter.getShiftLines().size() > 0; data.found_avoidance_path = found_new_sl || registered; @@ -494,17 +493,6 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de void AvoidanceModule::fillEgoStatus( AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const { - /** - * TODO(someone): prevent meaningless stop point insertion in other way. - * If the candidate shift line is invalid, manage all objects as unavoidable. - */ - if (!data.valid) { - std::for_each(data.target_objects.begin(), data.target_objects.end(), [](auto & o) { - o.is_avoidable = false; - o.reason = "InvalidShiftLine"; - }); - } - /** * Find the nearest object that should be avoid. When the ego follows reference path, * if the both of following two conditions are satisfied, the module surely avoid the object. From 0e5c3c39a0a5a59c863226b0fa004f25395d8c9a Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Sun, 10 Dec 2023 08:05:57 +0000 Subject: [PATCH 032/276] chore: update CODEOWNERS (#5811) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/CODEOWNERS | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index ea86022e7134d..3045b3746ea8e 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -154,10 +154,13 @@ perception/traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhon perception/traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp perception/traffic_light_visualization/** yukihiro.saito@tier4.jp -planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp zulfaqar.azmi@tier4.jp -planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp -planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_path_goal_planner_module/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner_common/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_path_start_planner_module/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_crosswalk_module/** kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_detection_area_module/** kyoichi.sugahara@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp From 56498ae10cacdff87a10d46f62924de940d7809d Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Mon, 11 Dec 2023 09:38:16 +0900 Subject: [PATCH 033/276] fix(localization_util): fixed rejection criteria of SmartPoseBuffer::interpolate (#5818) Fixed rejection criteria of SmartPoseBuffer::interpolate Signed-off-by: Shintaro Sakoda --- localization/localization_util/src/smart_pose_buffer.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/localization/localization_util/src/smart_pose_buffer.cpp b/localization/localization_util/src/smart_pose_buffer.cpp index ba293109dcc4d..bc62bfa690946 100644 --- a/localization/localization_util/src/smart_pose_buffer.cpp +++ b/localization/localization_util/src/smart_pose_buffer.cpp @@ -39,10 +39,16 @@ std::optional SmartPoseBuffer::interpolate( const rclcpp::Time time_first = pose_buffer_.front()->header.stamp; const rclcpp::Time time_last = pose_buffer_.back()->header.stamp; - if (target_ros_time < time_first || time_last < target_ros_time) { + if (target_ros_time < time_first) { return std::nullopt; } + // [time_last < target_ros_time] is acceptable here. + // It is possible that the target_ros_time (often sensor timestamp) is newer than the latest + // timestamp of buffered pose (often EKF). + // However, if the timestamp difference is too large, + // it will later be rejected by validate_time_stamp_difference. + // get the nearest poses result.old_pose = *pose_buffer_.front(); for (const PoseWithCovarianceStamped::ConstSharedPtr & pose_cov_msg_ptr : pose_buffer_) { From ee8c39e964723d9afcfd5b3ee2ccbbebfad6922f Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 11 Dec 2023 10:16:28 +0900 Subject: [PATCH 034/276] fix(lidar_centerpoint,image_projection_based_fusion): add guard to avoid exceeding max voxel size (#5824) --- .../pointpainting_fusion/preprocess_kernel.hpp | 5 +++-- .../src/pointpainting_fusion/pointpainting_trt.cpp | 4 ++-- .../src/pointpainting_fusion/preprocess_kernel.cu | 13 ++++++++----- .../preprocess/preprocess_kernel.hpp | 5 +++-- .../lidar_centerpoint/lib/centerpoint_trt.cpp | 4 ++-- .../lib/preprocess/preprocess_kernel.cu | 13 ++++++++----- 6 files changed, 26 insertions(+), 18 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/preprocess_kernel.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/preprocess_kernel.hpp index c913ac33d5e84..897609fa3d86d 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/preprocess_kernel.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/preprocess_kernel.hpp @@ -27,8 +27,9 @@ cudaError_t generateVoxels_random_launch( cudaStream_t stream); cudaError_t generateBaseFeatures_launch( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs, cudaStream_t stream); + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs, + cudaStream_t stream); cudaError_t generateFeatures_launch( const float * voxel_features, const float * voxel_num_points, const int * coords, diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp index 8911442f4c75d..d44620995c61b 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp @@ -69,8 +69,8 @@ bool PointPaintingTRT::preprocess( CHECK_CUDA_ERROR(image_projection_based_fusion::generateBaseFeatures_launch( mask_d_.get(), voxels_buffer_d_.get(), config_.grid_size_y_, config_.grid_size_x_, - num_voxels_d_.get(), voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), - stream_)); + config_.max_voxel_size_, num_voxels_d_.get(), voxels_d_.get(), num_points_per_voxel_d_.get(), + coordinates_d_.get(), stream_)); CHECK_CUDA_ERROR(image_projection_based_fusion::generateFeatures_launch( voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), num_voxels_d_.get(), diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu b/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu index d06b60633acf8..68e08ac61a569 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu @@ -105,8 +105,8 @@ cudaError_t generateVoxels_random_launch( } __global__ void generateBaseFeatures_kernel( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs) + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs) { unsigned int voxel_idx = blockIdx.x * blockDim.x + threadIdx.x; unsigned int voxel_idy = blockIdx.y * blockDim.y + threadIdx.y; @@ -120,6 +120,7 @@ __global__ void generateBaseFeatures_kernel( unsigned int current_pillarId = 0; current_pillarId = atomicAdd(pillar_num, 1); + if (current_pillarId > max_voxel_size - 1) return; voxel_num[current_pillarId] = count; @@ -140,15 +141,17 @@ __global__ void generateBaseFeatures_kernel( // create 4 channels cudaError_t generateBaseFeatures_launch( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs, cudaStream_t stream) + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs, + cudaStream_t stream) { dim3 threads = {32, 32}; dim3 blocks = { (grid_x_size + threads.x - 1) / threads.x, (grid_y_size + threads.y - 1) / threads.y}; generateBaseFeatures_kernel<<>>( - mask, voxels, grid_y_size, grid_x_size, pillar_num, voxel_features, voxel_num, voxel_idxs); + mask, voxels, grid_y_size, grid_x_size, max_voxel_size, pillar_num, voxel_features, voxel_num, + voxel_idxs); cudaError_t err = cudaGetLastError(); return err; } diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp index 824144fe3b22b..9488b67475509 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp @@ -27,8 +27,9 @@ cudaError_t generateVoxels_random_launch( cudaStream_t stream); cudaError_t generateBaseFeatures_launch( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs, cudaStream_t stream); + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs, + cudaStream_t stream); cudaError_t generateFeatures_launch( const float * voxel_features, const float * voxel_num_points, const int * coords, diff --git a/perception/lidar_centerpoint/lib/centerpoint_trt.cpp b/perception/lidar_centerpoint/lib/centerpoint_trt.cpp index 67271985d3b5e..2804e172b73fa 100644 --- a/perception/lidar_centerpoint/lib/centerpoint_trt.cpp +++ b/perception/lidar_centerpoint/lib/centerpoint_trt.cpp @@ -156,8 +156,8 @@ bool CenterPointTRT::preprocess( CHECK_CUDA_ERROR(generateBaseFeatures_launch( mask_d_.get(), voxels_buffer_d_.get(), config_.grid_size_y_, config_.grid_size_x_, - num_voxels_d_.get(), voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), - stream_)); + config_.max_voxel_size_, num_voxels_d_.get(), voxels_d_.get(), num_points_per_voxel_d_.get(), + coordinates_d_.get(), stream_)); CHECK_CUDA_ERROR(generateFeatures_launch( voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), num_voxels_d_.get(), diff --git a/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu b/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu index 6f77ff84c2cea..118e31f892d72 100644 --- a/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu +++ b/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu @@ -87,8 +87,8 @@ cudaError_t generateVoxels_random_launch( } __global__ void generateBaseFeatures_kernel( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs) + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs) { unsigned int voxel_idx = blockIdx.x * blockDim.x + threadIdx.x; unsigned int voxel_idy = blockIdx.y * blockDim.y + threadIdx.y; @@ -102,6 +102,7 @@ __global__ void generateBaseFeatures_kernel( unsigned int current_pillarId = 0; current_pillarId = atomicAdd(pillar_num, 1); + if (current_pillarId > max_voxel_size - 1) return; voxel_num[current_pillarId] = count; @@ -120,15 +121,17 @@ __global__ void generateBaseFeatures_kernel( // create 4 channels cudaError_t generateBaseFeatures_launch( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs, cudaStream_t stream) + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs, + cudaStream_t stream) { dim3 threads = {32, 32}; dim3 blocks = { (grid_x_size + threads.x - 1) / threads.x, (grid_y_size + threads.y - 1) / threads.y}; generateBaseFeatures_kernel<<>>( - mask, voxels, grid_y_size, grid_x_size, pillar_num, voxel_features, voxel_num, voxel_idxs); + mask, voxels, grid_y_size, grid_x_size, max_voxel_size, pillar_num, voxel_features, voxel_num, + voxel_idxs); cudaError_t err = cudaGetLastError(); return err; } From 67fad2efb1fff7236d07a0e75fe392c923618626 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 11 Dec 2023 10:55:20 +0900 Subject: [PATCH 035/276] feat(obstacle_cruise_planner): add jerk and acc limits for slow-down (#5810) Add jerk and acc limits for slow-down Signed-off-by: Daniel Sanchez --- .../config/default_common.param.yaml | 4 ++++ .../include/obstacle_cruise_planner/common_structs.hpp | 7 +++++++ planning/obstacle_cruise_planner/src/planner_interface.cpp | 4 ++-- 3 files changed, 13 insertions(+), 2 deletions(-) diff --git a/planning/obstacle_cruise_planner/config/default_common.param.yaml b/planning/obstacle_cruise_planner/config/default_common.param.yaml index 6bb130e8052b0..f900d309123cf 100644 --- a/planning/obstacle_cruise_planner/config/default_common.param.yaml +++ b/planning/obstacle_cruise_planner/config/default_common.param.yaml @@ -7,6 +7,10 @@ min_jerk: -1.0 # min jerk [m/sss] max_jerk: 1.0 # max jerk [m/sss] + slow_down: + min_acc: -1.0 # min slowdown deceleration [m/ss] + min_jerk: -1.0 # min slowdown jerk [m/sss] + # constraints to be observed limit: min_acc: -2.5 # min deceleration limit [m/ss] diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp index 27b2945f614d2..6c44c4744e96c 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp @@ -172,6 +172,8 @@ struct LongitudinalInfo limit_min_accel = node.declare_parameter("limit.min_acc"); limit_max_jerk = node.declare_parameter("limit.max_jerk"); limit_min_jerk = node.declare_parameter("limit.min_jerk"); + slow_down_min_accel = node.declare_parameter("slow_down.min_acc"); + slow_down_min_jerk = node.declare_parameter("slow_down.min_jerk"); idling_time = node.declare_parameter("common.idling_time"); min_ego_accel_for_rss = node.declare_parameter("common.min_ego_accel_for_rss"); @@ -197,6 +199,9 @@ struct LongitudinalInfo tier4_autoware_utils::updateParam(parameters, "limit.min_accel", limit_min_accel); tier4_autoware_utils::updateParam(parameters, "limit.max_jerk", limit_max_jerk); tier4_autoware_utils::updateParam(parameters, "limit.min_jerk", limit_min_jerk); + tier4_autoware_utils::updateParam( + parameters, "slow_down.min_accel", slow_down_min_accel); + tier4_autoware_utils::updateParam(parameters, "slow_down.min_jerk", slow_down_min_jerk); tier4_autoware_utils::updateParam(parameters, "common.idling_time", idling_time); tier4_autoware_utils::updateParam( @@ -220,6 +225,8 @@ struct LongitudinalInfo double min_accel; double max_jerk; double min_jerk; + double slow_down_min_jerk; + double slow_down_min_accel; double limit_max_accel; double limit_min_accel; double limit_max_jerk; diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index 2dc1247630eaf..a7dac94e1c38a 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -763,8 +763,8 @@ PlannerInterface::calculateDistanceToSlowDownWithConstraints( } // TODO(murooka) Calculate more precisely. Final acceleration should be zero. const double min_feasible_slow_down_vel = calcDecelerationVelocityFromDistanceToTarget( - longitudinal_info_.min_jerk, longitudinal_info_.min_accel, planner_data.ego_acc, - planner_data.ego_vel, deceleration_dist); + longitudinal_info_.slow_down_min_jerk, longitudinal_info_.slow_down_min_accel, + planner_data.ego_acc, planner_data.ego_vel, deceleration_dist); return min_feasible_slow_down_vel; }(); if (prev_output) { From afe477cc2df7a32074d6c7d4fdd26c51f7ac2de4 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Mon, 11 Dec 2023 11:28:34 +0900 Subject: [PATCH 036/276] fix(traffic_light): stop if the traffic light signal timed out (#5819) * fix(traffic_light): stop if the traffic light signal timed out Signed-off-by: Fumiya Watanabe * fix(traffic_light): fix README format Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- .../README.md | 23 ++++-- .../config/traffic_light.param.yaml | 1 + .../src/manager.cpp | 2 + .../src/scene.cpp | 74 ++++++++++++++----- .../src/scene.hpp | 15 +++- 5 files changed, 84 insertions(+), 31 deletions(-) diff --git a/planning/behavior_velocity_traffic_light_module/README.md b/planning/behavior_velocity_traffic_light_module/README.md index 866ab87070369..e85a171495e38 100644 --- a/planning/behavior_velocity_traffic_light_module/README.md +++ b/planning/behavior_velocity_traffic_light_module/README.md @@ -19,7 +19,13 @@ This module is activated when there is traffic light in ego lane. 1. Obtains a traffic light mapped to the route and a stop line correspond to the traffic light from a map information. -2. Uses the highest reliability one of the traffic light recognition result and if the color of that was red, generates a stop point. + - If a corresponding traffic light signal have never been found, it treats as a signal to pass. + + - If a corresponding traffic light signal is found but timed out, it treats as a signal to stop. + +2. Uses the highest reliability one of the traffic light recognition result and if the color of that was not green or corresponding arrow signal, generates a stop point. + + - If an elapsed time to receive stop signal is less than `stop_time_hysteresis`, it treats as a signal to pass. This feature is to prevent chattering. 3. When vehicle current velocity is @@ -63,12 +69,13 @@ This module is activated when there is traffic light in ego lane. #### Module Parameters -| Parameter | Type | Description | -| -------------------- | ------ | ----------------------------------------------- | -| `stop_margin` | double | [m] margin before stop point | -| `tl_state_timeout` | double | [s] time out for detected traffic light result. | -| `yellow_lamp_period` | double | [s] time for yellow lamp | -| `enable_pass_judge` | bool | [-] whether to use pass judge | +| Parameter | Type | Description | +| ---------------------- | ------ | -------------------------------------------------------------------- | +| `stop_margin` | double | [m] margin before stop point | +| `tl_state_timeout` | double | [s] time out for detected traffic light result. | +| `stop_time_hysteresis` | double | [s] time threshold to decide stop planning for chattering prevention | +| `yellow_lamp_period` | double | [s] time for yellow lamp | +| `enable_pass_judge` | bool | [-] whether to use pass judge | #### Flowchart @@ -91,7 +98,7 @@ if (state is APPROACH) then (yes) :change state to GO_OUT; stop elseif (no stop signal) then (yes) - :change previous state to STOP; + :change previous state to PASS; stop elseif (not pass through) then (yes) :insert stop pose; diff --git a/planning/behavior_velocity_traffic_light_module/config/traffic_light.param.yaml b/planning/behavior_velocity_traffic_light_module/config/traffic_light.param.yaml index a837ae1b46b9b..23746a61b6043 100644 --- a/planning/behavior_velocity_traffic_light_module/config/traffic_light.param.yaml +++ b/planning/behavior_velocity_traffic_light_module/config/traffic_light.param.yaml @@ -3,6 +3,7 @@ traffic_light: stop_margin: 0.0 tl_state_timeout: 1.0 + stop_time_hysteresis: 0.1 yellow_lamp_period: 2.75 enable_pass_judge: true enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_traffic_light_module/src/manager.cpp index a23edefff52ab..908627540bdcc 100644 --- a/planning/behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/manager.cpp @@ -38,6 +38,8 @@ TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node) const std::string ns(getModuleName()); planner_param_.stop_margin = getOrDeclareParameter(node, ns + ".stop_margin"); planner_param_.tl_state_timeout = getOrDeclareParameter(node, ns + ".tl_state_timeout"); + planner_param_.stop_time_hysteresis = + getOrDeclareParameter(node, ns + ".stop_time_hysteresis"); planner_param_.enable_pass_judge = getOrDeclareParameter(node, ns + ".enable_pass_judge"); planner_param_.yellow_lamp_period = getOrDeclareParameter(node, ns + ".yellow_lamp_period"); diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp index 90a547adeb930..a74ff8c0cb5e8 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp @@ -222,13 +222,33 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason * if (signed_arc_length_to_stop_point < signed_deadline_length) { RCLCPP_INFO(logger_, "APPROACH -> GO_OUT"); state_ = State::GO_OUT; + stop_signal_received_time_ptr_.reset(); return true; } first_ref_stop_path_point_index_ = stop_line_point_idx; // Check if stop is coming. - setSafe(!isStopSignal()); + const bool is_stop_signal = isStopSignal(); + + // Update stop signal received time + if (is_stop_signal) { + if (!stop_signal_received_time_ptr_) { + stop_signal_received_time_ptr_ = std::make_unique diff --git a/system/autoware_auto_msgs_adapter/package.xml b/system/autoware_auto_msgs_adapter/package.xml index 99a94fa043565..2941820550ba0 100644 --- a/system/autoware_auto_msgs_adapter/package.xml +++ b/system/autoware_auto_msgs_adapter/package.xml @@ -22,9 +22,11 @@ autoware_auto_control_msgs autoware_auto_mapping_msgs autoware_auto_perception_msgs + autoware_auto_planning_msgs autoware_control_msgs autoware_map_msgs autoware_perception_msgs + autoware_planning_msgs rclcpp rclcpp_components diff --git a/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json b/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json index f6aa87f774528..a5d6c93029d09 100644 --- a/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json +++ b/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json @@ -12,7 +12,8 @@ "enum": [ "autoware_auto_control_msgs/msg/AckermannControlCommand", "autoware_auto_mapping_msgs/msg/HADMapBin", - "autoware_auto_perception_msgs/msg/PredictedObjects" + "autoware_auto_perception_msgs/msg/PredictedObjects", + "autoware_auto_planning_msgs/msg/Trajectory" ], "default": "autoware_auto_control_msgs/msg/AckermannControlCommand" }, diff --git a/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index 15e3c90d227dd..6a23970246866 100644 --- a/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -67,6 +67,11 @@ MapStringAdapter AutowareAutoMsgsAdapterNode::create_adapter_map( return std::static_pointer_cast( std::make_shared(*this, topic_name_source, topic_name_target)); }}, + {"autoware_auto_planning_msgs/msg/Trajectory", + [&] { + return std::static_pointer_cast( + std::make_shared(*this, topic_name_source, topic_name_target)); + }}, }; } diff --git a/system/autoware_auto_msgs_adapter/src/include/adapter_planning.hpp b/system/autoware_auto_msgs_adapter/src/include/adapter_planning.hpp new file mode 100644 index 0000000000000..79d73bdda0575 --- /dev/null +++ b/system/autoware_auto_msgs_adapter/src/include/adapter_planning.hpp @@ -0,0 +1,70 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef ADAPTER_PLANNING_HPP_ +#define ADAPTER_PLANNING_HPP_ + +#include "adapter_base.hpp" + +#include + +#include +#include + +#include + +namespace autoware_auto_msgs_adapter +{ +using TrajectoryAuto = autoware_auto_planning_msgs::msg::Trajectory; +using PointAuto = autoware_auto_planning_msgs::msg::TrajectoryPoint; +using Trajectory = autoware_planning_msgs::msg::Trajectory; + +class AdapterPlanning : public autoware_auto_msgs_adapter::AdapterBase +{ +public: + AdapterPlanning( + rclcpp::Node & node, const std::string & topic_name_source, + const std::string & topic_name_target, const rclcpp::QoS & qos = rclcpp::QoS{1}) + : AdapterBase(node, topic_name_source, topic_name_target, qos) + { + RCLCPP_DEBUG( + node.get_logger(), "AdapterPlanning is initialized to convert: %s -> %s", + topic_name_source.c_str(), topic_name_target.c_str()); + } + +protected: + TrajectoryAuto convert(const Trajectory & msg_source) override + { + TrajectoryAuto msg_auto; + msg_auto.header = msg_source.header; + PointAuto trajectory_point_auto; + msg_auto.points.reserve(msg_source.points.size()); + for (size_t i = 0; i < msg_source.points.size(); i++) { + trajectory_point_auto.time_from_start = msg_source.points.at(i).time_from_start; + trajectory_point_auto.pose = msg_source.points.at(i).pose; + trajectory_point_auto.longitudinal_velocity_mps = + msg_source.points.at(i).longitudinal_velocity_mps; + trajectory_point_auto.lateral_velocity_mps = msg_source.points.at(i).lateral_velocity_mps; + trajectory_point_auto.acceleration_mps2 = msg_source.points.at(i).acceleration_mps2; + trajectory_point_auto.heading_rate_rps = msg_source.points.at(i).heading_rate_rps; + trajectory_point_auto.front_wheel_angle_rad = msg_source.points.at(i).front_wheel_angle_rad; + trajectory_point_auto.rear_wheel_angle_rad = msg_source.points.at(i).rear_wheel_angle_rad; + msg_auto.points.push_back(trajectory_point_auto); + } + + return msg_auto; + } +}; +} // namespace autoware_auto_msgs_adapter + +#endif // ADAPTER_PLANNING_HPP_ diff --git a/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp b/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp index f0e28f48aacd8..258bf01244499 100644 --- a/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp +++ b/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp @@ -17,6 +17,7 @@ #include "adapter_control.hpp" #include "adapter_map.hpp" #include "adapter_perception.hpp" +#include "adapter_planning.hpp" #include diff --git a/system/autoware_auto_msgs_adapter/test/test_msg_planning_trajectory.cpp b/system/autoware_auto_msgs_adapter/test/test_msg_planning_trajectory.cpp new file mode 100644 index 0000000000000..e2d44d6085c8a --- /dev/null +++ b/system/autoware_auto_msgs_adapter/test/test_msg_planning_trajectory.cpp @@ -0,0 +1,149 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include + +autoware_planning_msgs::msg::Trajectory generate_planning_msg() +{ + using TrajectoryPoint = autoware_planning_msgs::msg::TrajectoryPoint; + // generate deterministic random int + std::mt19937 gen(0); + std::uniform_int_distribution<> dis_int(0, 1000000); + auto rand_int = [&dis_int, &gen]() { return dis_int(gen); }; + + autoware_planning_msgs::msg::Trajectory msg_planning; + msg_planning.header.stamp = rclcpp::Time(rand_int()); + msg_planning.header.frame_id = "test_frame"; + + TrajectoryPoint point; + geometry_msgs::msg::Pose pose; + pose.position.x = 0.0; + pose.position.y = 0.0; + pose.position.z = 0.0; + pose.orientation.x = 0.0; + pose.orientation.y = 0.0; + pose.orientation.z = 0.0; + pose.orientation.w = 1.0; + + for (size_t i = 0; i < 100; i++) { + point.longitudinal_velocity_mps = 1.0; + point.time_from_start = rclcpp::Duration::from_seconds(0.0); + point.pose = pose; + point.longitudinal_velocity_mps = 20.0; + point.lateral_velocity_mps = 0.0; + point.acceleration_mps2 = 1.0; + point.heading_rate_rps = 2.0; + point.front_wheel_angle_rad = 8.0; + point.rear_wheel_angle_rad = 10.0; + + msg_planning.points.push_back(point); + } + + return msg_planning; +} + +TEST(AutowareAutoMsgsAdapter, TestTrajectory) // NOLINT for gtest +{ + const std::string msg_type_target = "autoware_auto_planning_msgs/msg/Trajectory"; + const std::string topic_name_source = "topic_name_source"; + const std::string topic_name_target = "topic_name_target"; + + std::cout << "Creating the adapter node..." << std::endl; + + rclcpp::NodeOptions node_options; + node_options.append_parameter_override("msg_type_target", msg_type_target); + node_options.append_parameter_override("topic_name_source", topic_name_source); + node_options.append_parameter_override("topic_name_target", topic_name_target); + + using autoware_auto_msgs_adapter::AutowareAutoMsgsAdapterNode; + AutowareAutoMsgsAdapterNode::SharedPtr node_adapter; + node_adapter = std::make_shared(node_options); + + std::cout << "Creating the subscriber node..." << std::endl; + + auto node_subscriber = std::make_shared("node_subscriber", rclcpp::NodeOptions{}); + + bool test_completed = false; + + const auto msg_planning = generate_planning_msg(); + auto sub = node_subscriber->create_subscription( + topic_name_target, rclcpp::QoS{1}, + [&msg_planning, + &test_completed](const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg) { + EXPECT_EQ(msg->header.stamp, msg_planning.header.stamp); + EXPECT_EQ(msg->header.frame_id, msg_planning.header.frame_id); + for (size_t i = 0; i < msg_planning.points.size(); i++) { + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.position.x, msg_planning.points.at(i).pose.position.x); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.position.y, msg_planning.points.at(i).pose.position.y); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.position.z, msg_planning.points.at(i).pose.position.z); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.orientation.x, msg_planning.points.at(i).pose.orientation.x); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.orientation.y, msg_planning.points.at(i).pose.orientation.y); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.orientation.z, msg_planning.points.at(i).pose.orientation.z); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.orientation.w, msg_planning.points.at(i).pose.orientation.w); + EXPECT_FLOAT_EQ( + msg->points.at(i).longitudinal_velocity_mps, + msg_planning.points.at(i).longitudinal_velocity_mps); + EXPECT_FLOAT_EQ( + msg->points.at(i).lateral_velocity_mps, msg_planning.points.at(i).lateral_velocity_mps); + EXPECT_FLOAT_EQ( + msg->points.at(i).acceleration_mps2, msg_planning.points.at(i).acceleration_mps2); + EXPECT_FLOAT_EQ( + msg->points.at(i).heading_rate_rps, msg_planning.points.at(i).heading_rate_rps); + EXPECT_FLOAT_EQ( + msg->points.at(i).front_wheel_angle_rad, msg_planning.points.at(i).front_wheel_angle_rad); + EXPECT_FLOAT_EQ( + msg->points.at(i).rear_wheel_angle_rad, msg_planning.points.at(i).rear_wheel_angle_rad); + } + + test_completed = true; + }); + + std::cout << "Creating the publisher node..." << std::endl; + + auto node_publisher = std::make_shared("node_publisher", rclcpp::NodeOptions{}); + auto pub = node_publisher->create_publisher( + topic_name_source, rclcpp::QoS{1}); + pub->publish(msg_planning); + + auto start_time = std::chrono::system_clock::now(); + auto max_test_dur = std::chrono::seconds(5); + auto timed_out = false; + + while (rclcpp::ok() && !test_completed) { + rclcpp::spin_some(node_subscriber); + rclcpp::spin_some(node_adapter); + rclcpp::spin_some(node_publisher); + rclcpp::sleep_for(std::chrono::milliseconds(50)); + if (std::chrono::system_clock::now() - start_time > max_test_dur) { + timed_out = true; + break; + } + } + + EXPECT_TRUE(test_completed); + EXPECT_FALSE(timed_out); + + // rclcpp::shutdown(); +} From a43a16f8707a83c4dcfd7738c99645ad9ab4a15e Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Wed, 13 Dec 2023 22:02:36 +0900 Subject: [PATCH 059/276] chore: add glog_component for pointcloud_container (#5716) Signed-off-by: badai-nguyen --- .../ground_segmentation/ground_segmentation.launch.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) 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 32a3fa102897d..fecdd29bcb7e9 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 @@ -474,7 +474,13 @@ def get_single_frame_obstacle_segmentation_concatenated_component(input_topics, def launch_setup(context, *args, **kwargs): pipeline = GroundSegmentationPipeline(context) - components = [] + glog_component = ComposableNode( + package="glog_component", + plugin="GlogComponent", + name="glog_component", + ) + + components = [glog_component] components.extend( pipeline.create_single_frame_obstacle_segmentation_components( input_topic=LaunchConfiguration("input/pointcloud"), From 2cad40cb97987efa79f72e1ca651314d5be11a40 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 14 Dec 2023 09:13:57 +0900 Subject: [PATCH 060/276] refactor(ar_tag_based_localizer): refactor pub/sub and so on (#5854) * Fixed ar_tag_based_localizer pub/sub Signed-off-by: Shintaro SAKODA * Remove dependency on image_transport Signed-off-by: Shintaro SAKODA --------- Signed-off-by: Shintaro SAKODA --- .../ar_tag_based_localizer.launch.xml | 20 ++--- .../launch/ar_tag_based_localizer.launch.xml | 10 ++- .../ar_tag_based_localizer/package.xml | 1 - .../src/ar_tag_based_localizer.cpp | 79 +++++++------------ .../src/ar_tag_based_localizer.hpp | 13 ++- .../ar_tag_based_localizer/src/main.cpp | 1 - .../ar_tag_based_localizer/test/test.cpp | 3 +- 7 files changed, 50 insertions(+), 77 deletions(-) diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml index 181f470a00800..ac7589ea2273b 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml @@ -1,17 +1,13 @@ - - - - - - - - - - - - + + + + + + + + diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml index 6437455875cc2..272338905c3f0 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml @@ -8,18 +8,24 @@ - + + + + - + + + + diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index 7e83220dadf2a..857ec4f16f051 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -17,7 +17,6 @@ aruco cv_bridge diagnostic_msgs - image_transport landmark_manager lanelet2_extension localization_util diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index e569a71bbb5b0..a1e2f3ec31dd3 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -66,10 +66,6 @@ ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options) : Node("ar_tag_based_localizer", options), cam_info_received_(false) -{ -} - -bool ArTagBasedLocalizer::setup() { /* Declare node parameters @@ -92,7 +88,7 @@ bool ArTagBasedLocalizer::setup() } else { // Error RCLCPP_ERROR_STREAM(this->get_logger(), "Invalid detection_mode: " << detection_mode); - return false; + return; } ekf_pose_buffer_ = std::make_unique( this->get_logger(), ekf_time_tolerance_, ekf_position_tolerance_); @@ -111,59 +107,50 @@ bool ArTagBasedLocalizer::setup() tf_buffer_ = std::make_unique(this->get_clock()); tf_listener_ = std::make_unique(*tf_buffer_); - /* - Initialize image transport - */ - it_ = std::make_unique(shared_from_this()); - /* Subscribers */ + using std::placeholders::_1; map_bin_sub_ = this->create_subscription( "~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal), - std::bind(&ArTagBasedLocalizer::map_bin_callback, this, std::placeholders::_1)); + std::bind(&ArTagBasedLocalizer::map_bin_callback, this, _1)); rclcpp::QoS qos_sub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); qos_sub.best_effort(); - pose_array_pub_ = this->create_publisher("~/debug/detected_landmarks", qos_sub); image_sub_ = this->create_subscription( - "~/input/image", qos_sub, - std::bind(&ArTagBasedLocalizer::image_callback, this, std::placeholders::_1)); + "~/input/image", qos_sub, std::bind(&ArTagBasedLocalizer::image_callback, this, _1)); cam_info_sub_ = this->create_subscription( - "~/input/camera_info", qos_sub, - std::bind(&ArTagBasedLocalizer::cam_info_callback, this, std::placeholders::_1)); + "~/input/camera_info", qos_sub, std::bind(&ArTagBasedLocalizer::cam_info_callback, this, _1)); ekf_pose_sub_ = this->create_subscription( - "~/input/ekf_pose", qos_sub, - std::bind(&ArTagBasedLocalizer::ekf_pose_callback, this, std::placeholders::_1)); + "~/input/ekf_pose", qos_sub, std::bind(&ArTagBasedLocalizer::ekf_pose_callback, this, _1)); /* Publishers */ - rclcpp::QoS qos_marker = rclcpp::QoS(rclcpp::KeepLast(10)); - qos_marker.transient_local(); - qos_marker.reliable(); - marker_pub_ = this->create_publisher("~/debug/marker", qos_marker); - rclcpp::QoS qos_pub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); - image_pub_ = it_->advertise("~/debug/result", 1); - pose_pub_ = - this->create_publisher("~/output/pose_with_covariance", qos_pub); - diag_pub_ = this->create_publisher("/diagnostics", qos_pub); + const rclcpp::QoS qos_pub_once = rclcpp::QoS(rclcpp::KeepLast(10)).transient_local().reliable(); + const rclcpp::QoS qos_pub_periodic(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); + pose_pub_ = this->create_publisher( + "~/output/pose_with_covariance", qos_pub_periodic); + image_pub_ = this->create_publisher("~/debug/image", qos_pub_periodic); + mapped_tag_pose_pub_ = this->create_publisher("~/debug/mapped_tag", qos_pub_once); + detected_tag_pose_pub_ = + this->create_publisher("~/debug/detected_tag", qos_pub_periodic); + diag_pub_ = this->create_publisher("/diagnostics", qos_pub_periodic); RCLCPP_INFO(this->get_logger(), "Setup of ar_tag_based_localizer node is successful!"); - return true; } void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg) { landmark_manager_.parse_landmarks(msg, "apriltag_16h5", this->get_logger()); const MarkerArray marker_msg = landmark_manager_.get_landmarks_as_marker_array_msg(); - marker_pub_->publish(marker_msg); + mapped_tag_pose_pub_->publish(marker_msg); } void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) { // check subscribers - if ((image_pub_.getNumSubscribers() == 0) && (pose_pub_->get_subscription_count() == 0)) { + if ((image_pub_->get_subscription_count() == 0) && (pose_pub_->get_subscription_count() == 0)) { RCLCPP_DEBUG(this->get_logger(), "No subscribers, not looking for ArUco markers"); return; } @@ -192,7 +179,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) } // for debug - if (pose_array_pub_->get_subscription_count() > 0) { + if (detected_tag_pose_pub_->get_subscription_count() > 0) { PoseArray pose_array_msg; pose_array_msg.header.stamp = sensor_stamp; pose_array_msg.header.frame_id = "map"; @@ -201,7 +188,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) tier4_autoware_utils::transformPose(landmark.pose, self_pose); pose_array_msg.poses.push_back(detected_marker_on_map); } - pose_array_pub_->publish(pose_array_msg); + detected_tag_pose_pub_->publish(pose_array_msg); } // calc new_self_pose @@ -267,24 +254,12 @@ void ArTagBasedLocalizer::cam_info_callback(const CameraInfo::ConstSharedPtr & m return; } - cv::Mat camera_matrix(3, 4, CV_64FC1, 0.0); - camera_matrix.at(0, 0) = msg->p[0]; - camera_matrix.at(0, 1) = msg->p[1]; - camera_matrix.at(0, 2) = msg->p[2]; - camera_matrix.at(0, 3) = msg->p[3]; - camera_matrix.at(1, 0) = msg->p[4]; - camera_matrix.at(1, 1) = msg->p[5]; - camera_matrix.at(1, 2) = msg->p[6]; - camera_matrix.at(1, 3) = msg->p[7]; - camera_matrix.at(2, 0) = msg->p[8]; - camera_matrix.at(2, 1) = msg->p[9]; - camera_matrix.at(2, 2) = msg->p[10]; - camera_matrix.at(2, 3) = msg->p[11]; - - cv::Mat distortion_coeff(4, 1, CV_64FC1); - for (int i = 0; i < 4; ++i) { - distortion_coeff.at(i, 0) = 0; - } + // copy camera matrix + cv::Mat camera_matrix(3, 4, CV_64FC1); + std::copy(msg->p.begin(), msg->p.end(), camera_matrix.begin()); + + // all 0 + cv::Mat distortion_coeff(4, 1, CV_64FC1, 0.0); const cv::Size size(static_cast(msg->width), static_cast(msg->height)); @@ -361,12 +336,12 @@ std::vector ArTagBasedLocalizer::detect_landmarks( } // for debug - if (image_pub_.getNumSubscribers() > 0) { + if (image_pub_->get_subscription_count() > 0) { cv_bridge::CvImage out_msg; out_msg.header.stamp = sensor_stamp; out_msg.encoding = sensor_msgs::image_encodings::RGB8; out_msg.image = in_image; - image_pub_.publish(out_msg.toImageMsg()); + image_pub_->publish(*out_msg.toImageMsg()); } return landmarks; diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp index b7dfb45a26ce3..eb7406f8c77f8 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp @@ -48,11 +48,12 @@ #include "landmark_manager/landmark_manager.hpp" #include "localization_util/smart_pose_buffer.hpp" -#include #include #include #include +#include +#include #include #include @@ -82,7 +83,6 @@ class ArTagBasedLocalizer : public rclcpp::Node public: explicit ArTagBasedLocalizer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); - bool setup(); private: void map_bin_callback(const HADMapBin::ConstSharedPtr & msg); @@ -104,9 +104,6 @@ class ArTagBasedLocalizer : public rclcpp::Node std::unique_ptr tf_buffer_; std::unique_ptr tf_listener_; - // image transport - std::unique_ptr it_; - // Subscribers rclcpp::Subscription::SharedPtr map_bin_sub_; rclcpp::Subscription::SharedPtr image_sub_; @@ -114,10 +111,10 @@ class ArTagBasedLocalizer : public rclcpp::Node rclcpp::Subscription::SharedPtr ekf_pose_sub_; // Publishers - rclcpp::Publisher::SharedPtr marker_pub_; - rclcpp::Publisher::SharedPtr pose_array_pub_; - image_transport::Publisher image_pub_; rclcpp::Publisher::SharedPtr pose_pub_; + rclcpp::Publisher::SharedPtr image_pub_; + rclcpp::Publisher::SharedPtr detected_tag_pose_pub_; + rclcpp::Publisher::SharedPtr mapped_tag_pose_pub_; rclcpp::Publisher::SharedPtr diag_pub_; // Others diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp index cbcd57b4b222a..8ef1dd6195580 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp @@ -48,7 +48,6 @@ int main(int argc, char ** argv) { rclcpp::init(argc, argv); std::shared_ptr ptr = std::make_shared(); - ptr->setup(); rclcpp::spin(ptr); rclcpp::shutdown(); } diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp index 1b44327fd9e8b..5d05dd7e3755a 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp @@ -55,7 +55,8 @@ class TestArTagBasedLocalizer : public ::testing::Test TEST_F(TestArTagBasedLocalizer, test_setup) // NOLINT { - EXPECT_TRUE(node_->setup()); + // Check if the constructor finishes successfully + EXPECT_TRUE(true); } int main(int argc, char ** argv) From 690feb1e714c7f9e4a688e90afa0affad5d2cd8c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Kaan=20=C3=87olak?= Date: Thu, 14 Dec 2023 04:07:00 +0300 Subject: [PATCH 061/276] feat(shape_estimation): add bicycle shape corrector (#5860) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * feat(shape_estimation): add bicycle shape corrector Signed-off-by: Kaan Çolak * style(pre-commit): autofix * feat(shape_estimation): add bicycle shape corrector Signed-off-by: Kaan Çolak --------- Signed-off-by: Kaan Çolak Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../corrector/bicycle_corrector.hpp | 40 +++++++++++++++++++ .../shape_estimation/corrector/corrector.hpp | 1 + .../shape_estimation/lib/shape_estimator.cpp | 2 + 3 files changed, 43 insertions(+) create mode 100644 perception/shape_estimation/include/shape_estimation/corrector/bicycle_corrector.hpp diff --git a/perception/shape_estimation/include/shape_estimation/corrector/bicycle_corrector.hpp b/perception/shape_estimation/include/shape_estimation/corrector/bicycle_corrector.hpp new file mode 100644 index 0000000000000..ec1a2b8a42973 --- /dev/null +++ b/perception/shape_estimation/include/shape_estimation/corrector/bicycle_corrector.hpp @@ -0,0 +1,40 @@ +// Copyright 2018 Autoware Foundation. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef SHAPE_ESTIMATION__CORRECTOR__BICYCLE_CORRECTOR_HPP_ +#define SHAPE_ESTIMATION__CORRECTOR__BICYCLE_CORRECTOR_HPP_ + +#include "shape_estimation/corrector/vehicle_corrector.hpp" +#include "utils.hpp" + +class BicycleCorrector : public VehicleCorrector +{ +public: + explicit BicycleCorrector(const bool use_reference_yaw = false) + : VehicleCorrector(use_reference_yaw) + { + corrector_utils::CorrectionBBParameters params; + params.min_width = 0.3; + params.max_width = 1.2; + params.default_width = (params.min_width + params.max_width) * 0.5; + params.min_length = 1.0; + params.max_length = 2.8; + params.default_length = (params.min_length + params.max_length) * 0.5; + setParams(params); + } + + ~BicycleCorrector() = default; +}; + +#endif // SHAPE_ESTIMATION__CORRECTOR__BICYCLE_CORRECTOR_HPP_ diff --git a/perception/shape_estimation/include/shape_estimation/corrector/corrector.hpp b/perception/shape_estimation/include/shape_estimation/corrector/corrector.hpp index d52bdc21f916f..e4efc17181e52 100644 --- a/perception/shape_estimation/include/shape_estimation/corrector/corrector.hpp +++ b/perception/shape_estimation/include/shape_estimation/corrector/corrector.hpp @@ -15,6 +15,7 @@ #ifndef SHAPE_ESTIMATION__CORRECTOR__CORRECTOR_HPP_ #define SHAPE_ESTIMATION__CORRECTOR__CORRECTOR_HPP_ +#include "shape_estimation/corrector/bicycle_corrector.hpp" #include "shape_estimation/corrector/bus_corrector.hpp" #include "shape_estimation/corrector/car_corrector.hpp" #include "shape_estimation/corrector/corrector_interface.hpp" diff --git a/perception/shape_estimation/lib/shape_estimator.cpp b/perception/shape_estimation/lib/shape_estimator.cpp index 9577b1e2d3197..e89eaac0a6db0 100644 --- a/perception/shape_estimation/lib/shape_estimator.cpp +++ b/perception/shape_estimation/lib/shape_estimator.cpp @@ -120,6 +120,8 @@ bool ShapeEstimator::applyCorrector( corrector_ptr.reset(new TruckCorrector(use_reference_yaw)); } else if (label == Label::TRAILER) { corrector_ptr.reset(new TrailerCorrector(use_reference_yaw)); + } else if (label == Label::MOTORCYCLE || label == Label::BICYCLE) { + corrector_ptr.reset(new BicycleCorrector(use_reference_yaw)); } else { corrector_ptr.reset(new NoCorrector); } From 7b623b627effcb5fa233e5c446239d5600c5f622 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 14 Dec 2023 14:05:50 +0900 Subject: [PATCH 062/276] feat(simple_planning_simulator): add mesurent_steer_bias (#5868) * feat(simple_planning_simulator): add mesurent_steer_bias Signed-off-by: kosuke55 * style(pre-commit): autofix --------- Signed-off-by: kosuke55 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- simulator/simple_planning_simulator/README.md | 23 ++++++++++--------- .../simple_planning_simulator_core.hpp | 3 +++ .../simple_planning_simulator_core.cpp | 4 ++++ 3 files changed, 19 insertions(+), 11 deletions(-) diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index b441f9f903d0d..ed2b06ee1f44d 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -40,17 +40,18 @@ The purpose of this simulator is for the integration test of planning and contro ### Common Parameters -| Name | Type | Description | Default value | -| :-------------------- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------- | :------------------- | -| simulated_frame_id | string | set to the child_frame_id in output tf | "base_link" | -| origin_frame_id | string | set to the frame_id in output tf | "odom" | -| initialize_source | string | If "ORIGIN", the initial pose is set at (0,0,0). If "INITIAL_POSE_TOPIC", node will wait until the `input/initialpose` topic is published. | "INITIAL_POSE_TOPIC" | -| add_measurement_noise | bool | If true, the Gaussian noise is added to the simulated results. | true | -| pos_noise_stddev | double | Standard deviation for position noise | 0.01 | -| rpy_noise_stddev | double | Standard deviation for Euler angle noise | 0.0001 | -| vel_noise_stddev | double | Standard deviation for longitudinal velocity noise | 0.0 | -| angvel_noise_stddev | double | Standard deviation for angular velocity noise | 0.0 | -| steer_noise_stddev | double | Standard deviation for steering angle noise | 0.0001 | +| Name | Type | Description | Default value | +| :--------------------- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------- | :------------------- | +| simulated_frame_id | string | set to the child_frame_id in output tf | "base_link" | +| origin_frame_id | string | set to the frame_id in output tf | "odom" | +| initialize_source | string | If "ORIGIN", the initial pose is set at (0,0,0). If "INITIAL_POSE_TOPIC", node will wait until the `input/initialpose` topic is published. | "INITIAL_POSE_TOPIC" | +| add_measurement_noise | bool | If true, the Gaussian noise is added to the simulated results. | true | +| pos_noise_stddev | double | Standard deviation for position noise | 0.01 | +| rpy_noise_stddev | double | Standard deviation for Euler angle noise | 0.0001 | +| vel_noise_stddev | double | Standard deviation for longitudinal velocity noise | 0.0 | +| angvel_noise_stddev | double | Standard deviation for angular velocity noise | 0.0 | +| steer_noise_stddev | double | Standard deviation for steering angle noise | 0.0001 | +| measurement_steer_bias | double | Measurement bias for steering angle | 0.0 | ### Vehicle Model Parameters diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp index 38f689c124439..d096130e65f05 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -195,6 +195,9 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node bool is_initialized_ = false; //!< @brief flag to check the initial position is set bool add_measurement_noise_ = false; //!< @brief flag to add measurement noise + /* measurement bias */ + double measurement_steer_bias_ = 0.0; //!< @brief measurement bias for steering measurement + DeltaTime delta_time_{}; //!< @brief to calculate delta time MeasurementNoiseGenerator measurement_noise_{}; //!< @brief for measurement noise diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 9a0ea6a6c3659..8de5be9d71503 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -102,6 +102,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt simulated_frame_id_ = declare_parameter("simulated_frame_id", "base_link"); origin_frame_id_ = declare_parameter("origin_frame_id", "odom"); add_measurement_noise_ = declare_parameter("add_measurement_noise", false); + measurement_steer_bias_ = declare_parameter("measurement_steer_bias", 0.0); simulate_motion_ = declare_parameter("initial_engage_state"); enable_road_slope_simulation_ = declare_parameter("enable_road_slope_simulation", false); @@ -381,6 +382,9 @@ void SimplePlanningSimulator::on_timer() add_measurement_noise(current_odometry_, current_velocity_, current_steer_); } + // add measurement bias + current_steer_.steering_tire_angle += measurement_steer_bias_; + // add estimate covariance { using COV_IDX = tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; From 6cb720d95ccc1fe8309989bb2d6568a05013d3b3 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 14 Dec 2023 16:00:11 +0900 Subject: [PATCH 063/276] feat(diagnostic_graph_aggregator): rename system_diagnostic_graph package (#5827) Signed-off-by: Takagi, Isamu --- .../CMakeLists.txt | 24 +- .../README.md | 49 +- .../config/default.param.yaml | 0 .../doc/format/and.md | 0 .../doc/format/diag.md | 10 + .../doc/format/graph-file.md | 0 .../doc/format/node.md | 0 .../doc/format/or.md | 0 .../doc/format/path.md | 0 .../doc/format/unit.md | 0 .../doc/message.drawio.svg | 677 ++++++++++++++++++ .../doc/overview.drawio.svg | 0 .../example/example.launch.xml | 7 + .../example/example_0.yaml | 4 +- .../example/example_1.yaml | 0 .../example/example_2.yaml | 0 .../example/example_diags.py | 0 .../diagnostic_graph_aggregator.launch.xml | 8 + .../package.xml | 4 +- .../src/common/graph}/config.cpp | 4 +- .../src/common/graph}/config.hpp | 10 +- .../src/common/graph}/debug.cpp | 4 +- .../src/common/graph}/debug.hpp | 10 +- .../src/common/graph}/error.hpp | 10 +- .../src/common/graph}/graph.cpp | 4 +- .../src/common/graph}/graph.hpp | 10 +- .../src/common/graph}/types.hpp | 10 +- .../src/common/graph}/units.cpp | 4 +- .../src/common/graph}/units.hpp | 10 +- .../src/node/aggregator.cpp} | 10 +- .../src/node/aggregator.hpp} | 16 +- .../src/node/converter.cpp} | 10 +- .../src/node/converter.hpp} | 12 +- .../src/node/plugin}/modes.cpp | 10 +- .../src/node/plugin}/modes.hpp | 12 +- .../src/tool/tool.cpp} | 12 +- .../test/files/test1/field-not-found.yaml | 0 .../test/files/test1/file-not-found.yaml | 0 .../test/files/test1/graph-circulation.yaml | 0 .../test/files/test1/invalid-dict-type.yaml | 0 .../test/files/test1/invalid-list-type.yaml | 0 .../test/files/test1/path-conflict.yaml | 0 .../test/files/test1/path-not-found.yaml | 0 .../test/files/test1/unknown-node-type.yaml | 0 .../files/test1/unknown-substitution.yaml | 0 .../test/files/test2/and.yaml | 0 .../test/files/test2/or.yaml | 0 .../test/files/test2/warn-to-error.yaml | 0 .../test/files/test2/warn-to-ok.yaml | 0 .../test/src/test1.cpp | 6 +- .../test/src/test2.cpp | 6 +- .../test/src/utils.cpp | 0 .../test/src/utils.hpp | 0 .../doc/format/diag.md | 11 - .../example/example.launch.xml | 6 - .../launch/system_diagnostic_graph.launch.xml | 9 - 56 files changed, 835 insertions(+), 144 deletions(-) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/CMakeLists.txt (56%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/README.md (51%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/config/default.param.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/and.md (100%) create mode 100644 system/diagnostic_graph_aggregator/doc/format/diag.md rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/graph-file.md (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/node.md (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/or.md (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/path.md (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/unit.md (100%) create mode 100644 system/diagnostic_graph_aggregator/doc/message.drawio.svg rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/overview.drawio.svg (100%) create mode 100644 system/diagnostic_graph_aggregator/example/example.launch.xml rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/example/example_0.yaml (83%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/example/example_1.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/example/example_2.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/example/example_diags.py (100%) create mode 100644 system/diagnostic_graph_aggregator/launch/diagnostic_graph_aggregator.launch.xml rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/package.xml (87%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/config.cpp (99%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/config.hpp (94%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/debug.cpp (96%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/debug.hpp (79%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/error.hpp (87%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/graph.cpp (98%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/graph.hpp (86%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/types.hpp (86%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/units.cpp (98%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/units.hpp (95%) rename system/{system_diagnostic_graph/src/main.cpp => diagnostic_graph_aggregator/src/node/aggregator.cpp} (90%) rename system/{system_diagnostic_graph/src/main.hpp => diagnostic_graph_aggregator/src/node/aggregator.hpp} (80%) rename system/{system_diagnostic_graph/src/tool.cpp => diagnostic_graph_aggregator/src/node/converter.cpp} (90%) rename system/{system_diagnostic_graph/src/tool.hpp => diagnostic_graph_aggregator/src/node/converter.hpp} (81%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/node/plugin}/modes.cpp (93%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/node/plugin}/modes.hpp (85%) rename system/{system_diagnostic_graph/src/tool/main.cpp => diagnostic_graph_aggregator/src/tool/tool.cpp} (94%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/field-not-found.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/file-not-found.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/graph-circulation.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/invalid-dict-type.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/invalid-list-type.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/path-conflict.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/path-not-found.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/unknown-node-type.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/unknown-substitution.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test2/and.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test2/or.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test2/warn-to-error.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test2/warn-to-ok.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/src/test1.cpp (94%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/src/test2.cpp (97%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/src/utils.cpp (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/src/utils.hpp (100%) delete mode 100644 system/system_diagnostic_graph/doc/format/diag.md delete mode 100644 system/system_diagnostic_graph/example/example.launch.xml delete mode 100644 system/system_diagnostic_graph/launch/system_diagnostic_graph.launch.xml diff --git a/system/system_diagnostic_graph/CMakeLists.txt b/system/diagnostic_graph_aggregator/CMakeLists.txt similarity index 56% rename from system/system_diagnostic_graph/CMakeLists.txt rename to system/diagnostic_graph_aggregator/CMakeLists.txt index be0fc19188a0b..188b1509dfca0 100644 --- a/system/system_diagnostic_graph/CMakeLists.txt +++ b/system/diagnostic_graph_aggregator/CMakeLists.txt @@ -1,29 +1,31 @@ cmake_minimum_required(VERSION 3.14) -project(system_diagnostic_graph) +project(diagnostic_graph_aggregator) find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED - src/core/config.cpp - src/core/debug.cpp - src/core/graph.cpp - src/core/units.cpp - src/core/modes.cpp + src/common/graph/config.cpp + src/common/graph/debug.cpp + src/common/graph/graph.cpp + src/common/graph/units.cpp ) ament_auto_add_executable(aggregator - src/main.cpp + src/node/aggregator.cpp + src/node/plugin/modes.cpp ) +target_include_directories(aggregator PRIVATE src/common) ament_auto_add_executable(converter - src/tool.cpp + src/node/converter.cpp ) +target_include_directories(converter PRIVATE src/common) ament_auto_add_executable(tool - src/tool/main.cpp + src/tool/tool.cpp ) -target_include_directories(tool PRIVATE src/core) +target_include_directories(tool PRIVATE src/common) if(BUILD_TESTING) get_filename_component(RESOURCE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/test/files ABSOLUTE) @@ -33,7 +35,7 @@ if(BUILD_TESTING) test/src/utils.cpp ) target_compile_definitions(gtest_${PROJECT_NAME} PRIVATE TEST_RESOURCE_PATH="${RESOURCE_PATH}") - target_include_directories(gtest_${PROJECT_NAME} PRIVATE src) + target_include_directories(gtest_${PROJECT_NAME} PRIVATE src/common) endif() ament_auto_package(INSTALL_TO_SHARE config example launch) diff --git a/system/system_diagnostic_graph/README.md b/system/diagnostic_graph_aggregator/README.md similarity index 51% rename from system/system_diagnostic_graph/README.md rename to system/diagnostic_graph_aggregator/README.md index df22121a778fb..4dc44feaafc33 100644 --- a/system/system_diagnostic_graph/README.md +++ b/system/diagnostic_graph_aggregator/README.md @@ -1,13 +1,23 @@ -# System diagnostic graph +# diagnostic_graph_aggregator ## Overview -The system diagnostic graph node subscribes to diagnostic array and publishes aggregated diagnostic graph. +The diagnostic graph aggregator node subscribes to diagnostic array and publishes aggregated diagnostic graph. As shown in the diagram below, this node introduces extra diagnostic status for intermediate functional unit. Diagnostic status dependencies will be directed acyclic graph (DAG). ![overview](./doc/overview.drawio.svg) +## Diagnostics graph message + +The diagnostics graph that this node outputs is a combination of diagnostic status and connections between them. +This graph consists of an array of diagnostic nodes, and each node has a status and links. +This link contains an index indicating the position of the node in the graph. +Therefore, the graph can be reconstructed from the array of nodes using links. +The following is an example of a message representing the graph in the overview section. + +![message](./doc/message.drawio.svg) + ## Operation mode availability For MRM, this node publishes the status of the top-level functional units in the dedicated message. @@ -22,7 +32,7 @@ This feature breaks the generality of the graph and may be changed to a plugin o - /autoware/operation/comfortable-stop - /autoware/operation/pull-over -## Interface +## Interfaces | Interface Type | Interface Name | Data Type | Description | | -------------- | ------------------------------------- | ------------------------------------------------- | ------------------ | @@ -32,12 +42,24 @@ This feature breaks the generality of the graph and may be changed to a plugin o ## Parameters -| Parameter Name | Data Type | Description | -| ----------------- | --------- | ------------------------------------------ | -| `graph_file` | `string` | Path of the config file. | -| `rate` | `double` | Rate of aggregation and topic publication. | -| `input_qos_depth` | `uint` | QoS depth of input array topic. | -| `graph_qos_depth` | `uint` | QoS depth of output graph topic. | +| Parameter Name | Data Type | Description | +| --------------------------------- | --------- | ------------------------------------------ | +| `graph_file` | `string` | Path of the config file. | +| `rate` | `double` | Rate of aggregation and topic publication. | +| `input_qos_depth` | `uint` | QoS depth of input array topic. | +| `graph_qos_depth` | `uint` | QoS depth of output graph topic. | +| `use_operation_mode_availability` | `bool` | Use operation mode availability publisher. | +| `use_debug_mode` | `bool` | Use debug output to stdout. | + +## Examples + +- [example_0.yaml](./example/example_0.yaml) +- [example_1.yaml](./example/example_1.yaml) +- [example_2.yaml](./example/example_2.yaml) + +```bash +ros2 launch diagnostic_graph_aggregator example.launch.xml +``` ## Graph file format @@ -48,12 +70,3 @@ This feature breaks the generality of the graph and may be changed to a plugin o - [Unit](./doc/format/unit.md) - [And](./doc/format/and.md) - [Or](./doc/format/or.md) - -## Example - -- [example1.yaml](./example/example1.yaml) -- [example2.yaml](./example/example2.yaml) - -```bash -ros2 launch system_diagnostic_graph example.launch.xml -``` diff --git a/system/system_diagnostic_graph/config/default.param.yaml b/system/diagnostic_graph_aggregator/config/default.param.yaml similarity index 100% rename from system/system_diagnostic_graph/config/default.param.yaml rename to system/diagnostic_graph_aggregator/config/default.param.yaml diff --git a/system/system_diagnostic_graph/doc/format/and.md b/system/diagnostic_graph_aggregator/doc/format/and.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/and.md rename to system/diagnostic_graph_aggregator/doc/format/and.md diff --git a/system/diagnostic_graph_aggregator/doc/format/diag.md b/system/diagnostic_graph_aggregator/doc/format/diag.md new file mode 100644 index 0000000000000..04e850129cbbf --- /dev/null +++ b/system/diagnostic_graph_aggregator/doc/format/diag.md @@ -0,0 +1,10 @@ +# Diag + +Diag is a node that refers to a source diagnostics. + +## Format + +| Name | Type | Required | Description | +| ---- | ------ | -------- | -------------------------------------- | +| type | string | yes | Specify `diag` when using this object. | +| diag | string | yes | Name of diagnostic status. | diff --git a/system/system_diagnostic_graph/doc/format/graph-file.md b/system/diagnostic_graph_aggregator/doc/format/graph-file.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/graph-file.md rename to system/diagnostic_graph_aggregator/doc/format/graph-file.md diff --git a/system/system_diagnostic_graph/doc/format/node.md b/system/diagnostic_graph_aggregator/doc/format/node.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/node.md rename to system/diagnostic_graph_aggregator/doc/format/node.md diff --git a/system/system_diagnostic_graph/doc/format/or.md b/system/diagnostic_graph_aggregator/doc/format/or.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/or.md rename to system/diagnostic_graph_aggregator/doc/format/or.md diff --git a/system/system_diagnostic_graph/doc/format/path.md b/system/diagnostic_graph_aggregator/doc/format/path.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/path.md rename to system/diagnostic_graph_aggregator/doc/format/path.md diff --git a/system/system_diagnostic_graph/doc/format/unit.md b/system/diagnostic_graph_aggregator/doc/format/unit.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/unit.md rename to system/diagnostic_graph_aggregator/doc/format/unit.md diff --git a/system/diagnostic_graph_aggregator/doc/message.drawio.svg b/system/diagnostic_graph_aggregator/doc/message.drawio.svg new file mode 100644 index 0000000000000..aef836dccf235 --- /dev/null +++ b/system/diagnostic_graph_aggregator/doc/message.drawio.svg @@ -0,0 +1,677 @@ + + + + + + + +
+
+
+ Top LiDAR +
+
+
+
+ Top LiDAR +
+
+ + + + +
+
+
+ Front LiDAR +
+
+
+
+ Front LiDAR +
+
+ + + + +
+
+
+ obstacle detection +
+
+
+
+ obstacle detection +
+
+ + + + +
+
+
+ pose estimation +
+
+
+
+ pose estimation +
+
+ + + + +
+
+
+ autonomous +
+
+
+
+ autonomous +
+
+ + + + +
+
+
+ remote +
+
+
+
+ remote +
+
+ + + + +
+
+
+ remote command +
+
+
+
+ remote command +
+
+ + + + +
+
+
+ local +
+
+
+
+ local +
+
+ + + + +
+
+
+ joystick command +
+
+
+
+ joystick command +
+
+ + + + +
+
+
+ stop +
+
+
+
+ stop +
+
+ + + + +
+
+
+ Front radar +
+
+
+
+ Front radar +
+
+ + + + +
+
+
+ MRM +
+
+
+
+ MRM +
+
+ + + + +
+
+
+ index +
+
+
+
+ index +
+
+ + + + +
+
+
+ status +
+
+
+
+ status +
+
+ + + + +
+
+
+ 0 +
+
+
+
+ 0 +
+
+ + + + +
+
+
+ 1 +
+
+
+
+ 1 +
+
+ + + + +
+
+
+ 2 +
+
+
+
+ 2 +
+
+ + + + +
+
+
+ 3 +
+
+
+
+ 3 +
+
+ + + + +
+
+
+ 4 +
+
+
+
+ 4 +
+
+ + + + +
+
+
+ 5 +
+
+
+
+ 5 +
+
+ + + + +
+
+
+ 6 +
+
+
+
+ 6 +
+
+ + + + +
+
+
+ 7 +
+
+
+
+ 7 +
+
+ + + + +
+
+
+ 8 +
+
+
+
+ 8 +
+
+ + + + +
+
+
+ 9 +
+
+
+
+ 9 +
+
+ + + + +
+
+
+ 10 +
+
+
+
+ 10 +
+
+ + + + +
+
+
+ 11 +
+
+
+
+ 11 +
+
+ + + + +
+
+
+ links +
+
+
+
+ links +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ 10, 11 +
+
+
+
+ 10, 11 +
+
+ + + + +
+
+
+ 9 +
+
+
+
+ 9 +
+
+ + + + +
+
+
+ 5, 6 +
+
+
+
+ 5, 6 +
+
+ + + + +
+
+
+ 8 +
+
+
+
+ 8 +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ 7 +
+
+
+
+ 7 +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/system/system_diagnostic_graph/doc/overview.drawio.svg b/system/diagnostic_graph_aggregator/doc/overview.drawio.svg similarity index 100% rename from system/system_diagnostic_graph/doc/overview.drawio.svg rename to system/diagnostic_graph_aggregator/doc/overview.drawio.svg diff --git a/system/diagnostic_graph_aggregator/example/example.launch.xml b/system/diagnostic_graph_aggregator/example/example.launch.xml new file mode 100644 index 0000000000000..71e59a1833d6e --- /dev/null +++ b/system/diagnostic_graph_aggregator/example/example.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/system/system_diagnostic_graph/example/example_0.yaml b/system/diagnostic_graph_aggregator/example/example_0.yaml similarity index 83% rename from system/system_diagnostic_graph/example/example_0.yaml rename to system/diagnostic_graph_aggregator/example/example_0.yaml index ed92259b50721..7b01883723c76 100644 --- a/system/system_diagnostic_graph/example/example_0.yaml +++ b/system/diagnostic_graph_aggregator/example/example_0.yaml @@ -1,6 +1,6 @@ files: - - { path: $(find-pkg-share system_diagnostic_graph)/example/example_1.yaml } - - { path: $(find-pkg-share system_diagnostic_graph)/example/example_2.yaml } + - { path: $(find-pkg-share diagnostic_graph_aggregator)/example/example_1.yaml } + - { path: $(find-pkg-share diagnostic_graph_aggregator)/example/example_2.yaml } nodes: - path: /autoware/modes/stop diff --git a/system/system_diagnostic_graph/example/example_1.yaml b/system/diagnostic_graph_aggregator/example/example_1.yaml similarity index 100% rename from system/system_diagnostic_graph/example/example_1.yaml rename to system/diagnostic_graph_aggregator/example/example_1.yaml diff --git a/system/system_diagnostic_graph/example/example_2.yaml b/system/diagnostic_graph_aggregator/example/example_2.yaml similarity index 100% rename from system/system_diagnostic_graph/example/example_2.yaml rename to system/diagnostic_graph_aggregator/example/example_2.yaml diff --git a/system/system_diagnostic_graph/example/example_diags.py b/system/diagnostic_graph_aggregator/example/example_diags.py similarity index 100% rename from system/system_diagnostic_graph/example/example_diags.py rename to system/diagnostic_graph_aggregator/example/example_diags.py diff --git a/system/diagnostic_graph_aggregator/launch/diagnostic_graph_aggregator.launch.xml b/system/diagnostic_graph_aggregator/launch/diagnostic_graph_aggregator.launch.xml new file mode 100644 index 0000000000000..272901a3f8045 --- /dev/null +++ b/system/diagnostic_graph_aggregator/launch/diagnostic_graph_aggregator.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/system/system_diagnostic_graph/package.xml b/system/diagnostic_graph_aggregator/package.xml similarity index 87% rename from system/system_diagnostic_graph/package.xml rename to system/diagnostic_graph_aggregator/package.xml index 7855edcde9c62..2a9efad2c0d6e 100644 --- a/system/system_diagnostic_graph/package.xml +++ b/system/diagnostic_graph_aggregator/package.xml @@ -1,9 +1,9 @@ - system_diagnostic_graph + diagnostic_graph_aggregator 0.1.0 - The system_diagnostic_graph package + The diagnostic_graph_aggregator package Takagi, Isamu Apache License 2.0 diff --git a/system/system_diagnostic_graph/src/core/config.cpp b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp similarity index 99% rename from system/system_diagnostic_graph/src/core/config.cpp rename to system/diagnostic_graph_aggregator/src/common/graph/config.cpp index 4a32398a1b08f..39044d1c82bf9 100644 --- a/system/system_diagnostic_graph/src/core/config.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp @@ -30,7 +30,7 @@ // DEBUG #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { template @@ -351,4 +351,4 @@ RootConfig load_root_config(const std::string & path) return load_root_config(root); } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator diff --git a/system/system_diagnostic_graph/src/core/config.hpp b/system/diagnostic_graph_aggregator/src/common/graph/config.hpp similarity index 94% rename from system/system_diagnostic_graph/src/core/config.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/config.hpp index d7cdd0ec3c5f7..40f16235ed5d6 100644 --- a/system/system_diagnostic_graph/src/core/config.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__CONFIG_HPP_ -#define CORE__CONFIG_HPP_ +#ifndef COMMON__GRAPH__CONFIG_HPP_ +#define COMMON__GRAPH__CONFIG_HPP_ #include @@ -23,7 +23,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { struct ConfigData @@ -124,6 +124,6 @@ T error(const std::string & text, const std::string & value) RootConfig load_root_config(const std::string & path); -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__CONFIG_HPP_ +#endif // COMMON__GRAPH__CONFIG_HPP_ diff --git a/system/system_diagnostic_graph/src/core/debug.cpp b/system/diagnostic_graph_aggregator/src/common/graph/debug.cpp similarity index 96% rename from system/system_diagnostic_graph/src/core/debug.cpp rename to system/diagnostic_graph_aggregator/src/common/graph/debug.cpp index e2771f08f9f1e..8f2b741edd805 100644 --- a/system/system_diagnostic_graph/src/core/debug.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/debug.cpp @@ -23,7 +23,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { std::string get_level_text(DiagnosticLevel level) @@ -72,4 +72,4 @@ void Graph::debug() } } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator diff --git a/system/system_diagnostic_graph/src/core/debug.hpp b/system/diagnostic_graph_aggregator/src/common/graph/debug.hpp similarity index 79% rename from system/system_diagnostic_graph/src/core/debug.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/debug.hpp index 297356cd36bab..69a0eeb2c8023 100644 --- a/system/system_diagnostic_graph/src/core/debug.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/debug.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__DEBUG_HPP_ -#define CORE__DEBUG_HPP_ +#ifndef COMMON__GRAPH__DEBUG_HPP_ +#define COMMON__GRAPH__DEBUG_HPP_ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { constexpr size_t diag_debug_size = 4; using DiagDebugData = std::array; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__DEBUG_HPP_ +#endif // COMMON__GRAPH__DEBUG_HPP_ diff --git a/system/system_diagnostic_graph/src/core/error.hpp b/system/diagnostic_graph_aggregator/src/common/graph/error.hpp similarity index 87% rename from system/system_diagnostic_graph/src/core/error.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/error.hpp index 7e110654bf475..dadfab450c783 100644 --- a/system/system_diagnostic_graph/src/core/error.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/error.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__ERROR_HPP_ -#define CORE__ERROR_HPP_ +#ifndef COMMON__GRAPH__ERROR_HPP_ +#define COMMON__GRAPH__ERROR_HPP_ #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { struct Exception : public std::runtime_error @@ -65,6 +65,6 @@ class GraphStructure : public Exception using Exception::Exception; }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__ERROR_HPP_ +#endif // COMMON__GRAPH__ERROR_HPP_ diff --git a/system/system_diagnostic_graph/src/core/graph.cpp b/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp similarity index 98% rename from system/system_diagnostic_graph/src/core/graph.cpp rename to system/diagnostic_graph_aggregator/src/common/graph/graph.cpp index 5ad7df09de1d1..5d7c11879a9cc 100644 --- a/system/system_diagnostic_graph/src/core/graph.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp @@ -28,7 +28,7 @@ // DEBUG #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { BaseUnit::UniquePtrList topological_sort(BaseUnit::UniquePtrList && input) @@ -223,4 +223,4 @@ std::vector Graph::nodes() const return result; } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator diff --git a/system/system_diagnostic_graph/src/core/graph.hpp b/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp similarity index 86% rename from system/system_diagnostic_graph/src/core/graph.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/graph.hpp index 7b0a5bf563106..8c29a303814b8 100644 --- a/system/system_diagnostic_graph/src/core/graph.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__GRAPH_HPP_ -#define CORE__GRAPH_HPP_ +#ifndef COMMON__GRAPH__GRAPH_HPP_ +#define COMMON__GRAPH__GRAPH_HPP_ #include "types.hpp" @@ -25,7 +25,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { class Graph final @@ -47,6 +47,6 @@ class Graph final std::unordered_map unknowns_; }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__GRAPH_HPP_ +#endif // COMMON__GRAPH__GRAPH_HPP_ diff --git a/system/system_diagnostic_graph/src/core/types.hpp b/system/diagnostic_graph_aggregator/src/common/graph/types.hpp similarity index 86% rename from system/system_diagnostic_graph/src/core/types.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/types.hpp index c0b901d1e4511..693094914db1d 100644 --- a/system/system_diagnostic_graph/src/core/types.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/types.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__TYPES_HPP_ -#define CORE__TYPES_HPP_ +#ifndef COMMON__GRAPH__TYPES_HPP_ +#define COMMON__GRAPH__TYPES_HPP_ #include #include @@ -21,7 +21,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { using diagnostic_msgs::msg::DiagnosticArray; @@ -34,6 +34,6 @@ using DiagnosticLevel = DiagnosticStatus::_level_type; class BaseUnit; class DiagUnit; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__TYPES_HPP_ +#endif // COMMON__GRAPH__TYPES_HPP_ diff --git a/system/system_diagnostic_graph/src/core/units.cpp b/system/diagnostic_graph_aggregator/src/common/graph/units.cpp similarity index 98% rename from system/system_diagnostic_graph/src/core/units.cpp rename to system/diagnostic_graph_aggregator/src/common/graph/units.cpp index cb830c8d1df51..6048cae85e633 100644 --- a/system/system_diagnostic_graph/src/core/units.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/units.cpp @@ -21,7 +21,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { using LinkList = std::vector>; @@ -178,4 +178,4 @@ void DebugUnit::update(const rclcpp::Time &) { } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator diff --git a/system/system_diagnostic_graph/src/core/units.hpp b/system/diagnostic_graph_aggregator/src/common/graph/units.hpp similarity index 95% rename from system/system_diagnostic_graph/src/core/units.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/units.hpp index 2b94b5f83a216..dce223b30f728 100644 --- a/system/system_diagnostic_graph/src/core/units.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/units.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__UNITS_HPP_ -#define CORE__UNITS_HPP_ +#ifndef COMMON__GRAPH__UNITS_HPP_ +#define COMMON__GRAPH__UNITS_HPP_ #include "config.hpp" #include "types.hpp" @@ -27,7 +27,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { class BaseUnit @@ -131,6 +131,6 @@ class DebugUnit : public BaseUnit std::string type() const override { return "const"; } }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__UNITS_HPP_ +#endif // COMMON__GRAPH__UNITS_HPP_ diff --git a/system/system_diagnostic_graph/src/main.cpp b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp similarity index 90% rename from system/system_diagnostic_graph/src/main.cpp rename to system/diagnostic_graph_aggregator/src/node/aggregator.cpp index 7393d9fb086f6..48f489c186bdb 100644 --- a/system/system_diagnostic_graph/src/main.cpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "main.hpp" +#include "aggregator.hpp" #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { -MainNode::MainNode() : Node("system_diagnostic_graph_aggregator") +MainNode::MainNode() : Node("diagnostic_graph_aggregator_aggregator") { // Init diagnostics graph. { @@ -69,11 +69,11 @@ void MainNode::on_diag(const DiagnosticArray::ConstSharedPtr msg) graph_.callback(now(), *msg); } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator int main(int argc, char ** argv) { - using system_diagnostic_graph::MainNode; + using diagnostic_graph_aggregator::MainNode; rclcpp::init(argc, argv); rclcpp::executors::SingleThreadedExecutor executor; auto node = std::make_shared(); diff --git a/system/system_diagnostic_graph/src/main.hpp b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp similarity index 80% rename from system/system_diagnostic_graph/src/main.hpp rename to system/diagnostic_graph_aggregator/src/node/aggregator.hpp index 495c51218cabc..dd64809e939cc 100644 --- a/system/system_diagnostic_graph/src/main.hpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MAIN_HPP_ -#define MAIN_HPP_ +#ifndef NODE__AGGREGATOR_HPP_ +#define NODE__AGGREGATOR_HPP_ -#include "core/graph.hpp" -#include "core/modes.hpp" -#include "core/types.hpp" +#include "graph/graph.hpp" +#include "graph/types.hpp" +#include "plugin/modes.hpp" #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { class MainNode : public rclcpp::Node @@ -44,6 +44,6 @@ class MainNode : public rclcpp::Node bool debug_; }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // MAIN_HPP_ +#endif // NODE__AGGREGATOR_HPP_ diff --git a/system/system_diagnostic_graph/src/tool.cpp b/system/diagnostic_graph_aggregator/src/node/converter.cpp similarity index 90% rename from system/system_diagnostic_graph/src/tool.cpp rename to system/diagnostic_graph_aggregator/src/node/converter.cpp index fda2c88a691a2..89acfce31a5ab 100644 --- a/system/system_diagnostic_graph/src/tool.cpp +++ b/system/diagnostic_graph_aggregator/src/node/converter.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "tool.hpp" +#include "converter.hpp" #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { std::string level_to_string(DiagnosticLevel level) @@ -35,7 +35,7 @@ std::string level_to_string(DiagnosticLevel level) return "UNKNOWN"; } -ToolNode::ToolNode() : Node("system_diagnostic_graph_converter") +ToolNode::ToolNode() : Node("diagnostic_graph_aggregator_converter") { using std::placeholders::_1; const auto qos_graph = rclcpp::QoS(1); @@ -66,11 +66,11 @@ void ToolNode::on_graph(const DiagnosticGraph::ConstSharedPtr msg) pub_array_->publish(message); } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator int main(int argc, char ** argv) { - using system_diagnostic_graph::ToolNode; + using diagnostic_graph_aggregator::ToolNode; rclcpp::init(argc, argv); rclcpp::executors::SingleThreadedExecutor executor; auto node = std::make_shared(); diff --git a/system/system_diagnostic_graph/src/tool.hpp b/system/diagnostic_graph_aggregator/src/node/converter.hpp similarity index 81% rename from system/system_diagnostic_graph/src/tool.hpp rename to system/diagnostic_graph_aggregator/src/node/converter.hpp index 5ad19b8460c4b..7a3e8e4e58033 100644 --- a/system/system_diagnostic_graph/src/tool.hpp +++ b/system/diagnostic_graph_aggregator/src/node/converter.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef TOOL_HPP_ -#define TOOL_HPP_ +#ifndef NODE__CONVERTER_HPP_ +#define NODE__CONVERTER_HPP_ -#include "core/types.hpp" +#include "graph/types.hpp" #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { class ToolNode : public rclcpp::Node @@ -33,6 +33,6 @@ class ToolNode : public rclcpp::Node void on_graph(const DiagnosticGraph::ConstSharedPtr msg); }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // TOOL_HPP_ +#endif // NODE__CONVERTER_HPP_ diff --git a/system/system_diagnostic_graph/src/core/modes.cpp b/system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp similarity index 93% rename from system/system_diagnostic_graph/src/core/modes.cpp rename to system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp index 1488387811d67..c73de86cba439 100644 --- a/system/system_diagnostic_graph/src/core/modes.cpp +++ b/system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp @@ -14,15 +14,15 @@ #include "modes.hpp" -#include "config.hpp" -#include "error.hpp" -#include "units.hpp" +#include "graph/config.hpp" +#include "graph/error.hpp" +#include "graph/units.hpp" #include #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { OperationModes::OperationModes(rclcpp::Node & node, const std::vector & graph) @@ -73,4 +73,4 @@ void OperationModes::update(const rclcpp::Time & stamp) const pub_->publish(message); } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator diff --git a/system/system_diagnostic_graph/src/core/modes.hpp b/system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp similarity index 85% rename from system/system_diagnostic_graph/src/core/modes.hpp rename to system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp index 47a31b8d2a152..1ed22c7d9d058 100644 --- a/system/system_diagnostic_graph/src/core/modes.hpp +++ b/system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__MODES_HPP_ -#define CORE__MODES_HPP_ +#ifndef NODE__PLUGIN__MODES_HPP_ +#define NODE__PLUGIN__MODES_HPP_ -#include "types.hpp" +#include "graph/types.hpp" #include @@ -23,7 +23,7 @@ #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { class OperationModes @@ -46,6 +46,6 @@ class OperationModes BaseUnit * pull_over_mrm_; }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__MODES_HPP_ +#endif // NODE__PLUGIN__MODES_HPP_ diff --git a/system/system_diagnostic_graph/src/tool/main.cpp b/system/diagnostic_graph_aggregator/src/tool/tool.cpp similarity index 94% rename from system/system_diagnostic_graph/src/tool/main.cpp rename to system/diagnostic_graph_aggregator/src/tool/tool.cpp index 6efb911d8e2d3..657f76c2d91b7 100644 --- a/system/system_diagnostic_graph/src/tool/main.cpp +++ b/system/diagnostic_graph_aggregator/src/tool/tool.cpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "graph.hpp" -#include "types.hpp" -#include "units.hpp" +#include "graph/graph.hpp" +#include "graph/types.hpp" +#include "graph/units.hpp" #include #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { struct GraphNode @@ -128,7 +128,7 @@ void dump_tree_path(const std::string & path) } } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator int main(int argc, char ** argv) { @@ -136,5 +136,5 @@ int main(int argc, char ** argv) std::cerr << "usage: " << argv[0] << " " << std::endl; return 1; } - system_diagnostic_graph::dump_tree_path(argv[1]); + diagnostic_graph_aggregator::dump_tree_path(argv[1]); } diff --git a/system/system_diagnostic_graph/test/files/test1/field-not-found.yaml b/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/field-not-found.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/file-not-found.yaml b/system/diagnostic_graph_aggregator/test/files/test1/file-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/file-not-found.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/file-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/graph-circulation.yaml b/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/graph-circulation.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/invalid-dict-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/invalid-dict-type.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/invalid-list-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/invalid-list-type.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/path-conflict.yaml b/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/path-conflict.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/path-not-found.yaml b/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/path-not-found.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/unknown-node-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/unknown-node-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/unknown-node-type.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/unknown-node-type.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/unknown-substitution.yaml b/system/diagnostic_graph_aggregator/test/files/test1/unknown-substitution.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/unknown-substitution.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/unknown-substitution.yaml diff --git a/system/system_diagnostic_graph/test/files/test2/and.yaml b/system/diagnostic_graph_aggregator/test/files/test2/and.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test2/and.yaml rename to system/diagnostic_graph_aggregator/test/files/test2/and.yaml diff --git a/system/system_diagnostic_graph/test/files/test2/or.yaml b/system/diagnostic_graph_aggregator/test/files/test2/or.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test2/or.yaml rename to system/diagnostic_graph_aggregator/test/files/test2/or.yaml diff --git a/system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml rename to system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml diff --git a/system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml rename to system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml diff --git a/system/system_diagnostic_graph/test/src/test1.cpp b/system/diagnostic_graph_aggregator/test/src/test1.cpp similarity index 94% rename from system/system_diagnostic_graph/test/src/test1.cpp rename to system/diagnostic_graph_aggregator/test/src/test1.cpp index d01822e93c2eb..48a0e1f45ce07 100644 --- a/system/system_diagnostic_graph/test/src/test1.cpp +++ b/system/diagnostic_graph_aggregator/test/src/test1.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "core/error.hpp" -#include "core/graph.hpp" +#include "graph/error.hpp" +#include "graph/graph.hpp" #include "utils.hpp" #include -using namespace system_diagnostic_graph; // NOLINT(build/namespaces) +using namespace diagnostic_graph_aggregator; // NOLINT(build/namespaces) TEST(ConfigFile, RootNotFound) { diff --git a/system/system_diagnostic_graph/test/src/test2.cpp b/system/diagnostic_graph_aggregator/test/src/test2.cpp similarity index 97% rename from system/system_diagnostic_graph/test/src/test2.cpp rename to system/diagnostic_graph_aggregator/test/src/test2.cpp index 3e4c946f73fb7..1098ff9efb0db 100644 --- a/system/system_diagnostic_graph/test/src/test2.cpp +++ b/system/diagnostic_graph_aggregator/test/src/test2.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "core/error.hpp" -#include "core/graph.hpp" +#include "graph/error.hpp" +#include "graph/graph.hpp" #include "utils.hpp" #include @@ -22,7 +22,7 @@ #include -using namespace system_diagnostic_graph; // NOLINT(build/namespaces) +using namespace diagnostic_graph_aggregator; // NOLINT(build/namespaces) using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; diff --git a/system/system_diagnostic_graph/test/src/utils.cpp b/system/diagnostic_graph_aggregator/test/src/utils.cpp similarity index 100% rename from system/system_diagnostic_graph/test/src/utils.cpp rename to system/diagnostic_graph_aggregator/test/src/utils.cpp diff --git a/system/system_diagnostic_graph/test/src/utils.hpp b/system/diagnostic_graph_aggregator/test/src/utils.hpp similarity index 100% rename from system/system_diagnostic_graph/test/src/utils.hpp rename to system/diagnostic_graph_aggregator/test/src/utils.hpp diff --git a/system/system_diagnostic_graph/doc/format/diag.md b/system/system_diagnostic_graph/doc/format/diag.md deleted file mode 100644 index 9835924f08996..0000000000000 --- a/system/system_diagnostic_graph/doc/format/diag.md +++ /dev/null @@ -1,11 +0,0 @@ -# Diag - -Diag is a node that refers to a source diagnostics. - -## Format - -| Name | Type | Required | Description | -| -------- | ------ | -------- | -------------------------------------- | -| type | string | yes | Specify `diag` when using this object. | -| name | string | yes | Name of diagnostic status. | -| hardware | string | yes | Hardware ID of diagnostic status. | diff --git a/system/system_diagnostic_graph/example/example.launch.xml b/system/system_diagnostic_graph/example/example.launch.xml deleted file mode 100644 index 1456bfd5c6593..0000000000000 --- a/system/system_diagnostic_graph/example/example.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/system/system_diagnostic_graph/launch/system_diagnostic_graph.launch.xml b/system/system_diagnostic_graph/launch/system_diagnostic_graph.launch.xml deleted file mode 100644 index 5b9a84947d179..0000000000000 --- a/system/system_diagnostic_graph/launch/system_diagnostic_graph.launch.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - From 0682af2e77cd442c50a0560bd39b66d22879fda4 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 14 Dec 2023 16:03:09 +0900 Subject: [PATCH 064/276] refactor(lane_change): separate lane change and external request (#5850) * refactor(lane_change): separate lane change and external request Signed-off-by: Muhammad Zulfaqar Azmi * refactored external request lane change Signed-off-by: Muhammad Zulfaqar Azmi * separate on external request Signed-off-by: Muhammad Zulfaqar Azmi * style(pre-commit): autofix * delete external request Signed-off-by: Muhammad Zulfaqar Azmi * fix interface Signed-off-by: Muhammad Zulfaqar Azmi * fix external lane change couldn't be initialize Signed-off-by: Muhammad Zulfaqar Azmi * fix documents Signed-off-by: Muhammad Zulfaqar Azmi * fix link in README Signed-off-by: Muhammad Zulfaqar Azmi * fix based on comments Signed-off-by: Zulfaqar Azmi * add ament auto package Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> * Update planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> * fix test Signed-off-by: Muhammad Zulfaqar Azmi * fix AbLC test Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- planning/.pages | 2 +- .../interface.hpp | 2 +- .../manager.hpp | 2 +- .../scene.hpp | 2 +- .../package.xml | 1 + ...t_behavior_path_planner_node_interface.cpp | 5 +- .../CMakeLists.txt | 25 ++++ .../manager.hpp | 54 ++++++++ .../scene.hpp} | 8 +- .../package.xml | 39 ++++++ .../plugins.xml | 4 + .../src/manager.cpp | 49 +++++++ .../src/scene.cpp} | 2 +- ...t_behavior_path_planner_node_interface.cpp | 128 ++++++++++++++++++ .../CMakeLists.txt | 29 ++++ .../README.md} | 36 ++--- .../config}/lane_change.param.yaml | 0 .../images}/lane_change-abort.png | Bin .../images}/lane_change-cancel.png | Bin .../lane_change-candidate_path_samples.png | Bin .../lane_change-cant_cancel_no_abort.png | Bin .../images}/lane_change-debug-1.png | Bin .../images}/lane_change-debug-2.png | Bin .../images}/lane_change-debug-3.png | Bin ...nable_collision_check_at_prepare_phase.png | Bin .../images}/lane_change-intersection_case.png | Bin .../lane_change-lane_change_phases.png | Bin .../lane_change-stop_at_terminal.drawio.svg | 0 ...hange-stop_at_terminal_no_block.drawio.svg | 0 ...hange-stop_far_from_target_lane.drawio.svg | 0 ...ane_change-stop_not_at_terminal.drawio.svg | 0 ..._at_terminal_no_blocking_object.drawio.svg | 0 .../lane_change-when_cannot_change_lanes.png | Bin .../images}/lane_change.drawio.svg | 0 .../images}/lane_objects.drawio.svg | 0 .../interface.hpp | 17 ++- .../manager.hpp | 31 +---- .../scene.hpp} | 8 +- .../utils}/base_class.hpp | 12 +- .../utils/data_structs.hpp} | 6 +- .../utils/markers.hpp} | 12 +- .../utils/path.hpp} | 10 +- .../utils}/utils.hpp | 12 +- .../package.xml | 38 ++++++ .../plugins.xml | 6 + .../src}/interface.cpp | 7 +- .../src}/manager.cpp | 17 +-- .../src/scene.cpp} | 4 +- .../src/utils/markers.cpp} | 2 +- .../src/utils}/utils.cpp | 6 +- ...t_behavior_path_planner_node_interface.cpp | 126 +++++++++++++++++ .../test/test_lane_change_utils.cpp | 3 +- planning/behavior_path_planner/CMakeLists.txt | 14 -- planning/behavior_path_planner/plugins.xml | 4 - ...t_behavior_path_planner_node_interface.cpp | 7 +- 55 files changed, 585 insertions(+), 145 deletions(-) create mode 100644 planning/behavior_path_external_request_lane_change_module/CMakeLists.txt create mode 100644 planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp => behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp} (79%) create mode 100644 planning/behavior_path_external_request_lane_change_module/package.xml create mode 100644 planning/behavior_path_external_request_lane_change_module/plugins.xml create mode 100644 planning/behavior_path_external_request_lane_change_module/src/manager.cpp rename planning/{behavior_path_planner/src/scene_module/lane_change/external_request.cpp => behavior_path_external_request_lane_change_module/src/scene.cpp} (92%) create mode 100644 planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp create mode 100644 planning/behavior_path_lane_change_module/CMakeLists.txt rename planning/{behavior_path_planner/docs/behavior_path_planner_lane_change_design.md => behavior_path_lane_change_module/README.md} (96%) rename planning/{behavior_path_planner/config/lane_change => behavior_path_lane_change_module/config}/lane_change.param.yaml (100%) rename planning/{behavior_path_planner/image/lane_change/cancel_and_abort => behavior_path_lane_change_module/images}/lane_change-abort.png (100%) rename planning/{behavior_path_planner/image/lane_change/cancel_and_abort => behavior_path_lane_change_module/images}/lane_change-cancel.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-candidate_path_samples.png (100%) rename planning/{behavior_path_planner/image/lane_change/cancel_and_abort => behavior_path_lane_change_module/images}/lane_change-cant_cancel_no_abort.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-debug-1.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-debug-2.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-debug-3.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-enable_collision_check_at_prepare_phase.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-intersection_case.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-lane_change_phases.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-stop_at_terminal.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-stop_at_terminal_no_block.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-stop_far_from_target_lane.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-stop_not_at_terminal.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-when_cannot_change_lanes.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_objects.drawio.svg (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change => behavior_path_lane_change_module/include/behavior_path_lane_change_module}/interface.hpp (87%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change => behavior_path_lane_change_module/include/behavior_path_lane_change_module}/manager.hpp (68%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp => behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp} (96%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change => behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils}/base_class.hpp (95%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp => behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp} (96%) rename planning/{behavior_path_planner/include/behavior_path_planner/marker_utils/lane_change/debug.hpp => behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp} (80%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp => behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/path.hpp} (82%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/lane_change => behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils}/utils.hpp (96%) create mode 100644 planning/behavior_path_lane_change_module/package.xml create mode 100644 planning/behavior_path_lane_change_module/plugins.xml rename planning/{behavior_path_planner/src/scene_module/lane_change => behavior_path_lane_change_module/src}/interface.cpp (98%) rename planning/{behavior_path_planner/src/scene_module/lane_change => behavior_path_lane_change_module/src}/manager.cpp (95%) rename planning/{behavior_path_planner/src/scene_module/lane_change/normal.cpp => behavior_path_lane_change_module/src/scene.cpp} (99%) rename planning/{behavior_path_planner/src/marker_utils/lane_change/debug.cpp => behavior_path_lane_change_module/src/utils/markers.cpp} (98%) rename planning/{behavior_path_planner/src/utils/lane_change => behavior_path_lane_change_module/src/utils}/utils.cpp (99%) create mode 100644 planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp rename planning/{behavior_path_planner => behavior_path_lane_change_module}/test/test_lane_change_utils.cpp (95%) diff --git a/planning/.pages b/planning/.pages index 7cbd36d2ca2d0..6ae8abe240d9b 100644 --- a/planning/.pages +++ b/planning/.pages @@ -14,7 +14,7 @@ nav: - 'Avoidance by Lane Change': planning/behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design - 'Dynamic Avoidance': planning/behavior_path_planner/docs/behavior_path_planner_dynamic_avoidance_design - 'Goal Planner': planning/behavior_path_planner/docs/behavior_path_planner_goal_planner_design - - 'Lane Change': planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design + - 'Lane Change': planning/behavior_path_lane_change_module - 'Side Shift': planning/behavior_path_planner/docs/behavior_path_planner_side_shift_design - 'Start Planner': planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design - 'Behavior Velocity Planner': diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp index 0bc08ccd400ca..016a6b2977701 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp @@ -17,7 +17,7 @@ #include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" #include "behavior_path_avoidance_by_lane_change_module/scene.hpp" -#include "behavior_path_planner/scene_module/lane_change/interface.hpp" +#include "behavior_path_lane_change_module/interface.hpp" #include diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp index b1beae9c6fc03..d996555365166 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp @@ -17,7 +17,7 @@ #include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" #include "behavior_path_avoidance_by_lane_change_module/interface.hpp" -#include "behavior_path_planner/scene_module/lane_change/manager.hpp" +#include "behavior_path_lane_change_module/manager.hpp" #include diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp index 1e667c207c64f..f22291c99b8e7 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp @@ -16,7 +16,7 @@ #define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ #include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" -#include "behavior_path_planner/scene_module/lane_change/normal.hpp" +#include "behavior_path_lane_change_module/scene.hpp" #include diff --git a/planning/behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_avoidance_by_lane_change_module/package.xml index da51dd9f235dc..3a4f42f2d2a6c 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/package.xml +++ b/planning/behavior_path_avoidance_by_lane_change_module/package.xml @@ -19,6 +19,7 @@ eigen3_cmake_module behavior_path_avoidance_module + behavior_path_lane_change_module behavior_path_planner behavior_path_planner_common motion_utils diff --git a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 2264669fdcdbe..3041ae7e1112e 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -47,6 +47,8 @@ std::shared_ptr generateNode() ament_index_cpp::get_package_share_directory("planning_test_utils"); const auto behavior_path_planner_dir = ament_index_cpp::get_package_share_directory("behavior_path_planner"); + const auto behavior_path_lane_change_module_dir = + ament_index_cpp::get_package_share_directory("behavior_path_lane_change_module"); std::vector module_names; module_names.emplace_back("behavior_path_planner::AvoidanceByLaneChangeModuleManager"); @@ -63,8 +65,7 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - ament_index_cpp::get_package_share_directory("behavior_path_planner") + - "/config/lane_change/lane_change.param.yaml", + behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml", ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + "/config/avoidance.param.yaml", ament_index_cpp::get_package_share_directory("behavior_path_avoidance_by_lane_change_module") + diff --git a/planning/behavior_path_external_request_lane_change_module/CMakeLists.txt b/planning/behavior_path_external_request_lane_change_module/CMakeLists.txt new file mode 100644 index 0000000000000..86dc0ccb61330 --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_external_request_lane_change_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/manager.cpp + src/scene.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_behavior_path_planner_node_interface.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package() diff --git a/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp b/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp new file mode 100644 index 0000000000000..dfcc4f61d8241 --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp @@ -0,0 +1,54 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__MANAGER_HPP_ + +#include "behavior_path_lane_change_module/manager.hpp" +#include "route_handler/route_handler.hpp" + +#include + +#include +#include + +namespace behavior_path_planner +{ +class ExternalRequestLaneChangeRightModuleManager : public LaneChangeModuleManager +{ +public: + ExternalRequestLaneChangeRightModuleManager() + : LaneChangeModuleManager( + "external_request_lane_change_right", route_handler::Direction::RIGHT, + LaneChangeModuleType::EXTERNAL_REQUEST) + { + } + std::unique_ptr createNewSceneModuleInstance() override; +}; + +class ExternalRequestLaneChangeLeftModuleManager : public LaneChangeModuleManager +{ +public: + ExternalRequestLaneChangeLeftModuleManager() + + : LaneChangeModuleManager( + "external_request_lane_change_left", route_handler::Direction::LEFT, + LaneChangeModuleType::EXTERNAL_REQUEST) + { + } + std::unique_ptr createNewSceneModuleInstance() override; +}; +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp b/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp similarity index 79% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp rename to planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp index d9c77d6db337e..c23d6f2f3996c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp +++ b/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__EXTERNAL_REQUEST_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__EXTERNAL_REQUEST_HPP_ +#ifndef BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__SCENE_HPP_ -#include "behavior_path_planner/scene_module/lane_change/normal.hpp" +#include "behavior_path_lane_change_module/scene.hpp" #include @@ -35,4 +35,4 @@ class ExternalRequestLaneChange : public NormalLaneChange }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__EXTERNAL_REQUEST_HPP_ +#endif // BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_external_request_lane_change_module/package.xml b/planning/behavior_path_external_request_lane_change_module/package.xml new file mode 100644 index 0000000000000..16216aa1f71e9 --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/package.xml @@ -0,0 +1,39 @@ + + + + behavior_path_external_request_lane_change_module + 0.1.0 + The behavior_path_external_request_lane_change_module package + + Fumiya Watanabe + Zulfaqar Azmi + Kosuke Takeuchi + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + behavior_path_lane_change_module + behavior_path_planner + behavior_path_planner_common + motion_utils + pluginlib + rclcpp + rtc_interface + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_external_request_lane_change_module/plugins.xml b/planning/behavior_path_external_request_lane_change_module/plugins.xml new file mode 100644 index 0000000000000..f3cc686837c38 --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/plugins.xml @@ -0,0 +1,4 @@ + + + + diff --git a/planning/behavior_path_external_request_lane_change_module/src/manager.cpp b/planning/behavior_path_external_request_lane_change_module/src/manager.cpp new file mode 100644 index 0000000000000..3cfe7aa51f0f1 --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/src/manager.cpp @@ -0,0 +1,49 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "behavior_path_external_request_lane_change_module/manager.hpp" + +#include "behavior_path_external_request_lane_change_module/scene.hpp" +#include "behavior_path_lane_change_module/interface.hpp" + +namespace behavior_path_planner +{ + +std::unique_ptr +ExternalRequestLaneChangeRightModuleManager::createNewSceneModuleInstance() +{ + return std::make_unique( + name_, *node_, parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, + std::make_unique(parameters_, direction_)); +} + +std::unique_ptr +ExternalRequestLaneChangeLeftModuleManager::createNewSceneModuleInstance() +{ + return std::make_unique( + name_, *node_, parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, + std::make_unique(parameters_, direction_)); +} + +} // namespace behavior_path_planner + +#include +PLUGINLIB_EXPORT_CLASS( + behavior_path_planner::ExternalRequestLaneChangeRightModuleManager, + behavior_path_planner::SceneModuleManagerInterface) +PLUGINLIB_EXPORT_CLASS( + behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager, + behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/external_request.cpp b/planning/behavior_path_external_request_lane_change_module/src/scene.cpp similarity index 92% rename from planning/behavior_path_planner/src/scene_module/lane_change/external_request.cpp rename to planning/behavior_path_external_request_lane_change_module/src/scene.cpp index 3a304a9b5bb53..913266bf79fa3 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/external_request.cpp +++ b/planning/behavior_path_external_request_lane_change_module/src/scene.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/lane_change/external_request.hpp" +#include "behavior_path_external_request_lane_change_module/scene.hpp" #include diff --git a/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..ff5be388704da --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,128 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "behavior_path_planner/behavior_path_planner_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + const auto behavior_path_lane_change_module_dir = + ament_index_cpp::get_package_share_directory("behavior_path_lane_change_module"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); + module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, { + planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml", + }); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} diff --git a/planning/behavior_path_lane_change_module/CMakeLists.txt b/planning/behavior_path_lane_change_module/CMakeLists.txt new file mode 100644 index 0000000000000..e5bce68ebfa44 --- /dev/null +++ b/planning/behavior_path_lane_change_module/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_lane_change_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/interface.cpp + src/manager.cpp + src/scene.cpp + src/utils/markers.cpp + src/utils/utils.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_behavior_path_planner_node_interface.cpp + test/test_lane_change_utils.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md b/planning/behavior_path_lane_change_module/README.md similarity index 96% rename from planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md rename to planning/behavior_path_lane_change_module/README.md index ee74f700c4d42..a1fa2068b9ab5 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -15,7 +15,7 @@ The Lane Change module is activated when lane change is needed and can be safely The lane change candidate path is divided into two phases: preparation and lane-changing. The following figure illustrates each phase of the lane change candidate path. -![lane-change-phases](../image/lane_change/lane_change-lane_change_phases.png) +![lane-change-phases](./images/lane_change-lane_change_phases.png) ### Preparation phase @@ -62,7 +62,7 @@ Note that when the `current_velocity` is lower than `minimum_lane_changing_veloc The following figure illustrates when `longitudinal_acceleration_sampling_num = 4`. Assuming that `maximum_deceleration = 1.0` then `a0 == 0.0 == no deceleration`, `a1 == 0.25`, `a2 == 0.5`, `a3 == 0.75` and `a4 == 1.0 == maximum_deceleration`. `a0` is the expected lane change trajectories should ego vehicle do not decelerate, and `a1`'s path is the expected lane change trajectories should ego vehicle decelerate at `0.25 m/s^2`. -![path_samples](../image/lane_change/lane_change-candidate_path_samples.png) +![path_samples](./images/lane_change-candidate_path_samples.png) Which path will be chosen will depend on validity and collision check. @@ -155,21 +155,21 @@ stop #### Candidate Path's Safety check -See [safety check utils explanation](../docs/behavior_path_planner_safety_check.md) +See [safety check utils explanation](../behavior_path_planner/docs/behavior_path_planner_safety_check.md) #### Objects selection and classification First, we divide the target objects into obstacles in the target lane, obstacles in the current lane, and obstacles in other lanes. Target lane indicates the lane that the ego vehicle is going to reach after the lane change and current lane mean the current lane where the ego vehicle is following before the lane change. Other lanes are lanes that do not belong to the target and current lanes. The following picture describes objects on each lane. Note that users can remove objects either on current and other lanes from safety check by changing the flag, which are `check_objects_on_current_lanes` and `check_objects_on_other_lanes`. -![object lanes](../image/lane_change/lane_objects.drawio.svg) +![object lanes](./images/lane_objects.drawio.svg) -Furthermore, to change lanes behind a vehicle waiting at a traffic light, we skip the safety check for the stopping vehicles near the traffic light. The explanation for parked car detection is written in [documentation for avoidance module](../docs/behavior_path_planner_avoidance_design.md). +Furthermore, to change lanes behind a vehicle waiting at a traffic light, we skip the safety check for the stopping vehicles near the traffic light. The explanation for parked car detection is written in [documentation for avoidance module](../behavior_path_planner/docs/behavior_path_planner_avoidance_design.md). ##### Collision check in prepare phase The ego vehicle may need to secure ample inter-vehicle distance ahead of the target vehicle before attempting a lane change. The flag `enable_collision_check_at_prepare_phase` can be enabled to gain this behavior. The following image illustrates the differences between the `false` and `true` cases. -![enable collision check at prepare phase](../image/lane_change/lane_change-enable_collision_check_at_prepare_phase.png) +![enable collision check at prepare phase](./images/lane_change-enable_collision_check_at_prepare_phase.png) The parameter `prepare_phase_ignore_target_speed_thresh` can be configured to ignore the prepare phase collision check for targets whose speeds are less than a specific threshold, such as stationary or very slow-moving objects. @@ -184,7 +184,7 @@ minimum_lane_change_distance = minimum_prepare_length + minimum_lane_changing_ve The following figure illustrates when the lane is blocked in multiple lane changes cases. -![multiple-lane-changes](../image/lane_change/lane_change-when_cannot_change_lanes.png) +![multiple-lane-changes](./images/lane_change-when_cannot_change_lanes.png) #### Stopping position when an object exists ahead @@ -195,25 +195,25 @@ The position to be stopped depends on the situation, such as when the lane chang Regardless of the presence or absence of objects in the lane change target lane, stop by keeping the distance necessary for lane change to the object ahead. -![stop_at_terminal_no_block](../image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg) +![stop_at_terminal_no_block](./images/lane_change-stop_at_terminal_no_block.drawio.svg) -![stop_at_terminal](../image/lane_change/lane_change-stop_at_terminal.drawio.svg) +![stop_at_terminal](./images/lane_change-stop_at_terminal.drawio.svg) ##### When the ego vehicle is not near the end of the lane change If there are NO objects in the lane change section of the target lane, stop by keeping the distance necessary for lane change to the object ahead. -![stop_not_at_terminal_no_blocking_object](../image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg) +![stop_not_at_terminal_no_blocking_object](./images/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg) If there are objects in the lane change section of the target lane, stop WITHOUT keeping the distance necessary for lane change to the object ahead. -![stop_not_at_terminal](../image/lane_change/lane_change-stop_not_at_terminal.drawio.svg) +![stop_not_at_terminal](./images/lane_change-stop_not_at_terminal.drawio.svg) ##### When the target lane is far away When the target lane for lane change is far away and not next to the current lane, do not keep the distance necessary for lane change to the object ahead. -![stop_far_from_target_lane](../image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg) +![stop_far_from_target_lane](./images/lane_change-stop_far_from_target_lane.drawio.svg) ### Lane Change When Stuck @@ -292,19 +292,19 @@ The function can be enabled by setting `enable_on_prepare_phase` to `true`. The following image illustrates the cancel process. -![cancel](../image/lane_change/cancel_and_abort/lane_change-cancel.png) +![cancel](./images/lane_change-cancel.png) #### Abort Assume the ego vehicle has already departed from the current lane. In that case, it is dangerous to cancel the path, and it will cause the ego vehicle to change the heading direction abruptly. In this case, planning a trajectory that allows the ego vehicle to return to the current path while minimizing the heading changes is necessary. In this case, the lane change module will generate an abort path. The following images show an example of the abort path. Do note that the function DOESN'T GUARANTEE a safe abort process, as it didn't check the presence of the surrounding objects and/or their reactions. The function can be enable manually by setting both `enable_on_prepare_phase` and `enable_on_lane_changing_phase` to `true`. The parameter `max_lateral_jerk` need to be set to a high value in order for it to work. -![abort](../image/lane_change/cancel_and_abort/lane_change-abort.png) +![abort](./images/lane_change-abort.png) #### Stop/Cruise The last behavior will also occur if the ego vehicle has departed from the current lane. If the abort function is disabled or the abort is no longer possible, the ego vehicle will attempt to stop or transition to the obstacle cruise mode. Do note that the module DOESN'T GUARANTEE safe maneuver due to the unexpected behavior that might've occurred during these critical scenarios. The following images illustrate the situation. -![stop](../image/lane_change/cancel_and_abort/lane_change-cant_cancel_no_abort.png) +![stop](./images/lane_change-cant_cancel_no_abort.png) ## Parameters @@ -451,11 +451,11 @@ Then add the marker in `rviz2`. -![debug](../image/lane_change/lane_change-debug-1.png) +![debug](./images/lane_change-debug-1.png) -![debug2](../image/lane_change/lane_change-debug-2.png) +![debug2](./images/lane_change-debug-2.png) -![debug3](../image/lane_change/lane_change-debug-3.png) +![debug3](./images/lane_change-debug-3.png) Available information diff --git a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/lane_change/lane_change.param.yaml rename to planning/behavior_path_lane_change_module/config/lane_change.param.yaml diff --git a/planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-abort.png b/planning/behavior_path_lane_change_module/images/lane_change-abort.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-abort.png rename to planning/behavior_path_lane_change_module/images/lane_change-abort.png diff --git a/planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-cancel.png b/planning/behavior_path_lane_change_module/images/lane_change-cancel.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-cancel.png rename to planning/behavior_path_lane_change_module/images/lane_change-cancel.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-candidate_path_samples.png b/planning/behavior_path_lane_change_module/images/lane_change-candidate_path_samples.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-candidate_path_samples.png rename to planning/behavior_path_lane_change_module/images/lane_change-candidate_path_samples.png diff --git a/planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-cant_cancel_no_abort.png b/planning/behavior_path_lane_change_module/images/lane_change-cant_cancel_no_abort.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-cant_cancel_no_abort.png rename to planning/behavior_path_lane_change_module/images/lane_change-cant_cancel_no_abort.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-debug-1.png b/planning/behavior_path_lane_change_module/images/lane_change-debug-1.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-debug-1.png rename to planning/behavior_path_lane_change_module/images/lane_change-debug-1.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-debug-2.png b/planning/behavior_path_lane_change_module/images/lane_change-debug-2.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-debug-2.png rename to planning/behavior_path_lane_change_module/images/lane_change-debug-2.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-debug-3.png b/planning/behavior_path_lane_change_module/images/lane_change-debug-3.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-debug-3.png rename to planning/behavior_path_lane_change_module/images/lane_change-debug-3.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-enable_collision_check_at_prepare_phase.png b/planning/behavior_path_lane_change_module/images/lane_change-enable_collision_check_at_prepare_phase.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-enable_collision_check_at_prepare_phase.png rename to planning/behavior_path_lane_change_module/images/lane_change-enable_collision_check_at_prepare_phase.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-intersection_case.png b/planning/behavior_path_lane_change_module/images/lane_change-intersection_case.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-intersection_case.png rename to planning/behavior_path_lane_change_module/images/lane_change-intersection_case.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-lane_change_phases.png b/planning/behavior_path_lane_change_module/images/lane_change-lane_change_phases.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-lane_change_phases.png rename to planning/behavior_path_lane_change_module/images/lane_change-lane_change_phases.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change-stop_at_terminal.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change-stop_at_terminal.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change-stop_at_terminal_no_block.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change-stop_at_terminal_no_block.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change-stop_far_from_target_lane.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change-stop_far_from_target_lane.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change-stop_not_at_terminal.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change-stop_not_at_terminal.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-when_cannot_change_lanes.png b/planning/behavior_path_lane_change_module/images/lane_change-when_cannot_change_lanes.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-when_cannot_change_lanes.png rename to planning/behavior_path_lane_change_module/images/lane_change-when_cannot_change_lanes.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_objects.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_objects.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_objects.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_objects.drawio.svg diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp similarity index 87% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp index b7cef007d6d9f..fd9a979ee0f76 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,14 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__INTERFACE_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__INTERFACE_HPP_ -#include "behavior_path_planner/scene_module/lane_change/base_class.hpp" -#include "behavior_path_planner/scene_module/lane_change/external_request.hpp" -#include "behavior_path_planner/scene_module/lane_change/normal.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" +#include "behavior_path_lane_change_module/scene.hpp" +#include "behavior_path_lane_change_module/utils/base_class.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" +#include "behavior_path_lane_change_module/utils/path.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/turn_signal_decider.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -146,4 +145,4 @@ class LaneChangeInterface : public SceneModuleInterface }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__INTERFACE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp similarity index 68% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp index 024c6685b28c4..b34f691bd2b0d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/lane_change/interface.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" #include "route_handler/route_handler.hpp" @@ -23,7 +23,6 @@ #include #include -#include #include namespace behavior_path_planner @@ -72,28 +71,6 @@ class LaneChangeLeftModuleManager : public LaneChangeModuleManager { } }; - -class ExternalRequestLaneChangeRightModuleManager : public LaneChangeModuleManager -{ -public: - ExternalRequestLaneChangeRightModuleManager() - : LaneChangeModuleManager( - "external_request_lane_change_right", route_handler::Direction::RIGHT, - LaneChangeModuleType::EXTERNAL_REQUEST) - { - } -}; - -class ExternalRequestLaneChangeLeftModuleManager : public LaneChangeModuleManager -{ -public: - ExternalRequestLaneChangeLeftModuleManager() - : LaneChangeModuleManager( - "external_request_lane_change_left", route_handler::Direction::LEFT, - LaneChangeModuleType::EXTERNAL_REQUEST) - { - } -}; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp index 61caf7b2b393f..50766621b2f44 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp @@ -11,10 +11,10 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__NORMAL_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__NORMAL_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_ -#include "behavior_path_planner/scene_module/lane_change/base_class.hpp" +#include "behavior_path_lane_change_module/utils/base_class.hpp" #include #include @@ -180,4 +180,4 @@ class NormalLaneChange : public LaneChangeBase double stop_time_{0.0}; }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__NORMAL_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp similarity index 95% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp index be49ec5b2e740..a7a35f07e5f30 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp @@ -11,12 +11,12 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__BASE_CLASS_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__BASE_CLASS_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_ -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" -#include "behavior_path_planner/utils/lane_change/utils.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" +#include "behavior_path_lane_change_module/utils/path.hpp" +#include "behavior_path_lane_change_module/utils/utils.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/turn_signal_decider.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -269,4 +269,4 @@ class LaneChangeBase mutable rclcpp::Clock clock_{RCL_ROS_TIME}; }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__BASE_CLASS_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp index debeef5ec573f..dd7760d31eaa7 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.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 BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -211,4 +211,4 @@ struct PathSafetyStatus }; } // namespace behavior_path_planner::data::lane_change -#endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/lane_change/debug.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp similarity index 80% rename from planning/behavior_path_planner/include/behavior_path_planner/marker_utils/lane_change/debug.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp index 96f0851ed33c0..d6deecd4f46fa 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/lane_change/debug.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__MARKER_UTILS__LANE_CHANGE__DEBUG_HPP_ -#define BEHAVIOR_PATH_PLANNER__MARKER_UTILS__LANE_CHANGE__DEBUG_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ -#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" -#include "behavior_path_planner_common/marker_utils/utils.hpp" +#include "behavior_path_lane_change_module/utils/path.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" +#include + #include -#include #include namespace marker_utils::lane_change_markers @@ -38,4 +38,4 @@ MarkerArray showFilteredObjects( const ExtendedPredictedObjects & target_lane_objects, const ExtendedPredictedObjects & other_lane_objects, const std::string & ns); } // namespace marker_utils::lane_change_markers -#endif // BEHAVIOR_PATH_PLANNER__MARKER_UTILS__LANE_CHANGE__DEBUG_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/path.hpp similarity index 82% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/path.hpp index c98f62c47860c..9e42b49635b82 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/path.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_PATH_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_PATH_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" #include "behavior_path_planner_common/turn_signal_decider.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -50,4 +50,4 @@ struct LaneChangeStatus }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_PATH_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index f99ed043eb5dd..de4db37571122 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" +#include "behavior_path_lane_change_module/utils/path.hpp" #include "behavior_path_planner_common/parameters.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/utils.hpp" @@ -208,4 +208,4 @@ lanelet::ConstLanelets generateExpandedLanelets( const double right_offset); } // namespace behavior_path_planner::utils::lane_change -#endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_lane_change_module/package.xml b/planning/behavior_path_lane_change_module/package.xml new file mode 100644 index 0000000000000..fb4bef9535a48 --- /dev/null +++ b/planning/behavior_path_lane_change_module/package.xml @@ -0,0 +1,38 @@ + + + + behavior_path_lane_change_module + 0.1.0 + The behavior_path_lane_change_module package + + Fumiya Watanabe + Zulfaqar Azmi + Kosuke Takeuchi + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + behavior_path_planner + behavior_path_planner_common + motion_utils + pluginlib + rclcpp + rtc_interface + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_lane_change_module/plugins.xml b/planning/behavior_path_lane_change_module/plugins.xml new file mode 100644 index 0000000000000..a598bc8176938 --- /dev/null +++ b/planning/behavior_path_lane_change_module/plugins.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp similarity index 98% rename from planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp rename to planning/behavior_path_lane_change_module/src/interface.cpp index 101dd43919361..1e80067842152 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/lane_change/interface.hpp" +#include "behavior_path_lane_change_module/interface.hpp" -#include "behavior_path_planner/marker_utils/lane_change/debug.hpp" -#include "behavior_path_planner/utils/lane_change/utils.hpp" +#include "behavior_path_lane_change_module/utils/markers.hpp" +#include "behavior_path_lane_change_module/utils/utils.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/interface/scene_module_visitor.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" @@ -26,7 +26,6 @@ #include #include #include -#include namespace behavior_path_planner { diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_lane_change_module/src/manager.cpp similarity index 95% rename from planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp rename to planning/behavior_path_lane_change_module/src/manager.cpp index 658ffb06c25fe..e4405a31a360d 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_lane_change_module/src/manager.cpp @@ -12,8 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/lane_change/manager.hpp" +#include "behavior_path_lane_change_module/manager.hpp" +#include "behavior_path_lane_change_module/interface.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" @@ -262,16 +263,10 @@ void LaneChangeModuleManager::init(rclcpp::Node * node) std::unique_ptr LaneChangeModuleManager::createNewSceneModuleInstance() { - if (type_ == LaneChangeModuleType::NORMAL) { - return std::make_unique( - name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, - std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); - } return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, objects_of_interest_marker_interface_ptr_map_, - std::make_unique(parameters_, direction_)); + std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); } void LaneChangeModuleManager::updateModuleParams(const std::vector & parameters) @@ -298,9 +293,3 @@ PLUGINLIB_EXPORT_CLASS( PLUGINLIB_EXPORT_CLASS( behavior_path_planner::LaneChangeLeftModuleManager, behavior_path_planner::SceneModuleManagerInterface) -PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::ExternalRequestLaneChangeRightModuleManager, - behavior_path_planner::SceneModuleManagerInterface) -PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager, - behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp rename to planning/behavior_path_lane_change_module/src/scene.cpp index ebb41ae63dcbe..21a600d11d83d 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/lane_change/normal.hpp" +#include "behavior_path_lane_change_module/scene.hpp" -#include "behavior_path_planner/utils/lane_change/utils.hpp" +#include "behavior_path_lane_change_module/utils/utils.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" diff --git a/planning/behavior_path_planner/src/marker_utils/lane_change/debug.cpp b/planning/behavior_path_lane_change_module/src/utils/markers.cpp similarity index 98% rename from planning/behavior_path_planner/src/marker_utils/lane_change/debug.cpp rename to planning/behavior_path_lane_change_module/src/utils/markers.cpp index c2a640f989b50..719acba405a68 100644 --- a/planning/behavior_path_planner/src/marker_utils/lane_change/debug.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/markers.cpp @@ -16,7 +16,7 @@ #include "behavior_path_planner_common/marker_utils/utils.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" -#include +#include #include #include diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/lane_change/utils.cpp rename to planning/behavior_path_lane_change_module/src/utils/utils.cpp index 8ba820231d7cc..b5a4fd15b4c6b 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/lane_change/utils.hpp" +#include "behavior_path_lane_change_module/utils/utils.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" +#include "behavior_path_lane_change_module/utils/path.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" #include "behavior_path_planner_common/parameters.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" diff --git a/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..7a606b5d126ce --- /dev/null +++ b/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,126 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "behavior_path_planner/behavior_path_planner_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + const auto behavior_path_lane_change_module_dir = + ament_index_cpp::get_package_share_directory("behavior_path_lane_change_module"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::LaneChangeRightModuleManager"); + module_names.emplace_back("behavior_path_planner::LaneChangeLeftModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml"}); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} diff --git a/planning/behavior_path_planner/test/test_lane_change_utils.cpp b/planning/behavior_path_lane_change_module/test/test_lane_change_utils.cpp similarity index 95% rename from planning/behavior_path_planner/test/test_lane_change_utils.cpp rename to planning/behavior_path_lane_change_module/test/test_lane_change_utils.cpp index 477af32893b0b..1f90114df8045 100644 --- a/planning/behavior_path_planner/test/test_lane_change_utils.cpp +++ b/planning/behavior_path_lane_change_module/test/test_lane_change_utils.cpp @@ -11,8 +11,7 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" #include #include diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 56456b08aac1e..3e7a46f4899c3 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -14,13 +14,7 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/behavior_path_planner_node.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp src/scene_module/dynamic_avoidance/manager.cpp - src/scene_module/lane_change/interface.cpp - src/scene_module/lane_change/normal.cpp - src/scene_module/lane_change/external_request.cpp - src/scene_module/lane_change/manager.cpp - src/utils/lane_change/utils.cpp src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp - src/marker_utils/lane_change/debug.cpp ) target_include_directories(${PROJECT_NAME}_lib SYSTEM PUBLIC @@ -46,14 +40,6 @@ if(BUILD_TESTING) ${PROJECT_NAME}_lib ) - ament_add_ros_isolated_gmock(test_${CMAKE_PROJECT_NAME}_lane_change_module - test/test_lane_change_utils.cpp - ) - - target_link_libraries(test_${CMAKE_PROJECT_NAME}_lane_change_module - ${PROJECT_NAME}_lib - ) - ament_add_ros_isolated_gtest(test_${PROJECT_NAME}_node_interface test/test_${PROJECT_NAME}_node_interface.cpp ) diff --git a/planning/behavior_path_planner/plugins.xml b/planning/behavior_path_planner/plugins.xml index 2028b0d571e68..a16f3dd7bddee 100644 --- a/planning/behavior_path_planner/plugins.xml +++ b/planning/behavior_path_planner/plugins.xml @@ -1,7 +1,3 @@ - - - - diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index bab77f9141a00..f2c22f774fc77 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -50,10 +50,6 @@ std::shared_ptr generateNode() std::vector module_names; module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); - module_names.emplace_back("behavior_path_planner::LaneChangeRightModuleManager"); - module_names.emplace_back("behavior_path_planner::LaneChangeLeftModuleManager"); - module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); - module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"); std::vector params; params.emplace_back("launch_modules", module_names); @@ -67,8 +63,7 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml", - behavior_path_planner_dir + "/config/lane_change/lane_change.param.yaml"}); + behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml"}); return std::make_shared(node_options); } From 80717f760e3fd0b6769ba2ee6185c437e52e0bf6 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 14 Dec 2023 16:31:00 +0900 Subject: [PATCH 065/276] feat(diagnostic_graph_aggregator): change default publish rate (#5872) Signed-off-by: Takagi, Isamu --- system/diagnostic_graph_aggregator/config/default.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/diagnostic_graph_aggregator/config/default.param.yaml b/system/diagnostic_graph_aggregator/config/default.param.yaml index e91664c5b82d8..2660396bd86df 100644 --- a/system/diagnostic_graph_aggregator/config/default.param.yaml +++ b/system/diagnostic_graph_aggregator/config/default.param.yaml @@ -2,6 +2,6 @@ ros__parameters: use_operation_mode_availability: true use_debug_mode: false - rate: 1.0 + rate: 10.0 input_qos_depth: 1000 graph_qos_depth: 1 From 27264ed7ec7bf1b89ba684ebbc6bf664c782c170 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Thu, 14 Dec 2023 15:08:52 +0100 Subject: [PATCH 066/276] build(detected_object_validation): move header files to a separate directory to avoid conflicts (#5851) * build(detected_object_validation): move header files to a separate directory to avoid conflicts Signed-off-by: Esteve Fernandez * style(pre-commit): autofix --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../detected_object_filter/object_lanelet_filter.hpp | 8 ++++---- .../detected_object_filter/object_position_filter.hpp | 8 ++++---- .../obstacle_pointcloud_based_validator/debugger.hpp | 6 +++--- .../obstacle_pointcloud_based_validator.hpp | 11 +++++++---- .../occupancy_grid_based_validator.hpp | 6 +++--- .../{ => detected_object_validation}/utils/utils.hpp | 6 +++--- .../src/object_lanelet_filter.cpp | 2 +- .../src/object_position_filter.cpp | 2 +- .../src/obstacle_pointcloud_based_validator.cpp | 2 +- .../src/occupancy_grid_based_validator.cpp | 2 +- perception/detected_object_validation/src/utils.cpp | 2 +- 11 files changed, 29 insertions(+), 26 deletions(-) rename perception/detected_object_validation/include/{ => detected_object_validation}/detected_object_filter/object_lanelet_filter.hpp (88%) rename perception/detected_object_validation/include/{ => detected_object_validation}/detected_object_filter/object_position_filter.hpp (84%) rename perception/detected_object_validation/include/{ => detected_object_validation}/obstacle_pointcloud_based_validator/debugger.hpp (93%) rename perception/detected_object_validation/include/{ => detected_object_validation}/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp (90%) rename perception/detected_object_validation/include/{ => detected_object_validation}/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp (89%) rename perception/detected_object_validation/include/{ => detected_object_validation}/utils/utils.hpp (84%) diff --git a/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp similarity index 88% rename from perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp rename to perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp index ae6162542a1c3..4331b5c19d3f1 100644 --- a/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ -#define DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ +#ifndef DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ +#define DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ -#include "utils/utils.hpp" +#include "detected_object_validation/utils/utils.hpp" #include #include @@ -69,4 +69,4 @@ class ObjectLaneletFilterNode : public rclcpp::Node } // namespace object_lanelet_filter -#endif // DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ +#endif // DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ diff --git a/perception/detected_object_validation/include/detected_object_filter/object_position_filter.hpp b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp similarity index 84% rename from perception/detected_object_validation/include/detected_object_filter/object_position_filter.hpp rename to perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp index b9384e0f70379..be25eb6a353e6 100644 --- a/perception/detected_object_validation/include/detected_object_filter/object_position_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ -#define DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ +#ifndef DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ +#define DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ -#include "utils/utils.hpp" +#include "detected_object_validation/utils/utils.hpp" #include #include @@ -55,4 +55,4 @@ class ObjectPositionFilterNode : public rclcpp::Node } // namespace object_position_filter -#endif // DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ +#endif // DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ diff --git a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp similarity index 93% rename from perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp rename to perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp index 6597475ae297e..8f5fa054090f5 100644 --- a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ -#define OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ +#ifndef DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ +#define DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ #include @@ -113,4 +113,4 @@ class Debugger }; } // namespace obstacle_pointcloud_based_validator -#endif // OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ +#endif // DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ diff --git a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp similarity index 90% rename from perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp rename to perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp index e7df2c409b18f..2d70247445043 100644 --- a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp @@ -12,10 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ -#define OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ +// NOLINTNEXTLINE(whitespace/line_length) +#ifndef DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ +// NOLINTNEXTLINE(whitespace/line_length) +#define DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ -#include "obstacle_pointcloud_based_validator/debugger.hpp" +#include "detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp" #include @@ -152,4 +154,5 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node }; } // namespace obstacle_pointcloud_based_validator -#endif // OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ +// NOLINTNEXTLINE(whitespace/line_length) +#endif // DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ diff --git a/perception/detected_object_validation/include/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp b/perception/detected_object_validation/include/detected_object_validation/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp similarity index 89% rename from perception/detected_object_validation/include/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp rename to perception/detected_object_validation/include/detected_object_validation/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp index f62b0d866dc3a..5fd866d09e725 100644 --- a/perception/detected_object_validation/include/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ -#define OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ +#ifndef DETECTED_OBJECT_VALIDATION__OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ +#define DETECTED_OBJECT_VALIDATION__OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ #include #include @@ -68,4 +68,4 @@ class OccupancyGridBasedValidator : public rclcpp::Node }; } // namespace occupancy_grid_based_validator -#endif // OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ +#endif // DETECTED_OBJECT_VALIDATION__OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ diff --git a/perception/detected_object_validation/include/utils/utils.hpp b/perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp similarity index 84% rename from perception/detected_object_validation/include/utils/utils.hpp rename to perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp index 21df77825176b..2c46e1b9dd110 100644 --- a/perception/detected_object_validation/include/utils/utils.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef UTILS__UTILS_HPP_ -#define UTILS__UTILS_HPP_ +#ifndef DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_ +#define DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_ #include @@ -33,4 +33,4 @@ struct FilterTargetLabel }; // struct FilterTargetLabel } // namespace utils -#endif // UTILS__UTILS_HPP_ +#endif // DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_ diff --git a/perception/detected_object_validation/src/object_lanelet_filter.cpp b/perception/detected_object_validation/src/object_lanelet_filter.cpp index fe8de37c778ac..cd16d414425cb 100644 --- a/perception/detected_object_validation/src/object_lanelet_filter.cpp +++ b/perception/detected_object_validation/src/object_lanelet_filter.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "detected_object_filter/object_lanelet_filter.hpp" +#include "detected_object_validation/detected_object_filter/object_lanelet_filter.hpp" #include #include diff --git a/perception/detected_object_validation/src/object_position_filter.cpp b/perception/detected_object_validation/src/object_position_filter.cpp index 0f59e60d57d55..a509fc7571dd5 100644 --- a/perception/detected_object_validation/src/object_position_filter.cpp +++ b/perception/detected_object_validation/src/object_position_filter.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "detected_object_filter/object_position_filter.hpp" +#include "detected_object_validation/detected_object_filter/object_position_filter.hpp" namespace object_position_filter { diff --git a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp index 3249581513dd9..d903a9ca3bb41 100644 --- a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp +++ b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp" +#include "detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp" #include #include diff --git a/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp b/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp index 948f040d7ebde..80e4dc66d35c2 100644 --- a/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp +++ b/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "occupancy_grid_based_validator/occupancy_grid_based_validator.hpp" +#include "detected_object_validation/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp" #include #include diff --git a/perception/detected_object_validation/src/utils.cpp b/perception/detected_object_validation/src/utils.cpp index d8f438e265c3a..53b21ee7ff5b6 100644 --- a/perception/detected_object_validation/src/utils.cpp +++ b/perception/detected_object_validation/src/utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "utils/utils.hpp" +#include "detected_object_validation/utils/utils.hpp" #include From 7bdda89ac39764ab9f990ac6bd7fcac0d2c2aa4b Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Thu, 14 Dec 2023 15:35:40 +0100 Subject: [PATCH 067/276] fix(traffic_light_visualization): move header directory to match package name (#5864) * fix(traffic_light_visualization): move header directory to match package name Signed-off-by: Esteve Fernandez * style(pre-commit): autofix * fix: fix include Signed-off-by: Esteve Fernandez --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../traffic_light_map_visualizer/node.hpp | 6 +++--- .../traffic_light_roi_visualizer/nodelet.hpp | 6 +++--- .../src/traffic_light_map_visualizer/main.cpp | 3 ++- .../src/traffic_light_map_visualizer/node.cpp | 3 ++- .../src/traffic_light_roi_visualizer/nodelet.cpp | 3 ++- 5 files changed, 12 insertions(+), 9 deletions(-) rename perception/traffic_light_visualization/include/{ => traffic_light_visualization}/traffic_light_map_visualizer/node.hpp (88%) rename perception/traffic_light_visualization/include/{ => traffic_light_visualization}/traffic_light_roi_visualizer/nodelet.hpp (95%) diff --git a/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp b/perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_map_visualizer/node.hpp similarity index 88% rename from perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp rename to perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_map_visualizer/node.hpp index 3f83cf6e926ad..5e981bbeafda1 100644 --- a/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp +++ b/perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_map_visualizer/node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ -#define TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ +#ifndef TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ +#define TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ #include #include @@ -49,4 +49,4 @@ class TrafficLightMapVisualizerNode : public rclcpp::Node } // namespace traffic_light -#endif // TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ +#endif // TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ diff --git a/perception/traffic_light_visualization/include/traffic_light_roi_visualizer/nodelet.hpp b/perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_roi_visualizer/nodelet.hpp similarity index 95% rename from perception/traffic_light_visualization/include/traffic_light_roi_visualizer/nodelet.hpp rename to perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_roi_visualizer/nodelet.hpp index 1c64eb2f9e82b..13d9045e89e98 100644 --- a/perception/traffic_light_visualization/include/traffic_light_roi_visualizer/nodelet.hpp +++ b/perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_roi_visualizer/nodelet.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 TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ -#define TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ +#ifndef TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ +#define TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ #include #include @@ -123,4 +123,4 @@ class TrafficLightRoiVisualizerNodelet : public rclcpp::Node } // namespace traffic_light -#endif // TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ +#endif // TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ diff --git a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/main.cpp b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/main.cpp index 02f7a67302945..62d416457c6f0 100644 --- a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/main.cpp +++ b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/main.cpp @@ -12,8 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "traffic_light_visualization/traffic_light_map_visualizer/node.hpp" + #include -#include #include diff --git a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp index 53e06e47a1873..e621a20450bbf 100644 --- a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp +++ b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "traffic_light_visualization/traffic_light_map_visualizer/node.hpp" + #include #include #include -#include #include diff --git a/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp b/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp index 2f2d80ba43233..4ff9729695be2 100644 --- a/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp +++ b/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp @@ -12,9 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "traffic_light_visualization/traffic_light_roi_visualizer/nodelet.hpp" // NOLINT(whitespace/line_length) + #include #include -#include #include #include From 856f55a957b811181fc1b415f663530b886e92ff Mon Sep 17 00:00:00 2001 From: Yuntianyi Chen Date: Thu, 14 Dec 2023 16:07:43 -0800 Subject: [PATCH 068/276] refactor(compare_map_segmentation): rework parameters (#5005) * refactor the configuration files of the node compare_map_segmentation according to the new ROS node config guideline. Signed-off-by: yuntianyi-chen * style(pre-commit): autofix * Add three parameters Signed-off-by: yuntianyi-chen * style(pre-commit): autofix * Update perception/compare_map_segmentation/config/distance_based_compare_map_filter.param.yaml Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> * Update perception/compare_map_segmentation/config/voxel_based_approximate_compare_map_filter.param.yaml Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> * Update perception/compare_map_segmentation/config/voxel_based_compare_map_filter.param.yaml Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> * Update perception/compare_map_segmentation/config/voxel_distance_based_compare_map_filter.param.yaml Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> * Update perception/compare_map_segmentation/schema/voxel_based_approximate_compare_map_filter.schema.json Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> --------- Signed-off-by: yuntianyi-chen Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> --- .../compare_map_segmentation/CMakeLists.txt | 4 +- .../compare_elevation_map_filter.param.yaml | 5 ++ ...stance_based_compare_map_filter.param.yaml | 8 +++ ..._approximate_compare_map_filter.param.yaml | 9 +++ .../voxel_based_compare_map_filter.param.yaml | 9 +++ ...stance_based_compare_map_filter.param.yaml | 9 +++ .../compare_elevation_map_filter.launch.xml | 4 +- ...stance_based_compare_map_filter.launch.xml | 4 +- ..._approximate_compare_map_filter.launch.xml | 4 +- .../voxel_based_compare_map_filter.launch.xml | 15 +---- ...stance_based_compare_map_filter.launch.xml | 4 +- .../compare_elevation_map_filter.schema.json | 43 ++++++++++++ ...tance_based_compare_map_filter.schema.json | 38 +++++++++++ ...approximate_compare_map_filter.schema.json | 43 ++++++++++++ ...voxel_based_compare_map_filter.schema.json | 65 +++++++++++++++++++ ...tance_based_compare_map_filter.schema.json | 43 ++++++++++++ .../src/compare_elevation_map_filter_node.cpp | 6 +- 17 files changed, 293 insertions(+), 20 deletions(-) create mode 100644 perception/compare_map_segmentation/config/compare_elevation_map_filter.param.yaml create mode 100644 perception/compare_map_segmentation/config/distance_based_compare_map_filter.param.yaml create mode 100644 perception/compare_map_segmentation/config/voxel_based_approximate_compare_map_filter.param.yaml create mode 100644 perception/compare_map_segmentation/config/voxel_based_compare_map_filter.param.yaml create mode 100644 perception/compare_map_segmentation/config/voxel_distance_based_compare_map_filter.param.yaml create mode 100644 perception/compare_map_segmentation/schema/compare_elevation_map_filter.schema.json create mode 100644 perception/compare_map_segmentation/schema/distance_based_compare_map_filter.schema.json create mode 100644 perception/compare_map_segmentation/schema/voxel_based_approximate_compare_map_filter.schema.json create mode 100644 perception/compare_map_segmentation/schema/voxel_based_compare_map_filter.schema.json create mode 100644 perception/compare_map_segmentation/schema/voxel_distance_based_compare_map_filter.schema.json diff --git a/perception/compare_map_segmentation/CMakeLists.txt b/perception/compare_map_segmentation/CMakeLists.txt index 4655cf4c2f73a..d56cb3fb31584 100644 --- a/perception/compare_map_segmentation/CMakeLists.txt +++ b/perception/compare_map_segmentation/CMakeLists.txt @@ -89,6 +89,8 @@ install( RUNTIME DESTINATION bin ) -ament_auto_package(INSTALL_TO_SHARE +ament_auto_package( + INSTALL_TO_SHARE launch + config ) diff --git a/perception/compare_map_segmentation/config/compare_elevation_map_filter.param.yaml b/perception/compare_map_segmentation/config/compare_elevation_map_filter.param.yaml new file mode 100644 index 0000000000000..3d5270d17479e --- /dev/null +++ b/perception/compare_map_segmentation/config/compare_elevation_map_filter.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + map_layer_name: "elevation" + height_diff_thresh: 0.15 + map_frame: "map" diff --git a/perception/compare_map_segmentation/config/distance_based_compare_map_filter.param.yaml b/perception/compare_map_segmentation/config/distance_based_compare_map_filter.param.yaml new file mode 100644 index 0000000000000..f95c0b0c94b92 --- /dev/null +++ b/perception/compare_map_segmentation/config/distance_based_compare_map_filter.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + distance_threshold: 0.5 + use_dynamic_map_loading: true + timer_interval_ms: 100 + map_update_distance_threshold: 10.0 + map_loader_radius: 150.0 + publish_debug_pcd: False diff --git a/perception/compare_map_segmentation/config/voxel_based_approximate_compare_map_filter.param.yaml b/perception/compare_map_segmentation/config/voxel_based_approximate_compare_map_filter.param.yaml new file mode 100644 index 0000000000000..d54f7a96ecda0 --- /dev/null +++ b/perception/compare_map_segmentation/config/voxel_based_approximate_compare_map_filter.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + distance_threshold: 0.5 + use_dynamic_map_loading: true + downsize_ratio_z_axis: 0.5 + timer_interval_ms: 100 + map_update_distance_threshold: 10.0 + map_loader_radius: 150.0 + publish_debug_pcd: False diff --git a/perception/compare_map_segmentation/config/voxel_based_compare_map_filter.param.yaml b/perception/compare_map_segmentation/config/voxel_based_compare_map_filter.param.yaml new file mode 100644 index 0000000000000..d54f7a96ecda0 --- /dev/null +++ b/perception/compare_map_segmentation/config/voxel_based_compare_map_filter.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + distance_threshold: 0.5 + use_dynamic_map_loading: true + downsize_ratio_z_axis: 0.5 + timer_interval_ms: 100 + map_update_distance_threshold: 10.0 + map_loader_radius: 150.0 + publish_debug_pcd: False diff --git a/perception/compare_map_segmentation/config/voxel_distance_based_compare_map_filter.param.yaml b/perception/compare_map_segmentation/config/voxel_distance_based_compare_map_filter.param.yaml new file mode 100644 index 0000000000000..d54f7a96ecda0 --- /dev/null +++ b/perception/compare_map_segmentation/config/voxel_distance_based_compare_map_filter.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + distance_threshold: 0.5 + use_dynamic_map_loading: true + downsize_ratio_z_axis: 0.5 + timer_interval_ms: 100 + map_update_distance_threshold: 10.0 + map_loader_radius: 150.0 + publish_debug_pcd: False diff --git a/perception/compare_map_segmentation/launch/compare_elevation_map_filter.launch.xml b/perception/compare_map_segmentation/launch/compare_elevation_map_filter.launch.xml index 42478c514b788..9cb41c8780f13 100644 --- a/perception/compare_map_segmentation/launch/compare_elevation_map_filter.launch.xml +++ b/perception/compare_map_segmentation/launch/compare_elevation_map_filter.launch.xml @@ -1,11 +1,13 @@ + + - + diff --git a/perception/compare_map_segmentation/launch/distance_based_compare_map_filter.launch.xml b/perception/compare_map_segmentation/launch/distance_based_compare_map_filter.launch.xml index 4a272646503f1..cdf17ebfeda9f 100644 --- a/perception/compare_map_segmentation/launch/distance_based_compare_map_filter.launch.xml +++ b/perception/compare_map_segmentation/launch/distance_based_compare_map_filter.launch.xml @@ -1,11 +1,13 @@ + + - + diff --git a/perception/compare_map_segmentation/launch/voxel_based_approximate_compare_map_filter.launch.xml b/perception/compare_map_segmentation/launch/voxel_based_approximate_compare_map_filter.launch.xml index 2942781ce8123..e3f4594729c2b 100644 --- a/perception/compare_map_segmentation/launch/voxel_based_approximate_compare_map_filter.launch.xml +++ b/perception/compare_map_segmentation/launch/voxel_based_approximate_compare_map_filter.launch.xml @@ -1,11 +1,13 @@ + + - + diff --git a/perception/compare_map_segmentation/launch/voxel_based_compare_map_filter.launch.xml b/perception/compare_map_segmentation/launch/voxel_based_compare_map_filter.launch.xml index 2fc2884fd5df9..01ad5cd9b1792 100644 --- a/perception/compare_map_segmentation/launch/voxel_based_compare_map_filter.launch.xml +++ b/perception/compare_map_segmentation/launch/voxel_based_compare_map_filter.launch.xml @@ -1,25 +1,16 @@ + + - - - - - - - - - - - - + diff --git a/perception/compare_map_segmentation/launch/voxel_distance_based_compare_map_filter.launch.xml b/perception/compare_map_segmentation/launch/voxel_distance_based_compare_map_filter.launch.xml index 09ea9022b97e5..13023a8c1c2c9 100644 --- a/perception/compare_map_segmentation/launch/voxel_distance_based_compare_map_filter.launch.xml +++ b/perception/compare_map_segmentation/launch/voxel_distance_based_compare_map_filter.launch.xml @@ -1,11 +1,13 @@ + + - + diff --git a/perception/compare_map_segmentation/schema/compare_elevation_map_filter.schema.json b/perception/compare_map_segmentation/schema/compare_elevation_map_filter.schema.json new file mode 100644 index 0000000000000..24ac2481a4e4a --- /dev/null +++ b/perception/compare_map_segmentation/schema/compare_elevation_map_filter.schema.json @@ -0,0 +1,43 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Compare Elevation Map Filter", + "type": "object", + "definitions": { + "compare_elevation_map_filter": { + "type": "object", + "properties": { + "map_layer_name": { + "type": "string", + "default": "elevation", + "description": "elevation map layer name" + }, + "height_diff_thresh": { + "type": "number", + "default": "0.15", + "description": "Remove points whose height difference is below this value [m]" + }, + "map_frame": { + "type": "string", + "default": "map", + "description": "frame_id of the map that is temporarily used before elevation_map is subscribed" + } + }, + "required": ["map_layer_name", "height_diff_thresh", "map_frame"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/compare_elevation_map_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/compare_map_segmentation/schema/distance_based_compare_map_filter.schema.json b/perception/compare_map_segmentation/schema/distance_based_compare_map_filter.schema.json new file mode 100644 index 0000000000000..10454b48d3d80 --- /dev/null +++ b/perception/compare_map_segmentation/schema/distance_based_compare_map_filter.schema.json @@ -0,0 +1,38 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Distance Based Compare Map Filter", + "type": "object", + "definitions": { + "distance_based_compare_map_filter": { + "type": "object", + "properties": { + "distance_threshold": { + "type": "number", + "default": "0.5", + "description": "Threshold distance to compare input points with map points [m]" + }, + "use_dynamic_map_loading": { + "type": "boolean", + "default": "true", + "description": "map loading mode selection, true for dynamic map loading, false for static map loading, recommended for no-split map pointcloud" + } + }, + "required": ["distance_threshold", "use_dynamic_map_loading"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/distance_based_compare_map_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/compare_map_segmentation/schema/voxel_based_approximate_compare_map_filter.schema.json b/perception/compare_map_segmentation/schema/voxel_based_approximate_compare_map_filter.schema.json new file mode 100644 index 0000000000000..3c301d5ad9fbb --- /dev/null +++ b/perception/compare_map_segmentation/schema/voxel_based_approximate_compare_map_filter.schema.json @@ -0,0 +1,43 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Voxel Based Approximate Compare Map Filter", + "type": "object", + "definitions": { + "voxel_based_approximate_compare_map_filter": { + "type": "object", + "properties": { + "distance_threshold": { + "type": "number", + "default": "0.5", + "description": "Threshold distance to compare input points with map points [m]" + }, + "use_dynamic_map_loading": { + "type": "boolean", + "default": "true", + "description": "map loading mode selection, true for dynamic map loading, false for static map loading, recommended for no-split map pointcloud" + }, + "downsize_ratio_z_axis": { + "type": "number", + "default": "0.5", + "description": "Positive ratio to reduce voxel_leaf_size and neighbor point distance threshold in z axis" + } + }, + "required": ["distance_threshold", "use_dynamic_map_loading", "downsize_ratio_z_axis"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/voxel_based_approximate_compare_map_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/compare_map_segmentation/schema/voxel_based_compare_map_filter.schema.json b/perception/compare_map_segmentation/schema/voxel_based_compare_map_filter.schema.json new file mode 100644 index 0000000000000..2e541662a1743 --- /dev/null +++ b/perception/compare_map_segmentation/schema/voxel_based_compare_map_filter.schema.json @@ -0,0 +1,65 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Voxel Based Compare Map Filter", + "type": "object", + "definitions": { + "voxel_based_compare_map_filter": { + "type": "object", + "properties": { + "distance_threshold": { + "type": "number", + "default": "0.5", + "description": "Threshold distance to compare input points with map points [m]" + }, + "use_dynamic_map_loading": { + "type": "boolean", + "default": "true", + "description": "map loading mode selection, true for dynamic map loading, false for static map loading, recommended for no-split map pointcloud" + }, + "downsize_ratio_z_axis": { + "type": "number", + "default": "0.5", + "description": "Positive ratio to reduce voxel_leaf_size and neighbor point distance threshold in z axis" + }, + "map_update_distance_threshold": { + "type": "number", + "default": "10.0", + "description": "Threshold distance to update map points with input points [m]" + }, + "map_loader_radius": { + "type": "number", + "default": "150.0", + "description": "Radius to load map points [m]" + }, + "timer_interval_ms": { + "type": "number", + "default": "100", + "description": "Timer interval to load map points [ms]" + } + }, + "required": [ + "distance_threshold", + "use_dynamic_map_loading", + "downsize_ratio_z_axis", + "map_update_distance_threshold", + "map_loader_radius", + "timer_interval_ms" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/voxel_based_compare_map_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/compare_map_segmentation/schema/voxel_distance_based_compare_map_filter.schema.json b/perception/compare_map_segmentation/schema/voxel_distance_based_compare_map_filter.schema.json new file mode 100644 index 0000000000000..4663dbe806223 --- /dev/null +++ b/perception/compare_map_segmentation/schema/voxel_distance_based_compare_map_filter.schema.json @@ -0,0 +1,43 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Voxel Distance Based Compare Map Filter", + "type": "object", + "definitions": { + "voxel_distance_based_compare_map_filter": { + "type": "object", + "properties": { + "distance_threshold": { + "type": "number", + "default": "0.5", + "description": "Threshold distance to compare input points with map points [m]" + }, + "use_dynamic_map_loading": { + "type": "boolean", + "default": "true", + "description": "map loading mode selection, true for dynamic map loading, false for static map loading, recommended for no-split map pointcloud" + }, + "downsize_ratio_z_axis": { + "type": "number", + "default": "0.5", + "description": "Positive ratio to reduce voxel_leaf_size and neighbor point distance threshold in z axis" + } + }, + "required": ["distance_threshold", "use_dynamic_map_loading", "downsize_ratio_z_axis"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/voxel_distance_based_compare_map_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp b/perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp index 7c8f2e8d4bd76..1eadeeb3bec05 100644 --- a/perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp +++ b/perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp @@ -40,9 +40,9 @@ CompareElevationMapFilterComponent::CompareElevationMapFilterComponent( : Filter("CompareElevationMapFilter", options) { unsubscribe(); - layer_name_ = this->declare_parameter("map_layer_name", std::string("elevation")); - height_diff_thresh_ = this->declare_parameter("height_diff_thresh", 0.15); - map_frame_ = this->declare_parameter("map_frame", "map"); + layer_name_ = declare_parameter("map_layer_name"); + height_diff_thresh_ = declare_parameter("height_diff_thresh"); + map_frame_ = declare_parameter("map_frame"); rclcpp::QoS durable_qos{1}; durable_qos.transient_local(); From cbe1a2b22ee625898d8be254e1df6d5ccf385920 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Fri, 15 Dec 2023 09:42:32 +0900 Subject: [PATCH 069/276] feat(behavior_velocity_planner_common): add objects_of_interest_marker_intereface to behavior_velocity_planner (#5875) * feat(behavior_velocity_planner_common): add objects_of_interest_marker_intereface to behavior_velocity_planner Signed-off-by: Fumiya Watanabe * fix(behavior_velocity_planner_common): add functions to publish objects of interest marker Signed-off-by: Fumiya Watanabe * feat(no_stopping_area): insert object data Signed-off-by: Fumiya Watanabe * refactor(behavior_velocity_planner_common): rename function Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- .../src/scene_no_stopping_area.cpp | 4 +++ .../scene_module_interface.hpp | 30 +++++++++++++++++++ .../package.xml | 1 + .../src/scene_module_interface.cpp | 18 ++++++++++- 4 files changed, 52 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index 47d4985ae643e..e049d02ffe9b5 100644 --- a/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -230,6 +230,8 @@ bool NoStoppingAreaModule::checkStuckVehiclesInNoStoppingArea( } const auto obj_v = std::fabs(object.kinematics.initial_twist_with_covariance.twist.linear.x); if (obj_v > planner_param_.stuck_vehicle_vel_thr) { + setObjectsOfInterestData( + object.kinematics.initial_pose_with_covariance.pose, object.shape, ColorName::GREEN); continue; // not stop vehicle } // check if the footprint is in the stuck detect area @@ -237,6 +239,8 @@ bool NoStoppingAreaModule::checkStuckVehiclesInNoStoppingArea( const bool is_in_stuck_area = !bg::disjoint(obj_footprint, poly); if (is_in_stuck_area) { RCLCPP_DEBUG(logger_, "stuck vehicle found."); + setObjectsOfInterestData( + object.kinematics.initial_pose_with_covariance.pose, object.shape, ColorName::RED); for (const auto & p : obj_footprint.outer()) { geometry_msgs::msg::Point point; point.x = p.x(); diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp index ced2e267cc025..fcde16d8a871c 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include @@ -47,6 +48,8 @@ namespace behavior_velocity_planner using autoware_auto_planning_msgs::msg::PathWithLaneId; using builtin_interfaces::msg::Time; +using objects_of_interest_marker_interface::ColorName; +using objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using rtc_interface::RTCInterface; using tier4_autoware_utils::DebugPublisher; using tier4_debug_msgs::msg::Float64Stamped; @@ -55,6 +58,19 @@ using tier4_planning_msgs::msg::StopReason; using tier4_rtc_msgs::msg::Module; using unique_identifier_msgs::msg::UUID; +struct ObjectOfInterest +{ + geometry_msgs::msg::Pose pose; + autoware_auto_perception_msgs::msg::Shape shape; + ColorName color; + ObjectOfInterest( + const geometry_msgs::msg::Pose & pose, const autoware_auto_perception_msgs::msg::Shape & shape, + const ColorName & color_name) + : pose(pose), shape(shape), color(color_name) + { + } +}; + class SceneModuleInterface { public: @@ -94,6 +110,8 @@ class SceneModuleInterface void resetVelocityFactor() { velocity_factor_.reset(); } VelocityFactor getVelocityFactor() const { return velocity_factor_.get(); } + std::vector getObjectsOfInterestData() const { return objects_of_interest_; } + void clearObjectsOfInterestData() { objects_of_interest_.clear(); } protected: const int64_t module_id_; @@ -107,6 +125,7 @@ class SceneModuleInterface std::optional infrastructure_command_; std::optional first_stop_path_point_index_; VelocityFactorInterface velocity_factor_; + std::vector objects_of_interest_; void setSafe(const bool safe) { @@ -118,6 +137,13 @@ class SceneModuleInterface void setDistance(const double distance) { distance_ = distance; } void syncActivation() { setActivation(isSafe()); } + void setObjectsOfInterestData( + const geometry_msgs::msg::Pose & pose, const autoware_auto_perception_msgs::msg::Shape & shape, + const ColorName & color_name) + { + objects_of_interest_.emplace_back(pose, shape, color_name); + } + size_t findEgoSegmentIndex( const std::vector & points) const; }; @@ -200,6 +226,8 @@ class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface RTCInterface rtc_interface_; std::unordered_map map_uuid_; + ObjectsOfInterestMarkerInterface objects_of_interest_marker_interface_; + virtual void sendRTC(const Time & stamp); virtual void setActivation(); @@ -220,6 +248,8 @@ class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface void removeUUID(const int64_t & module_id); + void publishObjectsOfInterestMarker(); + void deleteExpiredModules(const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override; }; diff --git a/planning/behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner_common/package.xml index 187720ff92a15..784b7cabfe9ad 100644 --- a/planning/behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner_common/package.xml @@ -32,6 +32,7 @@ motion_utils motion_velocity_smoother nav_msgs + objects_of_interest_marker_interface pcl_conversions rclcpp rclcpp_components diff --git a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp index 49a52fcd60df2..6f596be92ec8b 100644 --- a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -192,7 +192,9 @@ void SceneModuleManagerInterface::unregisterModule( SceneModuleManagerInterfaceWithRTC::SceneModuleManagerInterfaceWithRTC( rclcpp::Node & node, const char * module_name, const bool enable_rtc) -: SceneModuleManagerInterface(node, module_name), rtc_interface_(&node, module_name, enable_rtc) +: SceneModuleManagerInterface(node, module_name), + rtc_interface_(&node, module_name, enable_rtc), + objects_of_interest_marker_interface_(&node, module_name) { } @@ -202,6 +204,7 @@ void SceneModuleManagerInterfaceWithRTC::plan( setActivation(); modifyPathVelocity(path); sendRTC(path->header.stamp); + publishObjectsOfInterestMarker(); } void SceneModuleManagerInterfaceWithRTC::sendRTC(const Time & stamp) @@ -244,6 +247,19 @@ void SceneModuleManagerInterfaceWithRTC::removeUUID(const int64_t & module_id) } } +void SceneModuleManagerInterfaceWithRTC::publishObjectsOfInterestMarker() +{ + for (const auto & scene_module : scene_modules_) { + const auto objects = scene_module->getObjectsOfInterestData(); + for (const auto & obj : objects) { + objects_of_interest_marker_interface_.insertObjectData(obj.pose, obj.shape, obj.color); + } + scene_module->clearObjectsOfInterestData(); + } + + objects_of_interest_marker_interface_.publishMarkerArray(); +} + void SceneModuleManagerInterfaceWithRTC::deleteExpiredModules( const autoware_auto_planning_msgs::msg::PathWithLaneId & path) { From c01b2e15675baa7e9efc1c589e1b45c22b681c64 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 15 Dec 2023 13:15:27 +0900 Subject: [PATCH 070/276] refactor(behavior_path_planner): move utils function to `behavior_path_planner_common` package (#5877) * refactor(bpp): remove unused header file Signed-off-by: satoshi-ota * refactor(bpp, bpp-common): move occ grid based collision detector Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../geometric_pull_over.hpp | 2 +- .../goal_planner_module.hpp | 2 +- .../goal_searcher.hpp | 2 +- .../shift_pull_over.hpp | 2 +- planning/behavior_path_planner/CMakeLists.txt | 1 - .../utils/lane_following/module_data.hpp | 32 ------------------- .../CMakeLists.txt | 1 + ...ccupancy_grid_based_collision_detector.hpp | 6 ++-- ...ccupancy_grid_based_collision_detector.cpp | 2 +- 9 files changed, 9 insertions(+), 41 deletions(-) delete mode 100644 planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp rename planning/{behavior_path_planner/include/behavior_path_planner => behavior_path_planner_common/include/behavior_path_planner_common}/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp (91%) rename planning/{behavior_path_planner => behavior_path_planner_common}/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp (98%) diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp index c5ba04ba7f52e..6de1a726d4d4e 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp @@ -16,7 +16,7 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index 8100ed7c66128..e90162c958be5 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -21,8 +21,8 @@ #include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "behavior_path_goal_planner_module/goal_searcher.hpp" #include "behavior_path_goal_planner_module/shift_pull_over.hpp" -#include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include "behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" #include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp index 2d9e2c6cf3700..94cf7bc7ff5dd 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp @@ -16,7 +16,7 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_HPP_ #include "behavior_path_goal_planner_module/goal_searcher_base.hpp" -#include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include #include diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp index cc8686f4a9fef..bd19dc2e87de0 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp @@ -16,7 +16,7 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 3e7a46f4899c3..f3727f35a492f 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -14,7 +14,6 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/behavior_path_planner_node.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp src/scene_module/dynamic_avoidance/manager.cpp - src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp ) target_include_directories(${PROJECT_NAME}_lib SYSTEM PUBLIC diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp deleted file mode 100644 index 98d52b79e2edf..0000000000000 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// Copyright 2021-2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__LANE_FOLLOWING__MODULE_DATA_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__LANE_FOLLOWING__MODULE_DATA_HPP_ - -namespace behavior_path_planner -{ - -struct LaneFollowingParameters -{ - double lane_change_prepare_duration{0.0}; - - // finding closest lanelet - double distance_threshold{0.0}; - double yaw_threshold{0.0}; -}; - -} // namespace behavior_path_planner - -#endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_FOLLOWING__MODULE_DATA_HPP_ diff --git a/planning/behavior_path_planner_common/CMakeLists.txt b/planning/behavior_path_planner_common/CMakeLists.txt index 5dbf81280f9b1..d1996bf72037f 100644 --- a/planning/behavior_path_planner_common/CMakeLists.txt +++ b/planning/behavior_path_planner_common/CMakeLists.txt @@ -23,6 +23,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/utils/drivable_area_expansion/footprints.cpp src/utils/parking_departure/geometric_parallel_parking.cpp src/utils/parking_departure/utils.cpp + src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp src/marker_utils/utils.cpp ) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp similarity index 91% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp rename to planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp index 91d99fcd4a0d6..c24aa021cf57c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ +#ifndef BEHAVIOR_PATH_PLANNER_COMMON__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ +#define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ #include @@ -149,4 +149,4 @@ class OccupancyGridBasedCollisionDetector } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ +#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ diff --git a/planning/behavior_path_planner/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp b/planning/behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp similarity index 98% rename from planning/behavior_path_planner/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp rename to planning/behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp index 0f87c68e38289..1aab58ac2ff6e 100644 --- a/planning/behavior_path_planner/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp +++ b/planning/behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include #include From 81fe2cdb329f8c97be3a2ecc17eaf4edd584e086 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 15 Dec 2023 04:50:31 +0000 Subject: [PATCH 071/276] chore: sync files (#5600) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/workflows/cancel-previous-workflows.yaml | 2 +- .github/workflows/github-release.yaml | 2 +- .github/workflows/pre-commit-optional.yaml | 2 +- .github/workflows/pre-commit.yaml | 2 +- .github/workflows/spell-check-differential.yaml | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/workflows/cancel-previous-workflows.yaml b/.github/workflows/cancel-previous-workflows.yaml index f9c29b81b6e6c..1da4d24966de9 100644 --- a/.github/workflows/cancel-previous-workflows.yaml +++ b/.github/workflows/cancel-previous-workflows.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.11.0 + uses: styfle/cancel-workflow-action@0.12.0 with: workflow_id: all all_but_latest: true diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 95ebb8725f62b..b426d0cba6614 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -30,7 +30,7 @@ jobs: echo "tag-name=${REF_NAME#beta/}" >> $GITHUB_OUTPUT - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 ref: ${{ steps.set-tag-name.outputs.ref-name }} diff --git a/.github/workflows/pre-commit-optional.yaml b/.github/workflows/pre-commit-optional.yaml index e754ecab24f85..38738196a0bd3 100644 --- a/.github/workflows/pre-commit-optional.yaml +++ b/.github/workflows/pre-commit-optional.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index b231dbda87938..33c00ee1066ae 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -16,7 +16,7 @@ jobs: private_key: ${{ secrets.PRIVATE_KEY }} - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: ref: ${{ github.event.pull_request.head.ref }} diff --git a/.github/workflows/spell-check-differential.yaml b/.github/workflows/spell-check-differential.yaml index eb18ccdba38d0..1fbf2ff46925c 100644 --- a/.github/workflows/spell-check-differential.yaml +++ b/.github/workflows/spell-check-differential.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Run spell-check uses: autowarefoundation/autoware-github-actions/spell-check@v1 From 4800c23450e01f25c5c578eecc1774d3fe08a88b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 15 Dec 2023 16:38:27 +0900 Subject: [PATCH 072/276] feat(crosswalk): ignore predicted path going across the crosswalk (#5849) Signed-off-by: Mamoru Sobue --- .../config/crosswalk.param.yaml | 1 + .../util.hpp | 2 + .../src/manager.cpp | 2 + .../src/scene_crosswalk.cpp | 111 ++++++++++++++++-- .../src/scene_crosswalk.hpp | 15 ++- 5 files changed, 118 insertions(+), 13 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index 6559f39278fdc..240963309e9a2 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -63,6 +63,7 @@ # param for target object filtering object_filtering: crosswalk_attention_range: 1.0 # [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk + vehicle_object_cross_angle_threshold: 0.5 # [rad] threshold judging object is crossing walkway as a pedestrian or passing over as a vehicle target_object: unknown: true # [-] whether to look and stop by UNKNOWN objects bicycle: true # [-] whether to look and stop by BICYCLE objects diff --git a/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp b/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp index 3f4af4a5a1138..77de7d241c05c 100644 --- a/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp +++ b/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp @@ -50,6 +50,8 @@ enum class CollisionState { YIELD, EGO_PASS_FIRST, EGO_PASS_LATER, IGNORE }; struct CollisionPoint { geometry_msgs::msg::Point collision_point{}; + std::optional crosswalk_passage_direction{ + std::nullopt}; // denote obj is passing the crosswalk along the vehicle lane double time_to_collision{}; double time_to_vehicle{}; }; diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index cb0311ffe8ebb..b8190cb6124e7 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -116,6 +116,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) // param for target area & object cp.crosswalk_attention_range = getOrDeclareParameter(node, ns + ".object_filtering.crosswalk_attention_range"); + cp.vehicle_object_cross_angle_threshold = getOrDeclareParameter( + node, ns + ".object_filtering.vehicle_object_cross_angle_threshold"); cp.look_unknown = getOrDeclareParameter(node, ns + ".object_filtering.target_object.unknown"); cp.look_bicycle = diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 239eddca1fed9..69440aaddc2d0 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -25,6 +25,7 @@ #include #include +#include #include #include @@ -316,6 +317,8 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( const double ego_vel = planner_data_->current_velocity->twist.linear.x; const double ego_acc = planner_data_->current_acceleration->accel.accel.linear.x; + const std::optional ego_crosswalk_passage_direction = + findEgoPassageDirectionAlongPath(sparse_resample_path); const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; const auto dist_ego_to_stop = calcSignedArcLength(ego_path.points, ego_pos, p_stop_line->first) + p_stop_line->second; @@ -349,25 +352,44 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( // Check pedestrian for stop // NOTE: first stop point and its minimum distance from ego to stop + auto isVehicleType = [](const uint8_t label) { + return label == ObjectClassification::MOTORCYCLE || label == ObjectClassification::BICYCLE; + }; std::optional> nearest_stop_info; std::vector stop_factor_points; for (const auto & object : object_info_manager_.getObject()) { - const auto & collision_point = object.collision_point; - if (collision_point) { + const auto & collision_point_opt = object.collision_point; + if (collision_point_opt) { + const auto & collision_point = collision_point_opt.value(); const auto & collision_state = object.collision_state; if (collision_state != CollisionState::YIELD) { continue; } + if ( + isVehicleType(object.classification) && ego_crosswalk_passage_direction && + collision_point.crosswalk_passage_direction) { + const double direction_diff = tier4_autoware_utils::normalizeRadian( + collision_point.crosswalk_passage_direction.value() - + ego_crosswalk_passage_direction.value()); + RCLCPP_INFO( + rclcpp::get_logger("temp"), + "collision_point.crosswalk_passage_direction = %f, ego_crosswalk_passage_direction = %f, " + "direction_diff = %f", + collision_point.crosswalk_passage_direction.value(), + ego_crosswalk_passage_direction.value(), direction_diff); + if (std::fabs(direction_diff) < planner_param_.vehicle_object_cross_angle_threshold) { + continue; + } + } stop_factor_points.push_back(object.position); const auto dist_ego2cp = - calcSignedArcLength( - sparse_resample_path.points, ego_pos, collision_point->collision_point) - + calcSignedArcLength(sparse_resample_path.points, ego_pos, collision_point.collision_point) - planner_param_.stop_distance_from_object; if (!nearest_stop_info || dist_ego2cp - base_link2front < nearest_stop_info->second) { nearest_stop_info = - std::make_pair(collision_point->collision_point, dist_ego2cp - base_link2front); + std::make_pair(collision_point.collision_point, dist_ego2cp - base_link2front); } } } @@ -580,6 +602,70 @@ std::pair CrosswalkModule::clampAttentionRangeByNeighborCrosswal return std::make_pair(clamped_near_attention_range, clamped_far_attention_range); } +std::optional CrosswalkModule::findEgoPassageDirectionAlongPath( + const PathWithLaneId & path) const +{ + auto findIntersectPoint = [&](const lanelet::ConstLineString3d line) + -> std::optional> { + const auto line_start = + tier4_autoware_utils::createPoint(line.front().x(), line.front().y(), line.front().z()); + const auto line_end = + tier4_autoware_utils::createPoint(line.back().x(), line.back().y(), line.back().z()); + for (unsigned i = 0; i < path.points.size() - 1; ++i) { + const auto & start = path.points.at(i).point.pose.position; + const auto & end = path.points.at(i + 1).point.pose.position; + if (const auto intersect = tier4_autoware_utils::intersect(line_start, line_end, start, end); + intersect.has_value()) { + return std::make_optional(std::make_pair(i, intersect.value())); + } + } + return std::nullopt; + }; + const auto intersect_pt1 = findIntersectPoint(crosswalk_.leftBound()); + const auto intersect_pt2 = findIntersectPoint(crosswalk_.rightBound()); + + if (!intersect_pt1 || !intersect_pt2) { + return std::nullopt; + } + const auto idx1 = intersect_pt1.value().first, idx2 = intersect_pt2.value().first; + const auto & front = idx1 > idx2 ? intersect_pt2.value().second : intersect_pt1.value().second; + const auto & back = idx1 > idx2 ? intersect_pt1.value().second : intersect_pt2.value().second; + return std::atan2(back.y - front.y, back.x - front.x); +} + +std::optional CrosswalkModule::findObjectPassageDirectionAlongVehicleLane( + const autoware_auto_perception_msgs::msg::PredictedPath & path) const +{ + using tier4_autoware_utils::Segment2d; + + auto findIntersectPoint = [&](const lanelet::ConstLineString3d line) + -> std::optional> { + const auto line_start = + tier4_autoware_utils::createPoint(line.front().x(), line.front().y(), line.front().z()); + const auto line_end = + tier4_autoware_utils::createPoint(line.back().x(), line.back().y(), line.back().z()); + for (unsigned i = 0; i < path.path.size() - 1; ++i) { + const auto & start = path.path.at(i).position; + const auto & end = path.path.at(i + 1).position; + if (const auto intersect = tier4_autoware_utils::intersect(line_start, line_end, start, end); + intersect.has_value()) { + return std::make_optional(std::make_pair(i, intersect.value())); + } + } + return std::nullopt; + }; + const auto intersect_pt1 = findIntersectPoint(crosswalk_.leftBound()); + const auto intersect_pt2 = findIntersectPoint(crosswalk_.rightBound()); + + if (!intersect_pt1 || !intersect_pt2) { + return std::nullopt; + } + const auto idx1 = intersect_pt1.value().first, idx2 = intersect_pt2.value().first; + const auto & front = idx1 > idx2 ? intersect_pt2.value().second : intersect_pt1.value().second; + const auto & back = idx1 > idx2 ? intersect_pt1.value().second : intersect_pt2.value().second; + return std::atan2(back.y - front.y, back.x - front.x); +} + std::optional CrosswalkModule::getCollisionPoint( const PathWithLaneId & ego_path, const PredictedObject & object, const std::pair & crosswalk_attention_range, const Polygon2d & attention_area) @@ -625,6 +711,8 @@ std::optional CrosswalkModule::getCollisionPoint( // Calculate multi-step object polygon, and reset start_idx const size_t start_idx_with_margin = std::max(static_cast(start_idx) - 1, 0); const size_t end_idx_with_margin = std::min(i + 1, obj_path.path.size() - 1); + const auto object_crosswalk_passage_direction = + findObjectPassageDirectionAlongVehicleLane(obj_path); const auto obj_multi_step_polygon = createMultiStepPolygon( obj_path.path, obj_polygon, start_idx_with_margin, end_idx_with_margin); is_start_idx_initialized = false; @@ -660,7 +748,8 @@ std::optional CrosswalkModule::getCollisionPoint( if (dist_ego2cp < minimum_stop_dist) { minimum_stop_dist = dist_ego2cp; nearest_collision_point = createCollisionPoint( - intersection_center_point, dist_ego2cp, dist_obj2cp, ego_vel, obj_vel); + intersection_center_point, dist_ego2cp, dist_obj2cp, ego_vel, obj_vel, + object_crosswalk_passage_direction); debug_data_.obj_polygons.push_back( toGeometryPointVector(obj_multi_step_polygon, ego_pos.z)); } @@ -679,17 +768,18 @@ std::optional CrosswalkModule::getCollisionPoint( CollisionPoint CrosswalkModule::createCollisionPoint( const geometry_msgs::msg::Point & nearest_collision_point, const double dist_ego2cp, const double dist_obj2cp, const geometry_msgs::msg::Vector3 & ego_vel, - const geometry_msgs::msg::Vector3 & obj_vel) const + const geometry_msgs::msg::Vector3 & obj_vel, + const std::optional object_crosswalk_passage_direction) const { constexpr double min_ego_velocity = 1.38; // [m/s] - - const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y); const auto velocity = std::max(planner_param_.min_object_velocity, estimated_velocity); CollisionPoint collision_point{}; collision_point.collision_point = nearest_collision_point; + collision_point.crosswalk_passage_direction = object_crosswalk_passage_direction; collision_point.time_to_collision = std::max(0.0, dist_ego2cp - planner_param_.stop_distance_from_object - base_link2front) / std::max(ego_vel.x, min_ego_velocity); @@ -931,7 +1021,8 @@ void CrosswalkModule::updateObjectState( getCollisionPoint(sparse_resample_path, object, crosswalk_attention_range, attention_area); object_info_manager_.update( obj_uuid, obj_pos, std::hypot(obj_vel.x, obj_vel.y), clock_->now(), is_ego_yielding, - has_traffic_light, collision_point, planner_param_, crosswalk_.polygon2d().basicPolygon()); + has_traffic_light, collision_point, object.classification.front().label, planner_param_, + crosswalk_.polygon2d().basicPolygon()); if (collision_point) { const auto collision_state = object_info_manager_.getCollisionState(obj_uuid); diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index ef6d01fc43c23..7f020fbe5422c 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -150,6 +150,7 @@ class CrosswalkModule : public SceneModuleInterface double traffic_light_state_timeout; // param for target area & object double crosswalk_attention_range; + double vehicle_object_cross_angle_threshold; bool look_unknown; bool look_bicycle; bool look_motorcycle; @@ -160,6 +161,7 @@ class CrosswalkModule : public SceneModuleInterface { CollisionState collision_state{}; std::optional time_to_start_stopped{std::nullopt}; + uint8_t classification{ObjectClassification::UNKNOWN}; geometry_msgs::msg::Point position{}; std::optional collision_point{}; @@ -242,8 +244,8 @@ class CrosswalkModule : public SceneModuleInterface void update( const std::string & uuid, const geometry_msgs::msg::Point & position, const double vel, const rclcpp::Time & now, const bool is_ego_yielding, const bool has_traffic_light, - const std::optional & collision_point, const PlannerParam & planner_param, - const lanelet::BasicPolygon2d & crosswalk_polygon) + const std::optional & collision_point, const uint8_t classification, + const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon) { // update current uuids current_uuids_.push_back(uuid); @@ -265,6 +267,7 @@ class CrosswalkModule : public SceneModuleInterface crosswalk_polygon); objects.at(uuid).collision_point = collision_point; objects.at(uuid).position = position; + objects.at(uuid).classification = classification; } void finalize() { @@ -330,6 +333,11 @@ class CrosswalkModule : public SceneModuleInterface const std::vector & path_intersects, const std::optional & stop_pose) const; + std::optional findEgoPassageDirectionAlongPath( + const PathWithLaneId & sparse_resample_path) const; + std::optional findObjectPassageDirectionAlongVehicleLane( + const autoware_auto_perception_msgs::msg::PredictedPath & path) const; + std::optional getCollisionPoint( const PathWithLaneId & ego_path, const PredictedObject & object, const std::pair & crosswalk_attention_range, const Polygon2d & attention_area); @@ -366,7 +374,8 @@ class CrosswalkModule : public SceneModuleInterface CollisionPoint createCollisionPoint( const geometry_msgs::msg::Point & nearest_collision_point, const double dist_ego2cp, const double dist_obj2cp, const geometry_msgs::msg::Vector3 & ego_vel, - const geometry_msgs::msg::Vector3 & obj_vel) const; + const geometry_msgs::msg::Vector3 & obj_vel, + const std::optional object_crosswalk_passage_direction) const; float calcTargetVelocity( const geometry_msgs::msg::Point & stop_point, const PathWithLaneId & ego_path) const; From b7ca1005f2fedf8b3ab6c99e01c12bc4d4c8d4eb Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Fri, 15 Dec 2023 16:41:48 +0900 Subject: [PATCH 073/276] refactor(image_projection_based_fusion): add JSON Schema and remove default value spefications (#4902) * refactor: add JSON Schema and remove default values in `declare_parameter()` Signed-off-by: ktro2828 * refactor: update configuration file Signed-off-by: ktro2828 * refactor: add configuration file and update launcher to load this Signed-off-by: ktro2828 * refactor: update funsion node configuration Signed-off-by: ktro2828 * docs: update the document for roi cluster fusion Signed-off-by: ktro2828 * docs: update documents Signed-off-by: ktro2828 * refactor: move `debug_mode` into `roi_sync.param.yaml` Signed-off-by: ktro2828 * refactor: rework parameters for `roi_pointcloud_fusion` Signed-off-by: ktro2828 * chore: update maintainers Signed-off-by: ktro2828 * refactor: remove debug_mode Signed-off-by: ktro2828 * refactor: rename parameter to avoid failure of spell-check Signed-off-by: ktro2828 * fix: fix typo and parameters for initialization Signed-off-by: ktro2828 --------- Signed-off-by: ktro2828 --- .../config/pointpainting.param.yaml | 40 +- .../config/roi_cluster_fusion.param.yaml | 12 + .../config/roi_pointcloud_fusion.param.yaml | 5 + .../config/roi_sync.param.yaml | 8 + .../images/roi_cluster_fusion_pipeline.svg | 966 ++++++++++++++++++ .../docs/roi-cluster-fusion.md | 5 + .../launch/pointpainting_fusion.launch.xml | 7 - .../launch/roi_cluster_fusion.launch.xml | 36 +- .../roi_detected_object_fusion.launch.xml | 6 - .../launch/roi_pointcloud_fusion.launch.xml | 8 +- .../image_projection_based_fusion/package.xml | 2 + .../schema/pointpainting.schema.json | 152 +++ .../schema/roi_cluster_fusion.schema.json | 96 ++ .../roi_detected_object_fusion.schema.json | 70 ++ .../schema/roi_pointcloud_fusion.schema.json | 41 + .../schema/roi_sync.schema.json | 84 ++ .../src/fusion_node.cpp | 19 +- .../src/pointpainting_fusion/node.cpp | 60 +- 18 files changed, 1510 insertions(+), 107 deletions(-) create mode 100644 perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml create mode 100644 perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml create mode 100644 perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg create mode 100644 perception/image_projection_based_fusion/schema/pointpainting.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_sync.schema.json diff --git a/perception/image_projection_based_fusion/config/pointpainting.param.yaml b/perception/image_projection_based_fusion/config/pointpainting.param.yaml index e1be5426cba4b..21d31f216373b 100755 --- a/perception/image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/image_projection_based_fusion/config/pointpainting.param.yaml @@ -1,18 +1,26 @@ /**: ros__parameters: - class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] - paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] - point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle - max_voxel_size: 40000 - point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] - voxel_size: [0.32, 0.32, 8.0] - downsample_factor: 1 - encoder_in_feature_size: 12 - yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] - # post-process params - circle_nms_dist_threshold: 0.3 - iou_nms_target_class_names: ["CAR"] - iou_nms_search_distance_2d: 10.0 - iou_nms_threshold: 0.1 - # omp params - omp_num_threads: 1 + model_params: + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] + point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle + max_voxel_size: 40000 + point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + voxel_size: [0.32, 0.32, 8.0] + downsample_factor: 1 + encoder_in_feature_size: 12 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + has_twist: false + densification_params: + world_frame_id: "map" + num_past_frames: 0 + post_process_params: + # post-process params + circle_nms_dist_threshold: 0.3 + iou_nms_target_class_names: ["CAR"] + iou_nms_search_distance_2d: 10.0 + iou_nms_threshold: 0.1 + score_threshold: 0.4 + omp_params: + # omp params + num_threads: 1 diff --git a/perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml b/perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml new file mode 100644 index 0000000000000..90ba841d53b2d --- /dev/null +++ b/perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml @@ -0,0 +1,12 @@ +/**: + ros__parameters: + fusion_distance: 100.0 + trust_object_distance: 100.0 + trust_object_iou_mode: "iou" + non_trust_object_iou_mode: "iou_x" + use_cluster_semantic_type: false + only_allow_inside_cluster: true + roi_scale_factor: 1.1 + iou_threshold: 0.65 + unknown_iou_threshold: 0.1 + remove_unknown: true diff --git a/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml b/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml new file mode 100644 index 0000000000000..5b86b8e81d1aa --- /dev/null +++ b/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + fuse_unknown_only: true + min_cluster_size: 2 + cluster_2d_tolerance: 0.5 diff --git a/perception/image_projection_based_fusion/config/roi_sync.param.yaml b/perception/image_projection_based_fusion/config/roi_sync.param.yaml index 21ba13787f1c0..99d85089befb8 100644 --- a/perception/image_projection_based_fusion/config/roi_sync.param.yaml +++ b/perception/image_projection_based_fusion/config/roi_sync.param.yaml @@ -3,3 +3,11 @@ input_offset_ms: [61.67, 111.67, 45.0, 28.33, 78.33, 95.0] timeout_ms: 70.0 match_threshold_ms: 50.0 + image_buffer_size: 15 + debug_mode: false + filter_scope_min_x: -100.0 + filter_scope_min_y: -100.0 + filter_scope_min_z: -100.0 + filter_scope_max_x: 100.0 + filter_scope_max_y: 100.0 + filter_scope_max_z: 100.0 diff --git a/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg b/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg new file mode 100644 index 0000000000000..aaadfaf186dd2 --- /dev/null +++ b/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg @@ -0,0 +1,966 @@ + + + + + + + + + + +
+
+
+ + Check whether + the cluster RoI (inner) + is fully contained within + the scaled detected RoI (outer) + . +
+
+ *NOTE* +
+ Because the cluster RoI is calculated with the points projected on the image, our recommended scale factor is [1.1, 1.5] . +
+ Otherwise, set + only_allow_inside_cluster + to + False + . +
+
+
+
+
+
+ Check whether the cluster RoI (inner) is fully contained within the scaled... +
+
+ + + + +
+
+
+ use_iou +
+
+
+
+ use_iou +
+
+ + + + +
+
+
+ unknown_iou_threshold +
+
+
+
+ unknown_iou_threshold +
+
+ + + + +
+
+
+ + use_iou_x /  y +
+
+
+
+
+
+ use_iou_x /  y +
+
+ + + + + + +
+
+
+ only_allow_inside_cluster +
+
+
+
+ only_allow_inside_cluster +
+
+ + + + +
+
+
+ iou_threshold +
+
+
+
+ iou_threshold +
+
+ + + + + + + + +
+
+
+ Is UNKNOWN object? +
+
+
+
+ Is UNKNOWN object? +
+
+ + + + + + +
+
+
+ + IoU threshold < IoU score? + +
+
+
+
+ IoU threshold < IoU score? +
+
+ + + + + + + + + + + + +
+
+
+ IoU Score +
+
+
+
+ IoU Score +
+
+ + + + + + + + + + + + + + + + + + + + + +
+
+
+ Is Cluster RoI inside Detected RoI? +
+
+
+
+ Is Cluster RoI inside Detected RoI? +
+
+ + + + + + +
+
+
+ Fused Cluster +
+
+
+
+ Fused Cluster +
+
+ + + + + + +
+
+
+ Unfused Cluster +
+
+
+
+ Unfused Cluster +
+
+ + + + + + + + +
+
+
+ Fusion Target Cluster
&
Detected RoI
+
+
+
+
+ Fusion Target Cluster... +
+
+ + + + +
+
+
+ Unfused Cluster +
+
+
+
+ Unfused Cluster +
+
+ + + + + + + + + + + +
+
+
+ + + roi_scale_factor
(>=1.0)
+
+
+
+
+
+
+ roi_scale_factor... +
+
+ + + + +
+
+
+ + Check whether the IoU score between + the cluster RoI + and + the detected RoI + is greater than the threshold. +
+
+ **NOTE** +
+ Our default threshold is 0.65 with + only_allow_inside_cluster + is + True + . +
+ Also, please try the bigger score threshold and set + only_allow_inside_cluster + to + False + depending on your 2D RoI detector performance. +
+
+
+
+
+
+ Check whether the IoU score between the cluster RoI and the detected RoI is greater than the thr... +
+
+ + + + + + +
+
+
+
    +
  • + IoU = Intersection Area / Union Area +
  • +
  • + IoU X = Intersection Width / Union Width +
  • +
  • + IoU Y = Intersection Height / Union Height +
  • +
+
+
+
+
+ IoU = Intersection Area / Union AreaIoU X = Intersectio... +
+
+ + + + +
+
+
+ + Nodes overview + +
+
+
+
+ Nodes overview +
+
+ + + + +
+
+
+ Numeric Parameter +
+
+
+
+ Numeric Parameter +
+
+ + + + +
+
+
+ Result +
+
+
+
+ Result +
+
+ + + + + + + + +
+
+
+ Boolean Parameter +
+
+
+
+ Boolean Parameter +
+
+ + + + +
+
+
+ + true + +
+
+
+
+ true +
+
+ + + + +
+
+
+ + false + +
+
+
+
+ false +
+
+ + + + + + + + +
+
+
+ Condition +
+
+
+
+ Condition +
+
+ + + + +
+
+
+ + true + +
+
+
+
+ true +
+
+ + + + +
+
+
+ + false + +
+
+
+
+ false +
+
+ + + + +
+
+
+ use_cluster_semantic_type +
+
+
+
+ use_cluster_semantic_type +
+
+ + + + +
+
+
+ + Objects +
+ w/ Semantic Label +
+
+
+
+
+ Objects... +
+
+ + + + + + +
+
+
+ + All objects are set to +
+ UNKOWN Label +
+
+
+
+
+
+ All objects are set to... +
+
+ + + + + + + + +
+
+
+ Fusion Target Cluster +
+
+
+
+ Fusion Target Cluster +
+
+ + + + +
+
+
+ trust_distance +
+
+
+
+ trust_distance +
+
+ + + + + + +
+
+
+ + Is Cluster closer than + trust_distance + ? + +
+
+
+
+ Is Cluster closer than trust_... +
+
+ + + + + + + + + + + + +
+
+
+ + Input Cluster + +
+
+
+
+ Input Cluster +
+
+ + + + +
+
+
+ roi_scale_factor +
+
+
+
+ roi_scale_factor +
+
+ + + + +
+
+
+ Pre-Process +
+
+
+
+ Pre-Process +
+
+ + + + +
+
+
+ Fusion Process +
+
+
+
+ Fusion Process +
+
+ + + + +
+
+
+ Post-Process +
+
+
+
+ Post-Process +
+
+ + + + + + +
+
+
+ remove_unknown +
+
+
+
+ remove_unknown +
+
+ + + + + + +
+
+
+ Fused Cluster +
+
+
+
+ Fused Cluster +
+
+ + + + +
+
+
+ Is KNOWN object?
&&
0.1 <= RoI probability?
+
+
+
+
+ Is KNOWN object?... +
+
+ + + + + + +
+
+
+ Remove noise clusters, which are undetected by RoI detector, such as fog and exhaust gas. +
+
+
+
+ Remove noise clusters, which are undet... +
+
+ + + + +
+
+
+ + Output Fused Cluster + +
+
+
+
+ Output Fused Cluster +
+
+ + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md b/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md index 03eaab2a3c6ca..86d3a2fa070b2 100644 --- a/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md +++ b/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md @@ -30,6 +30,11 @@ The clusters are projected onto image planes, and then if the ROIs of clusters a ## Parameters +The following figure is an inner pipeline overview of RoI cluster fusion node. +Please refer to it for your parameter settings. + +![roi_cluster_fusion_pipeline](./images/roi_cluster_fusion_pipeline.svg) + ### Core Parameters | Name | Type | Description | diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index e15737f5ed222..33781461fa1cc 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -30,7 +30,6 @@ - @@ -43,9 +42,6 @@ - - - @@ -82,9 +78,6 @@ - - - diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index 60f6f943b8cda..52dd71e9579c1 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -18,24 +18,11 @@ + - - - - - - - - - - - - - - @@ -46,17 +33,8 @@ - - - - - - - - - - + @@ -86,16 +64,6 @@ - - - - - - - - - - diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index b6165fc7c87d2..c9da81af9ddb0 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -25,8 +25,6 @@ - - @@ -69,10 +67,6 @@ - - - - diff --git a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml index 181f4ccb88320..046d88d06e2a1 100644 --- a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml @@ -1,8 +1,5 @@ - - - @@ -23,6 +20,7 @@ + @@ -38,9 +36,7 @@ - - - + diff --git a/perception/image_projection_based_fusion/package.xml b/perception/image_projection_based_fusion/package.xml index 1648de210ec2c..49ff4dafc7900 100644 --- a/perception/image_projection_based_fusion/package.xml +++ b/perception/image_projection_based_fusion/package.xml @@ -9,6 +9,8 @@ Shunsuke Miura Yoshi Ri badai nguyen + Kotaro Uetake + Tao Zhong Apache License 2.0 ament_cmake_auto diff --git a/perception/image_projection_based_fusion/schema/pointpainting.schema.json b/perception/image_projection_based_fusion/schema/pointpainting.schema.json new file mode 100644 index 0000000000000..036628d72e70a --- /dev/null +++ b/perception/image_projection_based_fusion/schema/pointpainting.schema.json @@ -0,0 +1,152 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Point Painting Fusion Node", + "type": "object", + "definitions": { + "pointpainting": { + "type": "object", + "properties": { + "model_params": { + "type": "object", + "description": "Parameters for model configuration.", + "properties": { + "class_names": { + "type": "array", + "description": "An array of class names will be predicted.", + "default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "paint_class_names": { + "type": "array", + "description": "An array of class names will be painted by PointPainting", + "default": ["CAR", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "point_feature_size": { + "type": "integer", + "description": "A number of channels of point feature layer.", + "default": 7 + }, + "max_voxel_size": { + "type": "integer", + "description": "A maximum size of voxel grid.", + "default": 40000 + }, + "point_cloud_range": { + "type": "array", + "description": "An array of distance ranges of each class, this must have same length with `class_names`.", + "default": [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + }, + "voxel_size": { + "type": "array", + "description": "An array of voxel grid sizes for PointPainting, this must have same length with `paint_class_names`.", + "default": [0.32, 0.32, 8.0] + }, + "down_sample_factor": { + "type": "integer", + "description": "A scale factor of downsampling points", + "default": 1, + "minimum": 1 + }, + "encoder_in_feature_size": { + "type": "integer", + "description": "A size of encoder input feature channels.", + "default": 12 + }, + "yaw_norm_thresholds": { + "type": "array", + "description": "An array of distance threshold values of norm of yaw [rad].", + "default": [0.3, 0.3, 0.3, 0.3, 0.0], + "minimum": 0.0, + "maximum": 1.0 + }, + "has_twist": { + "type": "boolean", + "description": "Indicates whether the model outputs twist value.", + "default": false + } + } + }, + "densification_params": { + "type": "object", + "description": "Parameters for pointcloud densification.", + "properties": { + "world_frame_id": { + "type": "string", + "description": "A name of frame id where world coordinates system is defined with respect to.", + "default": "map" + }, + "num_past_frames": { + "type": "integer", + "description": "A number of past frames to be considered as same input frame.", + "default": 0, + "minimum": 0 + } + } + }, + "post_process_params": { + "type": "object", + "properties": { + "score_threshold": { + "type": "number", + "description": "A threshold value of existence probability score, all of objects with score less than this threshold are ignored.", + "default": 0.4, + "minimum": 0.0, + "maximum": 1.0 + }, + "circle_nms_dist_threshold": { + "type": "number", + "description": "", + "default": 0.3, + "minimum": 0.0, + "maximum": 1.0 + }, + "iou_nms_target_class_names": { + "type": "array", + "description": "An array of class names to be target in NMS.", + "default": ["CAR"], + "uniqueItems": true + }, + "iou_search_distance_2d": { + "type": "number", + "description": "A maximum distance value to search the nearest objects.", + "default": 10.0, + "minimum": 0.0 + }, + "iou_nms_threshold": { + "type": "number", + "description": "A threshold value of NMS using IoU score.", + "default": 0.1, + "minimum": 0.0, + "maximum": 1.0 + } + } + }, + "omp_params": { + "type": "object", + "properties": { + "num_threads": { + "type": "integer", + "description": "The number of threads that is set to the environment variable OMP_NUM_THREADS.", + "default": 1, + "minimum": 1 + } + } + } + }, + "required": ["model_params", "densification_params", "post_process_params", "omp_params"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/pointpainting" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json new file mode 100644 index 0000000000000..fc32e9d6d3d8b --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json @@ -0,0 +1,96 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for RoI Cluster Fusion Node", + "type": "object", + "definitions": { + "roi_cluster_fusion": { + "type": "object", + "properties": { + "fusion_distance": { + "type": "number", + "description": "If the detected object's distance is less than its value, the fusion will be processed.", + "default": 100.0, + "minimum": 0.0 + }, + "trust_object_distance": { + "type": "number", + "description": "If the detected object's distance is less than its value, IoU method specified in `trust_object_iou_mode` is used, otherwise `non_trust_object_iou_mode` is used.", + "default": 100.0, + "minimum": 0.0 + }, + "trust_object_iou_mode": { + "type": "string", + "description": "Name of IoU method applied to the objects in range of [0.0, `trust_distance`].", + "default": "iou", + "enum": ["iou", "iou_x", "iou_y"] + }, + "non_trust_object_iou_mode": { + "type": "string", + "description": "Name of IoU method applied to the objects in range of [`trust_distance`, `fusion_distance`], if `trust_distance` < `fusion_distance`.", + "default": "iou_x", + "enum": ["iou", "iou_x", "iou_y"] + }, + "use_cluster_semantic_type": { + "type": "boolean", + "description": "If this parameter is false, label of cluster objects will be reset to UNKNOWN.", + "default": false + }, + "only_allow_inside_cluster": { + "type": "boolean", + "description": "If this parameter is true, only clusters in which all their points are inside the RoI can be assigned to the RoI.", + "default": true + }, + "roi_scale_factor": { + "type": "number", + "description": "A scale factor for resizing RoI while checking if cluster points are inside the RoI.", + "default": 1.1, + "minimum": 1.0, + "maximum": 2.0 + }, + "iou_threshold": { + "type": "number", + "description": "An IoU score threshold. Note that the total IoU score is the sum of the IoU scores that are set to true in use_iou, use_iou_x and use_iou_y.", + "default": 0.65, + "minimum": 0.0, + "maximum": 1.0 + }, + "unknown_iou_threshold": { + "type": "number", + "description": "A threshold value of IoU score for objects labeled UNKNOWN.", + "default": 0.1, + "minimum": 0.0, + "maximum": 1.0 + }, + "remove_unknown": { + "type": "boolean", + "description": "If this parameter is true, all of objects labeled UNKNOWN will be removed in post-process.", + "default": false + } + }, + "required": [ + "fusion_distance", + "trust_object_distance", + "trust_object_iou_mode", + "non_trust_object_iou_mode", + "use_cluster_semantic_type", + "only_allow_inside_cluster", + "roi_scale_factor", + "iou_threshold", + "unknown_iou_threshold", + "remove_unknown" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_cluster_fusion" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json new file mode 100644 index 0000000000000..3030be1305d56 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json @@ -0,0 +1,70 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for RoI Detected Object Fusion Node", + "type": "object", + "definitions": { + "roi_detected_object_fusion": { + "type": "object", + "properties": { + "passthrough_lower_bound_probability_thresholds": { + "type": "array", + "description": "An array of object probability thresholds. The objects that have higher probability than their respective thresholds are kept.", + "default": [0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.5] + }, + "trust_distances": { + "type": "array", + "description": "An array of object distances thresholds. Any objects that is farther than this value will be skipped in the clustering process, but will still be published.", + "default": [50.0, 100.0, 100.0, 100.0, 100.0, 50.0, 50.0, 50.0] + }, + "min_iou_threshold": { + "type": "number", + "description": "An Iou score threshold.", + "default": 0.5, + "minimum": 0.0, + "maximum": 1.0 + }, + "roi_probability_threshold": { + "type": "number", + "description": "A object probability threshold.", + "default": 0.5, + "minimum": 0.0, + "maximum": 1.0 + }, + "use_roi_probability": { + "type": "boolean", + "description": "If this parameter is true, the objects are filtered out with their RoI probabilities.", + "default": false + }, + "can_assign_matrix": { + "type": "array", + "description": "An NxN matrix, where N represents the number of classes. A value 1 indicates that it is assignable, while a value of 0 indicates not.", + "default": [ + 1, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, + 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, + 0, 0, 0, 1, 1, 1 + ] + } + }, + "required": [ + "passthrough_lower_bound_probability_thresholds", + "trust_distances", + "min_iou_threshold", + "roi_probability_threshold", + "use_roi_probability", + "can_assign_matrix" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_detected_object_fusion" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json new file mode 100644 index 0000000000000..f39ef257ea789 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json @@ -0,0 +1,41 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for RoI PointCloud Fusion Node", + "type": "object", + "definitions": { + "roi_pointcloud_fusion": { + "type": "object", + "properties": { + "fuse_unknown_only": { + "type": "boolean", + "description": "Whether to fuse only UNKNOWN clusters.", + "default": true + }, + "min_cluster_size": { + "type": "integer", + "description": "The minimum number of points that a cluster must contain to be considered as valid.", + "default": 2 + }, + "cluster_2d_tolerance": { + "type": "number", + "description": "A cluster tolerance measured in radial direction [m]", + "default": 0.5, + "exclusiveMinimum": 0.0 + } + }, + "required": ["fuse_unknown_only", "min_cluster_size", "cluster_2d_tolerance"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_pointcloud_fusion" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_sync.schema.json b/perception/image_projection_based_fusion/schema/roi_sync.schema.json new file mode 100644 index 0000000000000..411fb678a49a7 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_sync.schema.json @@ -0,0 +1,84 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Synchronization of RoI Fusion Nodes", + "type": "object", + "definitions": { + "roi_sync": { + "type": "object", + "properties": { + "input_offset_ms": { + "type": "array", + "description": "An array of timestamp offsets for each camera [ms].", + "default": [61.67, 111.67, 45.0, 28.33, 78.33, 95.0] + }, + "timeout_ms": { + "type": "number", + "description": "A timeout value can be assigned within a single frame [ms].", + "default": 70.0, + "minimum": 1.0, + "maximum": 100.0 + }, + "match_threshold_ms": { + "type": "number", + "description": "A maximum threshold value to synchronize RoIs from multiple cameras [ms].", + "default": 50.0, + "minimum": 0.0, + "maximum": 100.0 + }, + "image_buffer_size": { + "type": "integer", + "description": "The number of image buffer size for debug.", + "default": 15, + "minimum": 1 + }, + "debug_mode": { + "type": "boolean", + "description": "Whether to debug or not.", + "default": false + }, + "filter_scope_min_x": { + "type": "number", + "description": "Minimum x position to be considered for debug [m].", + "default": -100.0 + }, + "filter_scope_min_y": { + "type": "number", + "description": "Minimum y position to be considered for debug [m].", + "default": -100.0 + }, + "filter_scope_min_z": { + "type": "number", + "description": "Minimum z position to be considered for debug [m].", + "default": -100.0 + }, + "filter_scope_max_x": { + "type": "number", + "description": "Maximum x position to be considered for debug [m].", + "default": 100.0 + }, + "filter_scope_max_y": { + "type": "number", + "description": "Maximum y position to be considered for debug [m].", + "default": 100.0 + }, + "filter_scope_max_z": { + "type": "number", + "description": "Maximum z position [m].", + "default": 100.0 + } + } + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_sync" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index b01a910aaded1..4abd92d7fb063 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -46,7 +46,7 @@ FusionNode::FusionNode( : Node(node_name, options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { // set rois_number - rois_number_ = static_cast(declare_parameter("rois_number", 1)); + rois_number_ = static_cast(declare_parameter("rois_number")); if (rois_number_ < 1) { RCLCPP_WARN( this->get_logger(), "minimum rois_number is 1. current rois_number is %zu", rois_number_); @@ -80,7 +80,7 @@ FusionNode::FusionNode( "/sensing/camera/camera" + std::to_string(roi_i) + "/image_rect_color"); } - input_offset_ms_ = declare_parameter("input_offset_ms", std::vector{}); + input_offset_ms_ = declare_parameter>("input_offset_ms"); if (!input_offset_ms_.empty() && rois_number_ != input_offset_ms_.size()) { throw std::runtime_error("The number of offsets does not match the number of topics."); } @@ -122,7 +122,7 @@ FusionNode::FusionNode( // debugger if (declare_parameter("debug_mode", false)) { std::size_t image_buffer_size = - static_cast(declare_parameter("image_buffer_size", 15)); + static_cast(declare_parameter("image_buffer_size")); debugger_ = std::make_shared(this, rois_number_, image_buffer_size, input_camera_topics_); } @@ -136,14 +136,15 @@ FusionNode::FusionNode( stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } + // cspell: ignore minx, maxx, miny, maxy, minz, maxz // FIXME: use min_x instead of minx - filter_scope_minx_ = declare_parameter("filter_scope_minx", -100); - filter_scope_maxx_ = declare_parameter("filter_scope_maxx", 100); - filter_scope_miny_ = declare_parameter("filter_scope_miny", -100); - filter_scope_maxy_ = declare_parameter("filter_scope_maxy", 100); - filter_scope_minz_ = declare_parameter("filter_scope_minz", -100); - filter_scope_maxz_ = declare_parameter("filter_scope_maxz", 100); + filter_scope_minx_ = declare_parameter("filter_scope_min_x"); + filter_scope_maxx_ = declare_parameter("filter_scope_max_x"); + filter_scope_miny_ = declare_parameter("filter_scope_min_y"); + filter_scope_maxy_ = declare_parameter("filter_scope_max_y"); + filter_scope_minz_ = declare_parameter("filter_scope_min_z"); + filter_scope_maxz_ = declare_parameter("filter_scope_max_z"); } template diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 48ef3d26806c8..76b561f677c0f 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -95,28 +95,29 @@ inline bool isUnknown(int label2d) PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & options) : FusionNode("pointpainting_fusion", options) { - omp_num_threads_ = this->declare_parameter("omp_num_threads", 1); + omp_num_threads_ = this->declare_parameter("omp_params.num_threads"); const float score_threshold = - static_cast(this->declare_parameter("score_threshold", 0.4)); - const float circle_nms_dist_threshold = - static_cast(this->declare_parameter("circle_nms_dist_threshold", 1.5)); + static_cast(this->declare_parameter("post_process_params.score_threshold")); + const float circle_nms_dist_threshold = static_cast( + this->declare_parameter("post_process_params.circle_nms_dist_threshold")); const auto yaw_norm_thresholds = - this->declare_parameter>("yaw_norm_thresholds"); + this->declare_parameter>("model_params.yaw_norm_thresholds"); // densification param const std::string densification_world_frame_id = - this->declare_parameter("densification_world_frame_id", "map"); + this->declare_parameter("densification_params.world_frame_id"); const int densification_num_past_frames = - this->declare_parameter("densification_num_past_frames", 0); + this->declare_parameter("densification_params.num_past_frames"); // network param - const std::string trt_precision = this->declare_parameter("trt_precision", "fp16"); - const std::string encoder_onnx_path = this->declare_parameter("encoder_onnx_path", ""); - const std::string encoder_engine_path = this->declare_parameter("encoder_engine_path", ""); - const std::string head_onnx_path = this->declare_parameter("head_onnx_path", ""); - const std::string head_engine_path = this->declare_parameter("head_engine_path", ""); - - class_names_ = this->declare_parameter>("class_names"); + const std::string trt_precision = this->declare_parameter("trt_precision"); + const std::string encoder_onnx_path = this->declare_parameter("encoder_onnx_path"); + const std::string encoder_engine_path = + this->declare_parameter("encoder_engine_path"); + const std::string head_onnx_path = this->declare_parameter("head_onnx_path"); + const std::string head_engine_path = this->declare_parameter("head_engine_path"); + + class_names_ = this->declare_parameter>("model_params.class_names"); const auto paint_class_names = - this->declare_parameter>("paint_class_names"); + this->declare_parameter>("model_params.paint_class_names"); std::vector classes_{"CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"}; if ( std::find(paint_class_names.begin(), paint_class_names.end(), "TRUCK") != @@ -138,17 +139,17 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt isClassTable_.erase(cls); } } - has_twist_ = this->declare_parameter("has_twist", false); - const std::size_t point_feature_size = - static_cast(this->declare_parameter("point_feature_size")); + has_twist_ = this->declare_parameter("model_params.has_twist"); + const std::size_t point_feature_size = static_cast( + this->declare_parameter("model_params.point_feature_size")); const std::size_t max_voxel_size = - static_cast(this->declare_parameter("max_voxel_size")); - pointcloud_range = this->declare_parameter>("point_cloud_range"); - const auto voxel_size = this->declare_parameter>("voxel_size"); - const std::size_t downsample_factor = - static_cast(this->declare_parameter("downsample_factor")); - const std::size_t encoder_in_feature_size = - static_cast(this->declare_parameter("encoder_in_feature_size")); + static_cast(this->declare_parameter("model_params.max_voxel_size")); + pointcloud_range = this->declare_parameter>("model_params.point_cloud_range"); + const auto voxel_size = this->declare_parameter>("model_params.voxel_size"); + const std::size_t downsample_factor = static_cast( + this->declare_parameter("model_params.downsample_factor")); + const std::size_t encoder_in_feature_size = static_cast( + this->declare_parameter("model_params.encoder_in_feature_size")); const auto allow_remapping_by_area_matrix = this->declare_parameter>("allow_remapping_by_area_matrix"); const auto min_area_matrix = this->declare_parameter>("min_area_matrix"); @@ -172,10 +173,11 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt { centerpoint::NMSParams p; p.nms_type_ = centerpoint::NMS_TYPE::IoU_BEV; - p.target_class_names_ = - this->declare_parameter>("iou_nms_target_class_names"); - p.search_distance_2d_ = this->declare_parameter("iou_nms_search_distance_2d"); - p.iou_threshold_ = this->declare_parameter("iou_nms_threshold"); + p.target_class_names_ = this->declare_parameter>( + "post_process_params.iou_nms_target_class_names"); + p.search_distance_2d_ = + this->declare_parameter("post_process_params.iou_nms_search_distance_2d"); + p.iou_threshold_ = this->declare_parameter("post_process_params.iou_nms_threshold"); iou_bev_nms_.setParameters(p); } From dbd801fab0bb9ecdb6cf79898faa918fc89d42d9 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 15 Dec 2023 18:44:07 +0900 Subject: [PATCH 074/276] fix(avoidance): fix unexpected sudden deceleration for avoidance maneuver (#5805) fix(avoidance): fix sudden deceleration Signed-off-by: satoshi-ota --- planning/behavior_path_avoidance_module/src/scene.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 46c3bbe55d69d..783877e9c753d 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -1700,7 +1700,7 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const // insert slow down speed. const double current_target_velocity = PathShifter::calcFeasibleVelocityFromJerk( shift_length, helper_->getLateralMinJerkLimit(), distance_to_object); - if (current_target_velocity < getEgoSpeed() && decel_distance < remaining_distance) { + if (current_target_velocity < getEgoSpeed() + parameters_->buf_slow_down_speed) { utils::avoidance::insertDecelPoint( getEgoPosition(), decel_distance, parameters_->velocity_map.front(), shifted_path.path, slow_pose_); From 7983baef1ff673648b52eeb9da840bb013bf0e96 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 15 Dec 2023 19:02:40 +0900 Subject: [PATCH 075/276] fix(goal_planner): set rederence path for candidate path (#5886) Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 6f1b1e7f41571..b50387b3f6b0e 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -943,6 +943,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(); output.modified_goal = pull_over_output.modified_goal; output.path = std::make_shared(generateStopPath()); + output.reference_path = getPreviousModuleOutput().reference_path; const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( *output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); From c125b144e1b4644adb39dbb10066e494af0aebd2 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 15 Dec 2023 19:37:11 +0900 Subject: [PATCH 076/276] fix(avoidance): check far objects during shifting (#5857) * fix(avoidance): check far objects during shifting Signed-off-by: satoshi-ota * fix(avoidance): update impl Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/helper.hpp | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 6717cefefc9f6..df9640fa75626 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -58,6 +58,8 @@ class AvoidanceHelper double getEgoSpeed() const { return std::abs(data_->self_odometry->twist.twist.linear.x); } + geometry_msgs::msg::Pose getEgoPose() const { return data_->self_odometry->pose.pose; } + size_t getConstraintsMapIndex(const double velocity, const std::vector & values) const { const auto itr = std::find_if( @@ -185,10 +187,20 @@ class AvoidanceHelper return parameters_->object_check_max_forward_distance; } + const auto & route_handler = data_->route_handler; + + lanelet::ConstLanelet closest_lane; + if (!route_handler->getClosestLaneletWithinRoute(getEgoPose(), &closest_lane)) { + return parameters_->object_check_max_forward_distance; + } + + const auto limit = route_handler->getTrafficRulesPtr()->speedLimit(closest_lane); + const auto speed = isShifted() ? limit.speedLimit.value() : getEgoSpeed(); + const auto max_shift_length = std::max( std::abs(parameters_->max_right_shift_length), std::abs(parameters_->max_left_shift_length)); - const auto dynamic_distance = PathShifter::calcLongitudinalDistFromJerk( - max_shift_length, getLateralMinJerkLimit(), getEgoSpeed()); + const auto dynamic_distance = + PathShifter::calcLongitudinalDistFromJerk(max_shift_length, getLateralMinJerkLimit(), speed); return std::clamp( 1.5 * dynamic_distance + getNominalPrepareDistance(), From d62247ffa1d7d94e0594bbeafc0c5a17f33fe0c4 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 15 Dec 2023 23:45:24 +0900 Subject: [PATCH 077/276] perf(run_out): improve calculation cost of smoothPath (#5885) * perf(run_out): improve calculation cost of smoothPath Signed-off-by: Takayuki Murooka * re-index enum elements Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/debug.hpp | 19 +++--- .../src/scene.cpp | 68 ++++++++++++------- 2 files changed, 54 insertions(+), 33 deletions(-) diff --git a/planning/behavior_velocity_run_out_module/src/debug.hpp b/planning/behavior_velocity_run_out_module/src/debug.hpp index 91656d542ea8e..b28725a92628e 100644 --- a/planning/behavior_velocity_run_out_module/src/debug.hpp +++ b/planning/behavior_velocity_run_out_module/src/debug.hpp @@ -35,14 +35,17 @@ class DebugValues public: enum class TYPE { CALCULATION_TIME = 0, - CALCULATION_TIME_COLLISION_CHECK = 1, - LATERAL_DIST = 2, - LONGITUDINAL_DIST_OBSTACLE = 3, - LONGITUDINAL_DIST_COLLISION = 4, - COLLISION_POS_FROM_EGO_FRONT = 5, - STOP_DISTANCE = 6, - NUM_OBSTACLES = 7, - LATERAL_PASS_DIST = 8, + CALCULATION_TIME_PATH_PROCESSING = 1, + CALCULATION_TIME_OBSTACLE_CREATION = 2, + CALCULATION_TIME_COLLISION_CHECK = 3, + CALCULATION_TIME_PATH_PLANNING = 4, + LATERAL_DIST = 5, + LONGITUDINAL_DIST_OBSTACLE = 6, + LONGITUDINAL_DIST_COLLISION = 7, + COLLISION_POS_FROM_EGO_FRONT = 8, + STOP_DISTANCE = 9, + NUM_OBSTACLES = 10, + LATERAL_PASS_DIST = 11, SIZE, // this is the number of enum elements }; diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index 2fa8cf241ee74..7a13c0c4f1052 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -60,7 +60,7 @@ bool RunOutModule::modifyPathVelocity( PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) { // timer starts - const auto t1_modify_path = std::chrono::system_clock::now(); + const auto t_start = std::chrono::system_clock::now(); // set planner data const auto current_vel = planner_data_->current_velocity->twist.linear.x; @@ -70,20 +70,27 @@ bool RunOutModule::modifyPathVelocity( // set height of debug data debug_ptr_->setHeight(current_pose.position.z); - // smooth velocity of the path to calculate time to collision accurately - PathWithLaneId smoothed_path; - if (!smoothPath(*path, smoothed_path, planner_data_)) { - return true; - } - // extend path to consider obstacles after the goal - const auto extended_smoothed_path = - run_out_utils::extendPath(smoothed_path, planner_param_.vehicle_param.base_to_front); + const auto extended_path = + run_out_utils::extendPath(*path, planner_param_.vehicle_param.base_to_front); // trim path ahead of the base_link to make calculation easier const double trim_distance = planner_param_.run_out.detection_distance; - const auto trim_smoothed_path = - run_out_utils::trimPathFromSelfPose(extended_smoothed_path, current_pose, trim_distance); + const auto trim_path = + run_out_utils::trimPathFromSelfPose(extended_path, current_pose, trim_distance); + + // smooth velocity of the path to calculate time to collision accurately + PathWithLaneId extended_smoothed_path; + if (!smoothPath(trim_path, extended_smoothed_path, planner_data_)) { + return true; + } + + // record time for path processing + const auto t_path_processing = std::chrono::system_clock::now(); + const auto elapsed_path_processing = + std::chrono::duration_cast(t_path_processing - t_start); + debug_ptr_->setDebugValues( + DebugValues::TYPE::CALCULATION_TIME_PATH_PROCESSING, elapsed_path_processing.count() / 1000.0); // create abstracted dynamic obstacles from objects or points dynamic_obstacle_creator_->setData(*planner_data_, planner_param_, *path, extended_smoothed_path); @@ -92,18 +99,24 @@ bool RunOutModule::modifyPathVelocity( // extract obstacles using lanelet information const auto partition_excluded_obstacles = - excludeObstaclesOutSideOfPartition(dynamic_obstacles, trim_smoothed_path, current_pose); + excludeObstaclesOutSideOfPartition(dynamic_obstacles, extended_smoothed_path, current_pose); - // timer starts - const auto t1_collision_check = std::chrono::system_clock::now(); + // record time for obstacle creation + const auto t_obstacle_creation = std::chrono::system_clock::now(); + const auto elapsed_obstacle_creation = + std::chrono::duration_cast(t_obstacle_creation - t_path_processing); + debug_ptr_->setDebugValues( + DebugValues::TYPE::CALCULATION_TIME_OBSTACLE_CREATION, + elapsed_obstacle_creation.count() / 1000.0); // detect collision with dynamic obstacles using velocity planning of ego - const auto dynamic_obstacle = detectCollision(partition_excluded_obstacles, trim_smoothed_path); + const auto dynamic_obstacle = + detectCollision(partition_excluded_obstacles, extended_smoothed_path); - // timer ends - const auto t2_collision_check = std::chrono::system_clock::now(); + // record time for collision check + const auto t_collision_check = std::chrono::system_clock::now(); const auto elapsed_collision_check = - std::chrono::duration_cast(t2_collision_check - t1_collision_check); + std::chrono::duration_cast(t_collision_check - t_obstacle_creation); debug_ptr_->setDebugValues( DebugValues::TYPE::CALCULATION_TIME_COLLISION_CHECK, elapsed_collision_check.count() / 1000.0); @@ -112,7 +125,7 @@ bool RunOutModule::modifyPathVelocity( // after a certain amount of time has elapsed since the ego stopped, // approach the obstacle with slow velocity insertVelocityForState( - dynamic_obstacle, *planner_data_, planner_param_, trim_smoothed_path, *path); + dynamic_obstacle, *planner_data_, planner_param_, extended_smoothed_path, *path); } else { // just insert zero velocity for stopping insertStoppingVelocity(dynamic_obstacle, current_pose, current_vel, current_acc, *path); @@ -124,14 +137,19 @@ bool RunOutModule::modifyPathVelocity( } publishDebugValue( - trim_smoothed_path, partition_excluded_obstacles, dynamic_obstacle, current_pose); + extended_smoothed_path, partition_excluded_obstacles, dynamic_obstacle, current_pose); - // timer ends - const auto t2_modify_path = std::chrono::system_clock::now(); - const auto elapsed_modify_path = - std::chrono::duration_cast(t2_modify_path - t1_modify_path); + // record time for collision check + const auto t_path_planning = std::chrono::system_clock::now(); + const auto elapsed_path_planning = + std::chrono::duration_cast(t_path_planning - t_collision_check); debug_ptr_->setDebugValues( - DebugValues::TYPE::CALCULATION_TIME, elapsed_modify_path.count() / 1000.0); + DebugValues::TYPE::CALCULATION_TIME_PATH_PLANNING, elapsed_path_planning.count() / 1000.0); + + // record time for the function + const auto t_end = std::chrono::system_clock::now(); + const auto elapsed_all = std::chrono::duration_cast(t_end - t_start); + debug_ptr_->setDebugValues(DebugValues::TYPE::CALCULATION_TIME, elapsed_all.count() / 1000.0); return true; } From cec1b2dcc32654c93222b45a1f31cf1360939f26 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 16 Dec 2023 15:31:04 +0900 Subject: [PATCH 078/276] feat(planning_debug_utils): add update_logger_level.sh (#5888) * feat(planning_debug_utils): update_logger_level.sh Signed-off-by: Takayuki Murooka * add error handling Signed-off-by: Takayuki Murooka * update README Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- planning/planning_debug_tools/CMakeLists.txt | 1 + planning/planning_debug_tools/README.md | 17 ++++++++ .../image/logging_level_updater.png | Bin 0 -> 53603 bytes .../image/logging_level_updater_typo.png | Bin 0 -> 58134 bytes .../scripts/update_logger_level.sh | 41 ++++++++++++++++++ 5 files changed, 59 insertions(+) create mode 100644 planning/planning_debug_tools/image/logging_level_updater.png create mode 100644 planning/planning_debug_tools/image/logging_level_updater_typo.png create mode 100755 planning/planning_debug_tools/scripts/update_logger_level.sh diff --git a/planning/planning_debug_tools/CMakeLists.txt b/planning/planning_debug_tools/CMakeLists.txt index 58f73ca3836c2..389bfdaa848d4 100644 --- a/planning/planning_debug_tools/CMakeLists.txt +++ b/planning/planning_debug_tools/CMakeLists.txt @@ -53,5 +53,6 @@ install(PROGRAMS scripts/closest_velocity_checker.py scripts/perception_replayer/perception_reproducer.py scripts/perception_replayer/perception_replayer.py + scripts/update_logger_level.sh DESTINATION lib/${PROJECT_NAME} ) diff --git a/planning/planning_debug_tools/README.md b/planning/planning_debug_tools/README.md index aa46c0e2fc7ef..a89cec2864857 100644 --- a/planning/planning_debug_tools/README.md +++ b/planning/planning_debug_tools/README.md @@ -6,6 +6,7 @@ This package contains several planning-related debug tools. - **Closest velocity checker**: prints the velocity information indicated by each modules - **Perception reproducer**: generates detected objects from rosbag data in planning simulator environment - **processing time checker**: displays processing_time of modules on the terminal +- **logging level updater**: updates the logging level of the planning modules. ## Trajectory analyzer @@ -264,3 +265,19 @@ The program allows users to customize two parameters via command-line arguments: - --display_frequency (or -f): This sets the frequency at which the terminal UI updates. The default value is 5Hz. By adjusting these parameters, users can tailor the display to their specific monitoring needs. + +## Logging Level Updater + +The purpose of the Logging Level Updater is to update the logging level of the planning modules via ROS 2 service. Users can easily update the logging level for debugging. + +```bash +ros2 run planning_debug_tools update_logger_level.sh +``` + +`` will be `DEBUG`, `INFO`, `WARN`, or `ERROR`. + +![logging_level_updater](image/logging_level_updater.png) + +When you have a typo of the planning module, the script will show the available modules. + +![logging_level_updater_typo](image/logging_level_updater_typo.png) diff --git a/planning/planning_debug_tools/image/logging_level_updater.png b/planning/planning_debug_tools/image/logging_level_updater.png new file mode 100644 index 0000000000000000000000000000000000000000..ae91140060b0f2a485d15aa6e814d89a69bbfbba GIT binary patch literal 53603 zcmaI7Wl$Z#7BxyBXmEG8KyY_=4-kU8yE_DT3-0a~+&RJB-QC^cz&YpTe)qnr_vd@7 zreGCLL?|CC=@wa$?s55@Ip{fpO6sX{F&{;v@Vik+36mdSIQszWz!} zTMOf}!Jin|K4|%y9$18+#O>sb>C7Fnmv9a86WYR8q5PAv2T^v24}^ zlixIAnB7S~|9?QNOb@RM_2vJLn0O;tA*OHtSD@O~6qJYkUom7Hhx6F{=l=@c8nxma zj2G??Iz><749AwWM1nbdf2=umkRw--)~s) zP*UcKjSx?TQWbsGYnr$}`EMWpxx-^z{S7P?jVDtCbvOq>nDwLV<)(u0sLaIE4J|we zeC0f25zxl9s+~W+Z-u$&d>Bf_6GpxVW0y#f<1&vt`P_-6NRyAC^!s~Y&Lf&!v+LcY zT=#g1<6ir|8#O;FN(-$Y0E~BB@axH~_)=o?By-_LDNS$#l{MghNXCx#r92VDZ~TaH zeODR0VGwKnc1SF_SK;iX0~Y&%(XlUKQe6Y}7&J6p!h`#8dM4m~b(-w$k=cT5-@p?5 z?2=Z!w)#8`q*E^o5Ir+KM3vg)t$V*!n?6$?p3JU42CI0uwEO1&!MfQ^U7;O_-N@iF z#VWK5TnIND!ZI|FoDV-~-)$;QA-$I8tN3spR||Oe&pgZ4#uMBpQmHeUDweZVw^VTC^KFx{egiS@a~5 z($9e7t+)^-)|x{LeHW0JSH+OkrSAQM|B-_6!<*OMB51%6ECJ8u%&K136S|;Gq_A^| z&*?}Lc9G8Zl55=!T*s8J{pl#cM!(Y>d-OnzAUf!7se02M!lWVF9?zHmFhaYBEtli= zXR~Pf1m`143t`3`@o%I{Kl}UGW=BBq##?Ya#b&qlJT94fp zjwhD>s5lus7yjppjGp`>@_|14|aDt0DX5oiSsQD7bWw130nAd}@(!Yl~I+9_J z_W9rHrA6&=s_x{49JIBrGbHwK+>)fnZwnz?r$^4)q?Ep`2CT--k89u@?mE2EmKRxe zBu2;6*NN+Q!)#odgqDXqW!u;PF^-)Y<`G7u8i-mH)mSRDV-U~nAh912i!&e*Jg=Iw zaFjt3Z75EV>q8I;g>I)f_?w%7vAJez#JCn-E5T;8Mj8H1H~;?gZ8~}y05bwA^o!?r zR0CbDQ}taHfz03>PU-?||AgwsGW$$axlV%s-({<^k0b1|*oKg-X+)K7$>-xMJA>w5 zYx$FArfX!z>c7ZcHd_SWws#2fDuMxNjk!{hp=RvT%E#RpSOg-kI?Nql%W(+8)RoJ} zH~(D|W?%AKk@v4EtnVQ8KO}mE;{8qDSOVQ6a}y4#trY3e5&?ZP{n)L>Igm>LZy$Gh zAmEjP(FS!G3UUyeE`eGd2>C^P4HVowLd#_i%p=7-0HF_;1fb5mC5YeOQW4DWM0FW4 zZg}9g@2ijIIbrtDD(}_U2JTlrI2?n_TWZ@l6>{(67+1H4edE-!WLhvPM67oad|sSX zyWCN#J$%*l*r+Wm*-uMIk@MJ7u?$~{w6?e-qER#RLoQ=Tk2C4Y6ZbwBw}yTwb&RfZ z`Y2||Pp{h9;N=YvW!F^vH?|LvCHdz+YV5M=vH^;Q0xX_vTpy3^}j2`5B-ry1>EgmB`IFBmVjMj!U$~p{8*^#B-n&g zYF;ph69s7wc#V&iW_Smq9*p*RO{>`bP%axRQi+lxBaS;bL#gm>gtx_~LmhIpu_Mn| zCRgzh1V8dV_USqcHo=xMrvN3a>YWM6pXPYwF+Z_?F$|G+l>pN*0ixgoDS0x!Zd@a?Au#9Qyhf&eph)Bub3J;=A+W<0vGIe9_s!de=LtGl1s2FwI4p9$(0mjhNCY ztEHQeW(Njw?zGYa9eS+^e%mzKIe-Xzn;5N~oirtnedw$itPFby%Xx()1FnQr<=Kf!!H-d!8anI04FR#6nnMR((GT(q~ zI|h6Oblc&-%6DQK%kWFTOFb({s%Z4##zQXcnp=p}YP?^`f`3%n3pk})!W4N3-A$}` zwv)!xNlB{gmz}T_c>ZL%FzC&X$O9%ly>a1BTYU#2TO1DlN?%dQ9IHL>W%W}eHgUg$+=Z?{R%R>pKpY}9!mBR-rCG$&KW7#OVnpNv z&omr?QCcjkibE0kE+=<%P9S@-`wOLq)fM3YS3|YFb*<~;K$(OCfcgS~vl;F9$L8#{ zC<@Wg5t=fM($k;kK7h*sOm)`iS-Hs(Pj`D`)91GT@+e+xYm!IB(SCnNvRK@}BpKw= z>qrZL*rZ;ltq%D~O4~+629$xwTFRwA@^+FN!JPims>id3Z^0OB71Xx zI6K$s7o6C4pot{)KADY7?nT%mwjUNI8#^T{Ch;gMiUz^#OqRaY&ZQ`mBfI{j?2xA$ zrL+&PbP7{}%8+QvQb7&FUv5`Ad2^zPxhxn{4LGnG;wgdgC<2ZfiJDqOW5egGh}w#< zfW?^~rV3XfdhMheALpXGYOAv>ywEdAb)rVifyDP+grOR9Go(?Lo7*>mR`J2k8nodg ziI_*}=Dfn+zWB+=)8=ge3nCB?ZxtVBV&)h$9}%tb8OTvmSnv)$nDPBC*S^dst>I^h zk|qU#%?WIB*ML*4T7CE_=m>x1Mb0C>I87qvt-22%fKFIH?x0PIS&Kf)!@G)(3-h%@ zIH0JM!?Ju*++kOH*W-2O%@i{lAQ_T=BV{IT2}mV(OURM|Z0jy8!?V<}obZdw1pxrm z4HiwN@4R2kUcL#oJ@(0ZQfP`$)?;72Gp+vcd~}y1Z&JS_%Z>+lQqRK{RSEBs_0C9a zZ9V_h{7!cV5%&AF@V?lz3%+OEruOW7*T$-4W%u07>yQHdtQ?x#{gahYm~nf3A5wsbEyiJ z^2#q`r2-JURIb%Ysm{DSsJXDvnIK=jyMB?7B{dpJcBW2^LKFk7vV{iiSN=6fQaFs) zY(FOgYV~b^zIj*fZkTd0{bLKZNpKCTwg3gW<62begq-DiT&2`bua zf9^V3b3RG|iGamsaUBZECj5ZQ&(bQy1Aq3mgWt<>|GcvIxB;*m2J9_Ohyn)a=~U!MS|&AOmR%KGH{!=@XsXBLLAMd9_b@pXH?tA8|}1XJcl_unsz6AoQYR!7_!xAza6jxqr()@?=ZFf0Q6`0EUBjt-M| zN-M_D5k*d5EdbmE7MsI|O~S>5s`JCHeNW}=cCutX$7YEc=s{Z*#eVNTxc<+$^@49C zx&nXJWaUUkVB2zrGLrny=BQHJ>FK-}==Hin4R?HVd3N*^o#D~ms$pi1wj-vERr3{p z?^8Kd2v>O?H3B1Myf5ZFe`f5o+iu(WPNlYSoW%_Z`urpR?Jxf$|JFos=viQ#qKKUF zp|+d}Hkl_HrftM)!f{V~I?o}Sw7_TDdjC9y3QO3(a>FST?LgoHKF7CQdNql@D%g)+ z4j9;Vy;#?0!7NvY&d9GLsD-*kB#vVq%ab2DZKMG)-rltWKP6H2C(Fy&UfcJ~=xi2m zw)^i{wog)J%9_f?zB)BMZ?*u{WWg8NeouoLv|niw_VetCI?Cm~7TfXjJa*@H_-5J9 zLo%2hG1b9S#AP5AS#V#Df9sA&=sMu|3Si4-D`GJc^LA%0EpnWHqp#w7sMW~4pL*oU zp{G3rk?nTdE$QoBo$yMxf-n&Z`rSHh+G+R&tzIO}a}uJ)oS6 z7&H#FBhaaS#8X0u8S(Vcxpm7WJIdA!`c=LL^v9_n0=>#?h&mfRqDG+fWoFE>HimSt zm&P}i6{%+dRNk-@my0Ef65^mK)Q;^?;RH3!Zm1vgjAe&D@f%^`Yh#G=HEQwqMmaMv zUAqg2sz0u&|{M8D(I+L23kRvEq-x_179&oWUDRX|J>-ovNz@i&ME(qDSpwIOY35t4`C;2sbC~Z9*^84vC?h4 zeOCKR5Rz9~;J~R3`Mzc5`zf99BO-|2@&5kkiJZ{lFr2JA*9nz@w#d1Uk%9Oil31{Z z%1N-9u%-6zGgwx6P=unxJ8Sn+!*5M#e6{#CUkD%Rm}|`momwb}cA{<6pz_sc*toj~ zVWeBtPzF0TD&#IFH&TNrknwN?#ot&E8_VY}FFUu)^w`%8A?B&>wHroCW!6%JS|-PdnpDJSK|8* z5oz-@)`MY>SIk;?5L_5ltbD8eHzfNN57{fOi1`Ej>8@ww@0w9+hEmpj%7U#wfBPov z4{pdf9VR8X3@uvQA+yaEJ?0F0Yvn3dQQj@3sOD%vt3{Q>@yCCWR@x7(OmGHuEd1OE z3S+=nj_Wh+!ZJ`5-Cn=Kf99R{c{2UL0pYvq1%jO)MKUz4LKh8Ok5I;WzFCYB!$YGZ z3K6XH1ndCWY6DYao5+sB@Kk6AKKUqp4cm}MSCgYYLZ+=;F$#}hI_XIa$umZ7Hz%Cg z5{R~v+OPdL3ggQ2r&zpNh{)%-3Y~*Wy}6b6^n92Qs($ zSak;vQ&T7!V;O%l)8+j%rLb>WF|vh!MFm38OjYowbLqCmYS2R*^sC9DJXd_urqyO8 zzio{iqtjKbwmQL-DlsH$c5o{5OajT8j;7}2z_rP&H)NCR-~Q96}=(%>`cFz*hFU~xnd*#pRY+0gyT&)x7<3o?1L0g<1%rXt`{ zG+nOGeT}awWAoBL>Zdn->c0x*Ubjci5e%1=D!;v`*LLwb!fyR9-#n#m{!z~KzeGGy zd+hc7GmI##lvVXbcFl(T>gn2pBMku4JXI$oysKqt>8Y+K%Dbo<*b4$ z1u!j8^1oUC&d9l^39-*_gwLmGn(*hsmY?&YFqm+sVA;FlGTb$}&OJPL!7~OJLFB4> zNZVrqPX6n|LcvF=715IDIOM4NF*ZF@#MkE6M$}l3LHc>D)Wp!2{eSTp;XN*y+`V6l2z3w5^#g`UW#eg-Z zcW3_4LLOP!hcG>S#+6#q+YW@f!jN+k%1t6_*RG#uczt6++e$a#-)gynyMZmi* z$x#LrtE&k9{w?%Lh@{1X$0H$_g@FK2MxHA~e`6R{8zv|%sbXUSoh>i9#Z5V0l_kWI z65WY@5CGSjMQLXYJ*6LU{tzVe$y1L#0Csl1V)9)26V07yOGVsgCc zO!6WOh-C+ed+n&VKjlJLpGJvZZ~Pf~UygTR@}u~}W5B|ZtTQ&-IX-+d(@eH{zf`GY zi4tW&0V*YoB{}{=mM>bfZGOX#`2v;zci(j)1|TrK-Rtt8<_@|-GNCtErfg^O^ls&L zr83{;BEpYUmv?CM|YA^Jj-8S>x(Au7vhi5q$hlj~;_$O*L?TCbxZLB<3 z<$H`5AL{)DfIZm>T9I%?ys#jCk31f}(D_kahvvQh4&sqI$m4?dHrGAA)M`G$9FAZC zwC>(4dBEQ!wrCF0fDB!g39BClW4s~027u7sz0!|>8>P+nN9gDta>{p?M8f}Q_x?yIi`iJhxf&s*6S-3AY5TP(oq8U=x z-`tZ)%u+VtDf*uvY0FY}xbl$k4zd7qH=@BL5Gg!PV1P{GACmQ5ug+L+{rEB7FD5opzIPw`(AKioTLQNKoj{L682k-FHaY zQNzp8zGvP(OR@f|OWtYj*#{^RVLV!4Tk;wPF$R+FL+9*W-yC{n+Gu7LIBL z{9l=aH%CoJN%eeuPIxQQ9!P7)NJvLW>4^7yM$~ZiwiaryIk3zYmC=HHBB9`{s2c(T zJ*^t*ggzYQBEUeGe=*I@?YEIMioK5TtoafuX}21BaMh1%%{H~fvYcMPX=i_pn?OqN z;c3Dtt>Hu<0HF4|Zz#T$0Sf^)Bkg^*!6E!-NkI!m*9F4!mrHr&Y#-G3t~NDG~Bil;o6 z93wYLgpg>qW3b7+Mubxo7u_Yqg(JP>(f7tS2dO1AGSX-4_Xo;z`vk*92gf2wNb{&g zGfb{HcJ^T2z0=xd2QS=AA`3zUF<;yVZuN2rPK$qw+mYQkq!QwqvxvM$Qb(2AIt#aA zk1TvyH%GgY2C7=rjev(eutWZi9ZF?409r|FslAGLx7YSzWhsyA`=53(iCLHi-u}ur zHyTCVe*TbH&)#phhRJ;`H~TySTT4rmuP)D4jZ&mMl1R9VQ~Ff*{^3!v z*KKUkw%JIdPo0P|6v+bRa5zZ zMV`VPu+DA~)#?gYInhhuyrnW|pQo_7J|m~yMapC~BduXWZeOcCIqvvF)U}}GuSrI=T&_8C7P40WDBj)hUabQ8uwsY#@;=|)RXl-D+V8v;%jyQ8N|4atP}JeRRFH#z1@7Z=}Uwpe|MS>rVLvZfHVx z7DSjk3STH;#=$=*H8;i726A-;6&@d`(&fg0*E`PPXeWb*5u3qTqW>lCy>3TzhpIhc zzhj~O;oft#&elxN3wET`!-yjU(5o#9^Vg6!!CGaqOsC2$fl##iqG_tNZQ^Mm4``3v zv5y%pBhLWvj}(AxpgSS>4Xf|WaYiyr8wTJCUBZRke8jvPXe*VHiSCaXj;0&dmA^HQ z4DSN;C)AvO_j}$P#*g4$%1JR)uRM%Bsj!w4Qqt!3hYlW-kb6#94#!Suz~gCcb%@+A z;>y-H_wpr2M%hBoZh^bd&K(`=Sjku-8?YbIaN5hF3R(zP3nBF;FTH zg=prTzE1B{ZeUu{J{gM*uzFy06c^l4?5&BLsY&e4#|v=NxOr1bt2rH}9+E8GpD=hl zUi2pTXd?T54v6?t)p~`9Wa`?2;dBixK9^8qa;G1-cYm>Mu9ioHv5+0LvNgb=5NHk@ z;o+!Ezkos@mAsh3kfAHaPyGPT)i+N%UFpB!?9?w~>`~zhFq5Y@_zDARYh(s<2LTqs zW2u3plHJ8|oiD+zw?l%!F%;yO8uOz-$NeZW#;)!7uFoRb=`}-CIC^JaB|U?BmZsiA z9arA|^+mu_*8*SdM|d7;&cv+=wulJZ0r-ykYOh_hyz0cLvSL z6*B*b6tdN7oJvQAe*v;E7g3eK`a2^G_}ZmWCZ-iFbrqPIlx$rI;1f-@~PRP3+0FGYT`s5qTL8k*2&DsB6A&NW5mHXDEVIY`b24Ag^U z<)tZSNhrSgWJ~f>5`{$Mv0qNDn;KPDOQMH;E}?QVw4>9W7goI+K`CUfMte$9!$-Lv zqXiqffx)@02-+fzzgrwPCp2#a<))p>o!4nBUGMLDM)O=y5@JPy(^UXD>3EB7{;aA> zv@}Ye{P6@@TN(spX6PKV$@nIfU8E_ITJXVf-QL$b2-(ku%voOSE4}WRTB#?Ew+m;A zfp=5^2D%+9`nS&kCl9xlZ5*_H1H&ivCuK5Pb8-=aXh=TpC{LJ0#M8U}8o3}?Z@Z0s z8B~|V-vo<*Gx?my&U3^(A1ik2_|~3E75c0DrvI)rO+c2kP8l><|Ipz)SfP4R@^>=M ztY;HPJ;@41MP-ROeLy#;0Z<|y z%>76me^qN@m)*w$=#r=hRG&#gc55q248%hjku9|*$rR`JPM(5JSvY_^j0u<$HWs`{ z{2h!uBp-9Q{SOX?Zf|~?p%?_k6s#4M6%J}W*>8}}L;--!j88&-%gpwuyCZkmt|nH5 z({Zwj^M&=w?W^rjj^}yTVRq_FMM+~n6o#^5ck=QxofA!2QWmVUF}y!s@PA!0Qh0NS z|2!DPLg+6vW3?*rS3IYmuzwUvN}05CJ}yM;GZ}>Xn=iQXz$oEv~`^hENh zAu87T(}7c3A@I!pZksS!cE}S&Xjh^F&uN7)zvMLq|95?Rz18uNHXrfm0R@2wm>+SF ziA{i@xTtB8-AcT%j#{Q({UEN&HOR|`ty)#3RuvqW;C{__$5=&3+YUE=Q|(;08ZAtY zN;UQ=0F9Cz_J*y`mxpme4T+k*aM7`-r#~L@Nc@QK32b9mU(?q*@XN5(6^I3B|i73v7>Wc@75?ykVIiIT zLpu%}X3k{WdUO5|^v8pGvxit7Z@b}*ZuU#TYrhNT_$#*9iTvK!{DcoOBL1_iv*}^_ zi~(0Vl8JJe+`+{!%15v2@kW+A4F;X+vwNiM1|ZD^Xi-8H=S%_W3XJNV(OI(P*R?X| z?_-qKT(vGv62$1iwOejw5bGnd$qmbLU_|Sw#=FRD1_=vAZ2f?aNGLgA`dI~FJVgRS z;5Rv@DEkr35@UxfY>A|uHJz5wYvlf*1(r}2$vq}>6S@^9mrS1`SDYi5xqz89EPHg6 z&l?U<#Wn^$JtUS_pP1^P`5admr8H8txpK6h4l%youEP`fEpjOG-6O|Oz5QC@d7pDf ztgy1bHeL<}ycA#jQk#5c;=(^D8YP&=x*9mLFZcal4f<80_{#P73bicxQjcO*3hT!R zH7xY+`Gk9r&80|cvBt%&{GjiS(Z~CEauQMb9AZ50hdKxy%c}OL0luOq;ow5zyrgK!m@n)LT_6WCp`~8Y)nPx1n2gltah}1Y z9730!6&??0=uG_X2+XL8d${@3G&xyp@=JWay+00tGwO z%kJe*!HmjdCTBvWav>VeyAZ>93}5K}E`#07tFECN)A@(n>7Id`;HDPEoM!w(zd~3P zu`~eds%5C)1rcs1CR)vtdo@bZZfXFmPx*v57=#(VErPtUY~-`tJ;htUwQ2m+A}4dX zV;J{*M2n3xD9v)rZt*2{F&tY6Q*F<|J>9X%ugRVuuv8$?Ki$3LVOrDmCg*dk~zZvm-+nS}`|2@%cm4WUhjSQp}>P4y}7bpP*tRv6kGs`UV{O zXf~)n&sgmEzl;xmGxQIz^iJOItZ$m3O66_S*XDu$5C>U)H}4iQ`<3y_LEKr z0B1ETtYlidT_i|MQawBGpP9qQ`7%Rka~hg6pKQ?~C5}H$M|a`oH^LT~UN<^Ex8=rD z>yzeHB7h2L9WQp&=-F|yPWlKrrep`knwtTe>{hpjETbRAJ#N^^>2hnXJ$|nAmn|wb zcG)7Fm9hfbhlD@zz`B+_?B|?ydzrFJ%ydK(U3dMWSP>dZUOKr=hhOFt-p&DaTu#07 zal=Fl1F|n1K9Y(;Quq{?mk!dWvv;&1N#Q|SasO;Ubj~nMw0VTL15N`pHOz$QT?=lOd>SfQQ<29 zc3g&>CXw7~HJf&G4uuACh?N8L)4+vdB3CUlsBaO^kB)R35b&xYB&&sos&CVaO`sRG zIbgEU&_A3Okn~QI4|(*2BNGY#T2A}$1nQ>BW}*kGSxyx8UdZ#OmaX*uwp`9l>rpA z*hJbxQeI7M^5#R_WCOi}LmKfCP5c=CQ+D);sKV6~_L>zNX&B>c(7PZC&-wf~?Gbg+ zVo!N4JKd)(4I2n(bf=~QZ_bIV{Ew*_&)1T*L{xP5KDkbH33)Vmxm$PEueelYU&Qm2 zs$&)Zij+{u78l#qB9~tQ-_-ZuZAA3rt`9Bky8qc!^Ykg(x?Yt~ zM&FK8+AkRuojW#`RxAsqk#|SzeZ^MI(qZ6vi@RAbnMKH&;8liuHJi-bKgOu@k-~;( zI0mLz7pqI1t0Z?As}t(^^M_@rNpr00S3>rptG4eLTq$36ULzBZd&cZ7&06J`7zANM zPo^lGpS~0O;=<6#Pr;dJ`HK#3YK{H87n(b&T|g#i*m@~xEp;HO<4-2BxsX=!laSXH zc|LDE{=(Nt+F~5`J#;V5&V{bZ$*9>b){SSI=Ue}+G$)fI+N+GG@H8A>Dst6A^0Oec z*-w$G--J00@Rr)fSl-m)j+=EX1If4CF_E3K_J!Sf0&_&cS&g_dW2klpEaHR+TPwq7 zo>AuxmtUwlbxp}GlRd`C8Uxmc+x&f5@hb|5BbUBFq;Ws=A`2ziu5&~%HpE5WXVv)} zenr>l_jm8SH2k_|Hhar{d3YfLl*;p;dSCL+zpQ4Dr?R+iEaf*nkk?(E zzX_~f!I!?1!wr&Po-jT~XSouOAb(HFTl%KGx?Vn-MR-n4e|I-{J!D{qN(6nYsp(o# zdxNjJv`AP$ON+5V;N1Yq{@GH4S~oz;v`T7;K2dwx}2n z@S`NjZRC^5nMQ=kPLNT5-u#yXMypA9GCJV|ihX9e)0<~rLT$n_SfOi5w3Vwyq%$}pxBYCKT!~gvGsIDpg_CUO@ zDxxpco&&Bg^nxoW1Fi>F=VZc|GirNA?P~Ib%5>oeT`s)a96q}O6hu3BmH56L9AyOm zw(cVxySKjd{KaqGmbBN1lwtoWwaU$D0**0X=5$Jsak3R)%0Hm?=kGST2xnUU39~87 zUV(ZQ_dJXz5@RT&5?DyXi)!ulWYH(UU&1{DoRZqCP&g;z3;`)ieZD02Y_D}h!7noe z_;u61O^Hk66FdDf1r~m zZKmN9-1z2)=&dwDETV+-4jb~!5>+Lj7SHGBZS2Z#k_r?yP8wo}x5Vuxe;RNkzTe-O z=P_efLEfF9HJzv6THBD@5K#H-!>HB9EPHA*W6A^MI!Jb^-^4{y%v?C|}L z0PO3C_ZKscQF-XnA&kuB#+gUY3Bjz^jB=bRg;Ap=1=__(s0nFF7WYicsHjCW48~9ZRiqHe zfwcVy0h1)CRT4!w+1H>aB`>RQ+Oz!5U!oOyMOC@$>RbFN&XQkx3ZcRc##(#mpy3Z` z_mJ0VwH)6mRXu6a{LN=*MqAzrd~X1oV=-BO{NX$#N3rczno1Q_wxq*e63DB}-+?yA z4JG!o{-EQj#TNfGF=fUp;bw#Psrtl$VunubJ@@Zd(;{dw_dQB$Sr$xes9ch2ZdFDc zlXAV$Gnjs~I8Gn2M?RQht!b;>6+y$&Jv?s{mhwQh z_Xf$GxOFgA8jh2feCd0Xw=Zs}3SYjp-J>?&#}RxTrg>ETZ}2+;S_cO*>T&~XiQ z0tSi+^)S_BP0cd-h2w@C4=@&XTz^n{GvKeYW!oFFZ_1~Niq^W@O@Y=cUXI_jx{e|G zmt_3ni@~IOFka(-ke(CF+4dv{T{w)<*lc;mtDx~e69@f#oTE`yqZ^W zecmx7@!ck&zqF>}dq2|ZI4I$z&lze$14&!b{)GNh8h>1*b+fD+rV@3*ClmIG>P7|t&o%pN=W{f#mH%X`-!8p4*rKhoC&pQsEjc+!s3wb?C{9` z#9X3v)a!!cc#8-&k+ib-!w!MNq6#+;9Q1{JgGd{0-F1wJ6w0c&IJQqyf}E^p|GH1? z(OFj$o{!pAbELz+-~3=cA*W>JT4nqHVMKeUYw((u z6JzwO$1@hVP!9}pbT~jUf$S?Fs+Fx2c+Dr6xs`jdLsx7fHxErv4OL=JkqInruk_bUP#VpnC8Kce`%p!WKSvU^S(L#1G( zn8xb|Q`v)jvZ3|{@fMg~_2Z6~iueX2BGi9p#s-CxW{NEc4fXe=u0BoZz&qRWV5;#Y z-s209v+8|q&nBMM>@P}6$wuy9#7t`oKdzje1?{=X1jO!&A(oqLr1q zcT9)}c|Yt##pKf8@!`t;C}m|mN;&o~Ei%K2@Ki1&OD5!f1&(B<)YDLGS?EPwD?C?}ns(2U;)tCFy{@*O8d7Revz@Nkgc-PMWrZHp*g^99?I2;BPk{)Cs(% z)cxF~n2w}0U$2q|2P4`V$xIgnHr>6sA-+$3Kz$F9dIKMpr=wDh_J{Qzr zpov(M8LCZwwU_INHa6ahxErNhgEF?;__5$v?h9wU%s+eT5^yc#o5k}5$J@mmUGiNz zl*-y^+5XO^1!L} zgta@9){mgY1nu?G8Py|CmV;vJ3BGp#m8|StV9X z1y3^<>%YRa2hj^ai}(XD{5L!A;BCR?w%S;du5_-}kzb9QRsQ&)|Ea!-?^X4l$tOz2 zKp>p1{&GtD1~MA;wy~;dPSqeo%f=k^4H#y5{T9x?cGzXmp0vSkus3%B=R6tW$Z=PP z>2XCrK$a&iT?T{NkwgDKt7~o);Zbb67J8(6=oynToSflqN#Q_HY$L@L(yP0qxzPCX z_h$2<3W1);dGCj4-j-D|a3ej7>OAW75D8f+m z9Y|m=6*$mKXSWf#cL_LM^~k+RExZ+U!P&c$42Dq@+ZD)5nv;xYLEAkjsCxJ$QO&az z5$`gK>FUOHHh(VUPipWekw6?xHH>ey;yFh(Ov@};DoIbf7(Axg4$#YwOKE4cV{C88WP_KZ#E*DqER@#_Rj=z zRiV^If+R5f%89%b(O8Y?E+^cYuwnw~MJTPSMeN7~;yhf{)=BFA3{Pa3FAb7_rNCHv zqQ5};rTi|jZyb@iF2Q-D$>Kko3V&*fBQwQyh4W+dH`6|t7mllyBISGxCYSYzA@*bVpE-~zNcEM}apL9oxZhEwc5%||R25zh$M`G)G z_}l`RBuo0iwl608Jk0$^*3|$(-f<+=B`3FR7zs^``H1t%;U7IAe|`(*v^9l)d z8vKB*f{|#V(&S21(tRoNscz7`8P;sY(el<-9f8x4VrH%nzjiXV;-OWMt+-XuZWQD;F)A=4d)KIg{Zrpx+JF9U^^e0n<4TdBZq=RW@OtmmRY^pj#S< z))Fz-l(MSjUNN{moZcJhzzMZ1OUlVoG;#U1mz7ZUp|=cvW^57$1-;qI&wZk?r99DR z4ZWS0@&lgx$!BMDu7mKwF59BS0w?!-8xs{sVjn_JH(3KGhBy70dD7pzQD&~EzWKZm zT=$#@PO@yqh@^1Y<+OyZA6}c8(_)aF3>xN4L_1pEFVvJ?R>3~9|L}hnx~L-gXH3A# z&Qi8`(I^`D+}=AAS12Tey!4qNh? z2;3o$At0NC191Ez7`EDMhWQ&S%DwaJPv94kZ>f)GL=g=ZaP@(mUnO^#D-9l~cKniK zcqp?n20vq}??=x1XYM)n(^V-d`@a$8>Ah^ATb^= z%$phBvAA2%0yMC*wC~<5sOfoN7aGSzQ!sx`W7QtGPIY}fZ}9Cnd1hH#r{p#o&g(J| ziCe7CpZKsx{oV9CQsv(nmGvmK&M+E7zlqDWiLVu3PDfH8Z2G-tG8=3LioiBigfU3- zhDb)UxA6YV|LX-%Nd{A-fVs>eB!xo%6p4Vzc)WjBeQ!9Lcg z^AEQ7X@OTWC0(YoU!Z0M@bHcG%EwMg;OY6Bglp%%_j<`QGvQ6y`pR zAal@RvzMMmlkJ&cfZx&AYrwO0!1nt7SBn1A!0l4SQ{#cu#P#P75e|ZmOH*M`ZBFEN zF~KU;?~GWx|A)2rjB2WD+eKAWRGNqssZs=yCLp~;5d@T?bfkCby@v!udXp|KQE4K* zNhkDPl-`51&>;x~0x28c_j|wRdA>dNIs1%p=8v`3m}8MyxXZln>zZ>_1$y)F$%HW! zrmuLvIz8T__utG^J_TuyJIllo#JL|trIe^?X?OgJ`BAZ!tna@$K#KjceymUh!5Kn@ zt)5-`vB_YWoUGcf!l6~1|87rf1B9c7f-66I&MCcq{gj&4{{8zgou{|2=Dj+2 za9icUhm=Jup893*Qy=kJE+#-ZqTjQ{!pCDH``{#7)YHe-hjxwZ7e9l9ICrTpX0a+w zcLxb&Nbj{%?DB5SE*p=a`3(xDfs#~5F8Hq8nt$u2xY(1p{e~g<_;gff;YazWlQ%2! zW^{(MI5p7XbU zyz+^?Q@xN;`qGg34LgIB+4+WAFJ@71m#2A6MKl?SwHECGZzt&rUs6UiN=lnGsx!Af zpSBVT=247NX?IU+NfX6X!&Ow~Up;lOfMuvEu0h+E4ngv7{Q$HY&}Ba-4*LvoTxV`1 z`AP2!>2sK0&L{{#GIh(#pXj{*eRU-!EADO@W#ES>aKMR2*tT+Xz9plpAR;DfK2S}# zRFnEoN&ISA_qvKsjv|X>5J`Rm-Tt_$f>|~yh#&|Q_n+N1$GHRHYVA{Hj||m2-Skks zeg1+w70*9k8+)m>6XhpkHu6DV`rJi=N1g}syZCM@TEt)h5Z;52X=LVj5c*)<6_nKy zZL98}h0SzO#4_aZFk4Lv6`vjts;cD>B>FYlHZ-wkarQGq`*ZO*H+T7V@CoCu@hX+p zyb$DuM{9jU3*wfk?2fkLpOW{@;8D7OD}y!QvN(UP+M9IcvM!h28%LJ`WY)G8sza9+ zpK^2jt-OyhyP3+7o*MSxO#=I!e+~D)E)6NPRR^fMf3KoOzL@$d82m2*`p-oLWDtiY z7M;r}{j2@|x^$fz2n1g?7e>wK{JmN+@3hiVDlnn&i_HJ_{x1s1-}=SDvC{3)Jg!{~ z{byxRNx-+#|Fr$DyPv4z8~UgJXoU+fA{g-YX&o^7A8*o2pKEBgjQ)F~{__XT<6*u5 zjE$53qc&k_i}xQbn+`{Z?Vk9*J&H7m_EvgFqDh1b_lM0Xlg-(}o9&H{4}?wG0NiLLE`aeMJip^p9X7k zo&k?;?h843$CkGa3S}CaNV9}7%+ul}Ld3CWCB44(Tq3)9H(r}> zoh@@{!T0T&-`X-obF(X{5MpNF9w3zGyIe1dy!xEfQOEI29wZaTIPvxE@yieCWL?w# znIG`;r=C;vvEUOP45YEyxShhK5I)}0fDNBh3`>14TBssf1(jnGuLez7%R^fth6aho ztj01+g9*Ja+*bF={TiwET)(L*KIOjIBwpdPZ3iT59WcvvD)HNV|9P7B$p?FagEM_8te+AopOlzoREYS9Xg)|{_KhXU zN)tYAI62)r?EamZei&IK8|eZ!IA4DHe(bc0@H43laBc(|Ra!qaN-=aEc{< z;3S=`b+~Q?$?S<|jYk=WYjhJE+wT*i=4Xv7BGASIZ&WgKR#Z|8#rIr^I|ChVxVX z(V7xI-)`>2snU4YwN!Vghxk%NZ5Iv%@6WCd_d7LbtoLJR{}NpEZZ=HE`7(31By&Wv z^wo&;?pqB)0dt`@c^%tld}C?sBr2{NKUW)k_mWL+Af)u%{Ve>BZZ2gh>C_jc-knnz z6EUH?H#<1_!=9r-(-0MzIj??Pcx`8ymSSiu=e$APQ1s#*1+T&F4{wuZ>jGqWJdF|J zNhcqzmwO290eiy>_)QkYIr41#{%qNRPhQa51Jh0~(h-?I3x`JTvOH`h|DF9yk ze$_f@6Vn(BIF3-a+(ipt{rC(;2-=;?3K9FvPp!NCvjlZ>gQCBI(UQHU(-U}P1Kz%B z*cS`vYTdKD5nVQNjE@*A(WWsyz%f+&nmqhiyza|t+JjQ3WRxgUAI#$T)V#XcE$m#b zR7{y@kfT~c@Rz&i(nS?4w#^+56w7QK97^*mzW)!<`ae_naTyd5^+JrO;y_Op>C zyYG^tij)G7U((V_${o|_GSx^`-?Z{h1KLpW*is0dq}+OMFnFU*c$07wC*mNZQDq>p z4Ps?ZZHaTO^EE(u*D?F%n+)8y*jHhNkezy4PlP0F?p7xX1pwMg>KEuNhW3e9dVgqc zPNSTESYMjC;UfR>mnh_`|BkZXw{tZJR-BcjLhoRZk8R<_1E}IuY(P@_(pk>T(eCI6 z3^4_3HP?7JeQVpV{cSa%ycM1rjgd@~BQkUX2r;MpeEE*Ps~NoI<1NE9&BB%>Ezq~_ zvw;{9q96490MeGWYUj~BH5oBxQ?d_B7TUDkXEKHc9}TPR6E3j{Bp^BhwC}(1?o@qM ze>h!|y1%?0g)cHWR}}6RB-Lk0WKLOXW1bv6$nRd0JW2kP#vgJC8o-!V^}xf9tU*KY z0af;sg$wNX_@D>LND8x>QFpC?%*i%8iBnC^_RHX+)St|Fgj7$h?OE| zb%r|$p47Q?!HV#RT-b3Ra^p0%7-^ekht~hg6)&W=l=%~oKb9rEKIT%AfoM5yR9#BD z@4|?ug$m)aBi^3dx|)2s@>`FG_ngX|uu)!86C1FWtJ1)b6(4KHbE)dh`yBL&#$r=>;*k&f{W1k4u3tr<{uuNyzU+Q%jK z0AJ;7VncC@vupHyVq^L+lPAC56-fs8Y`Bh%GX!bJZRCIyQ4AhB2kF})@Dl6jt! z)!FJn1^=}x^S-&xr|Xwfe6cLM8Fe4F(>Pq{XUM`cv#ZIOZapq>b@_}Uio>((E}g1UMZbyAnd$l zbDUM_E(maCRg4Q)e>Xb-%@{{}mO~t~E5V27Jx>@Vwg&jf1dL_QJZ%XTQOOOZxpR(V zXKB#}7g1aWN~S+O1s-YE+vrR=CswMoC+#EYLI`P(A4VGeZz98CU5s+ z-SpSzC)+d3y#}b`ml{o;6{lkro{j?sEX-I3W>3rpQe{v<(o{QI5|kZChaM~_jI!5C z;2wS@di@nw;0 zc9P8}GqX*FFW*@GlxaSJQz~NDLB6jFx}znQPF7T;lrk?r1Lar2+3aIDzE{y!#aGxN zGGqYdxR{yN0OXZJ!ZsewQ5P~X?cP*9iI)%wXZD^+08qc7N+;b zS@B=_LhoQI0yfBPW3zh7jgkdZ+UZnv9`MaP8nbKHJ2SS2zPQc)Mci#wpvZd9x;?g( zyhJ}?C$NU|v`LDK(cE<=)yQGaZ9l6wfp5X-mE(=X)K^yB?T|Pbw4jLvbNM|b7C?M1 zv-HQPUlS3B-yWCP?)1K$vc_l0nI_-L4^qd}6|BPQj}g}lAg@;A?s_7P7f^pQ8zY0J zN6m*`MsB-yqh)IK+(~_?eEWqK7MlcO-+ZzIYC?3+-YDn_Q!bz7pmZA~XLj_sS_1ST z(bebv7~^1-zS;U}Il=m%QsPWdE~llFk4#x_pN-m$ z)uiWBS>0oFc$wEhpiEAqiRK___*fPEsd!va2*T93>zC)T-R10?yKfsqa`lY^hs+T- zeP6Ab6NlJlQ9wCMm)5u+zdbWN7a~5H)@gO`o1fGi%$rdqhc8r@;PNxpybAkO(#^^+I9ewP69yX>B={QHe19=t$#9QZ<}L!;BrD_*o;zs!*kzWyhk{qL(=^o2 zQqhc27Q=c_aI^wRH0tx{@;LfPk;`T9=N9aCI0j zRlb{6BQ}&>mBaVL(iFL>b|2GcPktq;OrJ%@u?*y@&(3l%3rO>Az3YvedGzK1g1{2O zz0>P-AwEl)>HEQQAauV$l6`49CNaS`&{K=Y6xDfq#ScTWyKGUuRaxE4x&qPoX&Qh zgo~w2EoRZYzSJ~i=I>LnJ#8gf`mAQ#n}$8zxah>$Pljb@?y=T%m50*X{qu+9cJY-U zlp{H-2-LbW!J)3^>sN}tx&H6)_}?|U1>+=p4|j^}Y#H78GixHR=H87vhd&#a2^jx! zB@c%a1MI<2TBb|Lti1w-5l2A&cCO zAWnv8{%`@F)p*}O*ty3mqSKdtQ9bu$@^=TyEy(NDW4Y~Y_+ zJ=0g$PP60MHW?fgH;D3!+GH?`B~u=GVLXG>SC;&oN}Q~PaFl+7Hvhq?u*xU7cvp!+ ztD7x}2rw>^)U{mw-H0#M97$Ac(Th*DZVA)1K;Ev?%GpY&4F4R}+-&FApQ)!;W z3quLS2V(r>7F+jE>dLyo>=;C_)u;=lHRH^-SAkK?=Utc$lIQC)iUC8kA#3`|u#-P( zyj8r+|L_4TtokAXdi!e!-)paZ_MLS3_ugO5{w1AEdTZ4kx7~#wza^t)Cw>k!i^wt2Rd;1wVfzZxa~L6<)UD%Qlo5_W3)3=!Yo zj8hEi0WGAaakg3$eqOz!6?Bu5s;hT}%N~199%%ERC`^Yn5U)Y*=YC(;6cjh!OX;@h z#$iVeR>;jQV%R3#YQkc2mAJA?IS?bf&4*8QhqId=4dm60TX z79q+a8p(bfVQPWAFG)$M%?&#@KLuhpK35;cPj>@(OHL~%8N1d(<)UI`j zeuk^^y@x@C;j_yAthRrz9($cPF2Wlbh+$Jul95g_tVKV~lYOn2zzw0o`AV+rXX`hR z*yK0f=g7r3oqMQyMpxUxWGLpC>|u9`@9I3gSHz_MVX51bm96MsI2nuOs(%FNnH^*nHt!a5W%kmvkZ*(Z&`=u)*;?Q(e z*1x3VjXi9no##CWGYDnuBkB)IAE@sb-$L{+mf%71uhL2ooA&7QIz9W|#UQ5FXKTIM!lAEOlwBqepv+k_d4)=-OO6Q`yQnrE`*k}`7dTR!@mmK`)gkC7)`%!3`*i)6r7`$xxIb60q2w9-BvzJ5;<)b~=dD;`dd9$bLW`Ym@{ zi3?npP?>d)c0Bhk2q>~nBM*dZ8KKVd9FbeG@OD@24b=1-($>rQH~E>=W-IRFoHMxg z;2qx&=&ONS0hCaY1!+^?hBTp#)!q~}Qa!L)37w4mGn<=nH`v=Gm3Dhky9wqkOdzWS z^h$QecRQ*Iu&JjGP=5$ZnNl7u=F#U(PqU^ z3?;_RF9%8$?iins`ET(`;ZGZ2rzIzEyJE2wqGZA7T4iYL~nF%f>hQ4Bw~;>^LDHILZA=r>8M{xWVC5$D>in$4~2uLj^a z@j%+)%!xdd*kmM1SVdE^r_4+bxs#s!NgD5(>tC7%sTQj`cL!!y8mDHA%(*(&Or&DST4GqBlFFYZ+k2< zvaaH)E_=bMGj3;!@s!TnLQ(PM!&h!{1hH={>t0j$FD9uwa)gxZ*;9W9_)MaU923n( zNW@186gsZ^r z#_viiim)rz?JJDRtKS$APCPPbH5fo1NEzKa>>vO#;&vbmqti_K6-Qn061mz?@BS>q zR=dk)z>`P##uqfpHat75s~dg}zcU)&{f7&1)4u2D;Dj7MpP(cS!~c?Wa-?c^lnq{#V`kDL74cT__j(P2}& z8x!Μ;GVy*7tG>w|boBVQ(&4bbz-wi=J0IJX)~rS%@TD(|V7Y4kp@xCu)O$k|^@ zL>_pUf`|bntzs_Ez3d`EphM_gA#NQ`qyn~&eVtOwc36f zt#JRp0j!2^gX}98huLb~z-1k_Wf2R$3gndLvaUoWW(fjihBIF5MrQzOx z3>VBbJT;-hrBfn)%(t%i#XAb+2gcd-BUsFrUP~WkE8TKQ>(vVXf5xaPXezV_U;2lF z3a`l{06-FlQa*&lw6gl&jD$kY-}(&(9r7L8p-DP-3P)r%?zCxCS!pZ);giD zk6^dtVQnPH197JIxF*r%E%_SQ7jEjy8C<(_ZB<23B(@Odc~qs45htNvcOpQIy^{aU zYX>ijJB7Xb^^N0Mnl|%dO*Cx;pT#wgCguYzVB;(-!__R=cqH93t7!_#T;|8NIt^2? z+ToUe2coC(H4doD&w1f0Xx(9z*cHdtw)b4m!+ta=eXMR_*m-*HF(qg);=tJh>CRj> zUD$ByRSIbMNVS1pUw|W>aP;Yfwf7yLM%OeM=cjh>JHA$WpUX${&QNv4`)*tz{hBx= zZU1M)e6dmg+>{u0TF;k!YITz#J~=ybFeq`6aW=YD z^CVAce9kz~nd{55{QGi=Rz}lRUfYV?nx@Z<^l;N3iC{Fg27l z9=bY<>{!5lE=2u$+r5jOc>`)JOA`uzectMB3SsxgbhX9qA_+~z%}C>U_X zN}QGdO^%<-?^2x-T2+DQVQ^S`OTBnPb%5qgL|U{)hVT>n6D?zO61PT z-DA(3{XHDMZtdLB2R4^#o)_LjcbA?TUgC_IpmDztEp>iS3a?qnqYKf1xSElDVS%jX z3Y}~7^eNcl*fGw4=dZoI%MJi3wmF%H0f^pDEjtUOPKtzc3VA{vsV=@#q(IUyj?PYc~B@h`y`D%F~(2edY@7N(2+|bbt5*H?jXy z6U1_AM6FGu10z;qvJr8uBBl66=bVMU+|`|03D1*U-`n=0ZUqlKQJWTHK?)Des_&UV z92K&}U4<*ouli&k-1vV5WU&krDQ4F)%n*L}35%AwS_ed7%xakqDs(7swJYb4v&4mI zpLsHqvaYpvRj#*^x4XWgrN~dTx~2N++N(?6P)OUS-@`Y4Fj{l5@CeSPM{eY7IS;c2 z2sLo+1ppf-VHwV5)kABq#P!c<5Wj8s;cK7WljmxhdEfWT#G3*`+Dv2gSUCOw4tR9H zI2mO5Io{~)9cyp5-Cj0B#F(hi(B!|>wSNw{>*SOqRk|B%m~hepG7`21 z(-!>l#0PXIEA4N8NK<6yc|O{|+N()QZCZPI4|>KnoEbg_o43Ynd`fO)91Z(rx_>mv znxpw001LoBgr%6dY@`QHkITx*XO^=~BjzvqzIz-oj;r-!vDjAVLy+nJc0BULVU zRs5^!bD6XuiW0-b-6{IYQK10St=g{{;O0@hucrARQdEi%OqD-qFbe3Le!E3!3Yme< zjuRq>yyHA-?n|DOIJ-d@~P1? zo*29U0(KKhWjpx%=kS6=z5L~^tc(TxW%;+P;NMp=1U`Oi{GIo}xIQxFu`d_Z=rx?Q z$ab5u7iPAPzJ<+P&v;+myit~Whxm1GTvYfX#(iOX{ob`BMUmBIU-G6ciYe`^i1gu& zFVg3yD`t!S;M&yiTwCGa$SJQK*8c43gNcE+CzpNonTNMT>0dhkZ_svNneV%2ykF1b zHgZp-wb|Vtuwigi$ zijRo(eiIb%kT6^^wL4mT;G6$dF5YGo&~unTn5 z?MJzN0czdSAHx$*!cX+4C)&S_31Bh0gWDR4*#}ks4YDf3raZ1#HAiF)XP=|K_h{2!>@3@PH&;bI zRWe*+;DNh^ej<^ekKDbZ-)r_502dcq$|z!U6bn#iRX_PYB^xi8EXH|;9O-z~%fRC< zYPMRLAviILaX)fJQW}X~2HtQTPoS3%%={rCKMam=EjSScyUm3KjKs-YDB|4U@m>p< zU>hL6YLo@iURs505UlqN+jySCZO%GOxS%bk7Dy@{>4EmvY8iJ4u-t`hTU!Lw3&RhO zaA@NT1t~KHbU%PCEcc&{j{0risz!uL(fY|Zy36Zotqf<>r|~8<_kCdVO!8+)lx!fY;D^%$XF&bFS88swLVpB`V$-MTo-;lErb1DBv_M~~>f!*-Bl>hog-96v)* z;B2#S@6CI`t9O;f_aC(H70Yi7CTlMpgWp)pN)W{4KUG3ZnDig-MV%Px{nWoBdQ#`^o9Qri$^d6_*RwpcS^oms9T&puH3w2ZTIm%9X5t$eUPhE zs9E^N;vZjyMkNdRpYTv(hKxE0{ABraUY~VUMx_5i6KF&aYdYR$XV-hIk?huysx%Iq zD13$7vWLX~0S)hN0DD;INLU`p52LWz{?jjG87EH;YDUX`Li# z>Z+~4&z9a7`}t&K5QZ1AK9JR%{lIz!L z7%**jF*3V4jlTC;ILnW8P3h~kp|-u8nh9pzmIT`$u&Uc$^PNYIbis)gDZlCfBM7vR zaq#8GV=FV&GE2jR1t)y=x-EznNL2?tWsLzIT3&-Du*yRR ziavE`xvx=e49_b?le8@lL6n*$+{m-W1yc6LA~dG0N8t-`q^oKiJjtVRbd-1W;_Zgg zN!{OuHncvE&B9j~&hvrs)pm&F?a}g=*nFJG@GdeS0QkfRV2hZCAY$>U4~oaz3t1(+ z_`w$HH<_k?IKTWf`E0?JZ)SaCym0r@b#wPRSoL(?u>ftQw56fQx^I$@VUEbkbfrsH zsE@kio2Gb{700oaf?Ea`+-yx;$jtjP)#`OANR%js3IzZ3VwKy(-{wo0qcV78h)vwR z>V8>g!y5?haS~x=5G02cF$-+iHoHIg`%=k_lO1^7>knmMUdbq}u|R6Cscxe&lQ!zc zF(=>p)yjAk^3M19YPUn^1VMS3Ewawang#ICX^UBu81dvlAG`iK1b`Nd;P)wAeA!4H z2kyRg)#(0+UQU{XvW1uivUdX7(BT+%D*-il_hR+Jx+~T|=t2FVlzsYfRHb}q>y$k> znnn61*MjEl50u@;?xPFBu4xL=@G91_TqBo`-5@6lCv2y?1n&`Hf`W}3LuJn-s`q3T zao?K?(cP8)@?->1WW-MGaslPDp{%qNxtleAXH?X|j{UoPU#t~8-4RVc<^Sk9XdG6E zuB<=i36q7o=TOBd69?vg(Wi!&a1NeU9K`TTO5Apk^^VFnX83X;$yx zR{sFpqf9i5Cq7k(LZ+@DcCtOOyhqs1l@$TLmI=G|(To-9>IWkDiwy`Rp9{H6Uwjlu z1wSt<3(1sY)&5xz8J^ZCH&B*J{h$w0!TD~FO2Taoq`Lai^wY2;Tc>2Ha(V1K<>oW%Fh0vrD&?- zvBah9?g&oZdg4M8H<{7K25@yd|Md&O=DOo!W)Z{nJ&D$dcB|T)FQ}|0hgwnP8-){X zWXZd*lFr@5^$=aE>UDOSDxb#mh2C2&K<-R&o#;0# z@+M64DaAcII9vkD++I&Vr#)1QIj(YC{gLU5dZ+%l3WM6KCa&ry2>RK2=4EpX2j7Qj z&5oY`P@>kIy=AC8Q!QFoho=*{$XQmV7AmCBGAm2g3#A+TFt4<=^2fetO)0+{Kk3v= z>kgy~Xr1ZcHCwtBZ$QcB_PbcFV0GNdU+srb(T3IhI5w#^`I_htkqT3}vV&jo%Lf}D z-vzf==(`lzcQ&}P0?OQ~1#)<~c%<9!Javm?^N+W4nLtb$(?KDv7l`etkS$)dGG|m$ zb*VLcm~_1Tj^bpRup)Nf>LolPqei;7&Q%Q3*tN16I()G{<2JmO@jMy<>~8^ky0-4! z5h`Y5CY`C1A^cCW8*Uj1B?pR>thD)6?Us5&ACOvtJOcz zgC!lGz@~Ai!39Fh{PESc+~b2SWXCSn+~RNztHT;?(kvD4vH6tyg*ID9Zbt>3o2)e# zccSgn&)`e>3wuzxSyQD&Kvq6sVS$ip)&SaP%Q3T!pI%+fy)d&7VF|e4U5%Ai=r9|n z(XX;@XRmM4sl0*N1`3&;L7Xx##$KkaTgldjHZX~L*!(xog#Xob8BJ@~>>&Lj_ip8F z(~X62J)?Ld6SD8Jv)Rh&!Ua15L(O0K7SES73SFkhQ6XPyb|pTlTbV64(9^q5EJ~#@ zts`wQJqeFd!<33|tqd{S#X#I7bXP9z7J*%77kLK?nh5)BERT?_kHyM-AK%(|w|{2K zVRt6q6#>gWaw_zezcFePvbQU-RPA;*S*jLQ%q7a?s>BQpg9z#I+p%@*qsDK%d}%;05j2=Y&^aM3Qn>y?gdM`6Q!Gue>u} zmrX)&%&~K%vj);Bf&6LL(;M*gbyy4b37B#(nZyXG+(;-w+n?75Y1?q5o-#hp-RkfYfk3>UoG6V*Kg34H&%&E(bRW<4ntq$bQWk1y`2s2rNc#-rVhtl-vH`@J6R-n+%M=FA1%B zG1`$oWYJ0!(JLcF3RkZ;^xcaW%xbT<5oM6blcflxSc#$zvOk;&Y|a{s34Gzwuy&=4 zB!WiJ>%%n@$Vy*3WQ*RGjH1W}|h6z}yh;HtlK`ePZOLXTJzn$O`iV3=uCWP3oexX!W zw4orI6{iUs^l>{T3_G1~cmwrq#LbKm3!)LTFmmn!Z8DdZ7FhsLJIh7xYeinE#YV~= z)?l^I96bh;97k|J^4U|&q28JGs=ZmpbZmIvedl{KD!*a{R)54}Dh%znJgA@kwBRV6 z;Ke-jnUc)U`I(0gtQ2`yzen3{_gOqd_?ublqf`=s5=}RxPTzcwa(N`8*d5%OBT$YU zvBuAQ|K*5!*Qh^SoIYYb90_W!{+W6rpJg7Cr$x)g|AO0H*+a^;k53+L0%hHBM%TsE z|1^`LiInqT41M}_N4Iw*vlx87u!=S6Lw?jhr`yJf(hmrE-Z~FZcry(vME|-lAgx4* zBXSvoO{wdh&v#1wmQ+o2ze+bqn6=u|oxoQcZjTPX0rA2-exr~ZzCiv%v|~gA7Gnb* zRRd)-K%gDbNVw;6S;)k;C#g4_7%7rt^tvahW5sY#rC%9p83rudwcWFxbnSJUdo;ck z;*&D$NGs;Z0~Q2CjWenhgX`G)!gTd}zl3(#hKM!Fdq2O}{xXX)?$59)f#MiLBZhcp z4|C@PO27HpKbO)>OxnF_B*no|_H*r;E-Ss^dq$6gJbN`Gsf;haIt9zq(ag-*fW)W+ z4V%d?3r%;~0BrnEZ9Q(;vfZ$=X0gLo5M<8=Zmr-Q#}UP&_dKj-`9KN18QBWoX`Fsj zf4JM#e$mx&vqIsLFE#s1*}+$4Y(Rs#xW<)1_}Ssqw3HcJqNzD3YIaM2 z5Tgp#>OH=bZLOHOPOn@3Vdj8G9An!IeN+kJKi$v zb|&Z@qBFe2`OlJdI$u~rpLw-#C&LU1M@Nm%DMX2Cy>DAceZ65(lq{Y1-S3gnaj!cLqjp0%P}PSSBXgC|YQgT8Ve+}y z)6k_St=#u}znA};?*utlX9UL+!*jOi6arg^ibJz*Z)BN7Yo%r(%lD^E{C;g3j*!5r zJ(TIL)>yRd)VZr~kqOw>n!feF2mntd*36y zgXV==FnK;DqGPX{fYOr~Toq@UmOZ_b0H2Ly6fWI7Cal)*np|oU>uzsXpH~$t`LGZm zB)6R=PF%jsnW26lJG7jxpUCXS5(EQ6o5~0AV-5c#mj%>bzdc*?Bap_DGb$fS>=TZN zyLA$0ZUASTP4FcF@;&)%Rk+P+pwh~?esNa)&R3R;FT1h?`gq)X)ds{IpwAfU5Zj`(iNKL;wz6ccFn&@!-R5u-^sRnov|4!N7jvt_DpteHG zLsFJ{L2+)YubcY#^1iwmF_uWtlIZweu*R_H8-uj`QgV36N7&g>vn)FQ^$JY#V!6`S{>H!1+{t6Omtb@B*zSCo5IsL4Oujna{?`Tp-8Dv z&xZOWUtmC^Ji5?t7%nRe{XcNuRA>LieKYuyZAR}RySCUGCSi7w>sJM>^Mezo!4}!z z3@Nsui;R*v0XQ(YI&9kuDvM3i(s?KG@lEoXXQ_Z4Q5$$}H(H~Ql!NMC00knN*!4%# z@e<%Y-DSjd0b)KqrT4;Wwm=Rf+ZHNgRPvZvlwm68sEt=Yv)gGk<&(xeH1R`pNtmUx`|fo@e{Q~e6n^&X%%v6ojyhfL_h6(|e^;2S*Q&ElBZ6cDqq1hL zAdRWIpnTzziBo%{HJlpb>-|))U@ZjP+Z=gZs6#DFcQip|b-Fe^B^zWF2r+6%BK1Ak zcn7?GdhL!@gUEVmSu@9@I2fF52(8 z+Y!5d@wJra42)v&5~RIuoqVhIXdLfK0{8D5g31l%fRYy+Xw0w`K6?Tayty919h{aW9@zd#WU-AmaV-8lF04uU~iG^&y|oDZAH zTlM;8#9|~MS-t%WtWE0*|I(b?`U}kwfvV28@tnwN&PmudcNC@uq1uQj@^f1S4rHwk z>p9*|rowOu3evvsjJm-aMoWquT(X%Nq(6gN&I1C!wM6e=OU^w1qzpriWtVU@={zHU ze1@k;s#!rff{AP7-sn+j4ugRZvstf2YfiH)5k2?bpQ0jk6%hZ~EQa(HUa#admlI6Q z@In!L->IK;1~;yj=F;Eyiy{wsB16(pK6*ZM9>k{l;=T=uXcT@`x%HI0?j+?NmjEy> zWYN^Fr@SfBH|>i;?IWFsj_fvYcu9s#Xwi7xTK(~yv48eC$aW=b{M32UGztIc_F@J5 zv1J+iV{akH!UV+RNRXeSs!QDjW7lXvqB2`%-`KITO6@gj)_c*eV}g1b_^`!{aHI8p zO_^QXZjdc5^=VI0X9)xL=Bs3Mi#GaVyJsx|b`Lcs!B5wQ*@Kf z?yyJoi@2+LvVjsO0NIcSj#SAGR1Y{NRCm8aKVk5cRgWKwh%ADjkU!}##B`X4zbqlA za>##^eJQ6gty7h5Kry8|ts-V}JiYRuBXnNsXjpV%{I`GWDTt`2o-W+?oCfN@EE%}!UZ}%l);!C?{+DIq*e`tcU|_Iy(P76OKrf- z&oaKDt{NptRs>MPTW}o7X%H!x*~xbG?fMI?>49~>P$}(s;xx;Z4(*xvz6SQ`{F9fQ z0&)|z=+!MoD0wh*zQ5{TJw|A#ia|EyAkrrzD=`_p!Y?H(mcOwoHlnU^lryun@IX9u zU!(W<9zl**Wou#$wTb57XrcBmt$A#-J*dj^L-X?soC+8=C{xx|*t;Xj7Cng@_C#k4 znRwp&^@EQJfV~G0T5PY>rn@p2L38Kb?};UE{*0OravAgkzki+bUua5E5SiV-HKkFd z@*8**3eJ#W8zR+4nqzWFjn;;U2J4q3g@#aG5Jcoq1RsW$>MIUVT^C$&%9 zeNQxJyawvu!Mdx#7@a`cQMBPPVnC?wAoj zL^?0LP!YV@|{;-{l4G1_niOk{v*lE-r2MEn%OgJp7qSE=xD;&@qIG6SM%DX zOKQpQ&N0-F;Soqdb-m$WeWQxu6{Jx>@rttXWQl%!Rf7I7SZ_Wd90Sr*Uq6f;tA4X~ zDYm;Cj}H}mb4S$Bau4SxyPy{%Y9sHKu(^a6UA*DwRi2p6S}7XnbZ3F;>#jl!YJN2t z{jvIyXEdZ_A-gg~Ti|AQV&Lrsh`D({=G}W!u zTGGjjldsFhQ>hMYc4_o#)w$i&`lA`eW-qVzJ@{XGMqE0P@S7yztDKC(j^*vUqy&Z;X%t7$_+SuksO$5&uUSgm_1!=WJ%xzzrn+e0FFtKIA z=B(uCw;;`4SfW1S^uZ_6jZiwP`Ry8#3r?5= zMcxHwa?5g`i2Uwvk@3Vh9m&KOG`p)T2Yv!qBC1*GM|N-jMSum(>@E@c8S`fXT0zCu z-lN(XLrurp!=9TFgCwm2@B3#-uF8Z@B223QN*kXur%s*X1zcv}*V9}su-RD;d~lL+ za!{V(mpgs(Z4y*aUf}0=`>j|UU3@`Xs^3F6+wqE>AFe${_l=GvKcE0ao4B{)P6I)^)zE~B z#+_1mpV!G=8HMQm9|c6GRRHRKrNOEJ-qydF@u)d4Z)I?8{S3*KTNZL7g;8fv z8x?)t1u5d2;lp9oa8SLA0d674TxnM0;!jq(|F#e!!9=K zx`Dpr*reien_`t?A0jUE-E3beS^zNl0kJZruW1v#Ir3MFHsL~|UNATfIKLmYa3ljaf{KO+kXv_*v=jrvvW4yzqj-(EKK)8NZ_BsIJN z)PqTT=!IVDTQ0bzr`|pIVn;7{iodsn3VB#AVzgJoTL7!65hunx0c_&n)xoKty48t zlpFJQtimg9pxE=lfw58jL!% z>7>3Zz4VWy6XI2Fa8v!%aC-(kJ>etcigF}HV0MosPx*&(mv-(f_<9& z%7X7`4<@ayjhVQ(xCNl zKwQAxW-#hhiK=+aeM6>bN!(40Ja0G_H*J4dGX-6I0xEmRBqx!dH#PwVWd#)w&H2zs#d4Vn~+8ypwKy-2ZP7+t?r>19zFpw-d#tsBTT$-!eV zKQ}+S?y>Xni>cgD!7ETNXStZi9yrZqd9=7XI;rMSMqrKl`qwJpYM!+1S|8RbL-+j8 z20+h8h}$a~Ql?daMK=rNiWund?SJFryZLxJa=ZXCD^XY9)yDG8BG$u1v_Dp~Wz%}t zj=f-}Eqe7^RFJC=1z&?Y_2gJdNOEPp(sA7^l!zmx*=e+5d=5q_=&i-)W#fu!W>w%D z4EX~f*20!=A@-v?oVZmHHQ!#IFcU#xW=eY*;B3=IA<)?EBy zybV$r>W{coG8B^`67RS5G7E3hJ_AwDoOj4~sWmXVf7fCE8_r8$+SC4rBnJ{Qt6z3K zH#LtAwxjw=6B>9Pj4EMFLfaL!r0u&jqPYq?_Ya=X$*<;=$?IDWsI{i==)LGkSRqcK z?8jXyF1V-Uqxf=Jk9@iFXi!9@!XR4SvC6dpSo|Rw#vVD)iJ}p=ePY_Pd3m@(t_@}= z-v!nZ91H1~(Ht0SP3h&4HRVtU=5aowE ziK7E;XCr1?A63;e=j_6}pm5yplZb!mk>{TpmUM(lphbh&QaryoT3Ore-z)oNe&`O( zuO_8OP0|flkMgd!$8!k>SFB}2cxd$tWiBiqO^***Y;j1hTTkv&XRJ)Wp@k9G5S9rj zcQ?7+$#Zg;Id(bR0oT!H<76WD-5d4tkc@?6%>HGyGNff(0P#g{m%Zz%=nB@V_(EVH znIy&3W!x$MK{9tAgqv|O5+`v}bCfHWGRICsO-<1U`ie5u{au_g{K&S3Lhyza`JQsL zf~?xOPI}MIm>FQh*=1K#rCy=|Uz6^)`OjEcUL@U6HPHw)xJ0GAvV1<)Z)~|yan`+h zgi&jA`*lD>Pk`aGzp8Z}IN$;@t4IUYc1DRjVop{h#Otui*Ub(gOPUEN0n@0q`Z{9w zb(Bi-0l*D=&0l_wuE&f8HMdK+*&_KkW;$xu=BRc|z8If~u!lB^=f>TBUK-{z?@fLD zJbPxHk)dSDFvzAMTSyQ(RL?0<*w$4j#Hv^vb?lZJmUdW`o^dF7n&F-hu4MKdSSSkP z7KtnX*DnAFttM8JxFMtLNT-tLa8a`45ew`qj%Yf0^}CVUWS)P%5QFO&N!(ynd9Obo z0kPiL`3~JbBJz*j0#WJ{IuVvd_u)P7Uj*MW-qr`0qGHBqybO85?5i1O=fm@cOEuWUofZm5-NL`Tt^Z|=pkvTBKGJEfCJh$p z1>fOuVry@irI$VytYse!2?@~VWsmlmBy7cV`F7iDu~cgE<$@SkM&gg*!!m4T(C$~# z@f99rUjtyeG}*6NstSBzS$vTBM&M$t4b1pm!F%VBWq9<6$wb|V<|tzHtTG=!3DBQg zZWL^C6wotACwzq!0hEo1T>GICc*`s!oC@%g^L@{tx^`Jtyb>8f62`v5 z@D|fx9Y;Mvrh zefabs+%lK%7G|=fyM|M%-&4*9LaCMO;{)=eOdk;=Sc?JE262GY|PONN0h~x(R~datp{FkxgBabDmXC znVWi3!?{XkuRqpnd;98_W+r(M@1u}pNS^e;2# zKiGFkKTt$FOJ!f6mRasWga88WE4dw)gIq@EBTrtREFVuSATV69ttly=a9GlofH3@y zL@u)-tX%Hc4Hq#$A~z!hsVcn24UqaJnaR~#!xN){lIWexz;G7HuPGMew*^N>p*kb> zxiaGyY^RHI+|)db#VgnK4Z$iA3I6rO3FO`@_P%`-%lL=7uXWfn-X1+b)Us}KdXMz= zzuR1&cb=xwev409 ze}Wrkvj`k`S2eJ53%|U6o&diN18jH|r6P+z4LmGUb#m(aWiasyoKN42pM6I|vPv`@ zSF!30ZqE{v1h+F7!1I*t_6{8xHsX#1iJC30>nV7{7B#hDW&_GCJ`XZU^`ysZp*O?a zHsl;~>!86kVCZ^IoxfnnEh%BykZ$6bQAn?R_#JO+6umenxonDSI%1cTX^cx(|DIRr zwrJb?#n7mUb9vypn>f1$Uof0sDE!7)wbdqWQ_jH-eyLhD%0k-jW{T|%75Al=rq=$> za3No(fTJ{7{7G}}^(x;Sj+K%bDgg_MHy(SyN#;%0v^u~gaT`c``0l4iM-3}QhdAGB zEjnbxbCEfq{j*Mnmgyq0*RCG5@w=Gtu(h#!P9M@UJnXtG9aK$WN0t>Au=ohF95(gr;^yL&*7^ z4P@%woTlzxSdVnTa9AFdNCh6~6a;v5qQ140Eh6qmtJwMF)r;Y)v{wdJ%_=u1fIS)4 zvlje`cB`);;(L`)cT#ggg;1-7iQgh)SFM7tkJ*+8p&zXjdE&*%3~~#^>_hAev{!wH z0G59(WbEmuZLoo+7QR8t0|u&!yqj3Po5lf1eXGK`h{0)pHG(vTtuzI9RK8iz>u51t zI)ApVaK|&5#WAtPT)nI_VV&GrwHxT1*mA3bxiBaY(K&ki0elr4yMCxuW`nQrvuPLp zP;)s+I?a#xweG@C&3vLp{)kJ*+=UBna<_B?*Gg*&A>Ptyi%z`85e_-#MaXX(+Dbkt z>Pbh%A^uz8`obiDC^(cH22wVkit$MOw#}(spdK5*u^pjYBA9BtRlD#p!@;63rjMdZ zJytQw4c_I0Qrw`d^zU8q8oHqsk(~YZtVW?3K5uX4jT!QgWa}S0U>Y4UAynVB&9(HU zbWjBJD5et7l?xLpn(R_KG{ME+Aa-5NrfW;ppT7u?-b?UEuO;CzuE;BPapu;%3#vt_ zotr^ECFQBbv`$fyi%o=NJemoZ=PwFtsIDOIn!;dB3MOBZV97ETcmzswS32D-4EuAG zgQUfHBQ#O0{VLfB=^dG=4$mu{AmKaUB)-*3CyUcX`dZ_8N1-sTl;+2t`(SBAPMigJ|@ zFFm>Th;t#=zu50&QK}U-TfEC+uHsz25?+SEONlgv+W^%kgOlu5D}6xZJ6~MekXwh? zfj$3}O4rqMu#)AplFCId{}-MONu|X3LTLO`MuVUx+Wh{razj-S@h5vs9^s!R&_meU z+@iKw|9vFuT02*`HinjrFwE>%(lZ^bfR*c)C`~#PDbNL)1 z>xXL%Kh+NFhLk*71@~()s<|$0VJ6i@1u54K@;6EhNz%^UNyRw2TwBF3B`cqR{66{h z%nOo-R(7g|>W?vc@Q);0qe7>E9T@eJ5frpip^LwFc4((l;4{MwU%YK#2%pAqJ?wb> z^Wsd|0bh|GY+i)c)A7X8a)>s~Ma4?XdL}me^&U62Lg$T#^zFidyz8^ZI(X{k++5HZ zA&yU&2O!5M51T^xeEk~qQ#Za?0L-Tz`=bR-mA|q1%rCn5>`bjtcKRd~pfG>+C6Q^NyE0G=11+hH^*;vhi8H;^HXmtw4=-oOa5_O;7B2~=?-gDXHkL}S z-cGe3{XJ%`FqOo%WG9#r$(wx+uwYLwPPx5S%fSenMJ{2^ZLvW#X-1dix*8*F zP`?Ur!471$nrHdwv=*rDdoZN5BNhwYcxPGgUE6WRXg-2qigpG(DQPGr2RXyRNH@*c z)YFoD-&S=RA?48l_niPZg;^Y7$5?zRN`j@%r!t+iD$Ew$_s&n9_oImvylQE{BR=?3 zt!Idtf7UDcvUZ7SdbdYY2qiC^9`7g`x4B9Gbd`D>gR z_Mea5hH0oKqK336yY&MfR!5^eeC76y6ySlgj%iU+Ih-nVFw7oE*D~k!E5DpQ^xjbo zH2y_EL+y>eq#hzE20~9-A763RFqS)XWR;6^F?yS)A8*H>JHvf;&ZcNE6vjU68Cu>D zWKz{$+;_RM|hQ~WI-U+XnO zh9eR;;N|ZDMXrGr;FqaKdWJdae{f6b9A#cQn+qV4l%#k2`f$_n7~)(9a%F#Ac;&_1 z%P4MNzMN-L@Evi>bdr_@_Q3FDzs8Z|ySj><0R_?NB`D0MKWZE*hp-5pwGuW{w(26N z66z>kX0XT|ezfC&d{UjnoU;vMW85;%Q9UEv?sv zyParPwgz>OwkUJZ6 z13y3>oas+Vo>^jzaXCiGY zABMC018FC)`Y;E$!HeZ9d~%@eL&>FRhOUZDB|D9I{XvNkSe@q?$15SItDfk9h0-hlN3dRrz;I40Pg zY1jxvenD0s)RTgHwYpSc>1h=9LUT!DXWEcR^gV?@i8|_W>X-x zgpzPEe0W9$;c>!ntaTQcdZoBcVsB(tr^2Ac7?AH;qiENLx5b?xncMv%M*d4-UtPZ1 z;rQi-V0Jn<|GIJ~M}0Lbj zetCEvJQVGuNT~HHk>_oEZ4Ccz)KpBM^5u8Od*STmjp|3KuN<^(0mhAv@v~20krN0P z6#GCtTX5|LOS^({hc(OIswJ*yu(zn$kPz z!v{BmLhUbH((&TWek_P1>>J3LwB*KPe+ z?WP?uJmQx>%8NebvZ-|6;1+0kj2c+tBE+>c}VX_d)d`^ze1LPSgIIz;6XYT%6K)3jg%k-PY(;`d!k8rLvFB ze@Mquu9~{|hcD30kgIq1j|Zx~KlsPh|KT@G)9`W4|3g4pn9y=Z<}XO_q)=J<@jsvZ ze{v@NBPRR0{=i^El-@rXr(UKAamz)nUjGF>pPZ?A`~TAwS|OmOGfPzZ)e=wSaq5iS z6Dxtz{}%ek9q_;TQcoIO&ae0Cfev_cBubb&TZyJ$v;Xx)n_47-8@(WShqV!gap+a6?Clk z0MQR~I$vMl-^$hB5f^cn=F?V5j2?LxP!9X=HJ_-sUPtLY=?Zam(all?myZM&p!qO^U+GZv*?wy`izl=B`Rip=x_imoxD+ zS0JB9M~hFFYXep}t?r}&pO;0y;#BW!dj_~?|I;S{8FK#HT@$CKj;91J-wix57ZF7y z)uTGif%NcE<&hcBMt`BkXkAo`+Z-Kp-Q+O+(*$9rt$H zd&5@l>A2+Pyu_>=J#r)bOd98lE%1+VjuPrJB7Ln_ z2Fjw%(qvUp8`pF2q0R=;p97aFxHN{Fd>k}+l)gV>z;*7jkVlnU#{~gqjpY~myi`n$ zn({qWo`a(kA*Oz`v2)*XwM4Pw>M9%6SP*y0-e9Pk892^3L+@C~P5j{Sz|HZ;Gm=oX z4rX7cFWydFgiBOZkvUPA{r6i)-WE`%Ip6&gx?Xn{g(t)Yko(M#yA$Pgg6+U=$(Fs& zHU}XmafjTsfwj}w^zhqo+d)Irqu$2kKXGl1X5H8u1=3Yk=xb#f8&W3#{ADhKQhpx0 z?{uQ>-^>k0RSpYG-{0y`iA-Nc)p2XK_AzIUv^fDAOk-2k$8m8}zOG?e>x@c!D|!3V z3H&Rb?E%{`HgzKzLkqMtZ>ZiQ>hU4?NU*XSU%<#XkA{`>*8Dipz4wlivmwGzI7$zg z{7+4uvNZ3gRi$|jf~}ffExWI6I~sw7`?aboi3S8othu&t738jn_X-NY{sx0NIrHPD zOo(sO{XSN`@}KY}3>Mlr^lR5g%tQ`l1!q_mB6B_C6IzpUK;>ZG<#;BexD;6L<%E8IbN@0S4u5$#xvVr=+J*a*?%%GrA~Y^n|9#_2G089cV~I* zF6HE$!s+n7xyy*l;kA#@XlD8dz~%z)-F5(1t#IxwEf>h$2$ja9Ut}BTOCOsmKaiCq_s*)E8EQi4F#$H8IqhxPhpar zcQ^AV+ce!19`Yw(PL?)oDj)u?iT1Px9yvB1chVaJWNgmK`mF4J2RC?u>}FAvN>Bfn ze5vI7A5Zq}4OAD7T0+$IMPqpQCUNcU>z$<%4(~e?@UiCBfc+<_sWgFU_ZQ*;D*1jn z)fKzl4D($Dk8-p^k}}_OmbwCjeMt+q$+DHS{}lW(b?!)0=ilKj5!V3qs@|`*gB8`d z=1)rM68^yDV#ctK3nVdzc@KNjae%0Q3Z_IWZq2vC+B+gO;Z)^PK;D^>H*NJ(jrNd1 zfT&|5xI{Y6A3!#1eHJwzBYc^V zDSucI$}+K*h&%Mu~VOt;b(fb4g-Np3l8~rpQ;qtFl+xuU7sQWC&sM%Mp`B$BmaXA z4;~oVhQ-Xag{*2mN{!XlkVl*WmDN<3zhK2>c$sLcRgJCVzB?QN$&uAC>4kSuH?)Qf z2O$q*V!|%�(q{;AaE$ni*7JM(UW6Y^;E8-wE{~$B5y|jIeWf{MDoEDYiOYm&Gm_ zyyhUQFb4CwPr88crlitV_0_e329QY3>xRpDvEZowkCG7no*w+FJ*l`#2P_}ZYMBaU zv-dhgUf1|-X1?s2(-<&tU7G9T9LgIlSs^|Wu5>omfp=2y4=ETFl!jIa+NXh^_k9b# zk^8@xRdSie?8fh^#s?Ug8%$zgK%wu*@-`2<^;gcg`NQ&x`S{&3uP8ssC(&z$1#J{~ zV9Gd>SL{>q>vetxT#uy|`57WA19m)F$BuSbkHh(|rO7J0jiIv-k*SyrPKA*$OZ@CF z!2HB+d#sH3QO4xvNVW+x?R!$(f!TreK))Mj*0&WxcKgR1(NkA{H!EI%5F3}BN!tk; z@ay=bl^B~2*+fzP$~bjODV=-q_V1*wyZ4u*KkVWc|Ic~G|3JC>=eGaB@H+t|{!^}h zn;iTHvF}9Y1z5!I{_xa-f?CeTwl{;?zqO3q)S% zy)&JK+V#Hf&^EwM)70lvr?}LVJB;c!3&vq|8OV0ekTA)0>2}<0 z?ASDxMQ!I>d9TZ&hr~{~|B)e6S(mEuk6!RA@#J_rNA=TM{UmM~H}V2tzN!3QY(j9!$in2dYjQBh zlYlM9Ndvi*P^8xj7|f?Gt+{>X!%G6#F1zh(KtYlWW(i*-NW}IAC(GmIr)buvUS% zF}s85X`C9&vyd)qD6zE8;S;)}W_F7KROrVr>@=v`x)1x7w|XO(DHahS-H3qaeT2N@5kmj{e8V)H__qbu}WRC!1s@WD%pDt8VFLXP*!q>)G3mfCz$oUi8 z3!@)zRhWEP7<41$>v9J;Wmrr^FNM)re+)-+QIb~?u@PV}E5BNFaW( z93w(U=CLVpR9`z<$gn6e<&Hf8&E7B5CCg{$WhA4(oL}ukc*x=IoKMb>&0=87TX}FR zu;}M|sg#6R5^`*(rQvooF6O3^ShoC%i#jhUfDQ4P38G*y*BXhUC9bwkYxJHFp*y^l zdB8oxHYMEyW`|fv+-Afxz=DNp@442tdF#{Km1du>a_7G3{bvk zuL5ZqB;@m4_g^3&^3jn9{7R#to+yt)Clh-0V3fbh7+7`^)K)Y<)CdbUo&MaKQ(mBc z-$VCM!g(;4BhRk0!N1eJwxN2=uTq->w%fQSXhkB{NqZ2qT}HXQ1*fZ#BQJeHXeV(H z(gb`<68^4wx8fSj#z2OG_DEs|336Cs^m+DVR0HIev2lzHp4~7gCtjtzs}J*AWkE?B zff?0CC(VSx%QUdSf@J7D6fxh3P02cDG<1 z)|OD6lf=4->O6ui*S%#m2p-)!>sUp?)U9Z%$PM z*j(BYW+tjK3r$DJF>fRa=WowC1u}3!7E0=m=2yJxKWUm|_9>VkJS>cnI0H7Z{l!gs z#ipNx`*-f8 zL{+*wQ`u$mv7F-C_b9YGE?xxL&P!9G^i`-y5_Su%IYIpMY3kn_wO6zKELBCEkU2iX zLB|q4|0_bH(9|1G@c;;+VBv!ri$X)Gx{;<8*T1IP)sIppQ0xhAX)vWQrH788_7fxi zAkI&^)}*U!-~GX-W8lLTn^(l0u)3QQM-2-~GF-+ClZ3|DE$ZnanU+-n7W$BdbA3F4zusWe}e^KQ$N9ilFYC3+IG{Qx>on? zMOA0>JmaHpbyV=L1BfX&2$$DwnwEC{$UoBg+sb;(#}q@8aRH2rQB z$RNDRyzG8lg~#@tM7s3YM0@P8$!W&WX8~kGR@X|NB8T-OH3(N9Cw!d*Vp>&z( z$9J#|jW6bj)!1Ean272lS+#eKYsB(djm@|3;EP)~$NVaQ_SvBsbt>kJ21x~Z^u9~+ z^jEUBzOD}yy0A`8&Rb9~-BXhhx^suhl~m7;mO0`l6l|aMM8?Nt;szJYJR~-TP0&rX zo!0{LE(Gjm`iKj0hnshLOY8AObG7f`AWw&h_A!K%uhJ8O(2uiucgNa5=VbyXnVk)# z7(@?^1vvr=r6o2$jCXbqtXWw8vWodm2$9}T3&tSMk;^$3jf=9(yvcc20~JyQN^n9TIEJ#;vP{2z52M0%aCCRPbJ8LUD+X; z0-Q%e@a!XTn`ws~^}D=+hgELHRX*-(L=*qyW8-nr-eJ=+H3k3si&o;bIA+|Y2qXv{ zow%$_D&BG0s|Z13R8L278WDG>SfpSnv1=iIof4R{9DW}@)ib!EWD5_qi}cr)kLJu|CPa6Ol_JWd|r+mj=_CtCBT&E z7VpdN#$C<1sc7s=%kmuKrZ`UZ8uyNH(K0)=A|8}HrXyNmKRlCjk(j*IZ^#MgO>2PJW-jS z;CCCdMXhI9GdnOEEtDX&evvF@8cXZ`me`XJV|&h0&wy#1c0^RS>fAfWeRqrArngEV#yI98mo zHx*|75HuY0NFt|3G5#)c+c!?|0Que-ZGKPU|9uYPbQhx`RT=Pr)r`fEqEWM{u$Y%f6Bh)S%4;$v z9*)2gUOqifye=}h?=YSqAlbm(5reca-shiYF+49ycpdd6z44hthb97HvP2)cFKCh* z_AdaN1DTfl3ajq+g0?6xSEw%7ai@0nQ18oD*c5-YdC0%C z4IL`x@lJtCMfWv`SZ;4aRB;P+$FrA+BaMh0It?*g;nMEg`zJN(EB`Ors$X_en5mRn zOZxlFAexj;`7xdK=F1FU4?G0}@WhdeMMYs&MXq-?FzG>o=s98Gk?K_D|As;O=@)}E zFhI7(sOd*rw8lKOLhzKnf%wWu=d??B=lS`g3`v4Q;O>F9zg}`y^^Mq;Es$lTYgrxh z&s8ihvO5k<9~y(i8?!3}dbv=^m55Qm zXk(C7SE*x6!kT+K@06xz6?IKTN;xWd%%eb{kW;y<$rLrX(e#pkTyfFC*IHDb%IL3? zJvlw(I(A6_UNifxX;+lacsA~&c*`UA#%*^w28EM-#A(sF+&rmHZ5bK6+j}dcMiqlX z*wxi^4UdV#ZOGSx{9lVRu2yL>)@rZd{P`99-MT5<$Q&*hS9zO&!nDyQsjkd#1l|vHI z$N;9UMNt)XWbb?ZmpY|xi@pr*vY0DyA;*{-Jnnnnu`g+0lg}1x7ZH4gvzU;JL9Qh5O=?#`M2vw(IJV6MIn~tKwnRGQ!Chp z3(2>)LpJ){#naEOo&W39vv7R@)Y&)r^d(`h9$XEbX?#-*F1`%nwMXG!y$Kr%d&7J2 z_DxmY3o&XrH(%eQ^emh>NPznjcYi3H@oIm+2@4|T zME%j&nqNlm$*V>dak<6u5s`8~m3q>3Q`0t!)@Oo8fe9<=6XmCr8AB!4Zm%O@sZ=+l z4Oq8_sW}}vH}~tqTdQ%|$3G62-JqUMZ1+NpL*+iFyL^n-imXm=}~b&Ckwi%j4beJ~d_hr70Vpn&;x-$JU4jFvM1E zQ&~HaUM2M@eY5&u5RoqSzV}!(QnHVBt`rhyBE-wm(e|`Ydp^u&|+LRPW3GD&?whDYPav%m>)1^KifA`F6f-r6to>4V+%LzULGpH?s4qXeQf__^V#wB zWgb<2v1R)H1YQNIw}!)fGN2NL9?}^~tu1PrW^5(KCUtxc_UDocrxvCi{~u*l|+hhzOi4vSnx zzuK!RHGKVs*-`xWRyx7V%yW>cz9+8lP*|&{PtGpg+p0bX-PdO~-N^H#V6~o#eokmQ zrA||7VjpZ&JCHc&W(!T08XFgs z`hvkRU$5dNMl3148>Aqwr9P2L8FlWpSnW`+(oSQ;c0D;$cXuv3SYSdV^d9YFz4cqX z-8Wr&EtTb}V{Z(`y|4GVVi>nAs#Cs@EpC})HnDd|QA7AkrKVge_1Ib-%27{DD4jjf zD!Z2Oal7a*!TqbsatuK#AeW(!3aiO21bt@$RuvP+(pTc6PZC~eY;A&NwnTSUBk7>8A*AcLuyxb^n0}3uui#v`jqGH=GRSxP)P5X~s_Dx`^>=S2^dCYK?ruX?vX39vl|4vH4A^0#%RvOuiIs zBT?jv%G*u8Zbkd<`#kCT{r?0<%86((edxQRb3<67v=W_i=yZu!FxsfW4kHzHm;b@l zacoLUu?f}Zvv;;uIO^#(E5&+dr}To|ROzs7_O`pa2PLkFu)4)$aUkX*P`*LL0{`CZl1;!O;rbGVwC z^_@kBn(~x-qUg1#>osk(v%_kQTjB$Rg`i4HDDE8?HzO$uxwm^<6&K1Oi53Yz=GbK& zJ4ceWHWQp(K3Y?B-wsN~*-X0KhpuoRvkv;`kL(ui&!G+}GM@8&X&lr|zi|b;ugAzV z30k-?H(+=f7m#OHrTGe-=qvM2D4>-VbScP z@cjXC*na8aCu&TS@KQ%71nny9=oeTVVTejxOj5%PBnf;se$7268DY9jqceq#y3$8E zEGDU7^rh{JJq+P5Hy16suCc$hueH9k!n*jQkh4!XpD6!*Y-Yl1xYy@dW3i;CdzHE6 zb8EL}7P9{Tbch3Y0kTt7JDe2Co%T&c4>3tx<6muHrZBAEJzQiTeRj3z;sa)x1 z8rj8$8{g@%+F$AnuvuIRwRkTpjOa)4z~s>OkuIsic_>S-=+k>X<`>r!8al|&7H2(S z@Qj``}E9mfz);R&#zU^nUs{c@De1!zLTHs4stND@&7{3EdjK)N&GPE=>VfMIK?`X)9bfq1j0) z?DDe7Ue*q1de4SCesJnn^sJ$02bsy%1#c8u1CydLIzqR45>$ow!r<00lRN57+m$6wJ~=N0B5e*KTMi^yS{ z(Z-jYm>)iQeE+jqaL)RZJ|x>6$qK5^s_IYoXB4eG1Ej{Avd+Y!Cp$;Kt=f*)F=yVI ziceLu_H4FqGBsd9SHgtZ*(R8=<>OCeS1EeI-|Z@tu)P-19$!SQ=%^MpxY~;BWQWaN zih2MSHy4#!*`ePBSsoi;X-+p9+x==9Gpaj zyutqHLxv2uA&*pzx8Q1mvo(JE%!}~p-o?#ZcNAi*L?yvK$L|FlyYId?9nlt)xlYpC$S?t9k2Z9!PQXO1=q=s^>1;V)8j4{hVj5*C|ES$lxPN> zLt^a5Ww8Sy-E~IwCy%eBbC2e%jWw^J`<_lEQgjH2xp*|)&&aUq{3?y{NX2am%tGN& z{qr~anDTb9GcA$PG>ao6wXvg>h=2)m!6m zN&>0h)AyExuHW?t4a&+aUtcw{2>(BGUt(vv?N9!z*PfRjT>E@p$6LZ{GxK|+AJ;Nv ze(=9C$-Yu=So%5p3)i{iacCyJo(G?#-57g|4WzG z!LLL7cX(>7OzOj|{_SgpYPdlahcU-%USCQ*QiuX>;pd?`P>{ zMuoGu=E0lE(^o&K-1hZ@|8ARe)~n^0SN;Poa!L;l$T@7iM^*RG-i?7rHulFSUVG*= z{kHk6A8XIP{C!PCE-(J2>x6Kl^P3azc%plK)w4(PiI~pRT66 zZ=QIR5nwxShiIYW;x+OwS*+3!`hE&m*s{_20#rqtV#qBcv*MCDSypSwI~ z?+3%j^3}6*(@Xl7!<(n6r`~7gB*n&w@u2}i!?|I8A z@?ybunEDf;JEw}CSE8uvF!9Z^dWv#4 zr;_i?tqYk^FS}gHDQXK(c%bCJ#4{MtWCZ7jStc}6^4r{I@sgmRcKljT$ z=jOvEn@sY{PLi2t=6SMVKjkHn5%Ce?j3^g+w#sw__t4j)a8$Fvk#7< z(kdU{Ca;gip>N;uoW83&DchPlxf(c_yfd@0wKidNG;%O8v2irFb-I8B3cVSzTd1fz zi8+`UI9b@*kg8Z%o4l=j_l}K)jeW1Jk(F&fGnAEUKc$G2m3=?WpN)GjG?t9GeNJ&Z2kbM#T z{Ncw%7n~?FypdJ7wbhz^O+BM*@_a|**~ath(yx@WF8bjh+l_;1BX>@IPt*Oeha&a8 zX8)(NecNZVRUE!xc#D?IUl{H`oAlU+At}vz=ltibe&6geXBf_^=4PO@UU~n;W|K#B zz{5jraS9(*NQR9+cQs9&W8?(f_ZBR$=>pbC&-OCLU5Ctjd2m z1Hy|TT))odzwhb(+qE@HH23UVkGl6D-u9Vf8TSzX@Yk?MDn{ZW!#BCI0Mjjc?7#(k zu;ayFPdGjjjUXBgSt-h;vB)BxdgNRAd`vUP|G3BLBQ0G*54F6p6-huQkx3v}jv!ea zbhU%WPnSMZ1veJ~8}2WkuMAcu{qi9SGj1Svn40w{&>WHb?83=&WB&I4-c*D1$9aU= zlEj~kUi6QdBX6Ou;~oqZmeJKx#UFKiC@KiDM>`56TjPX5p=Tk-Oo_^uP%NXlZ`utB ztXAkV;m$m|j6&fvQn)+tTYSQ3y(lyBO*|WPf^Jt2KeS!%Mbxyqsuv3&X0!`BgI5XN z>2kw|v~y*?isEDC3Zch;CW450Q|pC#?KOVaUA#uOzEWAsb$NdYDj3+Zc||A)AJW_C z)u1Armc*u4*466oH9NQ&kuJHK)2t(6W4=Ni5X1M9$=ar?m7Md8`PpEW#OgM}F9uQFS?eQaI_iA1>#Ec2!zD zqT{z8$4i9m4iW>**k(U(Y_&t6`azN=Q#pFO(W6hX>D!cR)xL}0<)q(xE>v$mx9IJ> zPP!9<_C5-c=U>U41lxvUP^k7_w#GTi{5&|wJr@|5w3Gb4!%s_O9g8729ZY5+1&2jL ze{b-ZhdJz7%PoT&@Vwd02D@He(AkE&I&-%|X8@KT#^280E|3+6Op_>r0mjOFu zt@3LCcMbVs4zuwGLU1J+mRerrN{ERfYkWt*ZH9G?u?R^~-iTv<7ayCm9( ze^=>qbUDt+p`uz;yLk;X-EcXa>non%3$DX%a3r#ts0Znc^q^8bf^3Laj|9D5{j`rS zuqLp!^LB~yo5QBe*nrVdI3)41C|g3rg$|w+XM9jm!_kV0h=)>#8OZ6#!4B}`V;@u( zkv4iNm`rGLWad|cjOC+Z*LIyQ+VOlNcUZd>xSJrs&Cd0$Nv?k(FMOb!k(A%dN26x* zxxCf(*||@I;-|0fJ*Yc^Otjr|pn!#05|inU5+mMr(V#%j1C%@W;_1=)NCyw;5F&seV=o)K_w=xKmgd-qp-zfM*cFVe1}OnT zugi{FZBHYxXRY2bpnyg2+@AUifX#>}HKFqt33ZX`(cOeu44C>~prj z{PXy`(h_XFGEa&AD>yK1=z}-$v2hyByf=PIPd&)Fm-T$} z9PxNWQJC%?$|Tw2YYe_DpjRr%HT{W$!4qbch_0%++=I9tc%~6P%7)oegz~(R#Itgf z@{Aa|rn3pvk;(nL+z^qO?vRl`t*U&VFP@W*N_?jVk!5`?bYl4AFK&?6xEtPZ`*{PyaLE(WcD^i!ZJ6f9mqdXh*cHmCOx1nazUDGe2# zsTG8I6EMpHu~65Bf%`s#-T1IS!|=T5a32fiApwvlm2_S3_H1Nc&Y~%*b-78H};pG5l)cpBZ9aCeD)1&w6vJyijKchb?$w{ zchm$@LD)%NlO+(%o#f)(soz1P?~d|4xh>;&m*pvVp0|7|q3XJ3mbmj^oA&s`3eq+D zrXYYEt&oG@uFUFCAnzEKm1M!%uEoN$g26AmU14=h+{f9Av2`tuU>Yrrz6+ z?bx&)hyX8BuCCtS%h!Lq1bFVXn)l~(R|}-i*;C`F`Ifu47TKo-3G}vOdO;=awV4B| zk0Z;M;PpG;aJ}x6-f4x7aY+0a`lg$Wu|l+GP|$kp$1eSA&B|xf zbq0_baayx#K=!H9L^~V1a%@M+1)KK(!1VG>hE2s|5qWU=nJ54g)&3JCNcOkSR zsq7kbIDQ@>tB-4@hjtgbJY#eb-wMmto&OeuL4PW=^7@26mu#5Tf!$P__XBxB6z?^= z`w;EZL$Ib|vKuKQ-bLXDF!&?bjX)w5F?{PHNA6h>xE7+cVYQr{?SKEavC$4p69E)9 zAu6kccNcq~4EH#cbY>-6!39=4dXVTZC<-wUr^&UD!g3y3mHi1^j#4@ldvv2nP87nW zZ#LA>J#+mggWb4Hy_vmv$uIRhXy~OAU`%6v5Ys1kzIpH1C@ztc>SqIo1p64$w6sBg z1CVflKi7KB4U)#~WuFqFm8epg`dXAv@0&*fXhwWqd{1pWsoM%o4XT#Gr7kS+Rt;7% zYxZe4OPWULeIYWdEi5{C13 zNDHyns~e}Na5Zl@xBB5QS~MD=XiyCD}j7Co~6akI*VV zjC$VNyX1KIbl<~6p60&t31_ba(|2o(tj;9U+D2XKsuY`UeTo?{bI#Rzu}Cm+#cQ4+ z65qG(-~SYu@(;GOo{XX+2e_k}{W9B&SGnYUR?b?8c#@({&!^~+txK|^qO(O%t+AJK z2lpv2r!0wno9k4N9;QViOY_BYefmI$u?_ob^gYGN*cEOeoRIw9`i~-rrJF7L{J@@+ zqWH`#IHpkl;bSNI=JJp2$%wjD(Inv^$osizYIY_OiOJVkNyro02?0v}Vsb*uKEm}v z>Uk`eR9qU8unBsB0%33M*1EKOWG@~`fY|j{%WI`|%x{{9@Rh2If$huyqmM*TFQ*oJW(aSBF zgQ;=eN7EEROEmng^fYUo=_DZcq(wcw@Ae1*kR(4Ghx-5=mQn@yFnhEmOy>D#$EAmH z>dvc6t;!+Ga6^_=UB|tuAMVyzs5uAbtQUfxp%Y{5P+1Fp#4noAQE^n>fKi*a*kO$4 zcziPiHRQeL`}mtti3RT$z8bH1vC=vMeQNLhByGy~#k_xzk_KUgzHZ!ppa5pN(=u0gBy3&7XXAPc z)!5iF=8n{cU|-H4(_#YM;LO%Kkz&H0VsOcp5NK~zAkF$;ExeWNg7M~dt<7!+Yi?e| z^lA$*lq51LfEBk;n#dGalAMia6dbv>x4SWGvb7_*uJ-BD_A`D#@XLA;uCacdhM2rR zw*5%Z*oe~9&BnoS8v);>2>m~0jd{SzdHJ{%;+mMjA#T}~`FaMZF;Bnmdwx`eI01UZ zZCq2S^-Mem1p~^(W0{{hKgo3p!ArD4!>uR%&*taLsAgX)u?r%URTz3h>F<+>yHgw- zyK-1rbMHf9g*S`^9Vl0pXkw9e`}tv`72pb7$u%cgke1=`_2Z`4DSRCwbuHW!BCUVL z?J5-T<#B65rL0hGM9Z#G+vBprT}4l>*(8*ZG?kE6N5 zj47wA%)GK4-?+{0?K9+djmJwMqSw{-T+ zy2g-ea$TytdBKFr9_+-F_?pn3RN=o=2G}X%W-if73~XVD5nR<4cb?o29JMu>E2DT= z1QR?Mo5{i@%~IQ+W5I8flZT_K+Z7{k_6fg4)Xj!CK3A@4;O5^{Sw0W`X#mh$Vvm-_ zC!8BKge8?PH5d{UjnlE0JD6+Qq&5kgj%E}koN7@UYzU>!E3n^@C0-%RK|7+qfXC;& zShY61piX=DS?>NRdXsu%@yPhSl32U1F^SePTBf{GrtrW@vLBDL6p{FNqkAR5iE|XDgMgZUg{8x&6x*Hqm&SWn@TpL| zVy_A|WGQS?N`@{#l8WNU#7es^WvZ}+#qJoF+$8ERbGLre(Ct5smZ_qLE~%=8{rEWt z=H{#W_TO{gJ?j{jBHF8#&vix6j$xoD$il~W!LmrmyPYz-f<-hHcLk7IRA*~ArCtoz zR*Z|thX6@;Db+^D=dB3TLKK}gyw%Qq*X^`2J+TdSVmo!|LvOY;Z89M0aHgW2A59V;{09s49o!BYm zmgAdz~6W5!hs7!{QQKz|v{kcfL=9-X8ALy|y$}0wq$>ygj6yQav+5{uNhvTtCb z6?#J&i{9N1zS2B*`7EC*x-lPxnOZ)p)~rULO^NlM^vuFR*w>c}X!oqovc*a|opI1r z8v|-*U`vs27Slz(1JPPd{-}wnZ+PTiFJL5r*#6cwOrd}MIdix)`}6mWeIi!w(@PER z9dY74$+ARtXt*iD=i|FC%cN#Ipc7Fr^ho`8c&*C87R`oyA4E<(5i_4FGAUig#I$89 z(}HZswjA*8qImrD8h692P-Gn1-k9KZ%NftprBmeCoBn*Zat#tMc{IVeO|7k-#?Y z>nCv74?LEL2oE4n6=p>%~E@2k(PS0BUhpUcR+= zwyd%wTNM;j{(>`H`K$2XaJEoF01=R%y}7sB%6ipNJDW9HBcOzh-jb5NShx@M5x$Ok z{cnJ43|S?t^Yem0&v%R7R6aX+9Qg-ioEV|BGH>Rcq_^rJt;Bvjsmt8EbI8gwfd0a0 z99GTY7Q8%`CX{h<{z!W`6r#Tu*I;%NLoH9SuGCYGP`%kWRyT$(kd&s;o9faVV@)V* zS{L1!+;KrDotQl6pD}5mso$MBchU0loY2YTA}KE%(xKax*}YZt;&e|ncFdc0GdN)^ zQPbeI*&tfDOZ#%vJsW08WUX75&droQoCy9jcFY|-ELL+c{;R39Yhph-#I%`~gh6Lj z7=AAYG}tt2#(oglR#}SBdE&nF7sN)*vhP?txqp14r!V$L!*l_X+N@@Jg!#Pi_`#B7 z?3g;W4wWp@HuMSfD|LZ8;ili|5e2NE<^zI@pnYu8P96h=ebvC_v1XXAS}6o){0&=1 z^jJn^(AKu?hERxv-ib`QXAsl}vy>f3kBt!bmz4+%j5vg*UwZD3MIP3w_bh<+o&X$! zqb(Ua{G72y!(-7$fj2?uzgrU;w@U1mM<;Kd?N#Zp1t#btM73*1!kjLM0<0dEx=pnZ z*cARvxA^x!kqFeWxEN57(_iw?Ir!d{(o4RY^CzRa>OU4)^ic1e4?bKP z+Wv7$b22G+(E&=2LJk2cZwOkC`T}xO^R`*@y=nNsF zOeJ!7!Ty4J4&L@bWk-EzV;sCZ8d#E=|H9_!JH&?H)1XYka#5GrL zM142lg>XAeL9+qxnZmMG5aRgr=?h0Nj(d-4WzE_5g)2$AnzgXoq^eRXzmGdSo)xgD z@H5xQJjCizXOB%w7g{lz*feOwF}6~*Wic7tQ_;4j?ZQ=!d1Qcg^uZm1y6%QgtFQER z=N}`zwb?Xt7T~3fCL`{z`$A5Z+91>$z$1I?7EiXtU}|Ud?-Wdi&>?mjIfcQ+%8SS$ zvP3YEn6np*W=36Y^AC5e`i}1-s|!O(C!wqDp$~F7@zwG~`t@9CxVwC|ho3ebQk#0mQVHKuUvA*S>RY(bIhesf|vorma|6m2ly# zDvhxb+h)K!@4=2SZx;flzlV>u{Z_{j8LgWB6Vh zqh03|Hp;)br@fvJ&k2^aH}4PUY+e%)s(pg8gwh(99eFtCnX?G7LT0}j%$=L=Jk=*t zZ#LoI)qvz4$>dtZABHU3pmDT)=51at2WA=|={6t=XagnJ@&SLfNU?3(B-_iHIUTbn zlva!<^%k|;hp0-?j=5h}cl)kl!?30}-e;JwxX4MLeo{>#tHPw_0WsxjrXZq}3$tDV zId}Ya#dLLb?-k?6D|YZ$Tjo|Ae3G8v(Ahono^QvI;Q3Q@yAV-i_pyM7x-%l^3E{r8 zHBN@a*N@*8F2}n$DS4Fma{vG!h+%|`2}#AD^(-m zJ0qyW{`jhN(|!#o>4wqqKww;=MSLtWg11SFW+A`gd62>MEXLi_BsqGug^8TzSzlEc zHqem7pWNy70)Ol{X8F;u+e`APL>74A|F`l5pZ5m4Zjss`hb75=V&7Wn(0!l7qm*w? z570l7{`2_4L$nDsxWa#?Ja`6wZ&Y{pi2FWobUKs8*)9Y~5>Np=xrLTSrzlGPDnf-# z8%iBYj`^#^!w%^PYii=xgd_q-Pb(KdSgHepH|&)k;q(}Mf-@%13w;KOe8zu(JP1spB zsHBZc4fi=3_(N?y?+rZ-n6LAq2jP?f&a5NNe<*BhslKG~GN7HiOC9zzNGOX& z>HQN;?@a0(CPs51i0NtxEl;0j*t5oqp4n8kmgOV}Ww3V8Y%ACi?WSNgKgF91fx{F7 zDeQLp7c+mkXCjZlCrnkVMzOz~-)Hm}cjx$sHjdH{Tlvl{rflsS3KGbL!jB{8(2v&>5@+L|sHw;tpONsb1V+>KUAv&#)(8i*DTIQe?;yS+7TZ_#J^t>qWUU;7oakak?(S zelj3@ol-))wdI<<>vsU{;bd20LHb0?7T$|Mnqh6LcCWyHTd^FOl^Jd|SNoFni0Rs# zATw^dgiBqo+jBkXvtO%mGPe;aOogn$|0lmCdFIJ0OR+haQ;U;Qi{$CflG;&{9-JBE z)gmHRk8Ip`_{ET*qaE;L)My40s9!TSqxkGXX<_sRK+M?rY)Dq}5^jOL{{|pNm4GpH z|Cg14ng`Q}U`(Olgc1o(PoLx7Irav{Mp5jpj>z^eCl|l@CWYLV+e`_F#lEu92b9V~ zeXL3#OpDM0VO@kX39$mNRs01;t@UfON0;zbZH-*zI(Ix_?~c@*Zmr<~xknXu6GMe3 z3`Y#?fiatug{RdgVt_*||h>fJ)+)m_{8*+j_74*As35nu?KFcq&6Fx~EH?$ef5N zPlQZ255bXQ`F1Zdn#X_=)+FmLRO$LWDg=n0*SpbhKFVdZ7yWtnjC_Quv*7h+QLzm* zgo6Al5Z-TCjX`rMSWCB9*R(_K;c%A;76Ijgm*{V{jK`LibvB3J8vPV(J(lW5Hko># zHYZCz2^D5~99DBUD~K%(RqLpO>b7`=@z#C52yz_9MchsubFXgfBCT=XeQSCD9if(? zvL81)yr!i$2j*^jy47&e;JLE%7uXDewF*^a>LpD6lX`k^3JTXj#zv&dDa_w@pD0#- zL+A|6*gf^b`fu*T5TK2vUnVpwG*nEB8)b;7^Fr?Py`;FX(xdZeeEqcR2s|rTA{Jcl&%qjF!kVGDFYVDj8P_jLIs+$wzW{|Lg-5niDvVzR)}v zhWt!h4tW})0S|!T#!rEB%dClK7!FX}BrBgYn`-wH*7}mHevOozNsE#@a?5?^7tfbZ zopyJ>IxijN7Wv_lDC3n)rtTVS75Gb>8U-BgA6SAlq-7Mo6=ScrWGynk2pTZ2PZm*U z58T?0ZKq!os(OLRNQCZ%K(^Ha<|77{zzFxl9U$x1jqy7(o81^x+mC!_M|Gj9I$~Y# z6}db&Ax#qyU+ufoYXhYExJ||k%8Kjd{5lNKL8>)~JIgb&5SOqs`y2nbpdJ#> z66i>hF`6^k9u4hO8vAb6DVMGB2$rFvcZ&TR7S=G^{E8kOsG`J1#&s&SXa7%De7JR( z+Hpa)yohFOql}z}wb#j>e{1(_JGB_jQ6yVToxDULB zz`sdKY=d{Q(T~(>+hrJ-t9t9(0xTAe1-=~O8=fAr4gH!Q`sD}YKZ`>9qx7pcAUOJE zR^k+RDnaliBHJ7`hk%w1Z*uofS7y@Q5FGqa-kfcIS3DMIdD$Ed{h_?Bv-Q)c5RuPP zRFNlqHgDJTwhCDJc}ojOIC?I>=JMH8VEh;m607N*J!hQg-yhjY=2V0>OO)~*=J@04 z-KRPeRqZ1qS_K8MghJmPjH&Rjk@a=Ds4^@yFHPk)O6IM~x7PFRCDJ;QLAiIA6ea$| zXwMep?a>%@Dq!9YLlMfBCGzogr^5K4bJ5*+Bcqe&l-vfegCc*#8d*UMjK823=xLU3 z4{mRm{)~MCu2g<7-)5M|^oB3V_JJ{~X-}$488_%{aJ_8d2NvZfoyxSZx8Cn`q^9l~ zU04FPQCk?dXtc8yIYNw!b}WJk4vf@}lKgyX84yMCQGn6U#OX5OUcUX%7wXB*uK4w! zrcJwemphRARvF$0@12I_I~QkYW0_u$t-rUq4x8)lpEg8VH)Zno9=!a3mmvRua}v)b zMRaWwhZ9t;qDh@~VIYcVovp}h+FePMH%m=U)^C!P0_9t%l#xq!APX@11VZ-Vk@L<6 zOqF3nFtj;b!b-d4C`4b+^5CClT#nzd0ZoizBzcT!gB)=@=UPAx-b){++YX^D0y2*p zRsyn@5f6(_M~~Jb$u+N-J6&I4k+L5s*{L&oX_ujU^I1Y13ka7DGYY5B$gMr=@; zQ0UdYe`7UEEIg-g2bpXBhq$j7L;{&Fj8hhxk1~xN7&Dt*iBy0`cxbv#KM(jeI?FdO z?n`S4I&9g(Nn61J?b~2a}mJLn9i#?WPlx9#7-D^Zk7(JbWT)zd` zSm7j;qv`LKO3(}OmnPiLQ(A#{L7j0Qut!e3sK@^2V zgB4_*=oY)jbr$b)p(!cx8)gg?v)P8L8%)uxGl;ykdLgGAY#mw#vh-O>Y(vM@N|?u8(nNiw6@w<$J2wNxS1+%rMuGr%16BUV-qcWN0 z%CJ)lz6!ujxJ4Mu$cYTN#!l#{z@3~P3+&!AAh%dU=9$dpB(!QZNGHyqJ z5F|Mt!2@=o$8%I9A!j7^NvZ7!=-nQ;K{@VN?P^+UH9h%}=!``9W}QLDh@?HSdI4Hc zIeGjC123gaU!}%$euXI%rh44qUWh2uo|00gwjlVJ4z}>)Habyb*sjX9lvJ!pOc zy5KDdrcVN1lzh`h?SF2UJ4c4xyu|P`Iq|R0@d1ciQS*L~xTzBGAbV@q0H04xv001_W_U4d$4Arwck!rvbq=hPWrir-1r}EI#OT>jENdQstq>5)6zyOl<$k4 z_GVPkbDftKmdC5<3jMGgM8u54L%ZR9EW_c^cqXT$aYA>%Q_Xxn!&1QBiC`)3R}vxR z*{dk4DQ=SM1yyMHjk!m;tSi^yNqdf(m$&ng!jo#yXBT zYLQNx8c>)P-RDn_lJ;spM^^{mlMJmRu#(;_$ukxkD;Qmq!u58=&C{=}U=|by^TF=6 z@?;`R<3x=6e{icP=Uup42ABW-?ferR-QGo_+X{rjRaw;=YlH{bH|Kj@s2q4i9}bi? zvs*1t{0>#YHnMpHfViKK)6)nNAdPb%t_C*5tLzAW&uZ1vn>aJkN@F zVvTuOq=>C>J31A={!h6@O;n325@maE4Bg^6eMtXT%aOmj!qiv^5U>@;*}o&M;FIYy_{Xi_ty^n`b#aT0|q%=TB?0LDw zRtVHcdT$G4h)r9Mv%GFRB}>c1@u&2wne6*^W0Os33UhC?ur(tj3N~Y;dwG}hnfC!B zHA4F#=tM;aa4$acsG_Z2-~TDLzEC>s>@&zgXal|i_eBas@71`wc*_XR`6aiy4RFsh z-Uy_r4{I2`BCcd99OCrBJ6#?;*^VBYS=mANbC}?OHQHI2-jJ7NQwDdxkle%{0ta6? z_!2~`g_%j3ZioA~Mdwt@#EY_uAf>{-OB`#ikpteZENdynT`<%7vGRh2(WP7V<0{y?%{He+K1-Miakiz)v3~EgOXcoE9Zi|1 zfFFL+Y|vUmB>h^|HT4&URj=YckKXp}c5|yb~_Fiia+@pth?u12Dco^k-sV+@~y;s^T}e z>+uG6mArqdcBt7%m}5kXmh4pOn#h2dKZYC=hl~oiJU2Nwb`)zcF=I;d{of;D%SG4Rv4FG z4od5`UyB4KekQRdmXGPWtqe<%s-5>P=x<~k% z?RLb|{=I31NO=d({frl>*0A+p8EDwMCG(sAI4HTa=fGic zRBcLmei-mfwa;zLY=^X0sWrJ1sH@0WaEnRZC271Bi{xcuqQV_&OVS^-h}@rdaNSci zS>GL85T4zUXtL`4h0Bi~;*7ukHzVq(=KxYj$$zaCj5IeKl;ep~_9 z?iVb;EE;`AGn_VE*dmaVJPF30-lQ}NdI*?Y7k+A~#ekqGIMQ*SDpQcOGos;ps@Q5> z);ck4+r86-5bH#Zf&(rs#WVa~t3`m~a7>MtbY5|+*OB0wPzTPIpGW1eSgOl!7laE+ zmxkkIH4QZiG{GGd$jya@u_X5#OAn%{Q>^=lnLdonNt~kqtO%EcD9-WQfddodv zv(oEDh6m;wmlJh(y#eq0OsQ5M-$!P~!uvPa&_v4--C)2+q?_@{JnY_^|r2mw<~1*RrS{o5xabPgX%BeDdjYNThWGfcYp72;`^r_h9P2RS{}KOF)BhL z;)LNbgWm~hm&)_!SCnrN@!y*A?-k5nGP3dEg?~|;NFQz~9$ul3l@XJ@N^2t)WaEO5&IzLzF9LN0-CTnbRFQsZZU``kL!6JL{9U!eI4215YdC#ILu?YJ z0-B}`EoYlpLW)CrJ~{zwEY8LEw5dseWVw~d z#Vm*3?i@=ly2UuQRgSt{4q8awI~RVB9M!EH=`CC(=?p0mt<C!ygWS(}kYJYaQbTSpDZjrjC`36vE-*SAJ5By36@R#i;9#N2I;*W|HLR3S$~_V* zc8X}YH689`#9$gXF~ezK4n4Ue?6|bY&4lIDVy?J^=!x=+AN->O9dsMsyq=t@&fZ z6MD9h)u>L;>Uy=I4C2~2CpT2bf~TMa!ZmURM`?-Y&;T| zbi1-@G(dYL-(sKN>#sutdGz@FS{S0vFh0uNLj&#Wy8~@)EfM!9Q58{2RXhQH;e7~j zyr7ZjrsjZoGvYfptCs|c&+|OGJaeUZO!%OM#xN`_(+&U*o>Na?{00aoa#I3l1Q@h2@#B>o3KNI??5;808G@!C|Lhdbl5&}&>;(4IM(eV@A8^``HrJ8=C3 z21RZ?U$X5!2<_!yMR&|&OIH3>f%Q8U_V$cnE!=tF0-qg0YWI%Z`BU$^Y@huf@VeY7 z_Xl%Ix++1F_|iYL-3VT%T|4`U)J(4WMsa2@Mm*gg!#m2DnTzUCtXSpqdkw~ON-jGN z5H%@Xe?DpVo;*(!w6zRl?G>5a1sNzKlDInc(mw~mLuQeNU8-L7C-S^nI9 zn^Mc6nT`(a&;rs-?|!g;SkG%}znHvyqCmCgilq4*{0lxOSVbeIvjfxFnpLJ7p{xnEAoY3sV24w)CMDT~-P(mWoaCx7F8IYs>vIdi1527dQc(RppOz@LrYn?!tQ&T&Yz=MLMiVT>8K=QoPMOa;*7WD|!hX zmv<&LpFiDP%Z@MZRpZY^Ie#GtMl*Te|E;`IY(vG@#Ql>)H-eEkzDFXmHdSdxh2laY zDXj}q30Cjd=e-enNgelhCOIuZ0!ong3@0#Vq}Gb&$`~)vdR^GgK4kS9GLRR;IRRJ- zZMgM_#*&Yt`~-E?*7MSw^E9%bV@I7SBm522{*e3Gkj}Tp-Y4c;(TVZq8Xygep18O% z$2YQ*I9IG*ykutj+XyFW^?h5ZN97zmfO^};LGNiQ^jw?@AK4KE%4r`-3~ z-C*b9zkXz1C8Nah&hPmW_&t8v&@7&4-8hpMFHlz}*hsNtZM9%9Dp!DZ0r>rA3!Iq^ zM170~mqaPNh+H;1eG*9b%Ed?RWsJFT#2(4cB%^vV6=W(~RJW+Y~h$U&IK+sv+? zw=32G`+C7M!{P>O5hkEK3dCkBBIKZr9%dok_x&)@R%>`MW__Fp@EEHzepb?w{Nw@M z*Ed$8D_fs=lhyyB0reKck=)G4xn3U6giAcmLmE;Yr@s-_XQhHw;@MXorR{G$-jMG@q;W-unGJp*kUH_d7X!0ciObil=GRf>-29PuK(Qu|aNL1>M+Wc8xNmyvY4v-jVIp^h&+|_`!d(PHFMNPzK$~H=63+Na-$-u&^>P*#rN%L7DYko4JsM);-}4 zm&_MF)#A?P@Q}%ggQNucow6oLdUyr9#-G$LS(E!ZGTY51X@V|HtI^xur9d0ZcIY1L z2C#z!A-grT!B%UQ7D3BLFciXzjdr)C-hb+ab|ZUfDSFuO&l~%jOAReC44iWF%oU7CPY>AfZ*(wj&pKva6~y#%D!NH2jP z1QI$V0YV_<<$k{JJV&3eoHPGq|7K^hXRoZ8HT$}*HT&wr@7xbR{uS#3Zx#4MvWRy;M z+E4isa;MEX<~jKC+{UL$JNMnKzo(}#(u{n|bTV$S&Ur5vyttzjb##>mAvuyNR$3;{ z_Y|KVe_O@Iswm}tzZ#pT)y4PeuVbsrQ*wwws%NmSRZe}!gDc!gew>Q4b6KMw8GOW+@xRPadSunVul_ti zxdmXbzC#!7fG=FHq@4(GpB2k5$W^9n0%XtVZpF#P1#jNoPRBydkMOMMs;$RyGRBvU z*xt2#8lbrnB*GEUaI#uo7FXgey-S4HXVFE7{xbaRxE__s^i+n^__Vub$>bCJyjEdG zVdj^S_z>f9e^QHZ|S>jCx)7pMv5is=&a-Sb`?+#0_(UQEguo962)$W4(#L&@g<-SF(_-tF0|=7&bd44(e?vi`a3zstoC?uIr&4TBF+|E@Ya zP<>pvMtN@F_h)5gb=JbZXHJRyKaTP5a?f|}Me|zO@697rD=U+Mf7C>%{+d7){86QQ zxj+)Ic%S3`f8D^pK5zcgasr;&@XI{=R8Mn!&kf0N@-dwxwci+H#EbS+jPWj)rp`-3HG{M!~1^F zYCE)mvMKnhX#lkHRo=*VdPPC)Hk+Qw1fzdMy-em|-}#+h!^KZF-TVzey^msOjq&EOb#ULokk zflzCv?a(^J39l}Mjj_Yq5)MzR?}$fjdfl{}K2?5mu-nIEwQIeOj8^pu@CZb_U#S3v z;+OWGeeCKPqmrAell%BaQ`YU!gM**~GiX9Ll5bADBp@iE z&RVRcI$&IS@;SD*ELVRuR{O(eS{7-Wzf!{mR_1)5Z@t27XWj)2>qjf{(0Dk1idKLC zepCiPt??K}%3loXU9!~19;DNh-~CY^=Z2ezK?<;ViSgK22e>*4u_0J{v#jvHENkbW2*YIRFjs!b zW^|)s*O)VYA9oEOkzXFOy$oNrtB<5}{yFbkiUyJnd+=RT8 z8&$gVIjO$-;pM!$T$LhyS}PnrQ36;DV#A%Q8BF&Wpg*m}esZ9Yh*nmw|;2Wt}17&=kTUGFE(fA1~ z=dmYijd!`l#y2LS%Ycf!n>q6eACr$ao1Rc(#;GDXlLf9{CE!Fgbe8UOsyD$RwZRf* zw)nN*#w9N-)paW^{@4F~lZ7Xg?u%KrD^ z7c9I`Baw}BHB@Fv#1_w*!eIof2mo4*7FYP~C5Er3{0gdT=&ZVVMi#5Ro^-nEH$n8E8ER9#dCpl%;cU zzdWSWteVkahB|Ym{ZSlD|5${RQmyCIeaWf1UsbldGiR)O8v0?EzU^sC{nYIRpPO(k zg^Dq)o%0osce4~H=|VDjXw+o?Qa-d{cH5yfU3cqYTku(IDOIRrbSyYJ6c*cE|HB0yd8G_Hd;JaZ(=jA^+Dz>o(H14m=vYYn)7ixj&muo zg5UWhHnUY)WW&=)AMh|(twduI+g?+cbPL-|l{noV{F%P$H3@KS4&KVCas7KL%ead? zSZh&vT7%p&fM^L$rgf5zxqVYk;(JCy?~yf|OlC!M^F+OScga0pZ}Nf{jWnrb?!+pN zK#ci1*M(#`^^_}~U3kYOqx$;ILy39w(R0R#xH6$@xBfd?$pl=2p$cBb9w}rXI|fi| zTm286D)Q2hPFFCKl_3E$oJZD7cy8v?`khWSp5p0Pp6}fyw3@w0+wwAqXe-cU!r{IJMl(;L!VZ=c3h(akLH-@x4X*uw137M+bzwcQH++p zxQMU^J!-h-@p5Zt?zjL@pi;y4Bc* z;z|b-c-F+IrvN&)sp~5TyCrv&CPAs9Y5nah z3+$S(?lo#2zT&hI?HY_>UyyuqmpyO8VP>uX`9l?C`-gSO({N5fZO0p7V@JEjjdun$ zu?M!k*d2iC=q1;LvrJaAMjTK5>b&Z0@lR$L$vdBD!>;9fSxc#)h^Y(|nI=p+p3|uB zs<{sH)1iR9X=bEkb&R%02 z^*13p4bC1hu2Q6`&jihb(CW?;p7a*z{%-Oda-{l%NdDZFlFT;XJ(J^3l2u}Joke`2OP%aS z$^LNBVg9R0&*3P;C=j|U#ME=&NxP@2n z1>XrQ>LVGFuDiA{EmP$0Yvkvb*2Mr>j)eVJVeyM0v^0@jyqE!6rwz)wUZ5LEJj%>& zV-8cU5FoSuXG^iujs!DDTe_U{KwZuYKv-X?R?*XFP+R8~#aUmn zg=~X^{)%=(-9PFM^OV`=2I9x8*nL6-^ZAlVi!H0s1!i5AEB_rD7!qo-1zml1u>*5w ziJRs%5a|>7Ab!oLxrT%Fm=E*zk4lFBkDb-$E}E7 z9W!^Sssl7tqvM!o`!ZMeUwm6X^$o^q(m8xkS8q|guenRr9L47}I!&#QS12&#WrM`j zK{6kP%)-rlJadYByatj}wDM`Ut0W>sYVP_H&y_rgwK=BpQ1u8O+piwIm(&yXeU1o& zB|q`cpxs8l%u$vJQt6C7&T8?g0x&y93fk$9z?fEa<&&G%QxIt*w|JVFq_i^!Cwmfo z4>DwvX0oe)`xg!SyipwO9bX6&G#X}snV)YpxY|-YUM$uKl8@Q-p@0M?7D)%Xz^H@< z@w?dWNIr@69v)=)xOjI@TqH6bRJa-=!lq5=w6=vddduT zGQ45z=dvZN07(G4Aeb^~6;I-*wB+iX{lXYRSQ-5+Lmt&mUpm;HD*PGt>K1=*Q1_rG zTOD5tfds6=__P}YA(YbLzQ|m#ShO?fdC(S9N0YAV@k_2z#wYX#za92DyHSgXROX90~ z_35@yoPd8KL(Z*4zm?-0oVnG(sgtjlq18z%g`>?(bLFkWIrwmq!Dcdh7f| zwHIDN8Wh?4{Tkv?UGQv_;h;qvduU~`h;HPk%s0mF!!etA}_=SN@8jKgG4@` zgqW?Bka^~yQr8WXu2o6oT)9*o6lsg&m6vE`v0BlM;H`$SjrdsZF0J9FGW)3_O%XtuOoO*?Q9(b^LR3tu z$yK~9`$=0#67bNrst;ZL9!pyA?5PRFkf_J`dR|qS-Rq;64VK#OTD)8mDOJM@be_#; zTw2~B@@1(*-^_TZ(Ga=RwOFY|jo`sB!37OrJ8kQlCvJEZ?87OG{X1Q~VxS&QQI4s? zS0g>-Jc`w()Y(&5tehP067FRdJ8_rAdB>NgqV<&OJw>aNLobU}BB!cg=iMTu-Lexh zM{eqv4NCLt+FK31GBlgK&5g}0p4DmCKTV~bO9A8Q%6FE;mV1hb)t+qj7ImtQQ&A|v zEr#T#Sf&ZZUvon=SS*pp+PAZ2fC$Jk`~u}1PuJYjFhi3Jz7QKIT^2vx730`x+r#D&? zz%_qX$ifrPdq2f=c>Lqt-_6PGK0OeCvMmB2A2u632C2`IULSR+_v%<`E^KL-DKr_34MQ&fSOr81T7(?7x3^5?v<4TGH~ zKbNx=*_^)^1uK5ptZmXY_;jt=6Lqfmbc6geZrTSkKU@{#Ut2=6W*sEodG9+O8MuGA zB@Z?^b`|=t>?LdloR)Y`gllFE&f{5!h=bJTlg);%C`wdm7of1LD**B8=L62~)}d-1wW?yZFid9O|I3 z!*@gj##tm^U{Z9_2&mG*%@DyfHg(f}EccC!5?dkWqTHJ8Tg=-)hN1rn&E?;_6Y|Lx zsm@Z}Grj^*u!m0$49);-y_Eefek1D-hR<7lzJeuQX*_vwpSI(~##_+_b=*-1LBMD( z@Q?#9RFcyyMadtAC?9T|*?eM+Y5P#-=R-jBtKbvLTjsZiI%~$FF4(@w!0HRrG=1sh z<<;o|@R#xnULLN~Z1RL{NS^uAZSODD_7ZYmqJ>Ob==Sa{UV2+_LSS}x?y`&9LG+&l z8QoxgekglId@G1Y&>xSC62XfeV4mkTx5+5(NnmE6KTh}XcRQC?)`PRQ=Q*B~J;-W2 zX^JD}pi34!7EeoI`$xpTPhLNuGxa~guLE1h`sl%s(RcMi#!r%U4C2FX!dqFcywakh z)TNlJXi+b}o7v6DOUhbJ{S#BZ1^?`BL?D(ekOL7e--67o$hJX`plnZR-pF@q5m*d0 zVuV-B>)#x($fSAjm~0b>3}K6>f-Uio!T%G%F7J6&G!@n!)Y7u*p6fc#wout|>r z{K5k6T-+s2d-`1p2%-}ogjwo-B?D$J8Ip7fDZ`#;OtrRt$BC;y4!7#$Lc5bfaKUX$ zt1B-KM;OgrXal2`YaIz*- z@Id)od5)SR!VviF5>Ko!ckr{FSA$RGE9MAVXI#avmjOxDxhD@4AIouxDS&8? zPFS`vG;(WaX+VBz&%d9TR22oP+lYcb0)t@qlV1;A>k8yPyCnL@TpyB32r#&ycXR88 zwZMbCZhn_&8N}E}^{rc9l>bW$P@&O*T7bnvh%fxV&7e!cy;AC7nDw5lrtRwDVRC6M z>0J#bNtmadIew(&<0lVfM5JqCRRAM@dvuS93ZUb9 z+nb3>Exm0O@0#VlB8~J*i@RK^GbtkM@B=pU*ubzWv~(WLLv=cNUI6C+-#d%K&QD__ z*k9L|+AJs06V^%Qb3U#6YR^k+eAq27rHq339Qb;olOyZmg(rorA8jbGP0J0|AyOVA>vn_<^3vRw_s}9MG z(H;LnSLw0yG++LR8hY&dETHCaq|hXFI@K#Ls3Fc|RyN^{L@}d>mfnw8$2d-z;cQ4B zcKx&c_MpK|={A=D(u*XXYK9}&=L}vlaNFvlYCKrU?>4Bo*e9ks*Ah}zGE=p=r4}e| z#V=#liT z?pK1%H{a#Cza?G0rIFr|t2U&@Hy)^cuQKE7q-=eNYEux3igIGeau zF~mMN5hD+*AwipvBQp)v4)Hb@=L5&VFr92nd3(BM1+;H#;&5OaqZmk*kO3MY1-4*< zlt3p*pbKtEiL$*$9AQL^Hgs+hzA+;!RCdN3{nE?m6Feb}A5tr#-%;eGJfML*Pa1Eya+0>Gn3ir zb7Cuahb^8lYc_%|ge%XqLQ>v`08OjvIsJ=`;m~gGQ9^&v>1-2_ru?Tvx0GVM(6iAT zD;SP|zfVE+Q3;s@+^V)KOPqGf7~kNMNUOCs?~EIA6Uqwcw(#Jvn8TN7X=*4a02)>2 z8Z((_wdLQQW`@-|yjk4xBxE3nj&&{WJ5J8-<8)tY0iV)7*?6*%*|UUPMj{k>j>on} zL}-U*#?n9wV_@1Yu{o%X;OSGwreFCCwQX~;Tm4$(`AjVmZGZ>NcA0(maS}_5>4&U& zDl>}(xu8N0Y8e%}FP;x$Hb;b3=9!y+BBP`l_nLi-0ye={8N>s8<*gvjDokMT_8A@Z zf;Lb2bcp5c&{pA~_alTOFl@rITd7w8@#S*0+F8DZAiTQjxo)2FBF@eLeWQkJ-)Uyi zF^G19{MZW6{_!!DEBcGy!^k8KPz~fU-%RQA#j`m>TaRYzlxE0R4=_?NV*;En3L*`~ z1mIsdga?ZuAJf!x{fH=k600m&G}d^(j7MK&ZPGF(nXvaDV2@f~sCN0WrRw%%go83G zJk@E{wS8ICXEFE!?X&!eE&Bj`aqDoE#P(>ckEvSbh^AKW-7nspAJ+|6;D_&Cw(Oc9 z_Lz3r9+SJpI!5wm7LF}RzGx%DKdjUyX8HUqV&uT3o;uYXsW5ZH)(0t@(z_fK(0?`Z zn@ytk0kHHsv+058vy)ici6Z(B(*-lPDD<4i2luJ#N}@(wk+KT6+ZI$R_bhE}1W0Z)dFKAmfp+%Y2TES#m`YAJ^l;v56C@=?lOUX26&sR$C*GGXed+1{07@u{p7wAbmr(f?bRiAR+*= zKZ0{4C3Wt^H3D;r6_Bi?(EkXhs5L-q84fy~mImki1 zVj35S)MAd54w^zo#%jlW49GfPg}HKj%5Et~hAz|5tUc~Eq~RZi^pmf{Y-ihh`qS#D zfQ0BE_|dOi2EDCbhF7oWM|yQeO^gB7z71o zO38RApQ~3Hsdd-${ky(oA}v5j{)``6t;UAJn{c76R;B)T+R&Ix)C<$j)fN>|a*JTD z-1RdYbyR`T%;qJWERR{?)?Xx+84%2Gt!?&@ig zq9u+Pqolx-XvU+5E8rgY;Xd{Lwj!5vGU|xcBep&qx)VuIO#5`hXwG{xd(-+AsMMwy zc=FjS9$PbZN4d@Ge%-UzM&utM@&s(fHta&Bj?@0>Fblk{L#FKilT*|^8IXTbF>pkO z8XSUGe3F)GANmznQKiT$jGB#hUW=sX%HO(Ak6S935&4yHpIsu$ED?DI&t?&@*Sn8) zH7Tftea;4N|71YT`E6Z$z^BxFfYPauk67)JfjsuP=x(*Di=B>h7Li)2j-Jxx8L(3zd((TI&rwy9MdXjDY$QN}%dY_lzIm{ah12tG|8C0SRi9P%dlI)oz z_C=EihyEF5*&KT$G;PUzj?@Jw#SJIXpKPohTgTSa02+32b%%$2 zTjaSe^3T77QE+{jtp+;2=*X_Vbr=sQ0*u;@V4Q0K4YVAaG1h0B@R&z6RVoPbT+d`n zt@;ryTztW-3}V>CXy*B`8bzs}r(Ba?O=n`u^K$%(v0V`o_ zmI6{dtPWIozc-CXr%clb_nL!tXJ$VH8u+|voUm6KKg9tEJRTmMkR;e`-6ijQW((R9 z4aW(s1CTX4rM;MM8#44M(s*>gGk+Bs+po%f&DGk*wRD!TQ6?iha_G9UuC53eVuQTG zzKbkk*OHst{!i8wz<7uVXl%>?Q$gZ>VGL5Tn?E74+Jo)!ZM{D{BQ_DKvf=}Vtj0VZq8W>5RNA5WTDL`=rrP`P!=Y8;twi%A!g`m1#$YHb)@AlNJ`VnMw->{M!;XtE#W zW=kC~N4SUxv%&J9izRgGCBxU0p;oeC*};juy+23nx~ILoqz|=vexUYi`!3Z=G<5Drv1I?si$}r$ zxn^Hh4{~#43%DWA1AW;>qoKX;N+Cw*!xngNW5jwW>hN6?;}z|~=S);z1R#`8UAcRn6at14clJ`!^ z0LQJ_8wNeFic&L|19V_xKM@DUmO^@JyvZ)rt%JXCMU-*2%ed-JDA zJN>cjmJ-vP&QK#ykSva_jU6&-;HQnT+w^fz3tabpK+oFSZQav`s6j5Kr?Y!K(|C7p zS@Pk@SFMnU!GzgsuD0)7C!KbQoe$&=FZV6nVB&mopQ^Ht!5mI~bdh@06xJcu_VZtw z0$+*HA|+&t88Vh~bVsrDcs|8yR%@nfVPrU~J^Stmc;XvKsyI+4QCCX(&EazO18)oJHiyS7@?K{#R+nog)+gV1QA;&*({)vGY8Ee*dNz-4VrV_x`ALVm24 z3B{xxc{ctGKJB->MMgb?)8-PM$uv}8ji84-<}+d>4y^=&9!sgzNsS_NHi-HSh5lB9 zdE%Pht(~6ujqAsRFe!}+A3{72MF4&|?NLLbAeZ9cepP_$@*TJ1dy0PF1W8QOtym`G(I`K|;uq=+mDrKlKha;lWxy@-GUE!z;ZP8096gG)I0iGu5qR z8ZQ#&W8Ov``*|LqP#nJ%=U3 z3+DBPi6iqw8Tbjm@VN1p6%>4}sPV*{x-^q=oH|EdTEYC_+8N9Jo6Y>f4lc{6lLHFr zs}MElJjK<-n)eEO;C4DPU>9uyJh@I1SZe6T4tr_WNie1SR-)9hsZhS2G<%j5WKGfR z?Jap6O>}bCNg0S>p)di7I^Z=cmGbWd9X82N^AFdQll)(qS^qR6rXa4$EIpPXpCnM> zBk$JaE(oCEVom`*;)%{_y^9Lr9tQDEG1*}Kr>eG!2(PysTX<=EorZrDEEc;Jq22%| z3A?!}AxXR&`Hgq}sUJ9&H$oa;QqGa;#vvc6%y;zr1*$0V0*>Lh+5U8X`DgdjpyG{e8$fnN5CK z(Tn?zIm2h^kv{NrS)Mbr!M%BYQq%KoV~tFuT+zCe@{8y`ELIR3=9qPK%cWw-l5}L* ze)pGr2f0niF6r;Z?w7|~hMk~>nQuVyfh<3oV@W#L|9Z4c`|aJFKIz@C{kW>ak7a++5mUsthMsQ~u6t+2O^9;)*Jvv`;1{?hG9BfjYF zbmrj=OPqU8ywrjI!Wwu+7(H#7rKl|k#Ivp;qk{p1`H1qvt4bG=aj zG6A9ED5}s*FH#c(V1CL9vM22Ak>|AKvt3SQA&Fe;BN7IcWdXpp&z{f&H$*AKu$EI#f2Tw|SaC^cc;;~U2T=hkYs95- z=43GXt>92JBv>CnyU*R09VeWfVvt_X%s(AKi}4`|`??QphM>1hL!V&<+v*e9AiNN~ zQ7IN-Gx~?L=taQ%R(c%FXh?f$x5qj@=k%+P5|h7CKVjx)h1KPE0yc=&Nii3@j96a7 zRcD(GVH(%Dt)E+Q&boD97oPoi`uIa;t*3nZPMusN*8}q3Q7t#iXw09%-&6n0xs?l| zuu$NyDu<3XiM);D;{%?-3iZ??oZ|b54a)U;6^$zx0bVK|(IheOXN(d!S4^ zv+A)0*9IHz@V1~d-u~FqF>G#08?f1ZkU|bTmnxVsDn$%Qdy4r~-yD@ag3ZHEV*aHy zn%w`|=dp|EA)8d*um5T!;c-Q%hA0pGpqHpDMhuq8ZR)b~HL|_g%KnyUv=sFacVbmH zzFE+-F|s&34~Sc-*UM3d9x3^{2EP1fWn!lEXl>2*NLit&Hk89>T2@~GNAkPP882)t zf@l&|)%FM`u{&fI@dzSM^rw;b3}+x`^b~-ol@Hfi=xABjfl(lQWuuU&N%Q1+&NGar z;H|t}ygsf8bo7N6#}$9VPw72d=L+xm)W&SSzA;$vJxunSYI;qVt6k(QCyAz>fyzo6mCicmou8 z_P!m4HhPl>S2UY$xG^*+_}o9_)=vE}qVFy%H~`z%HzBQidD^j??!)e)%$ef4YSOo9*H5=qP>i6PYEq!_Ih2>dYVNklsT8UhbwO+ zbDIrZEZoStmE_{dBRknP#r;BsH)YpOY+cX*&LacFKQ4^7X?=W3_^z8W1N(c+r7Vt@ zOMTvorFSoMe5+szY4FYWMHYQpj5(lMJ0^tpW7~ZWbC~RNDk)4CQ zs4-WjT)MlSTcK!! zvp}1HvJN_OB(vBZPMjWmEI>x5WBEdkEbY%g6v`Gz@fOTho()8cm1v{;b)fJ`Fe}pF zJ5mhtc$vKN8u{*2C0^A3#dx~;?)-q1%kXmjC~4yeBsFocHA5)L4Uo@V_MMr26a#Ej z*o)s$tMIXLAJdVWO}+J`j9Mb{s#{|Fs*|z;^y6!&kBwyZo#lD?bl%-Um@yaKYAaj? zx9p_tA+YvXCGM%=)a_!Wvv*K7iybTmnJpgiA>mc6cn@aI_FTDmL9^j35M`u&)$wvP zcfJ;f!~8?CC>jZR>_y}&r)aZ{7A-#rAQWgAy{t`YRRsJ}Jf;$B5BNYgBe@dha?7n*SgS&F+>H@dC4-X`k_|eS#S}ysk0il?pdbFq6 z#l-N;ab*2_A3A>IBhmAJq1rP8GW4XL>_wh&*7`NFZ7OJJ?>Zj7zggLP;75`3Z_DWJ zoV-!Yt9ySqMe2?mF33P~7PsUWAk1IS$Lx+PsJWe%{^CVg*81$=r};YpLo-Bl)g1d# z7ju_JtgwE(&+a{xc3R(0_43>!O&5_85MQ`XwX3c|cv>JP$vUXUUH(v-x@022QDSfL zKza(mrU}IbxWa4~o8(R(7KM)wxao3NzYu5WbvJYH6NBuDQt0&2+RryDD-rov}&Zcg>28YFUKy6VrH0Rh;3|tbk+7 zac;=a)aD`M#MUe8*>?FTz~5-Newi)Gwud-);Gd(0n6}ma*ODQ~9?BUj{9tHk^T^T* zWGxA51vK^GSm^tfF5D%gnZXDA%z}*(Z`>{wTJWM4rfWAR^V1;HnZ|OhlREFnkJHn^ zCej&Zu&)Tc7toWMS)|9D1Oe#WykgXT45YG8UMVyX{(=MvTThGO9~bW3p7!qPW$5lnIKzYP&+g{EH53MlVx2?zP-3t)YDL>_rOJ^`7+lx``&6V4nS~FG(3GP%1`J+;^JAFE!l#(F>ZedZeE?!s2ynr;d14&LF~)< zS^N<7zTXldU%+=XDR`!gd0M}A3;%eWG|YacLM|wM3u6cwlqj~;p8HX4Pdf(`l}yAm zlCxoGq-~97kK~tX{#RvM@>9>^t9=M2ib3nQoVW3u@5M$xpJsPkc@Z*D@9^k&SDpAi z!ZEmR8+NteMJ+f9z$`+-$Te0i$(0JeG}JoM2ucFCDD($F1W|kUcwf~yxNBMW&o(6_ zFKJm}C+jkS-gRIeoU&N%o`(j-k9MGZaMHmr^^M;3@dio{)@b5PTL)Wld1Czp*jx{S zePS-a4vjnIhE8!;>G5YYl&a{WB=t2;KiCR$^$+2K8YN5Z;XbO4#Me2c9zIu2LE@o z(FMfrB^h4xmtlt^A2E~iTNB_K>sv6-ovun6!0PEGu=Hn(8+u|XX%9nUocPlLZi>cj zB<`#!f=p`*tUizm1~)aD_&NR0h&1=qQlPVt6=F zaJ032Y+2q~>LfgkHz1q=TiRI*D}_sk zkK8~#PQfGt4L>LRU}shs7@li*X@xYT_VN#j9el?idaW^ z2lLz0aSDuzP<`uq?zY)pAnWA%>A9S(f~-cz8MX242EX_7yg`0FL6kNJNRsg^KH=~ew#ntv!47D&D8c`K$7d<9CgQ5~PULF%3_%>6D4 zpP#v6YYehB@((fnkTNsZi##d9eyRTJ>!Bve?-JA3!=2I&Va7D=_Q2t@VuAo9RcmgAB_dPBhuR^7F8 zuuwPNd&cxRy7D8a;vwx3H}`bOF)})V%nThie9IG~iT zaT+b|LQTh$nIZUQqByIo25I`pv4XW5589V(yARMY&Gof4K9yZ|+^P^zcd4ZPiIs)> zngDkAgdaUSKMyDbRD8Wq+n%Mz*K>n~K`qP1%Z**3f10BC3y1D~?4hSTcBcJr&Edb>&`hTiy9sOtjLnV7rvMXm%d*}0?n%B2AS? ze=2SpU(Eg~h-J9K$>|7WZN~gZ_vGWtiIcG|fBxvtIV8`-cD}9kj z-P_8#7X*dcK9zG6yZ(Z;u}?@{8Fi>X9=#Um_>iiibP&ZwUWwQYiC8KO(qmWlG=1aU zlBR`jo@Yo4uT^K3tt7HC{;xTL?J#h{9Pi)TuDQ zm^{`Bz!Nk6`nAT0u<@W3R(+eZod*H|>b7)W{d-=lv&Z6*a)g^lG`=h%gjB?%RH3*(R+I!S;vhK>-!DFMnp_$_2-=(%H+OuVEhi9aWLw2vR z0;y6>O;TNHPcu90;#VFe8@OF)2vQp$zJl=h14e1gp`*wK3Ets725K6WtrlM=l%cZ1 zyu>*az3nNn$unb5ZSGZofI4fu)TEZUX zdPgi9vF5x(bY72FNaN1H`7bQ|$GaW89UF z6Q0myi?e-e)((vhYu^1I#@;iasc2i&wKo)01VoyOfKsJ*Vg-~Ek=|8$?>!_c(xgOs zCrS~ip?8AxPUu|%1PBmX2rVJy#=YM@_nv+3J?H)5$I1$sYt7N-nBN?O7tgmqgwcr7 zEw$G_i6%Gl6<^CoV{YB_{{w# z!j%26&GNg!DAzI!K6DM{dqcmb;d5bXWwx3Li*w_;wiL!60-8u1*zENVntk=R$UuFs zLh$ih#HSk&C7J`zxotHCOSbe2)FTU~^w5A=3g6vx&L^?4`AYgP?4fTp&p07&T*v)V zyiok{7ht|C8)wQN|HJ{xtbJ0va3)L10lf66s%!5%k@a!!kLKQ^yU4gnU*`F9#kMsF zMK#&fp(3l>%G>@3upd2*DW&jD4nL4`+28X0H@s3vt(#i$x2DalowHp4{n&3;EU zg;{Q-P~z$N^==lXmv5fFZ25fcATR8S)UAfk-|vQ#5F@Z~UhIB9}kypL*nT za>9N2)!lDtO|yMGe)Dj+`OLhPw{@nCwT<&pq}E)Y$P2R(SOklmh*qpBg!$Q}d#^cJ zQNa%p55U2@>^Gs$YLg_XTpm(SJfxpVN=#D(FRNQUL|dE*P;kR=927Lk2J-A8n;;c6TobP-)tbD#KUz*>wlNCtdBtM z^-M!t>|{QQ?#w^WuGhUJ!1WQz6SO=UI(;yE9}x)QWdmB*W|gpi2P3|}g%x1127V(D zNJ3^H#??$)aXxL3)~19^K@h6DJg8(j-4&+S=!T1KHq>Ydmpd;FWVsykFSo;#T3W8* zQ;z3M4)f&StY{7!gT<}V<^~sH&ek6M^w;4xzaX4@9YVYvTC?+Ewv|=g*fY7YX;3Gh zO{943mF1sHpUDz$HMed0T3JDac_6#$uy8Xxlad|rj9hpKEPYe$XU@qk`)yEq{9eCE z&~ebLq4{grKrA(Pg36T;XaZ!6?;`>yv+b}Ep z`F=&D(i7xt>Kmc4w0)1RsiqG%P>3TTEEKcT-AmS}qCQN#==#`92dm;jaZ^By&FBZ` zCU;Gal1`d;t_e2-GMWtsPRQhN$`aTa@}AKTCJ3#&c{Z_lxr08X2wcgH9Ml{-U^*L} z*ky8X`llnCh6i3#$stgB^k}xkmrr0|-neCqk2@@5?`{pCBC|-QAF;v2pnl+cW7KKlFr^xjxJ; z?WBl-l^W3QGsB8xjRg6bzBQu$7DM#F(VQ+|1F!oWJGzK7LV;*)`$YHr^%7*WID(W9 z^ECSW$9~;-s``diRqd`dl35R#IT*>B7VcF}jM{YB4l_T%-q5v2$DmhykR;Y`gblCT zNnGyc*&}Ak$WYy0cs*q``ta>Kz@GNGe?&i0jYu+aYob%Z;AJlcOn@#w29YPa4`Y1= z>u?Y8HVnxCwsiRZ^6ckZt{59{!lUD-wWrK7RK#$zna9begyP0L%G$Z)Uq~pO3(?Oh zFu!oQy68v^(3Di{&~Kp8@}jEvW!R(eY_=meC7{xHEPdQsJAY&k{7%%Y@*-sQYS$5a z+cw9u+?fMAK&6sX{rqq09};(`_62CqNI`` zIp>*1>V$x~tx$@CH3#?l zG$V6*n({Z#R>$Mp*%d<{J&Y_hin?6*CwUb-n;h8jA-2v$D78|Ro9B?-M&#TLqo&Il zu#=B^LeFoH*j!K%Yca)T8By)Yqt8}Ob3I;?&aBd_GV4<4}@ zZKp;s8}!{Y8T{fc5#lj@u@(R`2;ZdA!yq7md#}=xeUCf@b>@%HDUzp6(6n-)B>MY; zcMc<7r2{;^O2BF9^vbL*HKDbk#lVomj9!Y`cQ_>V()!*_Mg-e4@?Az&H$K_=otsa! zs%qW3BPus0KG)O(da{D*I5dl!^AEWW_GCCk3J$WxsSn$ej7|zlnefN;FFr1=H2-dH zc3BxQm1gwTX3Hu{+k?QppNJbtRDI~38eH{yRWF^zE(9fy-I>^~9BzE6I5U5nx z2dk(O-l~7`u9~mhjZodk;vRh@O&dG(0(YL6o4P=6s^kbG@@Cqyh5>f_>SLP$1$d*L z);hqS*gSLmD-*c?Sbw|Ql)>KeK?aZ1OvFO>1nuUt0l<>}sVJDNOaNO3+(eqIbXDga#hfD!hs;y(+|lud zHO1T9>!71P@i-JOlw3+e4D9B91nPHkz@GTPIY9CY@0mO6o!5Chur_mSvYB*A?x@i_ z^NC%n>PsyXO@8}7@=2o3<}DFv!YgwGW;2)}JHUK=?-wVmXTpsE*Iio#@H--e>7tH$ zDk98J?f75KBwRkKI^;p`x_}5vUH!&x-*PrP?#8)1)Jkw<_v%~C^Ct{cUBD4-Xv&cA zd({oOw{Zet%((FGo@KW_NvzD`6TE^evm;E?rCfOMg25$c`N$(MC{>Rm^PMe{&{+Q9 zd`)`<G5(G$T9bXIbp#Zn6JaF99o8 zcPw}?H%PYjOp6(>t>CY2Kx#Tlg zw@H0%-+Z7=W0e7cH?3K|RCl9MF_0xZg%`wMvlM+ak0wxcCm;wv zGqfvJpPehC$Ay3MvT-tD%JwG(^vyCYTuf39f4qOhI#$jFZ>&jlI-<7w4gB>aF>h@x)8kz#j3BrkfqUI{+x+4vdV^F=ABEw(v1*boCEI6oflpsF@Ab3Cf zGuXHa04k5iBb&*Oev)I;9-gj@C}UT;g$aqWS8TKu^Sm^0R`MpqFG*`>S@6N>Db)tw zt&{aCwae+ia#JNKF!>fQ*yl_`ouIV0-R97R1bliSwe=*AL5M5hBk$=uZuqXf4Gc|& zFTdmS+WF9_C>9lzVtxPOwOr%eqA?44eqbr|ve3b$2Jhup@u#Y3&9Y^lfihcvvAf9o zeHNEuRAOqoBzF4eU1wH6gq^@o(V`|Fy(pa`)nC(^du4GZl+v(7>7Y$1F_FoNsP-sxJVCmvH06x#a9#KyW&I_Zj}!CrdQ`Guwl5** zS`wG+51t*Xd2OyTUe+^mM?Wmq#+f!$m2|Lxf)!jPD3{YbiFF9kp@^8%0tf8Fie{28 zm|d&OcaW(o{_sP&D=}VrHjM1RaS^Ww(}`(YDRc9k=8v{YeK`7qZtF8%uRJ(4u;Fc+ zJs)M#d@BBo=7DtR@d$B|GPYaID315))SQ0#;gIqAh^Dh;Pi)gI10jDR^f}pFaz3Na zg}-u?TIx9cG`51JScJo@hwnLGxxm1SI?l7}dP0SiKO-m|)(JD^$z}=(E`bs+1&^&3 zb{^S`6EcP6x>%rfndeJq%S?q;FO)gtiES*VuvZx7gQ#!nm1SapSFtVyU2Fh=PPQB; zD~E`f`M^>EHpVez;)meoFKRKpT%_6&m|Vo}3{Mw@}8NKW%PPemS_ z!85d|3&D!ANg-4W6MCy~y1z4E(T)NBnPTHcqjfF;&c7I68H6#U^kBlOUw*gaRsZz# zT(axNFjMAF-%Pl)MnetXkRy7(s7FwCDREZbw96=>x<;?HD0dgRxza8tx!%37FcFyJ zFn+1XEch;?X5dJN=!MDVDthU8_UP%%?)thy_y%NMKCv7$nLXw_^SOEpWcXNwDPSK! zYC_*1Fy3D}VB)opgmr#~dAn2Y5cF4kPu3aJUyc6a(h7e=mo6}xdbkxRn$kD4H{owU znfjFbmWSV9lU>%6-#kl70a3K*$qoo=fzExjJ31nvGF*1MUID*`s?$49KTl;2cCmcf zoBD*%RyrY9*(`LkLMT;NoXWfYb<)Ajc)EU4IWN&GUmtbFW}NGwa10XPXK`2r%H>9s z3=j^5ws9+od$ShD9u(%xt*Pjrf%1$}R=mUBzfEFRIkFzlq6xGfq3I`jd|iDOvj=p| zWa-GoYqPFuNp}+mH2PCXM%a;D7a_sw+j@b`N?7d};VqZ*r4w0(Y47?E&ruA^pRSLF z3?9Kg6PuTg*Fs3%iid5@v_9@J63)Zln2X6NffCbBG|NVtVbOYusjPWD1%yl{YNf;d zXMDH5Ecpd`2C_^b(Mi;8bXkay-Q*zjCH?>fw^FC*D9rC3>(b2FKZU04{3N&E?O3k# zH3l9L^SV{y@DL%7t%uZjZV+i|LOnl#QFK69l88SVR?psq@;v6GyN9}h^o65E zunCa&{N8LZt6$_b70{kD3qRqO$>G(wx~YuuDkd~u@*<;F2bZ`M{f^AS;dz-nLw>FN zudHG~kK>Pw=5nz@iuYn7?wmU&YVl$`E-H)FQ-l_EiYzb8+G(;2E&OrflLbpK7NN;x5Wk@C2{q>9`(4|GlUmIJ?c}mXe-Z3YUfWAJx$jn-i=iw^3qa`1 zasLN3&Bd$>PnE37VGQu&3yGKbb)|xMVm~!+y#9{rVZSG$3t4?QMh_=UDP@Lz z8wrPAv5+4eex70*1^Q+1QU!7T>Xu7zKi3>*bAe75cXpo$ew-94FK>SS>HtGM@p;dH z{-8OazM6XLS_;hk2n26KV=yJ#u)lI(hp;>*{*eDG2a}2@?C!CzU}Qgx<6%NvWIs(9 z;F|-;xduha%B(-9#>)dfPJiZ>4lzyxbk6R0-D_nZNR^&nh%ii(xfyo_(emOjAOX(1 zf46(+OoKj72{o5#C6zW5NPcT6XdrkhWy%CMC6gv3AfvJURR&oEIZ2UJ-}GXmbKZD~ zdRjADjEt%bJbpPt&)GZp3cfqCmXO{v=GM4%JCwotN!6wMtz^6T8pf4DN`EM7Y_Sd_ zKUy}SNo=s%#SJPVonS71Bp;EOnT>AJSaY+vRe=J0 zaXCq|-JoO9EBa8u=peO0^Cpfh$W3tFy(pJ0jjo|wL0Rlebb$ZcaeMU8T*qep;pnVs ze`L?qcdg6sSUl~hbp=#xn2+>w4VLWcahl1-k~X!D0q{0;M9eRjF9|z4shMOdwn3uB)Srnt4M~g=hwzq3TR=PLMsR~8vL{5sI`4w^BtC_t zE~ByI7oXQfpVbow+jZMhoI5()7Ra>O`HeHW(sh{GGB5d=|6o?TM&%MFQP2v3tmq$AW z1e5DTj&KOg6%Y0uWEFS5Ud6{FpJ9TWI&Evm0W9z_S4@|#2$D^lWx5ij5;RLokVu0N z_MQ;Ee;EFZW>@;iyzNFMu_a>3b(-nYKWNRdx*kyf(eHy+S9U?xAWT0&#ZAGzfTY|H zvqJa>W=e7T87O4cQ>-6zkX0ZAMVltgRm|jq9o|D9Q{ym*Y2jW~8ypO!OM~53;`-(* zIE*v6odRfxIZf!DKCb^POFar)b%fmco%zf?mP3%~5?#aL^>?)BZ%zHNie%PP)kPlM z9)-Ev48fx>!nJ+=Q_V9*JH2FC4HEZLTe~1;OSnaGDx~Os4O3R^&dcQvCn#ZQTKT0 z#aSP!d2g5`>O#jtPwni5NN&uLAJ&YOzmuz>`doz*WGoY4nW$xhgg2TbZl|7joB63SLyCihhv3m+l zDz*h6or$u7Q}H2ndVuZi06Nq9#LzF2r0V;_`9S0bKa{zz*G2CpJmCl7o4l=G*Qt7) zFUu<^Jhn_hTbb`94NaE)M$fSSJLa*dHzoV_&dUT;d4k%sA>f9*eJWx;o&8p|D2vQyIawosr(s{DKI)`z~%LKl?qp0AE>I|0A3_b^&z zFdp^o??RsrZHJCg>EPbLx`d1jLp+mEaT8ceF!&m$6u`#~+%OMPg56IOk(K5W_5?45 z5I(kN3((|;`PnM+WxFn+w}UW|e&Rnc6{>B?xi~~omvGSVS8!vyp(M+5DaXDcP{K6GDtAhz%!4aGHDw|5XcYdbc|>-Ko@>cBBqSH?L#({q z>tEcHRLWbGzpzQ_YQgKG=LmNOyx##-MkM>a>PO+)gd!k3nH*+oC?c<=1w2Imiv@6K z7fJ1BXc&1MJlEd`04~JLVsFGAO;1mpx_@Ufr;% z`^>RTGt{Sp*KG*Hm-*S>H)cA@Ye7fSv0Z1KO{8mfio8aTu`91DZ(4g>0V6}8Jj04^oQ-sw7(2Lgvvcd7LwhCV8gP41G zyvfgQ@BIzaq;j)Uyd--cG{Fu!Jfy-6o_0*+61a;!T`;Qqda+T-w=pnJr z0U(_Vpp_XyjwD82NpcU2&pTadpr>KpQkoW^O+X+GW<);WadrlMx_74n7dicUwVW+Jw@s;sWO3iEb!By87K>9CxJyK&lM%L|F+FsuQQiCIB)Iq2t z9lE4-ltyctvUSmVueWWSu!;RN23gZUfL*V$ppkLDr$N2vwI{f$l~5_~T0=*lE}5NmO5SJFu@Jf_t03jWa3!nW;Aqf_4T`%a_0*;hV(!sNcW{Mp)* z3}&56qpB!{i0MMQV~GMr^1u%YXhGhLZTMrj`F`%A1?;hpEkDjCu6v(8$HWhkG*B7x!?;+P9gh2bbgpzt8|eyoFnIT zXu(_pfI|d2%+MItx&6VRU5I@E-S)G>f7b4;(9iVMrm1G#~u@~3xj4U=NjmC(AH9hS}h zQQ0k(Byn<69jR*Z(kmsVaQm6~kf_2N-~7J_;eYNbAAM?U=0DO3Ea>uB2T*1+!oA(N z>1?#KR_0+p6CxE>E}kjuBSr z4}okp5YD~@DF%GYa>AyrZcp>yumwAwZ29+0s$;#UBR8tQ@D@ zzfA3mebLE(;kQFaD{#bCks0tY-~`+=81K;7aDyylzQ`V?(l*;SMZ6et3Ae3SUt`Qw!EM?j@}R9Inua zGZ&}oLx@TP^nniK6r2?HYJGJ~AmZuvRNA&K&=?*^AXNE|kWBoV)ZCPI!tp$R@b5!Q zP}iJA!niCo4uKsG(Z3_C#_XSlz3q55Mu$(9|EV+# zyOx8Z6`m_S&Hv?kmSyQ%OfDB;JK1Z{N{Q`J@|Xn1() z{RywwuPwgKIOQ9(?fNg*mr`k-hdqI8Kzk=J{jD_S1C|??79TY}&wpDXXhxunMC>_T z!1tFD4V;FHOsiFxV`-C)TEaG)l6+-pBkhQ&I^6~)BpWxz4SgD-M zIoa!8)&q|&kaBLb-x{g+aqbqVq6btJwzlblVm0Q!_d4WlDl$UIPUPN~LRFd;NM_%$v|CF|uSK zbKG@-LfU4tMxH<))OGyD9csi{j!y{MxleVASO(pXC)fM^9L}g!=f?LU;}Yz*laasn zr5Q5JS$|e$xJc2m>o=On8cMggUo5`1Qxd7pY5H=#*Nr#AisS z_zbb5{qN7Hb@dj4@W?0d%D+F)*V7eq(~tiBg*?1m6g)ruC@uTnpEK;k@0&|35*NB> zmIZCI#ZPuXVpkx~{`o8d$!G4{d141V8_NVm8-N~KoNYV9f2W2gVOd(sDEV{2NbRUb zWpSa~@e_6_MVBQO&8EXGyV(Lk%u!~H@1vCmkSi*652#^p)ripRxuN!rX(Ck3J_=lQ zXMg`EURr)C)&C;|PpWy}bE=o+t+2MLymAo@J?=`{BbvteX{yU;Lda|yGy3sLnQYKj zrkp@J3p?WVodI%KQl=g7{41ic#h5SumTv4T1phScQ*OeR|J)x)f4q~MG&iQ-qGx!^ zF%s1RJAqgnmIDdRHu5*$i!RwDa)K4jtb1FbeuS2g<24Y2173w-+w;NU4t%hcF3a})z@fg*3W;(d`_gviS`rG*3PRh2#@Zy*y;!(HNTfjTc8AI8E6p*BiJH0Ry!SI$)53H3n7NAB4ZJ_KuehcV` zytsNXm$Z7F6{QyI0O*t2(X5`8dL}+iJbcILFOLPz2P%CSKMLG+Ur4aK$l!XvNua7} zt9?se{quv@9Q%{a!#RPb{e`S&`5HBS;8l&Hgp1XAw<<8mTSt5H?H=f|G0~jnS0`Vy z7TwTxZb(c=6Nx?sv?6M$aFequiri%qW0oEIW)eA=FN+i>g~Me09-Y8Q&+-jB+86s3 zx{|(<1ivOO0~fFMz;c7TOd)=^^I;!4NB4s4!5(3eJ3OyiXmk^K!m|U;*lvR_1V0{<#0rpNcM z3%Mc@x*3ku>{^_EYa;0TIb25L4I~)b%q>7s84LkPd-eHiIb4^eIV|N{gXx zN~N74^p52HOPBf2+FfqnoNnEi9!(Lo5HDMIekl9x;CyA89}O=+D9-Go%yVr}vgslV z>HP^a;%oV{b`v?mk`B7OmCsJiAJVmR&G!8aMv1MU&1K*I#uxOBHKqh)27b(}k^Euw zOL`p>T^7(m1Fm+AC%AkLzX-)U%_m({q0hlHe7~7GI@lL^WZ|?5qRl06VyNy0jAj_ zcljU{`h|(K4Xu0-Yi;~9(z*rvJR-u0R+7kR`2C)8Ssa-F6iB4k_-}wK#=5tNsu#lt12(mJ#vb;1k3xBH4+0>tzRldB_4QAlj_my%WURqs zf5B0GSl9LoGTW=Yyk(#b6PC2@O2Osfr3-123m7(^LvD#U-bcj=3?$qxb>tE8?zW_L zu=MlxKEun6Y3n7Z>>RL!6r&2#;dL8l)u*LWS64GY6GZ2qJ2j>_O}*5nn$P(_1{}0fX-`8ya#iM8Z3@)I zYBvFH`yu?7)K)-}BfuRi>>Y7E?Z;Y94mUo$URvv%(qajzL8YdkWP9LqNE5QRF27_pBQ_4~?kx@a953~Ob&k#p z358eiX~r&^MqiO+8?M&0Fgo5@IN9v5_9|G>3Rm%IkBAo6TLWZD&#$vV`&aCTb6(zg zRECiWxED6Gp|M7qyI5(@+WJjNTqYL7KQ%=xdqdbhN|C6OP6+&+=$@IJjd^@N_=aAg z==&3-_Axm=8rNZzX3V+$R2-#~<+HgQ>2phCo9$)aiR5N@7h&g# z*m&B(0&XWz7J`1voKYDtMbu^PfyDw21hxs(F4nL}8c!Pqsz46yk9mL}VP@mThj(EI)=2rpGR=s%%o zY_MoJa3i1V0M|DK%9=6DtZ815@man&33tJ)N*_HOL^qVs`ZZB5l%&H~l@9fAS~dSc z%bfDPG4uX09HbZ>w#5lx=_B_s zxV$)23{3H;bf(^JBML7NxR!=ad929$IuWmL5MVZcl5JS=>lZ$Zw%js+HXu@4)dJ=4 zbF+a4;_qTgfH#w|R~Msz0XOWTtOojkVyh95@IDE&Ih+BB1Vtb?GFLOoW?6UV>WeU$ z0h1QH{lHpyl?ZDn1l`91u%7=K^uP*uMji3vg>Jc|15)1~sevEREF+@uk2(d?Zz zbpy7p6)vaC-`@tk5$?q3K9A2IxqPxxaavSJq?LOMI3A9(T8YiiFNk@ZM98q=CP=Tj9@vr;A-=UeLK z!Wn4G4~d+`!~#tUU6(<+*ijRQ>n`e>DqgT#hw9)c{Vrj&>)VMGQ_6!B#`szNN1Rbm z7RCL2E+Fg9ezeMATgC0+b&ZLR=~HwqPNBGYC~&l(jq&Q1EKEOfxkQiE2=ISl;1Ul~ zzuhy(^|eP6dYya&SG8y!={ArFDIIFD#q(EHCjX@{ZvmVNoU+e~6$;3xYyZ?1u(rZ{ z!-{KXr1Pt9TMq;>*;-~tePWXBTJzimwtaULGpXiQNjhcxxw>AzVnX6j`u%K8 zj1V6lsTY;bP`J#sa$qlAgpvaxs?kNJ;BS0J6S?mvtK-S`r~N{u)X0OL1y(JbM=Z_o zx=X)GfCc8T4c6vJn(N2{z59m92$`LtW-tyIb z2`NuEXYwQceR;ba_4rYM_>vo(6ssTJY$-_rY5y5ii?%nv-;jm~!od^~x0F-fZ;ynn=eS2@lI?ii zhu+ldikohK0n=u?$>s@)Uf{+?QIHyVktkUUxhm zn?>8EUH_`FbMvOkA>KyD!3OX3IT)Uon(f$EtPdIzN$M9i~zs5|50KmiAGjKI89?qWSkMQfw8Zirr z!99%lYvEZ{|Jr*`T;<*`@k63!6<7y)lzY%d&R=xmvtGqUW|T*?Z}N%dWXyHP@&w=k zdLx%-)*%Mfn|FI?KzFmJFAwZ$Mt6w>)9Ailq6PPvo;_rD+i8yJ!h-^3GosC5NV&bm9bd`ipCyZaA7-9KMGHN0slIVCDMxR1 z@JzZtRCf>he6A9V-6hP(G&(YMiD|^I4+VR-_zAQ;8$g)mzprAXVnrNZpGHsec}1It ztT2ur?p2b{1GVS+V8v6>J2dod$hY|db|oR$A#f+}GaVL#>w_HO4B8Sa9WY&41phZb?laPAFXZ0U8{ z0vLJ2DdNefdh(f|OOF>PR3>F#R4Ji1hE@~5CRbTbXi_iRq>k{c$fmt_q_}ZoPJlNe zeS|rnVluT}TLUNgbJ2;Gk?OmBs3BF$NWgVD@puLwT1{8qu7eU?v2V47JdJWwpNda0 z#LIZRO!WzCb%bJIE3+KFMY(jVZTd}l9t4d2wsEtU1j4ZayjVjG5p8_W=DdEhy}T~m zaQ4DPz2~|yU4&4GE((sUcbLz`mYp9Oh1^0O&0N_4eBHA0B;7HkDhq6{AhUg=cQ#gV zW4Prw8#D%UL$TUe!a^b>IJi02`g8P-LJ4nUfO#UcM$meKSNSx zzs}!a|8RPo@0D?DzCq8`>d|x=qu&ny3Fb-@x$!S9?9DMy{9+-;4t>f=is-^+(oaO& z*$jXDaZQu21m!UsOTP_exsFuFrv-s&6(gUuVhSkVZE(m0On?<=UB>)5dN{?mZl4RK zgyX3x2}ry!{|!MD;3av^*C8!#b2JA(tfj{PILzk4^)#6NTGn>`Jn+~w@Hs-|O)*gI z<^B5u-~7IEU%X~8Fg}V->0JUl0D@83@hTU0` z;#H@qZ)_)CS({Kb)uG=rl`J*mW$ys>kuZ-9)Y`!-Q*zgD(1*886x<0AkMVs?cB{WoEXm9>P8m8u7_)~QLI=hUGE+)8^#xtnZ`wB25p7VfQkY>|yID=y!cVh(4o~?%#5vX3Q1hIvg&&*g`&UGw%z9Gp z*D^P}eoB6NaWcb2G)&|VZV8zER55=mL3h&3iR<02Mg%KWzuY6R`XRdJBgMjra@(bO zGWe2*gu}dVkchR@lBzoY@dd`|9bH7~P|)48UzfyQAK0~8o*8m4%z9ivc%gE_oJP_< zm2}8e1N9N+ggRCi^~60o3XCe|GN^oY^e+}b?U2u3yi9fmpkPn={<@1`20XoGCBq7J z|GTP=iRkf-4~_gY)%OBD&nh+K7qq|AglKX z+8KEXD&YuHcE(A@OEu&$Zk~6)R{ZPq4p(apSwrF=m`*^iYk5+KpX4 z94n&n4w%9^+UnNjCng%n{=dN%}Fj$eR)d3B#Rk!COE=mVmNAQI@!QTvrHfg4lX;Z@5&7xz1Htc z5_&@bc}$mD=~{1d%cbYao2j2WVjp1R-uNI}|B(Sv{Ch~>C5y@;Qh`7V6bbJV!sz2s zYsb2@0O9|In57BjuRhn;E(SVW9k$tgQ*l$bkYxx!_dOn%Zf`#BD{AH^T}WWC!bB%}56N_e4XBHptZVJ|UG}Ce_>?=jEfq$J z6{t@72!1xkPiaK2MhG73B5N~na+ z%xpP5*c^gpz462cki<2T-Dnyl)==6?v}=d+^`B2ZLkpvq&w0B%|NbZi#Zq$5&>;W zDW@!Oh4-x_-Ho$cx%ySDnr{z|N$mNM*&fChHlJk+Zd`ljsW+5+yL!Mk?go_>C5lSyIUE$BWSPahuTyu<`Cc7Y89EkqBJV?z<6XJaxoCG>i+jFKPCFBh;BY8m1nAliL^V7PvOEy%8{h-A%!Gh$6;s0&K;x%yr0rK%Z4v6-{aV_vhQ zOAaxQ^`(kRzZU^EBS*;nWddB=b!d&ctv121n;OBx61E%=7jP`D_lkv#b;|m=Zb@UyV+s zI{sYxjRWDPPo?VP`zkCP|4AC{S3kRx#y9XT;A{8-INL8^IqD11vdQHQns(9zdokax z%ENv_ClOYC_6{zB7vEMQp?*&qzlUV>T|V^xvK*LLDfuz1Q}U6Eau<#u`<8l$hE#wd zyvJS(Ej9ky1AwEZfz>nfV>OSc0c8N`3HshPeb7zhv7IUZ z6moAC?@~^Z`0__Km1X;C6EV)5KH;wcvO>2H2IkmXe-4-jHeaB;_UZq%`g~Hm7#ZQ1 zDi(Uyj`ta{xs#3C=*>La?-wcj#mD9-wi5sCdLyObVT3;(dJh+CzPN=op*~6<#x2eH z>c|9PRn#mGDq-PehQE$~8z^5Zh=O>_HVH`maHug_Zl1$clH$yNp!4?#a!)(6KlfQY z{2O7`OR++~;kqveA8|=1cKz}dJtk@vgU6sK1v|Ofx9ag*xGP-IJ1>jNWfeQWbZoSC zctLnetgLL5qV;LNm7si2PRB1dhSIY2=u@v`3M!37$Dys?LgLl1;I8Rb*)HC z%5cJu?Se~e{GCC$MagaD+}@3M7*@B+GIncJDnJ`M50+>Byqy&%$_~sDC>EY41=UG; z|CGl>E(J$L05leWC`{^_I&|LxNm4Cb;B}|{56n~hq|g*YHP+?QKYAJKch|aB?}N z^nfsUH4UUZ=`{KOgLcAznQ$FjAU{-JJe8tBoF5AAYToI$SZ7g{Nm37~x=OJM+7)-Q z2BA+Eg z_uRX&3Vv$WStg;FDCD8pw!q9Z>Uen^Whb61U^?#~4bzYO;5DC;5cJn>>gJLpVnnEp z$nG?G{0Q+t!F}zz&C*B<-^T@h-AmGKRh)?IREDVUMzECGJh8)KDfK(EshVg+UfUXt zQ7S&Cd+GPA$?tdB$v~aHYw|xK1xcaU7E~`@AjQy^DWod)&+`_7mk9T~XUYz9x4=05{ z16${Q>YPWgio)hzk_0e?tDuuqejizwNn7hQ z)m3mht^D46PR4xS%quuv74!F$?#ppUsC7^2dyql^UEWQNb0Gp;z0DCTvtUozQB+!=Ia~C% zW$l<>KQ-*8YVVxRSD6xXx#Hr<)qPS}f?K;1I-}pD6qR!X;(&@YVG3{5xJp17(gru2 z@?KS)yK(2nXP>2~6G%$XbJotTh)0!d+{!h4kDV@#W~Q|K02%fTPICd?5oz_tULLOW zJ^i5T&bOodr5v2DfNbj8>MMR`Y6M+C* zs!~LxLn1YFgwR5l7J8&4A&~NA@9&(ob$ix2@1M+%Bu^&Kz2<%1nQQJL9XSvdSW`CqK|8#1UJyVjBJsf9@(kONGsJ25|5iQWja= zzdTOB4mbHpL!I4^c;c*PK5}Q$% zz@dbXb&{V&iMbrgb(jm%cCX!~C7=1IC;{@wC!#ne1x>Mv>0l*7x+B>rrob#U(5J(+ zlF(cnIW;!~MKPVEfcrMc4J^jS$}?a8RZ=u|SjpH*O;tUD6~DP;BS0GcFD^=G6=B9e zv>!RWQ5sKB%rKLxrW6iO7sWBXv6>{ip&~>1UmuJ!HGp(ll$dv5=ZhkKAy2rFwj6V+ z+Q4lLjBWsFJ^tp5DJ31djj5Up-PQnw^S-JcL#-xOmM`E>Scz-+y#~|W(f*+0`ulvD zURN0Yf>i|E{zk6$7=m%3hM*BUAhQX_N8+^05Gpf2{>?-XNQJ`CN;8V+u@cDxU^KFc zL$mf;a^<;uH(@#Z5~fubwV;vV{1>`MAtBkpeR13fe z)IEDTF6fE0og0*EkXL^)=iR1+^a!+5TI^S^gI@DL8tkF)s)frNH z;4nu=HyeeV(aRQ{SdQaA{(|3j+xWv%p$K37VsX;#U(D4yjnVhw5@kvQK3u(PR^yqN zCp>TD|0S>#IUbFD7DZ2Agg;D0I+hF62HA9tDR#366eugmYdY$#{um=r{`LmAxGm1q6mZ405>OKTZ_=r2&Doo{7b$3SadQ~g zv4HuFVEPfTxqv_o+Yh35vk3o-)BQs;0sF0f^zlb$cN|v!AJi2^s_9qaR;R%;lmYDQ zH`XfzbP;?ERU0iU=Syw>TXaAFI(o|KDqFwCdwQl=t%Kh`Oiyd7fRaX!8vNE@0sYU? z%2NHIv(-O;-QOS=y@t!34XhXk?DFs7_&4)47N5nl3jCYlx&|B$+fW4Z`N^nk9Q+ne z&DS1u1T<(NHU141W6kxCa^ynmkF|rve6d}X!TzRaC*Jy@{@)XR%hD_I`nE<{z1#aY z>sGy|*=+}RgC9ONK2Mq6Og$QZlh}@T&=91zpzxLh)W=p=lAp?q0a&uBiXzhYXu>T* zwOI^40t|!<2JEhO0bd-PO zL16H+fHxya(izs&{=XR8^-pzgewbOvcHwv2MGG(O93}o@PPZ;-9I#m~LH$T)|Ey;r zgpDmcpv+U3JLV$pu-Y==R(6D+c#8klxeNy055sx|^P}EVw@VhO*VP^8C_X4G$z_#E zN_DSRevOtPB;4F(V zqU4WWVBp2Y={Q)<_CwlOs6zEcT^prR)ASTEbNKb|Q(!~?)9GjzQ0K;YAi z-4-MuVI1B!ElJ_SPcRb)i{^HpT!EVVbAl(<d`;qirU-R`lO&;0t1tOS9N&yrBG+X+|pTMy_xUVApZQbWb27(Ke52W|Gf6SV|P z3w|@{$zpzYO|?vK{=Nk-bbBzYBIWE40>WV9i03E2z8sD`^XHL;UUlz7{lhpEgrm(h zQFW3N8R)ba@`hb9L$J#Q{(TafiC|)qwP}T;OTFmkB+=lN<`h*S^M+o1-L}numfLA= z@~MyZTpw9VwDyrX20DH68Ycq&iDu8FIa_tOpRvhyJ@*{Aw}7Ka^mssA-rQmZP!n45 zw!%6hQT-KCdvaba(2|u&!->ZWKd3#mQppS7>!?sU(m_7&J$gvX+pxlfzULjGkk7cp zcvYX(iI4&fk$F`F{Q;OLHkAkJghb1>eXNyO(~YW14i`Vg=UtK3Wo;?H7qxyZ)C)A} zKKFbnwds90I_GAtWPHIxYBkf^8BUKCopzkQZI{AVU|{|v4)Q64{Kn1edUj5dcco+` z-dAAUu1ULcd4sbw-;&civGVS}CC7`j`463X^&oS5R7scYbv9w6;SYBpPpb4Bm?I2q zW2*Vc%psccK2+_b6x-LvzR}e2@aU}i#ZS8<;<3u&nQp0i@cSNLWe-IARx!g&)*m*Dz5G>|idzHyr1vU}nY%;HkUAHWTbQ zOSrz%;+2X;PkJ;ThG8n{ZN0CEhqu9(BlgxxM8ohuMPxy|n4F z?$FH!H5E^{Dpr4?E6BEt*><`*Hg?BRZ_H@`;4M>MV6h1=QRyf)#2tlpp~P`t9%&B) zMBEjuPk#^MY`pz6;OR3H2M^Qf*!mgMvZz5k?k5w=^pD9?!sqWO#SKb*?(9qULIgPF zC2C{1=V0;x*@1XQg*M3e6nY^g;Xy`8$gO$S5;3c-d)}5@ue4vSsR7bx66Cb3M>IU z(v>VTlGME4#$vmM9ZP0o@9I%z&n<JLEQzp==LIM z#yzP>XY5*)3#0OgnVN;UH?Tpf6pBQCk`p&mbbnZhTqi8c2+xJlrhCqfm%3Af@(Zj_ z%%4oAe%z?a9f?`?ax^v$Zw;y*$QS!Ogr6X5E@2mKIQvB&Db%6`ef%WxZD!bBX?697 z}%|dYkr3#IY-kw zG#+sZV8>1iHoC$D-pg9;BYzoB*yej_iX`O+Y)98-?i#A0_l5#5EZ;#_u#7jMia{fz zKy%xAWPVe@oP+uyHtt?b^&eFco6JjR0gC63>x*BA72^t5I%LAutPfg5%tW$0{LM); z9Tkz~fJXp>US{E$p4+>A)vMJd1H&O%@!1AMTs-M=q zR)!3M?8I6pitMq}l72D+`M8UY{KBPM0^edJY4)_Zmve2>udCzKrG;ITD#@YRh!6hv zMm@ahEk+B)!mn!3$Z?9tazK(DCghj`_Xde8D)4e1;-K#vLkD5KW|LaKx0N>)=zKPWAH(p^kB(N@X%L*@>Is2_nm?<-onj#hy z7Cw=Xm5UF2bcz7(pJiNgwsY}z8rfNRT$pEWzW&w@iH4vf7U#RHt8lj&60YmlwuL={ z^d^c(uz!$NE^Q9$h;N%c@~0`AO7+rWt2Ez4%A21@3etR(vG(q`uzcgNxv3@bG`kn! z?R;be#G3MQa{+ z46jeWyVT^ZZcC z!0GO@pK!9}y%|O9+{}b=pIa<6G?8-g4-<3>%UqY+5=hDT)RQiq1)`KBa!M~huja0F zC+l}yn>T`Gy79X9147-8I2~?HD)0|nwn_dok*en1mmD?&-XkMXQJdP_&R3Pknhh+M zs97Mh#p#o0jsobS=^pf}q7YieRBCU7wH#qe5RTA&{9gY0iZ34xV#_k*C|2IhK^~1a z5mk1EgI9%%t+n>%sW@avD5bc=54R=_)k5Evj1_kNx&CUh{Nrw?`PBI@a?Pr>7{f}Y ziaL+BYitGRTxyEyh*7HCp6$R^u7Q9|L`$&g7HSAoS;BqLZqX zyY-;Rj9@ULZ)?{vG-Bk|!BTw!H~&#*H|6pVpB?k>5n?)0?-skiER&~YXHzR(xO5ig z&^wx#RV$7fkjh*#B~MY+ISs;e_ndh3c~Y8;i%F3t1Y1WePD_9`*dn5Odg^xR@R6pf ze1JP~jNHJDSouOe8QeW)*%d{^}TL zCM5@v#B)e=tP7J(e$T)7gSI+00jaw?Itoi^c7#g;BbpihDtmH#IqFvmw@aS3tVox$!9w!h<>}=&a*=l>FF;bWf;3*DAR5gNmk2BYYO37y%ejSI^r@7717L9 zh{HQd7eGlmB4Dk`oeP+5iUs2QX`8MCBrG1 zsgaQ|zZ*o)Q3GzBi)fVQ4sjfyi1ADDmE7QIA-gPfQH6r0;`syi0chb`EQf*Z-W?s{ zp?sPY^uD@20+rryV2?k`@g!IrwGgz eKS}s7Lm;IJuWF8qY*r#6URn?J)oN7iV*Ue25TyVB literal 0 HcmV?d00001 diff --git a/planning/planning_debug_tools/scripts/update_logger_level.sh b/planning/planning_debug_tools/scripts/update_logger_level.sh new file mode 100755 index 0000000000000..3a789f3416c02 --- /dev/null +++ b/planning/planning_debug_tools/scripts/update_logger_level.sh @@ -0,0 +1,41 @@ +#!/bin/bash + +declare -A node_name_dict +declare -A logger_name_dict + +# behavior path planner +behavior_path_module_list=("avoidance" "avoidance_by_lane_change" "dynamic_avoidance" "lane_change_right" "lane_change_left" "external_request_lane_change_right" "external_request_lane_change_left" "goal_planner" "start_planner" "side_shift") +for module in "${behavior_path_module_list[@]}"; do + node_name_dict[$module]="/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner" + logger_name_dict[$module]="planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner."$module +done + +# behavior velocity planner +behavior_velocity_module_list=("crosswalk" "walkway" "traffic_light" "intersection" "merge_from_private" "blind_spot" "detection_area" "virtual_traffic_light" "no_stopping_area" "stop_line" "occlusion_spot" "run_out" "speed_bump" "out_of_lane" "no_drivable_lane") +for module in "${behavior_velocity_module_list[@]}"; do + node_name_dict[$module]="/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner" + logger_name_dict[$module]="planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner."$module +done + +# obstacle avoidance planner +node_name_dict["obstacle_avoidance_planner"]=/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner +logger_name_dict["obstacle_avoidance_planner"]=/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner + +# motion velocity smoother +node_name_dict["motion_velocity_smoother"]=/planning/scenario_planning/motion_velocity_smoother +logger_name_dict["motion_velocity_smoother"]=/planning/scenario_planning/motion_velocity_smoother + +if [ -z "${node_name_dict[$1]}" ]; then + echo "[ERROR] $1 is not found." + echo -n "[ERROR] The available modules are [ " + for node_name in "${!node_name_dict[@]}"; do + echo -n "${node_name} " + done + echo "]" + exit 0 +fi + +# update logger +node_name=${node_name_dict[$1]} +logger_name=${logger_name_dict[$1]} +ros2 service call "$node_name/config_logger" logging_demo/srv/ConfigLogger "{logger_name: $logger_name, level: $2}" From 418aa5d27c60127548997ffda0a5c05cb6291ad7 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Sun, 17 Dec 2023 16:18:11 +0900 Subject: [PATCH 079/276] fix(static_drivable_area_expansion): fix bug in expansion logic for hatched road marking (#5842) fix(utils): fix drivable area expansion logic for zebra zone Signed-off-by: satoshi-ota --- .../static_drivable_area.cpp | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index f6344b94a6bc5..af4bebe183d1d 100644 --- a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -1183,6 +1183,8 @@ std::vector getBoundWithHatchedRoadMarkings( } else { if (!polygon) { will_close_polygon = true; + } else if (polygon.value().id() != current_polygon.value().id()) { + will_close_polygon = true; } else { current_polygon_border_indices.push_back( get_corresponding_polygon_index(*current_polygon, bound_point.id())); @@ -1217,6 +1219,17 @@ std::vector getBoundWithHatchedRoadMarkings( (*current_polygon)[mod(target_poly_idx, current_polygon_points_num)]); } } + + if (polygon.has_value() && current_polygon.has_value()) { + if (polygon.value().id() != current_polygon.value().id()) { + current_polygon = polygon; + current_polygon_border_indices.clear(); + current_polygon_border_indices.push_back( + get_corresponding_polygon_index(current_polygon.value(), bound_point.id())); + continue; + } + } + current_polygon = std::nullopt; current_polygon_border_indices.clear(); } From 3b379ff6193f65e6417fe5c48dc98f025d0e7716 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 18 Dec 2023 13:07:04 +0900 Subject: [PATCH 080/276] chore(motion_velocity_smoother): remove unnecessary info of non autonomous control (#5891) Signed-off-by: Takayuki Murooka --- .../src/motion_velocity_smoother_node.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp index 5e3924796f95f..90f7295c4cf6f 100644 --- a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp +++ b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp @@ -799,7 +799,8 @@ MotionVelocitySmootherNode::calcInitialMotion( // use ego velocity/acceleration in the planning for smooth transition from MANUAL to AUTONOMOUS. if (node_param_.plan_from_ego_speed_on_manual_mode) { // could be false for debug purpose const bool is_in_autonomous_control = operation_mode_.is_autoware_control_enabled && - operation_mode_.mode == OperationModeState::AUTONOMOUS; + (operation_mode_.mode == OperationModeState::AUTONOMOUS || + operation_mode_.mode == OperationModeState::STOP); if (!is_in_autonomous_control) { RCLCPP_INFO_THROTTLE( get_logger(), *clock_, 10000, "Not in autonomous control. Plan from ego velocity."); From dd5af3e22c24e569f24dfffed17dda4e93760b90 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 18 Dec 2023 14:05:11 +0900 Subject: [PATCH 081/276] refactor(behavior_path_planner): remove use_experimental_lane_change_function (#5889) Signed-off-by: Takayuki Murooka --- .../lane_driving/behavior_planning/behavior_planning.launch.xml | 1 - planning/behavior_path_planner/README.md | 1 - 2 files changed, 2 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 4539e15a55954..b36b40ed6a980 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -210,7 +210,6 @@ - diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 884767315ac12..40a23a09030de 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -139,7 +139,6 @@ Enabling and disabling the modules in the behavior path planner is primarily man The `default_preset.yaml` file acts as a configuration file for enabling or disabling specific modules within the planner. It contains a series of arguments which represent the behavior path planner's modules or features. For example: - `launch_avoidance_module`: Set to `true` to enable the avoidance module, or `false` to disable it. -- `use_experimental_lane_change_function`: Set to `true` to enable experimental features in the lane change module. !!! note From 89b627317f2f6ec1b10a9a4bc31273f4433c0b37 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 18 Dec 2023 14:25:56 +0900 Subject: [PATCH 082/276] perf(planning_debug_tools): improve calculation time of perception_reproducer (#5894) Signed-off-by: Takayuki Murooka --- .../perception_replayer/perception_reproducer.py | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py index d837abccc0670..b2b6a3c0ef38e 100755 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py @@ -84,9 +84,14 @@ def on_timer(self): # copy the messages self.stopwatch.tic("message deepcopy") - msgs = pickle.loads(pickle.dumps(msgs_orig)) # this is x5 faster than deepcopy - objects_msg = msgs[0] - traffic_signals_msg = msgs[1] + if self.args.detected_object: + msgs = pickle.loads(pickle.dumps(msgs_orig)) # this is x5 faster than deepcopy + objects_msg = msgs[0] + traffic_signals_msg = msgs[1] + else: + # NOTE: No need to deepcopy since only timestamp will be changed and it will be changed every time correctly. + objects_msg = msgs_orig[0] + traffic_signals_msg = msgs_orig[1] self.stopwatch.toc("message deepcopy") self.stopwatch.tic("transform and publish") From efbf4d2591f7816b61e65d0bddb33d6d72091d1e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Dec 2023 14:57:10 +0900 Subject: [PATCH 083/276] fix(avoidance): unintentional path cut (#5887) * fix(avoidance): unintentional path cut Signed-off-by: satoshi-ota * fix(bpp): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_common): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_side_shift): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_avoidance): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_lane_change): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_goal_planner): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_start_planner): nouse pointer Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/scene.cpp | 28 ++++++++-------- .../src/default_fixed_goal_planner.cpp | 5 ++- .../src/goal_planner_module.cpp | 33 +++++++++---------- .../utils/base_class.hpp | 11 +++---- .../src/interface.cpp | 16 ++++----- .../src/scene.cpp | 24 +++++++------- .../src/behavior_path_planner_node.cpp | 3 +- .../src/planner_manager.cpp | 16 ++++----- .../dynamic_avoidance_module.cpp | 32 +++++++++--------- .../data_manager.hpp | 4 +-- .../interface/scene_module_interface.hpp | 2 +- .../src/utils/path_utils.cpp | 8 ++--- .../src/scene.cpp | 15 +++++---- .../src/start_planner_module.cpp | 14 ++++---- 14 files changed, 105 insertions(+), 106 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 783877e9c753d..ebe42f73d538b 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -220,7 +220,7 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat // lanelet info data.current_lanelets = utils::avoidance::getCurrentLanesFromPath( - *getPreviousModuleOutput().reference_path, planner_data_); + getPreviousModuleOutput().reference_path, planner_data_); data.extend_lanelets = utils::avoidance::getExtendLanes(data.current_lanelets, getEgoPose(), planner_data_); @@ -233,8 +233,8 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat }); // calc drivable bound - const auto shorten_lanes = - utils::cutOverlappedLanes(*getPreviousModuleOutput().path, data.drivable_lanes); + auto tmp_path = getPreviousModuleOutput().path; + const auto shorten_lanes = utils::cutOverlappedLanes(tmp_path, data.drivable_lanes); data.left_bound = toLineString3d(utils::calcBound( planner_data_->route_handler, shorten_lanes, parameters_->use_hatched_road_markings, parameters_->use_intersection_areas, true)); @@ -244,9 +244,9 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat // reference path if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) { - data.reference_path_rough = extendBackwardLength(*getPreviousModuleOutput().path); + data.reference_path_rough = extendBackwardLength(getPreviousModuleOutput().path); } else { - data.reference_path_rough = *getPreviousModuleOutput().path; + data.reference_path_rough = getPreviousModuleOutput().path; RCLCPP_WARN(getLogger(), "Previous module lane is updated. Don't use latest reference path."); } @@ -910,17 +910,17 @@ BehaviorModuleOutput AvoidanceModule::plan() } if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) { - output.path = std::make_shared(spline_shift_path.path); + output.path = spline_shift_path.path; } else { output.path = getPreviousModuleOutput().path; RCLCPP_WARN(getLogger(), "Previous module lane is updated. Do nothing."); } output.reference_path = getPreviousModuleOutput().reference_path; - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); - const size_t ego_idx = planner_data_->findEgoIndex(output.path->points); - utils::clipPathLength(*output.path, ego_idx, planner_data_->parameters); + const size_t ego_idx = planner_data_->findEgoIndex(output.path.points); + utils::clipPathLength(output.path, ego_idx, planner_data_->parameters); // Drivable area generation. { @@ -995,7 +995,7 @@ BehaviorModuleOutput AvoidanceModule::planWaitingApproval() } path_candidate_ = std::make_shared(planCandidate().path_candidate); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); return out; } @@ -1169,11 +1169,11 @@ void AvoidanceModule::updateData() helper_->setData(planner_data_); if (!helper_->isInitialized()) { - helper_->setPreviousSplineShiftPath(toShiftedPath(*getPreviousModuleOutput().path)); - helper_->setPreviousLinearShiftPath(toShiftedPath(*getPreviousModuleOutput().path)); - helper_->setPreviousReferencePath(*getPreviousModuleOutput().path); + helper_->setPreviousSplineShiftPath(toShiftedPath(getPreviousModuleOutput().path)); + helper_->setPreviousLinearShiftPath(toShiftedPath(getPreviousModuleOutput().path)); + helper_->setPreviousReferencePath(getPreviousModuleOutput().path); helper_->setPreviousDrivingLanes(utils::avoidance::getCurrentLanesFromPath( - *getPreviousModuleOutput().reference_path, planner_data_)); + getPreviousModuleOutput().reference_path, planner_data_)); } debug_data_ = DebugData(); diff --git a/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp b/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp index f028b8aff8b98..cbbe5f585dbe2 100644 --- a/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp +++ b/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp @@ -33,9 +33,8 @@ BehaviorModuleOutput DefaultFixedGoalPlanner::plan( BehaviorModuleOutput output = // use planner previous module reference path getPreviousModuleOutput(); - const PathWithLaneId smoothed_path = - modifyPathForSmoothGoalConnection(*(output.path), planner_data); - output.path = std::make_shared(smoothed_path); + const PathWithLaneId smoothed_path = modifyPathForSmoothGoalConnection(output.path, planner_data); + output.path = smoothed_path; output.reference_path = getPreviousModuleOutput().reference_path; return output; } diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index b50387b3f6b0e..2ea6f1e100e91 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -282,7 +282,7 @@ void GoalPlannerModule::updateData() resetPathCandidate(); resetPathReference(); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); updateOccupancyGrid(); @@ -761,7 +761,7 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const // because it takes time for the trajectory to be reflected auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); keepStoppedWithCurrentPath(current_path); - output.path = std::make_shared(current_path); + output.path = current_path; } setModifiedGoal(output); @@ -777,14 +777,14 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) const { if (prev_data_.found_path || !prev_data_.stop_path) { // safe -> not_safe or no prev_stop_path: generate new stop_path - output.path = std::make_shared(generateStopPath()); + output.path = generateStopPath(); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path"); } else { // not_safe -> not_safe: use previous stop path - output.path = prev_data_.stop_path; + output.path = *prev_data_.stop_path; // stop_pose_ is removed in manager every loop, so need to set every loop. - stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); + stop_pose_ = utils::getFirstStopPoseFromPath(output.path); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, use previous stop path"); } @@ -800,20 +800,19 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output current_path, planner_data_, *stop_pose_, parameters_->maximum_deceleration_for_stop, parameters_->maximum_jerk_for_stop); if (stop_path) { - output.path = std::make_shared(*stop_path); + output.path = *stop_path; RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, generate stop path"); } else { - output.path = - std::make_shared(thread_safe_data_.get_pull_over_path()->getCurrentPath()); + output.path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Collision detected, no feasible stop path found, cannot stop."); } } else { // not_safe safe(no feasible stop path found) -> not_safe: use previous stop path - output.path = prev_data_.stop_path_after_approval; + output.path = *prev_data_.stop_path_after_approval; // stop_pose_ is removed in manager every loop, so need to set every loop. - stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); + stop_pose_ = utils::getFirstStopPoseFromPath(output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, use previous stop path"); } } @@ -826,7 +825,7 @@ void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); + output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -853,9 +852,9 @@ void GoalPlannerModule::setTurnSignalInfo(BehaviorModuleOutput & output) const { const auto original_signal = getPreviousModuleOutput().turn_signal_info; const auto new_signal = calcTurnSignalInfo(); - const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path->points); + const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points); output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal( - *output.path, getEgoPose(), current_seg_idx, original_signal, new_signal, + output.path, getEgoPose(), current_seg_idx, original_signal, new_signal, planner_data_->parameters.ego_nearest_dist_threshold, planner_data_->parameters.ego_nearest_yaw_threshold); } @@ -942,11 +941,11 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() BehaviorModuleOutput output{}; const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(); output.modified_goal = pull_over_output.modified_goal; - output.path = std::make_shared(generateStopPath()); + output.path = generateStopPath(); output.reference_path = getPreviousModuleOutput().reference_path; const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); + output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info{}; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -1054,7 +1053,7 @@ void GoalPlannerModule::postProcess() void GoalPlannerModule::updatePreviousData(const BehaviorModuleOutput & output) { if (prev_data_.found_path || !prev_data_.stop_path) { - prev_data_.stop_path = output.path; + prev_data_.stop_path = std::make_shared(output.path); } // for the next loop setOutput(). @@ -1086,7 +1085,7 @@ void GoalPlannerModule::updatePreviousData(const BehaviorModuleOutput & output) if (!isActivated() || (!is_safe && prev_data_.stop_path_after_approval)) { return; } - auto stop_path = std::make_shared(*output.path); + auto stop_path = std::make_shared(output.path); for (auto & point : stop_path->points) { point.point.longitudinal_velocity_mps = 0.0; } diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp index a7a35f07e5f30..4bfd461a0815f 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp @@ -107,14 +107,13 @@ class LaneChangeBase virtual bool specialExpiredCheck() const { return false; } virtual void setPreviousModulePaths( - const std::shared_ptr & prev_module_reference_path, - const std::shared_ptr & prev_module_path) + const PathWithLaneId & prev_module_reference_path, const PathWithLaneId & prev_module_path) { - if (prev_module_reference_path) { - prev_module_reference_path_ = *prev_module_reference_path; + if (!prev_module_reference_path.points.empty()) { + prev_module_reference_path_ = prev_module_reference_path; } - if (prev_module_path) { - prev_module_path_ = *prev_module_path; + if (!prev_module_path.points.empty()) { + prev_module_path_ = prev_module_path; } }; diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 1e80067842152..4a8eb34b088af 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -201,8 +201,8 @@ BehaviorModuleOutput LaneChangeInterface::plan() module_type_->setPreviousDrivableAreaInfo(getPreviousModuleOutput().drivable_area_info); module_type_->setPreviousTurnSignalInfo(getPreviousModuleOutput().turn_signal_info); auto output = module_type_->generateOutput(); - path_reference_ = output.reference_path; - *prev_approved_path_ = *getPreviousModuleOutput().path; + path_reference_ = std::make_shared(output.reference_path); + *prev_approved_path_ = getPreviousModuleOutput().path; stop_pose_ = module_type_->getStopPose(); @@ -219,12 +219,12 @@ BehaviorModuleOutput LaneChangeInterface::plan() BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() { - *prev_approved_path_ = *getPreviousModuleOutput().path; + *prev_approved_path_ = getPreviousModuleOutput().path; module_type_->insertStopPoint( module_type_->getLaneChangeStatus().current_lanes, *prev_approved_path_); BehaviorModuleOutput out; - out.path = std::make_shared(*prev_approved_path_); + out.path = *prev_approved_path_; out.reference_path = getPreviousModuleOutput().reference_path; out.turn_signal_info = getPreviousModuleOutput().turn_signal_info; out.drivable_area_info = getPreviousModuleOutput().drivable_area_info; @@ -240,9 +240,9 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() } // change turn signal when the vehicle reaches at the end of the path for waiting lane change - out.turn_signal_info = getCurrentTurnSignalInfo(*out.path, out.turn_signal_info); + out.turn_signal_info = getCurrentTurnSignalInfo(out.path, out.turn_signal_info); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); stop_pose_ = module_type_->getStopPose(); @@ -366,9 +366,9 @@ void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & o const auto current_position = module_type_->getEgoPosition(); const auto status = module_type_->getLaneChangeStatus(); const auto start_distance = motion_utils::calcSignedArcLength( - output.path->points, current_position, status.lane_change_path.info.shift_line.start.position); + output.path.points, current_position, status.lane_change_path.info.shift_line.start.position); const auto finish_distance = motion_utils::calcSignedArcLength( - output.path->points, current_position, status.lane_change_path.info.shift_line.end.position); + output.path.points, current_position, status.lane_change_path.info.shift_line.end.position); steering_factor_interface_ptr_->updateSteeringFactor( {status.lane_change_path.info.shift_line.start, status.lane_change_path.info.shift_line.end}, diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 21a600d11d83d..3adef17fc3b4d 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -145,38 +145,38 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() BehaviorModuleOutput output; if (isAbortState() && abort_path_) { - output.path = std::make_shared(abort_path_->path); - output.reference_path = std::make_shared(prev_module_reference_path_); + output.path = abort_path_->path; + output.reference_path = prev_module_reference_path_; output.turn_signal_info = prev_turn_signal_info_; - insertStopPoint(status_.current_lanes, *output.path); + insertStopPoint(status_.current_lanes, output.path); } else { - output.path = std::make_shared(getLaneChangePath().path); + output.path = getLaneChangePath().path; const auto found_extended_path = extendPath(); if (found_extended_path) { - *output.path = utils::combinePath(*output.path, *found_extended_path); + output.path = utils::combinePath(output.path, *found_extended_path); } - output.reference_path = std::make_shared(getReferencePath()); + output.reference_path = getReferencePath(); output.turn_signal_info = updateOutputTurnSignal(); if (isStopState()) { const auto current_velocity = getEgoVelocity(); const auto current_dist = calcSignedArcLength( - output.path->points, output.path->points.front().point.pose.position, getEgoPosition()); + output.path.points, output.path.points.front().point.pose.position, getEgoPosition()); const auto stop_dist = -(current_velocity * current_velocity / (2.0 * planner_data_->parameters.min_acc)); - const auto stop_point = utils::insertStopPoint(stop_dist + current_dist, *output.path); + const auto stop_point = utils::insertStopPoint(stop_dist + current_dist, output.path); setStopPose(stop_point.point.pose); } else { - insertStopPoint(status_.target_lanes, *output.path); + insertStopPoint(status_.target_lanes, output.path); } } extendOutputDrivableArea(output); - const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path->points); + const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points); output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal( - *output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info, + output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold, planner_data_->parameters.ego_nearest_yaw_threshold); @@ -189,7 +189,7 @@ void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) const auto drivable_lanes = utils::lane_change::generateDrivableLanes( *getRouteHandler(), status_.current_lanes, status_.target_lanes); - const auto shorten_lanes = utils::cutOverlappedLanes(*output.path, drivable_lanes); + const auto shorten_lanes = utils::cutOverlappedLanes(output.path, drivable_lanes); const auto expanded_lanes = utils::expandLanelets( shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, dp.drivable_area_types_to_skip); diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 4828a0d62e7f6..85abf774d159e 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -738,7 +738,8 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath( { // TODO(Horibe) do some error handling when path is not available. - auto path = output.path ? output.path : planner_data->prev_output_path; + auto path = !output.path.points.empty() ? std::make_shared(output.path) + : planner_data->prev_output_path; path->header = planner_data->route_handler->getRouteHeader(); path->header.stamp = this->now(); diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index c867bffc8e9bd..36d5c7773fd24 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -198,7 +198,7 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da void PlannerManager::generateCombinedDrivableArea( BehaviorModuleOutput & output, const std::shared_ptr & data) const { - if (!output.path || output.path->points.empty()) { + if (output.path.points.empty()) { RCLCPP_ERROR_STREAM(logger_, "[generateCombinedDrivableArea] Output path is empty!"); return; } @@ -206,20 +206,20 @@ void PlannerManager::generateCombinedDrivableArea( const auto & di = output.drivable_area_info; constexpr double epsilon = 1e-3; - const auto is_driving_forward_opt = motion_utils::isDrivingForward(output.path->points); + const auto is_driving_forward_opt = motion_utils::isDrivingForward(output.path.points); const bool is_driving_forward = is_driving_forward_opt ? *is_driving_forward_opt : true; if (epsilon < std::abs(di.drivable_margin)) { // for single free space pull over utils::generateDrivableArea( - *output.path, data->parameters.vehicle_length, di.drivable_margin, is_driving_forward); + output.path, data->parameters.vehicle_length, di.drivable_margin, is_driving_forward); } else if (di.is_already_expanded) { // for single side shift utils::generateDrivableArea( - *output.path, di.drivable_lanes, false, false, data->parameters.vehicle_length, data, + output.path, di.drivable_lanes, false, false, data->parameters.vehicle_length, data, is_driving_forward); } else { - const auto shorten_lanes = utils::cutOverlappedLanes(*output.path, di.drivable_lanes); + const auto shorten_lanes = utils::cutOverlappedLanes(output.path, di.drivable_lanes); const auto & dp = data->drivable_area_expansion_parameters; const auto expanded_lanes = utils::expandLanelets( @@ -228,19 +228,19 @@ void PlannerManager::generateCombinedDrivableArea( // for other modules where multiple modules may be launched utils::generateDrivableArea( - *output.path, expanded_lanes, di.enable_expanding_hatched_road_markings, + output.path, expanded_lanes, di.enable_expanding_hatched_road_markings, di.enable_expanding_intersection_areas, data->parameters.vehicle_length, data, is_driving_forward); } // extract obstacles from drivable area - utils::extractObstaclesFromDrivableArea(*output.path, di.obstacles); + utils::extractObstaclesFromDrivableArea(output.path, di.obstacles); } std::vector PlannerManager::getRequestModules( const BehaviorModuleOutput & previous_module_output) const { - if (!previous_module_output.path) { + if (previous_module_output.path.points.empty()) { RCLCPP_ERROR_STREAM( logger_, "Current module output is null. Skip candidate module check." << "\n - Approved module list: " << getNames(approved_module_ptrs_) diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index de76166e068d3..99d7931dff907 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -264,12 +264,12 @@ bool DynamicAvoidanceModule::isExecutionRequested() const RCLCPP_DEBUG(getLogger(), "DYNAMIC AVOIDANCE isExecutionRequested."); const auto input_path = getPreviousModuleOutput().path; - if (!input_path || input_path->points.size() < 2) { + if (input_path.points.size() < 2) { return false; } // check if the ego is driving forward - const auto is_driving_forward = motion_utils::isDrivingForward(input_path->points); + const auto is_driving_forward = motion_utils::isDrivingForward(input_path.points); if (!is_driving_forward || !(*is_driving_forward)) { return false; } @@ -401,7 +401,7 @@ void DynamicAvoidanceModule::updateTargetObjects() const auto input_path = getPreviousModuleOutput().path; const auto & predicted_objects = planner_data_->dynamic_object->objects; - const auto input_ref_path_points = getPreviousModuleOutput().reference_path->points; + const auto input_ref_path_points = getPreviousModuleOutput().reference_path.points; const auto prev_objects = target_objects_manager_.getValidObjects(); // 1. Rough filtering of target objects @@ -427,7 +427,7 @@ void DynamicAvoidanceModule::updateTargetObjects() // 1.b. check obstacle velocity const auto [obj_tangent_vel, obj_normal_vel] = - projectObstacleVelocityToTrajectory(input_path->points, predicted_object); + projectObstacleVelocityToTrajectory(input_path.points, predicted_object); if ( std::abs(obj_tangent_vel) < parameters_->min_obstacle_vel || parameters_->max_obstacle_vel < std::abs(obj_tangent_vel)) { @@ -435,7 +435,7 @@ void DynamicAvoidanceModule::updateTargetObjects() } // 1.c. check if object is not crossing ego's path - const double obj_angle = calcDiffAngleBetweenPaths(input_path->points, obj_path); + const double obj_angle = calcDiffAngleBetweenPaths(input_path.points, obj_path); const double max_crossing_object_angle = 0.0 <= obj_tangent_vel ? parameters_->max_overtaking_crossing_object_angle : parameters_->max_oncoming_crossing_object_angle; @@ -455,7 +455,7 @@ void DynamicAvoidanceModule::updateTargetObjects() } // 1.e. check if object lateral offset to ego's path is small enough - const double obj_dist_to_path = calcDistanceToPath(input_path->points, obj_pose.position); + const double obj_dist_to_path = calcDistanceToPath(input_path.points, obj_pose.position); const bool is_object_far_from_path = isObjectFarFromPath(predicted_object, obj_dist_to_path); if (is_object_far_from_path) { RCLCPP_INFO_EXPRESSION( @@ -499,7 +499,7 @@ void DynamicAvoidanceModule::updateTargetObjects() [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); // 2.a. check if object is not to be followed by ego - const double obj_angle = calcDiffAngleAgainstPath(input_path->points, object.pose); + const double obj_angle = calcDiffAngleAgainstPath(input_path.points, object.pose); const bool is_object_aligned_to_path = std::abs(obj_angle) < parameters_->max_front_object_angle || M_PI - parameters_->max_front_object_angle < std::abs(obj_angle); @@ -513,13 +513,13 @@ void DynamicAvoidanceModule::updateTargetObjects() } // 2.b. calculate which side object exists against ego's path - const bool is_object_left = isLeft(input_path->points, object.pose.position); + const bool is_object_left = isLeft(input_path.points, object.pose.position); const auto lat_lon_offset = - getLateralLongitudinalOffset(input_path->points, object.pose, object.shape); + getLateralLongitudinalOffset(input_path.points, object.pose, object.shape); // 2.c. check if object will not cut in const bool will_object_cut_in = - willObjectCutIn(input_path->points, obj_path, object.vel, lat_lon_offset); + willObjectCutIn(input_path.points, obj_path, object.vel, lat_lon_offset); if (will_object_cut_in) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, @@ -537,7 +537,7 @@ void DynamicAvoidanceModule::updateTargetObjects() // 2.e. check time to collision const double time_to_collision = - calcTimeToCollision(input_path->points, object.pose, object.vel, lat_lon_offset); + calcTimeToCollision(input_path.points, object.pose, object.vel, lat_lon_offset); if ( (0 <= object.vel && parameters_->max_time_to_collision_overtaking_object < time_to_collision) || @@ -561,13 +561,13 @@ void DynamicAvoidanceModule::updateTargetObjects() const auto future_obj_pose = object_recognition_utils::calcInterpolatedPose(obj_path, time_to_collision); const bool is_collision_left = - future_obj_pose ? isLeft(input_path->points, future_obj_pose->position) : is_object_left; + future_obj_pose ? isLeft(input_path.points, future_obj_pose->position) : is_object_left; // 2.g. check if the ego is not ahead of the object. const double signed_dist_ego_to_obj = [&]() { - const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(input_path->points); + const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(input_path.points); const double lon_offset_ego_to_obj = motion_utils::calcSignedArcLength( - input_path->points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); + input_path.points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); if (0 < lon_offset_ego_to_obj) { return std::max( 0.0, lon_offset_ego_to_obj - planner_data_->parameters.front_overhang + @@ -898,7 +898,7 @@ double DynamicAvoidanceModule::calcValidStartLengthToAvoid( const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const { - const auto input_path_points = getPreviousModuleOutput().path->points; + const auto input_path_points = getPreviousModuleOutput().path.points; const size_t obj_seg_idx = motion_utils::findNearestSegmentIndex(input_path_points, obj_pose.position); @@ -1027,7 +1027,7 @@ DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( return std::nullopt; } - auto input_ref_path_points = getPreviousModuleOutput().reference_path->points; + auto input_ref_path_points = getPreviousModuleOutput().reference_path.points; const size_t obj_seg_idx = motion_utils::findNearestSegmentIndex(input_ref_path_points, object.pose.position); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp index 3dcfdcc2bdcef..d52906ef4684f 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp @@ -119,10 +119,10 @@ struct BehaviorModuleOutput BehaviorModuleOutput() = default; // path planed by module - PlanResult path{}; + PathWithLaneId path{}; // reference path planed by module - PlanResult reference_path{}; + PathWithLaneId reference_path{}; TurnSignalInfo turn_signal_info{}; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index a5e2c3245f3c3..0ad30520815e8 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -405,7 +405,7 @@ class SceneModuleInterface virtual BehaviorModuleOutput planWaitingApproval() { path_candidate_ = std::make_shared(planCandidate().path_candidate); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); return getPreviousModuleOutput(); } diff --git a/planning/behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner_common/src/utils/path_utils.cpp index 994a7ba1a19d5..57a5743a5963b 100644 --- a/planning/behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_utils.cpp @@ -642,8 +642,8 @@ BehaviorModuleOutput getReferencePath( dp.drivable_area_types_to_skip); BehaviorModuleOutput output; - output.path = std::make_shared(reference_path); - output.reference_path = std::make_shared(reference_path); + output.path = reference_path; + output.reference_path = reference_path; output.drivable_area_info.drivable_lanes = drivable_lanes; return output; @@ -692,8 +692,8 @@ BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr(reference_path); - output.reference_path = std::make_shared(reference_path); + output.path = reference_path; + output.reference_path = reference_path; output.drivable_area_info.drivable_lanes = drivable_lanes; return output; diff --git a/planning/behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_side_shift_module/src/scene.cpp index 69df77672cd96..6df8c1ec629c9 100644 --- a/planning/behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_side_shift_module/src/scene.cpp @@ -203,17 +203,17 @@ void SideShiftModule::updateData() ? planner_data_->self_odometry->pose.pose : utils::getUnshiftedEgoPose(getEgoPose(), prev_output_); if (prev_reference_.points.empty()) { - prev_reference_ = *getPreviousModuleOutput().path; + prev_reference_ = getPreviousModuleOutput().path; } - if (!getPreviousModuleOutput().reference_path) { + if (getPreviousModuleOutput().reference_path.points.empty()) { return; } const auto centerline_path = utils::calcCenterLinePath( planner_data_, reference_pose, longest_dist_to_shift_line, - *getPreviousModuleOutput().reference_path); + getPreviousModuleOutput().reference_path); constexpr double resample_interval = 1.0; - const auto backward_extened_path = extendBackwardLength(*getPreviousModuleOutput().path); + const auto backward_extened_path = extendBackwardLength(getPreviousModuleOutput().path); reference_path_ = utils::resamplePathWithSpline(backward_extened_path, resample_interval); path_shifter_.setPath(reference_path_); @@ -286,7 +286,7 @@ BehaviorModuleOutput SideShiftModule::plan() output.reference_path = getPreviousModuleOutput().reference_path; prev_output_ = shifted_path; - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); debug_data_.path_shifter = std::make_shared(path_shifter_); @@ -329,7 +329,7 @@ BehaviorModuleOutput SideShiftModule::planWaitingApproval() output.reference_path = getPreviousModuleOutput().reference_path; path_candidate_ = std::make_shared(planCandidate().path_candidate); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); prev_output_ = shifted_path; @@ -409,7 +409,8 @@ BehaviorModuleOutput SideShiftModule::adjustDrivableArea(const ShiftedPath & pat { // for new architecture // NOTE: side shift module is not launched with other modules. Therefore, drivable_lanes can be // assigned without combining. - out.path = std::make_shared(output_path); + out.path = output_path; + out.reference_path = getPreviousModuleOutput().reference_path; out.drivable_area_info.drivable_lanes = expanded_lanes; out.drivable_area_info.is_already_expanded = true; } diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 0d3892cde8023..c9fa15d855268 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -402,11 +402,11 @@ BehaviorModuleOutput StartPlannerModule::plan() path = status_.backward_path; } - output.path = std::make_shared(path); + output.path = path; output.reference_path = getPreviousModuleOutput().reference_path; output.turn_signal_info = calcTurnSignalInfo(); path_candidate_ = std::make_shared(getFullPath()); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); setDrivableAreaInfo(output); @@ -512,11 +512,11 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() p.point.longitudinal_velocity_mps = 0.0; } - output.path = std::make_shared(stop_path); + output.path = stop_path; output.reference_path = getPreviousModuleOutput().reference_path; output.turn_signal_info = calcTurnSignalInfo(); path_candidate_ = std::make_shared(getFullPath()); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_unique(getPreviousModuleOutput().reference_path); setDrivableAreaInfo(output); @@ -1182,7 +1182,7 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput() { BehaviorModuleOutput output; const PathWithLaneId stop_path = generateStopPath(); - output.path = std::make_shared(stop_path); + output.path = stop_path; setDrivableAreaInfo(output); @@ -1201,7 +1201,7 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput() } path_candidate_ = std::make_shared(stop_path); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); return output; } @@ -1258,7 +1258,7 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *output.path, generateDrivableLanes(*output.path), + output.path, generateDrivableLanes(output.path), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; From 871c49d44c702f428f02c7cae12016983778d8ac Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Mon, 18 Dec 2023 17:42:27 +0900 Subject: [PATCH 084/276] chore: add maintainer in map packages (#5865) * add maintainer Signed-off-by: Kento Yabuuchi * modify map_tf_generator's maintainer Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- launch/tier4_map_launch/package.xml | 1 + map/map_height_fitter/package.xml | 1 + map/map_loader/package.xml | 1 + map/map_projection_loader/package.xml | 1 + map/map_tf_generator/package.xml | 4 +++- 5 files changed, 7 insertions(+), 1 deletion(-) diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml index d8f69c124526a..f75a181bfb659 100644 --- a/launch/tier4_map_launch/package.xml +++ b/launch/tier4_map_launch/package.xml @@ -7,6 +7,7 @@ Ryohsuke Mitsudome Ryu Yamamoto Koji Minoda + Kento Yabuuchi Apache License 2.0 ament_cmake_auto diff --git a/map/map_height_fitter/package.xml b/map/map_height_fitter/package.xml index f50eba9218d67..2dc864b0cb925 100644 --- a/map/map_height_fitter/package.xml +++ b/map/map_height_fitter/package.xml @@ -7,6 +7,7 @@ Takagi, Isamu Yamato Ando Masahiro Sakamoto + Kento Yabuuchi Apache License 2.0 Takagi, Isamu diff --git a/map/map_loader/package.xml b/map/map_loader/package.xml index 5230d4bd03214..c8fcce6f7002f 100644 --- a/map/map_loader/package.xml +++ b/map/map_loader/package.xml @@ -8,6 +8,7 @@ Ryu Yamamoto Koji Minoda Masahiro Sakamoto + Kento Yabuuchi Apache License 2.0 diff --git a/map/map_projection_loader/package.xml b/map/map_projection_loader/package.xml index b128c2cf15e15..76e40d4379de4 100644 --- a/map/map_projection_loader/package.xml +++ b/map/map_projection_loader/package.xml @@ -7,6 +7,7 @@ Koji Minoda Yamato Ando Masahiro Sakamoto + Kento Yabuuchi Apache License 2.0 ament_cmake_auto diff --git a/map/map_tf_generator/package.xml b/map/map_tf_generator/package.xml index 6dc68911699aa..6e266b0ad82f0 100644 --- a/map/map_tf_generator/package.xml +++ b/map/map_tf_generator/package.xml @@ -4,7 +4,9 @@ map_tf_generator 0.1.0 map_tf_generator package as a ROS 2 node - azumi-suzuki + Yamato Ando + Kento Yabuuchi + Masahiro Sakamoto Apache License 2.0 ament_cmake_auto From 42a48b58bb59ed10ffe73822a3d7533c4c529325 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 18 Dec 2023 21:11:48 +0900 Subject: [PATCH 085/276] chore(crosswalk): remove debug print (#5896) Signed-off-by: Mamoru Sobue --- .../src/scene_crosswalk.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 69440aaddc2d0..b8a34bf5a9d00 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -371,12 +371,6 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( const double direction_diff = tier4_autoware_utils::normalizeRadian( collision_point.crosswalk_passage_direction.value() - ego_crosswalk_passage_direction.value()); - RCLCPP_INFO( - rclcpp::get_logger("temp"), - "collision_point.crosswalk_passage_direction = %f, ego_crosswalk_passage_direction = %f, " - "direction_diff = %f", - collision_point.crosswalk_passage_direction.value(), - ego_crosswalk_passage_direction.value(), direction_diff); if (std::fabs(direction_diff) < planner_param_.vehicle_object_cross_angle_threshold) { continue; } From da19aaf4e7aafc1230784f2440700d32b5d1bcb9 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 18 Dec 2023 21:57:20 +0900 Subject: [PATCH 086/276] feat(pid_longitudinal_controller): change the condition from emergency to stopped (#5892) chore(pid_longitudinal_controller): change the condition from emergency to stopped Signed-off-by: Takayuki Murooka --- .../src/pid_longitudinal_controller.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 12f0eece1e477..698d4a8403069 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -646,10 +646,11 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d // in EMERGENCY state if (m_control_state == ControlState::EMERGENCY) { + if (stopped_condition) { + return changeState(ControlState::STOPPED); + } + if (!emergency_condition) { - if (stopped_condition) { - return changeState(ControlState::STOPPED); - } if (!is_under_control) { // NOTE: On manual driving, no need stopping to exit the emergency. return changeState(ControlState::DRIVE); From 7f49e672f13e47493128b52f5ccd3db1fd93f92a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 18 Dec 2023 21:58:05 +0900 Subject: [PATCH 087/276] chore(behavior_velocity_planner): use DEBUG for launching modules (#5897) Signed-off-by: Takayuki Murooka --- .../src/scene_module_interface.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp index 6f596be92ec8b..362493005eb17 100644 --- a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -174,7 +174,7 @@ void SceneModuleManagerInterface::deleteExpiredModules( void SceneModuleManagerInterface::registerModule( const std::shared_ptr & scene_module) { - RCLCPP_INFO( + RCLCPP_DEBUG( logger_, "register task: module = %s, id = %lu", getModuleName(), scene_module->getModuleId()); registered_module_id_set_.emplace(scene_module->getModuleId()); scene_modules_.insert(scene_module); @@ -183,7 +183,7 @@ void SceneModuleManagerInterface::registerModule( void SceneModuleManagerInterface::unregisterModule( const std::shared_ptr & scene_module) { - RCLCPP_INFO( + RCLCPP_DEBUG( logger_, "unregister task: module = %s, id = %lu", getModuleName(), scene_module->getModuleId()); registered_module_id_set_.erase(scene_module->getModuleId()); From 7b3e4a563f76ea10b241e2aae4a428c6a3931c96 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 18 Dec 2023 22:07:45 +0900 Subject: [PATCH 088/276] fix(intersection): generate yield stuck detect area from multiple lanes (#5883) Signed-off-by: Mamoru Sobue --- .../README.md | 6 + .../config/intersection.param.yaml | 4 +- .../docs/yield-stuck.drawio.svg | 750 ++++++++++++++++++ .../src/debug.cpp | 8 + .../src/scene_intersection.cpp | 83 +- .../src/scene_intersection.hpp | 6 +- .../src/util.cpp | 161 +++- .../src/util.hpp | 7 +- .../src/util_type.hpp | 1 + 9 files changed, 961 insertions(+), 65 deletions(-) create mode 100644 planning/behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index db26be11b1c9a..58c2ce59edd48 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -184,6 +184,12 @@ If there is any object on the path inside the intersection and at the exit of th ![stuck_vehicle_detection](./docs/stuck-vehicle.drawio.svg) +## Yield stuck vehicle detection + +If there is any stopped object on the attention lanelet between the intersection point with ego path and the position which is `yield_stuck.distance_threshold` before that position, the object is regarded as yielding to ego vehicle. In this case ego is given the right-of-way by the yielding object but this module inserts stopline to prevent entry into the intersection. This scene happens when the object is yielding against ego or the object is waiting before the crosswalk around the exit of the intersection. + +![yield_stuck_detection](./docs/yield-stuck.drawio.svg) + ## Collision detection The following process is performed for the targets objects to determine whether ego can pass the intersection safely. If it is judged that ego cannot pass the intersection with enough margin, this module inserts a stopline on the path. diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 1e6ce843de528..997addd48d7f8 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -29,9 +29,9 @@ yield_stuck: turn_direction: left: true - right: false + right: true straight: false - distance_threshold: 1.0 + distance_threshold: 5.0 collision_detection: consider_wrong_direction_vehicle: false diff --git a/planning/behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg b/planning/behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg new file mode 100644 index 0000000000000..e0078540ba407 --- /dev/null +++ b/planning/behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg @@ -0,0 +1,750 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + w/ traffic light, right +
+
+ (Left-hand traffic) +
+ + +
+
+
+
+
+
+
+ w/ traffic light, right... +
+
+ + + + + + + + + + + + + + + + + + + +
+
+
+ + ego lane + +
+
+
+
+ ego lane +
+
+ + + + + + +
+
+
+ attention lane +
+
+
+
+ attention lane +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + T-shape junction w/o traffic light +
+
+ Right-hand traffic +
+
+
+
+
+
+ T-shape junction w/o traffic light... +
+
+ + + + + + + + + + + + + + + + + + +
+
+
+ + ego lane + +
+
+
+
+ ego lane +
+
+ + + + + + +
+
+
+ attention area +
+
+
+
+ attention area +
+
+ + + + + + + + + + + + +
+
+
+ + yield stuck detect area + +
+
+
+
+ yield stuck detect area +
+
+ + + + + + + + + + + + + +
+
+
+ + yield stuck detect area + +
+
+
+
+ yield stuck detect area +
+
+ + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_intersection_module/src/debug.cpp index 8d9beb34d05ee..83e218185a5ad 100644 --- a/planning/behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_intersection_module/src/debug.cpp @@ -196,6 +196,14 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray( &debug_marker_array, now); } + if (debug_data_.yield_stuck_detect_area) { + appendMarkerArray( + createLaneletPolygonsMarkerArray( + debug_data_.yield_stuck_detect_area.value(), "yield_stuck_detect_area", lane_id_, 0.6588235, + 0.34509, 0.6588235), + &debug_marker_array); + } + if (debug_data_.ego_lane) { appendMarkerArray( createLaneletPolygonsMarkerArray( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 0d483b501d1ee..e036fac13fd3b 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1056,29 +1056,33 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // stuck vehicle detection is viable even if attention area is empty // so this needs to be checked before attention area validation const bool stuck_detected = checkStuckVehicle(planner_data_, path_lanelets); - if (stuck_detected && stuck_stopline_idx_opt) { - auto stuck_stopline_idx = stuck_stopline_idx_opt.value(); + if (stuck_detected) { if (is_private_area_ && planner_param_.stuck_vehicle.enable_private_area_stuck_disregard) { - if ( - default_stopline_idx_opt && - fromEgoDist(stuck_stopline_idx) < -planner_param_.common.stopline_overshoot_margin) { - stuck_stopline_idx = default_stopline_idx_opt.value(); - } } else { - return IntersectionModule::StuckStop{ - closest_idx, stuck_stopline_idx, occlusion_peeking_stopline_idx_opt}; + std::optional stopline_idx = std::nullopt; + if (stuck_stopline_idx_opt) { + const bool is_over_stuck_stopline = fromEgoDist(stuck_stopline_idx_opt.value()) < + -planner_param_.common.stopline_overshoot_margin; + if (!is_over_stuck_stopline) { + stopline_idx = stuck_stopline_idx_opt.value(); + } + } + if (!stopline_idx) { + if (default_stopline_idx_opt && fromEgoDist(default_stopline_idx_opt.value()) >= 0.0) { + stopline_idx = default_stopline_idx_opt.value(); + } else if ( + first_attention_stopline_idx_opt && + fromEgoDist(first_attention_stopline_idx_opt.value()) >= 0.0) { + stopline_idx = closest_idx; + } + } + if (stopline_idx) { + return IntersectionModule::StuckStop{ + closest_idx, stopline_idx.value(), occlusion_peeking_stopline_idx_opt}; + } } } - // yield stuck vehicle detection is viable even if attention area is empty - // so this needs to be checked before attention area validation - const bool yield_stuck_detected = checkYieldStuckVehicle( - planner_data_, path_lanelets, intersection_lanelets.first_attention_area()); - if (yield_stuck_detected && stuck_stopline_idx_opt) { - const auto stuck_stopline_idx = stuck_stopline_idx_opt.value(); - return IntersectionModule::YieldStuckStop{closest_idx, stuck_stopline_idx}; - } - // if attention area is empty, collision/occlusion detection is impossible if (!first_attention_area_opt) { return IntersectionModule::Indecisive{"attention area is empty"}; @@ -1124,6 +1128,32 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // filter objects auto target_objects = generateTargetObjects(intersection_lanelets, intersection_area); + const bool yield_stuck_detected = checkYieldStuckVehicle( + target_objects, interpolated_path_info, intersection_lanelets.attention_non_preceding_); + if (yield_stuck_detected) { + std::optional stopline_idx = std::nullopt; + const bool is_before_default_stopline = fromEgoDist(default_stopline_idx) >= 0.0; + const bool is_before_first_attention_stopline = + fromEgoDist(first_attention_stopline_idx) >= 0.0; + if (stuck_stopline_idx_opt) { + const bool is_over_stuck_stopline = fromEgoDist(stuck_stopline_idx_opt.value()) < + -planner_param_.common.stopline_overshoot_margin; + if (!is_over_stuck_stopline) { + stopline_idx = stuck_stopline_idx_opt.value(); + } + } + if (!stopline_idx) { + if (is_before_default_stopline) { + stopline_idx = default_stopline_idx; + } else if (is_before_first_attention_stopline) { + stopline_idx = closest_idx; + } + } + if (stopline_idx) { + return IntersectionModule::YieldStuckStop{closest_idx, stopline_idx.value()}; + } + } + const double is_amber_or_red = (traffic_prioritized_level == util::TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) || (traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED); @@ -1376,13 +1406,10 @@ bool IntersectionModule::checkStuckVehicle( } bool IntersectionModule::checkYieldStuckVehicle( - const std::shared_ptr & planner_data, const util::PathLanelets & path_lanelets, - const std::optional & first_attention_area) + const util::TargetObjects & target_objects, + const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::ConstLanelets & attention_lanelets) { - if (!first_attention_area) { - return false; - } - const bool yield_stuck_detection_direction = [&]() { return (turn_direction_ == "left" && planner_param_.yield_stuck.turn_direction.left) || (turn_direction_ == "right" && planner_param_.yield_stuck.turn_direction.right) || @@ -1392,13 +1419,9 @@ bool IntersectionModule::checkYieldStuckVehicle( return false; } - const auto & objects_ptr = planner_data->predicted_objects; - - const auto & ego_lane = path_lanelets.ego_or_entry2exit; - const auto ego_poly = ego_lane.polygon2d().basicPolygon(); - return util::checkYieldStuckVehicleInIntersection( - objects_ptr, ego_poly, first_attention_area.value(), + target_objects, interpolated_path_info, attention_lanelets, turn_direction_, + planner_data_->vehicle_info_.vehicle_width_m, planner_param_.stuck_vehicle.stuck_vehicle_velocity_threshold, planner_param_.yield_stuck.distance_threshold, &debug_data_); } diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 4c33c0960afc3..7366bdc1bc0e6 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -336,9 +336,9 @@ class IntersectionModule : public SceneModuleInterface const util::PathLanelets & path_lanelets); bool checkYieldStuckVehicle( - const std::shared_ptr & planner_data, - const util::PathLanelets & path_lanelets, - const std::optional & first_attention_area); + const util::TargetObjects & target_objects, + const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::ConstLanelets & attention_lanelets); util::TargetObjects generateTargetObjects( const util::IntersectionLanelets & intersection_lanelets, diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 1c7e366347fec..e491d2ce7c5ce 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -31,6 +31,7 @@ #include #include +#include #include #include @@ -298,7 +299,7 @@ std::optional generateIntersectionStopLines( const auto path_footprint = tier4_autoware_utils::transformVector( local_footprint, tier4_autoware_utils::pose2transform(base_pose)); if (bg::intersects(path_footprint, first_attention_lane_centerline.basicLineString())) { - // TODO(Mamoru Sobue): maybe consideration of braking dist is necessary + // NOTE: maybe consideration of braking dist is necessary first_footprint_attention_centerline_ip_opt = i; break; } @@ -1179,40 +1180,145 @@ bool checkStuckVehicleInIntersection( return false; } -bool checkYieldStuckVehicleInIntersection( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr, - const lanelet::BasicPolygon2d & ego_poly, const lanelet::CompoundPolygon3d & first_attention_area, - const double stuck_vehicle_vel_thr, const double yield_stuck_distance_thr, DebugData * debug_data) +static lanelet::LineString3d getLineStringFromArcLength( + const lanelet::ConstLineString3d & linestring, const double s1, const double s2) { - const auto first_attention_area_2d = lanelet::utils::to2D(first_attention_area); - Polygon2d first_attention_area_poly; - for (const auto & p : first_attention_area_2d) { - first_attention_area_poly.outer().emplace_back(p.x(), p.y()); - } - - for (const auto & object : objects_ptr->objects) { - if (!isTargetStuckVehicleType(object)) { - continue; // not target vehicle type + lanelet::Points3d points; + double accumulated_length = 0; + size_t start_index = linestring.size(); + for (size_t i = 0; i < linestring.size() - 1; i++) { + const auto & p1 = linestring[i]; + const auto & p2 = linestring[i + 1]; + const double length = boost::geometry::distance(p1.basicPoint(), p2.basicPoint()); + if (accumulated_length + length > s1) { + start_index = i; + break; } - const auto obj_v_norm = std::hypot( - object.kinematics.initial_twist_with_covariance.twist.linear.x, - object.kinematics.initial_twist_with_covariance.twist.linear.y); - if (obj_v_norm > stuck_vehicle_vel_thr) { - continue; // not stop vehicle + accumulated_length += length; + } + if (start_index < linestring.size() - 1) { + const auto & p1 = linestring[start_index]; + const auto & p2 = linestring[start_index + 1]; + const double residue = s1 - accumulated_length; + const auto direction_vector = (p2.basicPoint() - p1.basicPoint()).normalized(); + const auto start_basic_point = p1.basicPoint() + residue * direction_vector; + const auto start_point = lanelet::Point3d(lanelet::InvalId, start_basic_point); + points.push_back(start_point); + } + + accumulated_length = 0; + size_t end_index = linestring.size(); + for (size_t i = 0; i < linestring.size() - 1; i++) { + const auto & p1 = linestring[i]; + const auto & p2 = linestring[i + 1]; + const double length = boost::geometry::distance(p1.basicPoint(), p2.basicPoint()); + if (accumulated_length + length > s2) { + end_index = i; + break; } + accumulated_length += length; + } - const auto obj_footprint = tier4_autoware_utils::toPolygon2d(object); + for (size_t i = start_index + 1; i < end_index; i++) { + const auto p = lanelet::Point3d(linestring[i]); + points.push_back(p); + } + if (end_index < linestring.size() - 1) { + const auto & p1 = linestring[end_index]; + const auto & p2 = linestring[end_index + 1]; + const double residue = s2 - accumulated_length; + const auto direction_vector = (p2.basicPoint() - p1.basicPoint()).normalized(); + const auto end_basic_point = p1.basicPoint() + residue * direction_vector; + const auto end_point = lanelet::Point3d(lanelet::InvalId, end_basic_point); + points.push_back(end_point); + } + return lanelet::LineString3d{lanelet::InvalId, points}; +} - // check if the object is too close to the ego path - if (yield_stuck_distance_thr < bg::distance(ego_poly, obj_footprint)) { +static lanelet::ConstLanelet createLaneletFromArcLength( + const lanelet::ConstLanelet & lanelet, const double s1, const double s2) +{ + const double total_length = boost::geometry::length(lanelet.centerline2d().basicLineString()); + // make sure that s1, and s2 are between [0, lane_length] + const auto s1_saturated = std::max(0.0, std::min(s1, total_length)); + const auto s2_saturated = std::max(0.0, std::min(s2, total_length)); + + const auto ratio_s1 = s1_saturated / total_length; + const auto ratio_s2 = s2_saturated / total_length; + + const auto s1_left = + static_cast(ratio_s1 * boost::geometry::length(lanelet.leftBound().basicLineString())); + const auto s2_left = + static_cast(ratio_s2 * boost::geometry::length(lanelet.leftBound().basicLineString())); + const auto s1_right = + static_cast(ratio_s1 * boost::geometry::length(lanelet.rightBound().basicLineString())); + const auto s2_right = + static_cast(ratio_s2 * boost::geometry::length(lanelet.rightBound().basicLineString())); + + const auto left_bound = getLineStringFromArcLength(lanelet.leftBound(), s1_left, s2_left); + const auto right_bound = getLineStringFromArcLength(lanelet.rightBound(), s1_right, s2_right); + + return lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); +} + +bool checkYieldStuckVehicleInIntersection( + const util::TargetObjects & target_objects, + const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::ConstLanelets & attention_lanelets, const std::string & turn_direction, + const double width, const double stuck_vehicle_vel_thr, const double yield_stuck_distance_thr, + DebugData * debug_data) +{ + LineString2d sparse_intersection_path; + const auto [start, end] = interpolated_path_info.lane_id_interval.value(); + for (unsigned i = start; i < end; ++i) { + const auto & point = interpolated_path_info.path.points.at(i).point.pose.position; + const auto yaw = tf2::getYaw(interpolated_path_info.path.points.at(i).point.pose.orientation); + if (turn_direction == "right") { + const double right_x = point.x - width / 2 * std::sin(yaw); + const double right_y = point.y + width / 2 * std::cos(yaw); + sparse_intersection_path.emplace_back(right_x, right_y); + } else if (turn_direction == "left") { + const double left_x = point.x + width / 2 * std::sin(yaw); + const double left_y = point.y - width / 2 * std::cos(yaw); + sparse_intersection_path.emplace_back(left_x, left_y); + } else { + // straight + sparse_intersection_path.emplace_back(point.x, point.y); + } + } + lanelet::ConstLanelets yield_stuck_detect_lanelets; + for (const auto & attention_lanelet : attention_lanelets) { + const auto centerline = attention_lanelet.centerline2d().basicLineString(); + std::vector intersects; + bg::intersection(sparse_intersection_path, centerline, intersects); + if (intersects.empty()) { continue; } + const auto intersect = intersects.front(); + const auto intersect_arc_coords = lanelet::geometry::toArcCoordinates( + centerline, lanelet::BasicPoint2d(intersect.x(), intersect.y())); + const double yield_stuck_start = + std::max(0.0, intersect_arc_coords.length - yield_stuck_distance_thr); + const double yield_stuck_end = intersect_arc_coords.length; + yield_stuck_detect_lanelets.push_back( + createLaneletFromArcLength(attention_lanelet, yield_stuck_start, yield_stuck_end)); + } + debug_data->yield_stuck_detect_area = getPolygon3dFromLanelets(yield_stuck_detect_lanelets); + for (const auto & object : target_objects.all_attention_objects) { + const auto obj_v_norm = std::hypot( + object.object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.object.kinematics.initial_twist_with_covariance.twist.linear.y); - // check if the footprint is in the stuck detect area - const bool is_in_stuck_area = bg::within(obj_footprint, first_attention_area_poly); - if (is_in_stuck_area && debug_data) { - debug_data->yield_stuck_targets.objects.push_back(object); - return true; + if (obj_v_norm > stuck_vehicle_vel_thr) { + continue; + } + for (const auto & yield_stuck_detect_lanelet : yield_stuck_detect_lanelets) { + const bool is_in_lanelet = lanelet::utils::isInLanelet( + object.object.kinematics.initial_pose_with_covariance.pose, yield_stuck_detect_lanelet); + if (is_in_lanelet) { + debug_data->yield_stuck_targets.objects.push_back(object.object); + return true; + } } } return false; @@ -1527,6 +1633,7 @@ lanelet::ConstLanelet generatePathLanelet( const double yaw = tf2::getYaw(p.orientation); const double x = p.position.x; const double y = p.position.y; + // NOTE: maybe this is opposite const double left_x = x + width / 2 * std::sin(yaw); const double left_y = y - width / 2 * std::cos(yaw); const double right_x = x - width / 2 * std::sin(yaw); diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 8d0e673fc931e..33e511d911b82 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -131,9 +131,10 @@ bool checkStuckVehicleInIntersection( DebugData * debug_data); bool checkYieldStuckVehicleInIntersection( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr, - const lanelet::BasicPolygon2d & ego_poly, const lanelet::CompoundPolygon3d & first_attention_area, - const double stuck_vehicle_vel_thr, const double yield_stuck_distance_thr, + const util::TargetObjects & target_objects, + const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::ConstLanelets & attention_lanelets, const std::string & turn_direction, + const double width, const double stuck_vehicle_vel_thr, const double yield_stuck_distance_thr, DebugData * debug_data); Polygon2d generateStuckVehicleDetectAreaPolygon( diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index 3c7ba3041b0bd..d05031bf19436 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -45,6 +45,7 @@ struct DebugData std::optional ego_lane{std::nullopt}; std::optional> adjacent_area{std::nullopt}; std::optional stuck_vehicle_detect_area{std::nullopt}; + std::optional> yield_stuck_detect_area{std::nullopt}; std::optional candidate_collision_ego_lane_polygon{std::nullopt}; std::vector candidate_collision_object_polygons; autoware_auto_perception_msgs::msg::PredictedObjects conflicting_targets; From 475c545e318918a7638fb42c83b5196332fe7e9d Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 19 Dec 2023 05:20:01 +0900 Subject: [PATCH 089/276] refactor(lane_change): standardizing lane change logger name (#5899) Signed-off-by: Zulfaqar Azmi --- .../config/logger_config.yaml | 8 ++++++-- .../utils/base_class.hpp | 2 +- .../utils/utils.hpp | 13 +++++++++++++ .../src/interface.cpp | 7 +++---- .../behavior_path_lane_change_module/src/scene.cpp | 7 +------ .../src/utils/utils.cpp | 5 +++++ .../interface/scene_module_interface.hpp | 4 ++-- 7 files changed, 31 insertions(+), 15 deletions(-) diff --git a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml index 11dd050658aeb..17955fc5d0b9b 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml @@ -38,9 +38,13 @@ Planning: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance - behavior_path_planner_lane_change: + behavior_path_avoidance_by_lane_change: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: lane_change + logger_name: lane_change.AVOIDANCE_BY_LANE_CHANGE + + behavior_path_lane_change: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: lane_change.NORMAL behavior_velocity_planner: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp index 4bfd461a0815f..aa3ee0dc4c98b 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp @@ -264,7 +264,7 @@ class LaneChangeBase mutable double object_debug_lifetime_{0.0}; mutable StopWatch stop_watch_; - rclcpp::Logger logger_ = rclcpp::get_logger("lane_change"); + rclcpp::Logger logger_ = utils::lane_change::getLogger(getModuleTypeStr()); mutable rclcpp::Clock clock_{RCL_ROS_TIME}; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index de4db37571122..67506326d92aa 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -20,6 +20,7 @@ #include "behavior_path_planner_common/parameters.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "rclcpp/logger.hpp" #include @@ -207,5 +208,17 @@ lanelet::ConstLanelets generateExpandedLanelets( const lanelet::ConstLanelets & lanes, const Direction direction, const double left_offset, const double right_offset); +/** + * @brief Retrieves a logger instance for a specific lane change type. + * + * This function provides a specialized logger for different types of lane change. + * + * @param type A string representing the type of lane change operation. This could be + * a specific maneuver or condition related to lane changing, such as + * 'avoidance_by_lane_change', 'normal', 'external_request'. + * + * @return rclcpp::Logger The logger instance configured for the specified lane change type. + */ +rclcpp::Logger getLogger(const std::string & type); } // namespace behavior_path_planner::utils::lane_change #endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 4a8eb34b088af..00793532023b9 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -44,6 +44,7 @@ LaneChangeInterface::LaneChangeInterface( prev_approved_path_{std::make_unique()} { steering_factor_interface_ptr_ = std::make_unique(&node, name); + logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); } void LaneChangeInterface::processOnEntry() @@ -78,8 +79,7 @@ bool LaneChangeInterface::isExecutionReady() const ModuleStatus LaneChangeInterface::updateState() { auto log_warn_throttled = [&](const std::string & message) -> void { - RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, message); + RCLCPP_WARN_STREAM_THROTTLE(getLogger(), *clock_, 5000, message); }; if (module_type_->specialExpiredCheck()) { @@ -111,8 +111,7 @@ ModuleStatus LaneChangeInterface::updateState() if (module_type_->isEgoOnPreparePhase() && module_type_->isStoppedAtRedTrafficLight()) { RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, - "Ego stopped at traffic light. Canceling lane change"); + getLogger(), *clock_, 5000, "Ego stopped at traffic light. Canceling lane change"); module_type_->toCancelState(); return isWaitingApproval() ? ModuleStatus::RUNNING : ModuleStatus::SUCCESS; } diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 3adef17fc3b4d..f0972d66416c8 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -997,12 +997,7 @@ PathWithLaneId NormalLaneChange::getTargetSegment( std::min(dist_from_start, dist_from_end), s_start + std::numeric_limits::epsilon()); }); - RCLCPP_DEBUG( - rclcpp::get_logger("behavior_path_planner") - .get_child("lane_change") - .get_child("util") - .get_child("getTargetSegment"), - "start: %f, end: %f", s_start, s_end); + RCLCPP_DEBUG(logger_, "in %s start: %f, end: %f", __func__, s_start, s_end); PathWithLaneId target_segment = route_handler.getCenterLinePath(target_lanes, s_start, s_end); for (auto & point : target_segment.points) { diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index b5a4fd15b4c6b..9ff4ed95e09dd 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -1159,4 +1159,9 @@ lanelet::ConstLanelets generateExpandedLanelets( const auto right_extend_offset = (direction == Direction::RIGHT) ? -right_offset : 0.0; return lanelet::utils::getExpandedLanelets(lanes, left_extend_offset, right_extend_offset); } + +rclcpp::Logger getLogger(const std::string & type) +{ + return rclcpp::get_logger("lane_change").get_child(type); +} } // namespace behavior_path_planner::utils::lane_change diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index 0ad30520815e8..62dc690e6ba28 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -362,8 +362,6 @@ class SceneModuleInterface std::string name_; - rclcpp::Logger logger_; - BehaviorModuleOutput previous_module_output_; StopReason stop_reason_; @@ -581,6 +579,8 @@ class SceneModuleInterface return std::abs(planner_data_->self_odometry->twist.twist.linear.x); } + rclcpp::Logger logger_; + rclcpp::Clock::SharedPtr clock_; std::shared_ptr planner_data_; From 7e966dcfbfe159c487cf4f708aa980f60100b427 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 19 Dec 2023 06:16:57 +0900 Subject: [PATCH 090/276] chore(map_loader): visualize crosswalk id (#5880) Signed-off-by: Takamasa Horibe --- .../lanelet2_map_loader/lanelet2_map_visualization_node.cpp | 3 +++ 1 file changed, 3 insertions(+) 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 082dc95d6500a..e14defcb47f26 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 @@ -224,6 +224,9 @@ void Lanelet2MapVisualizationNode::onMapBin( insertMarkerArray( &map_marker_array, lanelet::visualization::generateLaneletIdMarker(road_lanelets, cl_lanelet_id)); + insertMarkerArray( + &map_marker_array, lanelet::visualization::generateLaneletIdMarker( + crosswalk_lanelets, cl_lanelet_id, "crosswalk_lanelet_id")); insertMarkerArray( &map_marker_array, lanelet::visualization::laneletsAsTriangleMarkerArray( "shoulder_road_lanelets", shoulder_lanelets, cl_shoulder)); From 1fb0ed0958b89c63c4882fec3d597ec58dfd9554 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 19 Dec 2023 10:13:08 +0900 Subject: [PATCH 091/276] feat(dynamic_avoidance): always launch the module when requested (#5900) Signed-off-by: Takayuki Murooka --- .../scene_module/dynamic_avoidance/manager.hpp | 2 ++ .../src/scene_module/dynamic_avoidance/manager.cpp | 5 +++++ 2 files changed, 7 insertions(+) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp index c02ee88d3fa3e..9e08f309a78b3 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp @@ -44,6 +44,8 @@ class DynamicAvoidanceModuleManager : public SceneModuleManagerInterface void updateModuleParams(const std::vector & parameters) override; + bool isAlwaysExecutableModule() const override; + private: std::shared_ptr parameters_; }; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index 2824a6221591a..ca0bc070d0fdb 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -255,6 +255,11 @@ void DynamicAvoidanceModuleManager::updateModuleParams( if (!observer.expired()) observer.lock()->updateModuleParams(p); }); } + +bool DynamicAvoidanceModuleManager::isAlwaysExecutableModule() const +{ + return true; +} } // namespace behavior_path_planner #include From 97a2d12182aea349173425dc88d39ca7d96ba811 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 19 Dec 2023 14:04:16 +0900 Subject: [PATCH 092/276] docs(raw_vehicle_cmd_converter): update readme (#5822) Signed-off-by: Takamasa Horibe --- vehicle/raw_vehicle_cmd_converter/README.md | 24 +++++++++++++++++- .../figure/accel-brake-map-table.png | Bin 0 -> 409971 bytes 2 files changed, 23 insertions(+), 1 deletion(-) create mode 100644 vehicle/raw_vehicle_cmd_converter/figure/accel-brake-map-table.png diff --git a/vehicle/raw_vehicle_cmd_converter/README.md b/vehicle/raw_vehicle_cmd_converter/README.md index c033f4348b927..5767c4fbf672b 100644 --- a/vehicle/raw_vehicle_cmd_converter/README.md +++ b/vehicle/raw_vehicle_cmd_converter/README.md @@ -1,6 +1,28 @@ # raw_vehicle_cmd_converter -`raw_vehicle_command_converter` is a node that converts desired acceleration and velocity to mechanical input by using feed forward + feed back control (optional). +## Overview + +The raw_vehicle_command_converter is a crucial node in vehicle automation systems, responsible for translating desired steering and acceleration inputs into specific vehicle control commands. This process is achieved through a combination of a lookup table and an optional feedback control system. + +### Lookup Table + +The core of the converter's functionality lies in its use of a CSV-formatted lookup table. This table encapsulates the relationship between the throttle/brake pedal (depending on your vehicle control interface) and the corresponding vehicle acceleration across various speeds. The converter utilizes this data to accurately translate target accelerations into appropriate throttle/brake values. + +![accel-brake-map-table](./figure/accel-brake-map-table.png) + +### Creation of Reference Data + +Reference data for the lookup table is generated through the following steps: + +1. **Data Collection**: On a flat road, a constant value command (e.g., throttle/brake pedal) is applied to accelerate or decelerate the vehicle. +2. **Recording Data**: During this phase, both the IMU acceleration and vehicle velocity data are recorded. +3. **CSV File Generation**: A CSV file is created, detailing the relationship between command values, vehicle speed, and resulting acceleration. + +Once the acceleration map is crafted, it should be loaded when the RawVehicleCmdConverter node is launched, with the file path defined in the launch file. + +### Auto-Calibration Tool + +For ease of calibration and adjustments to the lookup table, an auto-calibration tool is available. More information and instructions for this tool can be found [here](https://github.com/autowarefoundation/autoware.universe/blob/main/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md). ## Input topics diff --git a/vehicle/raw_vehicle_cmd_converter/figure/accel-brake-map-table.png b/vehicle/raw_vehicle_cmd_converter/figure/accel-brake-map-table.png new file mode 100644 index 0000000000000000000000000000000000000000..c1e756ed9a363232ff25f4fa429a919c6ec340e6 GIT binary patch literal 409971 zcmeFXRX|)#ur7)uNN{%v5G1%egy6w~LvVK;Tm}p7?hqtcaCZqZ5G+V=8wPiGxs&YV z-}l_-`*`YQWcBK<{_5-M>Z%U^s3?v0iue@_3=EpAjD!jd3<5k13_J`H0`wnbFu^$V z;|1WotQrzje2`4TpudS+B(+>r9n4+ajhxM3EbJZZ%$NZt&Sqxz080m#WB4u+Xd_N5 zH7yr$XEP%gD+hZ@H7h$a=$|k!9Bdq%n=SS199vmoYa*#2DE=-2aemV;W&$zhtg8xu_Cz z*MxO#a=yQYWtV>9qp0_)-gspZYyyDJxo3ofLsh7TWgm%$+o5AH<*vu%X{GRs&+BtJ zfUyeRyXNBf3Ot=s8x(f0tv6W)33mjYiQ*2vFZWj~U+?fqKlUYa1jw;wibb4G?Bii! z#orXN{SVh^(7BFvhecN((Q?&TgS_~mqDo>S8W8KeERMpqkTD_XOim^`QX&9`}2K2Pr|i1 zQr+iVpVLM}%i36U_=m)n z<(6U18hoRvFK3lQa`KVK&*$KWlUHeFndx%?3tYb@V50sa_Qaf)U$tthsw+{_VY-K0 zs2jx(7*EzfW>KyS?K9lq75ra>sZmVvPi`rMM*0mfz~iLi+D>Q6qQ^^J$%x1IbSw4v zCmqknZbiwaeI+U~!?}Hz1`n%CY`qwS&Avm$54;v~^~LFB*?80LlJqSuUwUw&E#L>=k{(q z%a8G~P0c2REW805E|Zf!>=p1|+FFti7u}}JiUGft<_lknd{QV{l(ydc=`De%deW+A zkuMMJSr&%+vPA*<<@a}7jkw0U4_C97pwdu z8Tzde6knX`zz!~M?ulO%11F|zMrZVjJobwL@vBs9GJoHq{t;b=Wm4RzOhP( zUy29>@sRty@(k`brO8g8IG&K9P(ZZaMb9+dz>mw#jZnX7@F3$A{nO*US zeY|9LdD+|C!LWfJ^VR1{lF7gcFIBHTjse2Kr%%vIMpkGKLeTd(vdRGh(T)#Gidv{& z$PPu38;sqeq&hviY66DZOE)ZTFlPCF>W{NN?QsB4>Fx1pI(@1ebOsH;+?@%?DQrIPD90 zb@n(_?Vgy6^2RfgDD)JnjyFZ$zM11ZpZ5B#2P9W1FK!#D$ua;~a}*-R3#;nVecO0X z7w`4A`&0GTnnDjY}Fa|yo~ZYcu9Qaa`GVVmw$Thu4+kYvD6B$UiF;rP7>t7Ic72u zT*vT(e2?D!z>EBO=(_pXz3S&NE4Y<)X{=(_U|>2yD50GeUby05zBXj_`3{()_xx7$ z85URZhTEN)MWjODursI}cth~8(Up@|v~09jTXkMhrQbU(Ych!HQT=|Ii*#;CuIu@w zD9{q#M&k+9;RAl~H88n$2&=B&0fi?8m4{rT#c9caaj@$_g>QnLTX_27NyRfTtRH5bWA zLUN+~o*84>Er?g!peflxzho^%^6QPNFolocw*ZT$`W$=2NluXSP_o?6c}^*^Gb-v* zvn~Rr>3FMXHS6AXKI=0zubx0^AQMLXlQ~aUb%Mdlvv=c+`q`r2Gdp^cLVBMk^3h9Lt zTERwz{<^M>E{zT`2SX}e;1;@lhxuz9=}pX&jL+g7T))(6uS%tF4k--4x2umy$OO70 z<6T_$sJ;Zy9W5d3U!0v4mpQRLZZXz3(XRJP?7Rr%(Q;OGW83l!U*(eZ*#5AQ>7q?* zGCXE7=DAsjzUtKA@ZbQv`1xs}LY}4b4#j7C(XaQQX186`)eqTBwTO*&^h@1sXnX6u zEAaH&cFScxE5&kvk1oFJB2V?+I4hvqB(5+#7Yq`8Mr6rNa-HUShcjH{v{LUw+~gDZ zJU=s5q^WVXerG1%ZvOow+9>Jr*_YLC$pe!UfIaJbWPfzKzlmGaDXKRyGQZ6(Fq&7n zbzi=EO&crJ8AC##XsR|4o{KIsMqkKAOv`OmQoOjSK+D?XpP#=ZzDf%Dv0Y>N^nypE zGn+TpU^K=-x4*v>6jK=5Q`R8VvP(&baI4A+iI5D=nooB^@6d_c%XZa$9Q6bHJ&#t% z4+_-#sxpv}eKFt0FQf2_y!ugmtDr|Ds&y%Tq^t5B{1v5W)UdWIM7_!u(rt+GYjHIX zxMn?>5UVBp-KpeLQ%r^kA+H|?1cXP?DdwIfvf_J*wh+kXbYv`YAIu8)H6kCQTa?%C zBfv?wiG$weVJ1!YSivme50Rk%eL#Y-xM`LB6Nl0Cc+`$V%HD9w$Xyv?sGS_BE{2hB zyXNWnt)HSX^Bvh1jpdBj*B*csFM#?UYglF8RHiW*eZOXX&(bIj!-g||c&6%)eT^)N z-;4NoyVP55*QliTWqByZj-+(%*XPX_T6edCEeFuHH#jmB4QXx1pFWdh#sqnLdQZ^` zgzyd^Yo7e`Ca4QUFZoTyps7s=8;*O3vTy?W;9j8508Wmv20OsEp4rS421MytnW0VmIN8MHN6z zIFqB#$%ri;P8rgK>=Kbr7kWTsD;4*|*GZSmfWsAuW#P)nEScg)vh0 zt16M`)}Sj!zKbg=90E&Ktp9lA{@lkw$3$)?_SM^=D$l!J^@kfj<_SwtsEgxg_;KIz9EO+N%z7+EF>trQ5w1tLt4FcJRG&r=PWTn++$y zF?*K7B5qC6Fo`Q$!b0~ypUpG}!f65F)eckSUd;ZK_uuyY8R#mQr)QOH0GvVSgjW4Y zxE@M(UhYp?5ea$+goK5~--1_ikT&ji__U<6Hw``7X|@Rxv2HxtQc#Met;2qgsDR%!ktJiy{ z$phG5`ihG7)MTZ9Ps4hIwvN8>QRJAzJleAhXMXqai{J)~a>lj8hUl{u#LCZJM-Qd= z6+BfuQcn*h%u_vAf*u_OtAodstb(i9H%WR@THFX25ibGnP@sLr3pk)+`>XDGqoO3o zq5NB+vke3R8^+s9zpBkCQ60qu*tzBQ^DV(?E|+(P90u+Cug2Uoz-}$(b86 z$IZa~a@w_qumJN^l{oV5>4M+6A7||Uf(h|?bzVm+FtyOHrQR5Ys@h_RvH5m$w>6|i z-Nw?Ll!HUAc_ZSDDftA${v1yuJfXcaXvB10ogm&lLwLUb97Sp0_3C7rJ!bQ}qvGjG zNI1KY@v@VA7I>S)HiodpzQverGb*-LGP3#00ej=D=Gj>8(e~)E?!Y7!2Dq`q)~hXW zs}d;~#bL8Zn?kpnKW9$Qq0UR3nZ=Lz%_e|;^wDs~usJc!ZOGzgBFWQMzbi-K*uKEo zo%_D5Y|ed+(xK~&j;G^_3nMyvhJvF-Ver)Z0gYX?I-HL803P*KamCssigWCpyZHwmZIPfLG2UPZ!O86Ni3tl6 zAK<*TS(yAmRy?~K+(V9FyI)x4PStUNq2(ViyWhW0)XFR`OO#PE(8!E{*oKt5Av}if z2PUo5=EzJYDYJ9{MkkLSY_1E^sdfPbbsE(t95znp$MqEQ=sH8Y-P`Y9kr4OZa89NJ z!7oj-PK?lbiC&uNx~US$Rgn}n)Z_%+U)NQcizefdcz}ZmJl$s(AC5Yu5ZViFN8MAw zk;he1(3y@=jWYe&mZ+RRsc4_IWD-&MU)}k(cUYk;r}S5HS1C`-p@oD7&#n&kO&55Z zEWd=L$8EyWy?1aBj<%cN{FKa#Ny#gi=nw1WfOAPkcRUcwb5z{I`s!wAWRRBH*YYv2 zd>zhN0lpmR@o?1Tg1k-U4Ad=e0>0E_rxry69hogpjeivUIo4?BP~&TW$biGLy%i}Z z^3*z3LYZmc8<~PsXsT#FmNilAYGUsJw-KE_nDr(VaK7C+vikJ={M}dd0eyHYDx^~& z$LGY|7OmefH#{s%X6e5JOa_Pf%6Hegy09yrTJL*&>kJ!@%?9_~12mID)~%v_I>5nX zcZlCBg7GnUriDz5TEL<{72R!=3|jZgMkU4!3S0O{`iydDKL=k+$i zWV>d=Hy8al-A)JSvOZ#yt(1oZO<9QNR_@Xt>(x+1*>)UdlEX5zc{Z z!%-(by651NFiCRA?xWl8k$tg^8U{^(e?_*>^o?^ z!+umdUKzXkHC|)CC~`;5V>Wzjto&4?4D$}37kK-s7Imj|wRiZNX5Ida>_)d|ec+`# zFMFvi5AVvYoV8+s!>r>ro7s<-Nzrof7IAdP&&>A)Ad1&VT5UH&;|Av40TqV=j<+OmM2RHAq4<<&NZ#~hL0 z-QDf%S{IkvGj=^~%{Kc15Lq1X>sany4729+-B11UZrRdVHFI)$r7;fF5V=tWKAn71 z`^7!6G9l(|!>O(_d)}?oIj(x#2v%T);NLSkM%x|M zH*rmI-t^=h@1od4&d=+@E*eg^_Cn`A;u!z<{*{Sb6v0pT+Fi$XwK^F7F^KSpovGDy z%gG?wYeh(kUFJUE75Pnn*Xi6hylLKs$@ygk2M3I0z3h6fBa3AmzxDaq#-C;_gl z0i3RptWd8{hrcTR_D{qrA)5eCoj?)EPuD`;G>i%4UFUNkDYB@A(JQX4UZ{ zEMnkusKrXzI@s@#mL&IHIC3jn8kmx5C{2y$(9zSjXia!w%6T8L*nFL1qeRF;IxNq+ zStQu?!PS?f%hw#o;bBXT$?sStg(XAMDJ8e_3SQ0DC;L*zrp9-EMB9te@4m^PPzbVv zaT48??APLsvU&qrJz44GemI|XKkJK1m(SLXnpl+SFXEloo|RL%@~G@QB=PaQMOA4p zW|=%xGCoM!-9T9RnrB7*>@~jJE>fISZ^#Qcy2CSQtKCUswdF9l`;jcvysIpbudEy3 z#H7y=s~qekBKfgCCHnZlh>fsc^iG8(V@vdCzui;QdAvzP9Ma)uxNXw~X4IKw16(l` zDUwTm>XxqVN`x0|tZp$DRPeQzQfkX`cz!G%iroM58_Y4De^D#NdrIa+PfaGH>AE(4 zK0|mbUEna9{6%&<9gp7t+QU>=G3O>&^z7`8S#7o*Wb)h*W7yY&gA^B^4BBWJPOGyd zYVtk8-%=QS_~^Qsq(9cwd2C_3TTrfl&y(!E0;xgNrz4D6KckC}Pam)M)a2OC-(0$C zQL1ac;5&989BJ7-zUg|RBL8$N$y)tG@ZgIrZh`nb>DTUvsz zjslP4MXb?8a-yT#4ol^gqtK);Y;iINpi>Yt$68Y#w zASEwzbVd!4x!e%B2j5WdcF{?JV7kTOwIuO_HZ?AN{qY^0_tj^Vn;%Wj$&5OP zL+Q>>P9i-t7H8N`d&d@zo6&-E>gsZG(ilBq!NUZU!kn=aZ@$Xsip19^E+Kotr8Bjk z`YH4H@h1zqt1kZhpyY?t4m-(-!jP^e<+-ah`5>(%3y~W&@7EKhbkJtC>gOcNbni>V z4#^CZMY+j5ehl+uY@C|r_6H-!fejI zF2&88r0AIp-t{GJP}34!*$GR9<>>iXXlAO+SN3_bHXPUV z>srKd)^AdZAcR2p=yaR@=YT3fgWo88rp@yBo%*x0#o4Gg#hOm8aBg8N*Bf9OqJ2(x zHsd}K;EDTTCqVRUNSng`6ykwn2h8qjy<~haS9r5kSXI+-CPJJ30qr;8)j#RU{2oL? zLMln-Q1xM1^eNqKc>MD@%jO8@6;nMqc zZ%f3)5^9?t>Q*89O^QMg z-pZhCG+QsTHwTw6vk^K~-#6AZm7*+8$h?D|gZ^c* zsn|F8jELPTAOX1#X&vxua*8HuyS6OtXNpgo-c2fN!c%}H!TO`c5v8NskrThRmOVt) zQ`_5qiyMG(cTK79W9pLUB0Sf;G%H3)rXRH9iOaub)4nL9J9-v_5rSvh4}dvJ=HfIf z0w$x~bs|%bF;h%K4%b_Pn@`Huh) zjt58w^Th!6QlW9rKapvltPl7N(qH-iqgXp=(A{WfyBOn2^rzEe$-njA!BA6ed_ngk z)6op>i;IiCR?`1DM>>OA{}x+3jG+zO4%TA*9;nI4$S$t00sVNIYv;GddKtep9z@># zSC_%a%g+x)r0|K$$RKWQZJnz&f`>{Ci`;M8Y!qIY{ttMARtvReDA&vG6cd)X{>lYX zPWOjRiShARkRQJrN+|v-P7gA?2ojsAG8nJ&d$b`1^=vw`JFQFDw`}5nkdrgf%lR`r z!@sf{fB4v#qQ2)QUXJ$>KeY9s8>j1@T4mRh*ULYpZ*1Ow?uRrK!dKtWaJmG5Mpw%M zfjyK(R?a;y2^^PQXW7k1(zH_lMAgm<|Gm)bM4FM2;jvd*>;cu4h>);*)7j~EGquj= z*4Y^VFwx8Zqf2Q1-$G<8H5=T&y8s)6(b3TlPuE=*pct~x?_c|fP%vtg8_w676&4ou zwF>C~cI!=n5f{tfDX%V)d3r$?;OcK$mgR#Z`18WEzawL7%Nz!3rIw@C{WN}ndDJ(Y-^%a<{z5v)Z)Irc zzn$xsGpp}?c!C34XFj^VmFZx<)a+EltoTO{)PKR?c9smy_cHZwT21z3zP`R`MMHrv zQJSw7Y#3NrVq87{Fxuk3Sr((BqB=f5UaKlAi_znLhZ<_=O{(K4_bha_IQwV6yOtPx z^>_bv9@{xQ-0ZwRGMTN^WtqkO_vB0io^MnzF`>o~ zzQAmAKOS%*O-M}CZuem4U3S3lHP{?hgiw3KoLv9lLP7C&rU{OuAaFl{f$8Pm zulo9Wn2#D718BTU-AN3pxG(+~l3)5Ssc3MAYk#ZE+HrvmH7Q|;n6@@i?%i~88k0S7cZYEPZC5(*na*%%4!{Y%de_Muo$3T8A zFOT9V3H2;A*dPbLZ`Nh`F+AL|U)eVJ<41&R_#chgzy9UZdIofv*4LjL)Qz9r?N{NT zho0X0jAU>}j{7~G7Zw+TS|xsSDn9KWPn;?$D`Sdtff>;xyx7rFvWkl4LkVw|T&5Im z9-p*Q>3(<5LG?F15Z|n>r#Jc|nQ^|+j-=5pF+F`~@~fP7qiuTNAI}$0{a?d+6A(JN z=LVLwwKdG(=;-F&w<>e+_h9JK1U2&gQ2|TpFLZs`(6MWsH$M;)6T=J+4?_}jA84R7 z7ZJ&29r*Q!O;P`fIyClkjidWjU1Lxsc6WAQC^Ep)N7qXr!u*mhnuR6%`W-@nP_|6>wXRaI5&tbt#4agJ9+P7b*)3qc~S z!g`G0(U~ zm0OP29>Ywzwm1#;YfL0ZXo8~Fxc}Avcv&inz`qI;#qaI!YqvPR$>enysAYl+fQckv z-75Q5NkvB|9r-fyH|Kni{%O$1?{PvID{@B<-D|pQnV?P*$|rtJJy$#{E2|n7rQfTT z=IEbEu*_CFeT6Q5iXY6^A%dJ>ns2ut{Crj4(&TG~x;!tVB< zC7i(Y8&u~I=rVS7<&G7;LPRI!gYh5Vh5&N!NeT4%c>m}1!Im+|>H4XMvEG1zyb?kd zEu(df(=r0-l+jbd%d{e*{RG8KGi}16@KPA+*Yh!A2AE!mXystr@ptzEGo&C`@q4N( zQc}d1&D8!u@CyXgfk9(<)WKtTpjx7Xa`0tC)#SyQ%Zw?y$t=)+# zf~g)ZQMBZTQ+@evyr(;a3QR@2aa&EYr*tz;pFV0y0D-{r;hRVX)EhQb#}?h@W&066 zFQFFmXAzFN+QG4*XjcYj{CYQ?2cQClpv`OShESG}b^7uTYK?YAgy!$FPu3HI%;qyx zj9)mCB7$nz6%He{0Jh#cw8KAJsAg;z2iQ=v8DSFXiPYi+saG(BNd3~M#cpT|?{~5#1u3^>zMDRx#jhGR+M1)B)hGPI#wt9snZO z`U-qAwCY81Vy~?7Pn#cgA;V_hKTp)KY(_b?LEIxKp$R4IYo^85xHYgcr;8hAEiy{b zI{mNy7zm$>tIHb33nZF1{jFJmPc+zh1s%}`S-MO1*=NR9j*f9XPe6{kI&Natfjcj6 zn4qNTX{}Ue#X9E9oE-ay02pAG=*(tc6b=#P(glxf&@q@6DFj7n!K2nWHO_Pk+^1ap zj*YOet17kpfV2UC-0ei_<=qP1Y-!#UTjtWjEY|KE?)Fe1tqF!ME=zFmv30Ml!D!F( z*RV*AK_BiO?hfpqVT!`H9r@b^0DuE0FFofnwVQl$%vL85CW7d!dQUL3kHtc0j4>c13#K!KK) zjQ6})T+_1?KYtEop|~g{B7Fzv*%Vwv(L_W@8D*Thl2J;3TQUg8BmML(3Vg|IX8KdT zOa{&=9bHx==mIzPyFXzqQz8vTAwtMia9<3LE7r+eVR5tUL}yrOCru(vmAF@gPPQp~ z$^kDM8gv@?XLB_7uepa@6^|mHRur!~&vDV(c-QCfVNB@8&4*mw*RDKFbe9dxtH){9 z8f2ADOS0u)Cg`E>tWj9A;vw{jRxy64#ZXBc0n{!lNC?9w7J}V0*A3`RF;=BBp(Fn) z#@a?_g{vSn?3++8qoG7xjKD^gu6Bf6Lai$=Y{V1D-x!P+Z9G4Azm446%_T3Nijr!D zZ4m^I;~!+QsMQ#3$3GVXPe@o4VAbl_A}@cKR5##cYs>gyx^|U9g1vn%+X|fwhnV5~ zlz&=E@(`jsM9i{ePhg*FuOWioi1&s#`m9IK$go-0V~M3ffjS&wxQL%(XR?SscG5y4 zG}oKrs-)8Kr~tD>&YC!;Gtxfn5Z+b{JBAlyXQYjf&(dx`J27h(BkZF~+`L3SO*)X< zJG&l2600-of!tdY8l$t=rB9AHTv#IuleJTE)V48lB;g9CdWV35|1dLARs4PEg-InRNgv zDq9B)K{5b%OL#Wv+gd{mOG@{lx+`)fM8KLPWB1^Q4!0&;DoA4S8gs7_kuol8API%V zWG`zN_eGQzzFxFu4i;3*HH@X457JT%wIuKwNl?~ z(*(mN7}^Fdk4|eIe#vjm5i3spF@!TXBu~vRmkm!H51D&$FKA_FmA6VyDaxAYk4VZW z?=CHT?|p|Pi6)dNop{9g>(sN6pGTuGbqn5mUR7OArz?n+Ke*l$gBHIL!bTW{8NEcn#?KW4%FYtAPLRG|GXZ1n9Tyc8M2bYvlVwI{iW~Wp_?dHv#9s9cu3;WI zK-O}W)hKLDeiFUn%nta3K+$`g{t;mec`%j?D^ zao=-2_i0{2+=MZ>zrV0FcZ~^9eTei}!L6o#l+T_fr7z21X5uV!)xusACPDT2G_h!G zyl$k2N4HtkIgQIzAeab<%J|;0I<+x`xa^yC=?Y{`R>9(f5eNBKQ;Xc;Al{C&+ETNP zuN|VslWfb)!uGB{zEP-3Z;9q1>FhReA|VbyH2A5_o_(iMy9j>7>fMrx!m`!?eFxY# zI3TdgVR2KdH9Zm=>SXO%x`+e+8?$Z5fi zsm03cla7Q4DU^2~%LCAf_cE*wlq_cQZ{-h&Hj?gm*tlOqR?c@U3UJUjF0o&QEsQXY<* z7s76-NY+Qz#jA$u<9CcW=WxvmuKqc8Ax4I+?KcmwaI#NehJYyW^X}ra77;B=Z0tJ~ z7>ZCSN*jYH+!&mf#i2p!4K6xFxY6X17S%D2g0pNtm*L(?X~1q9IO7z2_yKXNSpy`( zqt7))+v$YH@+>;77_35zZex6)S5s47{wXoE)&jyCsq%R)>-5mj_l!W9kPVJ620jL$ zK``e=inyqF5gNzTsrXlhL{Tx{ z_c^2>WM|+;G`4AK~N61wXyY)Ju^Aw!ZIqn)5AgSA+RJ_H9mGzOaB3n#Gv8c-kQQ>}; zeQq`w!dGa%QES;xFvLO_ZPkixyNK~Pq*!t&Knf=jbm4wnU<_cDl@;$cXPaLmPQ#%(BsX4_T0Bj&cTn0$oF%Z6SPH z;AchL(1nb?CFuV3#qD#?kyn`;KcD$4Psj&`%#RWpWdzhcF~6?;M9J2VbHHk(S=9IT zq}`3ObE?DaS>T=*;Z!S&D#5VSJ=#YlqCT*h?+{lI`S~X7KN0U+?uV8qu;UhaINgId ziX1tQxp-7o=LY697)?87fhgR&E2v_P6*cXeAl!TF#hA_gg+4rVhUw7;juK32OWEo&92(?_vOs`mt z9b|3{3-F=!#N)wZ8GT|6Ca)y=(3MTF@h8-+O5Y3{~E=6bel9V~T=akY;!xfO=xkCs$VoJ3F$)VY|TnnMq2{$|6JzPgoRD zWX2e|&yMS*z5?8!#_Awn)R6qo;@*~rOA%yf@Ns%e`b*OCO50E$>VQzK8zIkgLJ6EgB^>P6+aI@UOmsfqeX`o& zl^Gg0_K^}83dm!4i(}Uo`u-c(ZLpSo#G}=MFB$A;azj22&1ZsM_qc(>-+am~{0_s9 z6C-~(jv&~Ri|TlQ1g`Yjv$nR}zvLXiD?I8JlNUrK=Z(+7FT>#B=%mS=u(Dr5c0t=9 z1zhoQ5ew@t&@Q@#u#9wA;o>Tq+$9-LKC)z4hFuN3z0&wqS3KFbkHKcU=^0;qKn6fI_WPV(;Xk98;+rI z#_fERfpsIx49eb%xTJ*7bU9LkXtNoPN(gg2@iIw+@8C83a1hXocJm#VaJN|RxkOSG zddHgPTz-!C&DW)I31n_~h)j_7#4NfUsfAQAF3T3;%NswnI~Cpvhvqgm-0znxb!LW8 zif6~hBvL|q4HX38+z-&$fI3e;5Yk9a?amrDpr#g2vw-2I3^@ck;%9M32E`yj-fN$_BgGHdt3n}_TKjcF>ouCvx&Qzkr zhXjlQ8~>*jkw6WEq41=f{tmG6M91<)Fls{WByw|9GrH}1Xuxoy#3wHV?OkaWN?XgE zyV!K2)>8zPp^=e3l+Z3;&OE8u{;Gf{eK%WRs-Yh>!rIvleGXfYHi4d;iZ!iA8$yQ$Q4<+Qfa(#9zEZ}a?e<%Hw!MVZvrz$MLeq?e&5?H>p(eW@}o(%ZKwOI<~o zx-cWKkg;Dfq-d_Ih;2XB#}+c_Gt7SKCG4TwdLoob3bRN{9E}JW0_x>m+3fZ`Jq_BWUu79 zII)HrzWxP5N!9XufUodqw#guJGmZst!NY>hWebpxdgVH~v}4q5V=UQwQO`U1QzVSe z7k56L!9ziBBTEmVXi-UHf^Wd(O7+*z?jyU`cadi@C?0HRk(PZ_5^oEnx8sxdW)=G9 zH?$3m|rw#u5+T1SS=1*`?HhYMAqb^tgCuaE?yNPuq^) zFmOkY9B}z8;5o-QlV(CAx5lnZIJA2=80e`~c9;m{FPQ1uz z)c04dr*{uY8*g@z?>w;4CTD+r(5pZhKQTxzLNRbg&?aJdfo*$7N8|}zi%WoVHoNFc zE|<@zvBcua`T`6?0lnFeG2@bM6Z8>vZ%Zu8iaTo(YroUzM(9YtfQN_P)&rqVDQgZb zDnO5lv_-o;`{#)%!Wp%v5TeA?K%&%;PW%_D+T)>yb z@fm_S2M@L!Fw3f0WFc1TR3Dn#(j%Haoiyut23G6`@t+ zlBxD(J+?3J2bgBq7I7BUXQdOB-f(?Q$qFI`6}7mr;*sQhtpHM_;Pr1_Ij;nM8yaKG zuWSrh*s^Y<2s4~#<7!=^;TH_1=|Zr8CLc}5KI)L}9Tyt;;Zz8}&QC!r$}P{wrcH{W zTeK+Yi1rp&Lb_3LCe#r~w!9H`Q`4+7DbBs9cXo!e=OS_TsSYILs=u84)qH>QSU;Tk zer9fWBwasn6*4&md-go%Jx<9#^-z6$9WvHZOlKkg0)cZdsQnf@R!BuUMJ7Wivq!!0 z&7yijXUPv1zmM~q&ioT^wDHaGm{mknQR&W_HuQgrOn|5}upD*qU{k)#W<@#SCXpwrn7*ce4MApAE07Y0Ubt^!42D}9O@UVo6H}5Xb1E3L4>~?ytJMK*c9On$ zF%d(jHIRqT8(%Acy-QkF36EVn8a{vG~@J|i#@5R~rIdT4?Y>K`WHcX~AYV@e@ z@DzOR?IcJeVWZ-MjN}nnW_jonG-z~*oGW+|-0M+ZGLq^q(Y%LL>~onm#>P|4v35l` zMgIb>RrCSFwu04|PyjtO6tMch{1&6(H4<%(A;V?^0|)<0bzZC&$n)l)-BT>omKvSR zA=r0)2D+e$DWkp5lp<{x3}o+IQhxrNkqtMd#>8fRTT{z%R6X7w(elF5X$>yL9!*wt;3C3eCA zRb1gz_owrcjAE9n)c%$QC0F#>D<4!mA*#QyC5K|BG$p#<=m0SyQ)BQ@tNBil^3nWc z(VmRots!&ENt(8$*4}A+82!FIv)&quDM7k|`85agtI|Erx86>d7s>;>XyB92^uWn& zjofxM)3(fy+T3}ybbj_7 GZHr2>4Y>()KA)OXFl-ENRWKb9Bb;8odS3O~_8wpO z&d2L_2Qp1?lAr3^JO$jgbxB*L)V>KsZ||Wyq?!5T=7{Nd_nxo)^@khVE@U27 zFb9Sa{dD6>B<&|3*cVwjl<4j!;g2>>Fqp59HG+lD>h>#s6(i!oW=_e;HZ+|W#9l#6 z9_=nqd){Hv2=%Be^%Q%Gly}zOI9CV4;u|2p5c5#rWtPBm!hW>NIL>N!&2yDueCV@<&9$&6e?IGAtaog6|sbk$eo zK`~#?ecx2iELKsDr)6sRQOK7A>*f%(dSFoglSs0>jk=L&H^6m=Xg`~age88RLKf{3Z(YG`We|2Sv9 zN*Pr^Bab2L;{wzccWWH#{`XG0}ZSC=iGvh6qaUe2oGE_Hb|#U*PCQpPi@$~f0J9_&mao7y&WzVPFD?)X3W!zx3x51-sY+Hh2&9( zQ3b49?+NPngBfW%@mBX~j~I4MvGr!>7b0GVr=+|7oN&$d5s3|#^Ygd(NQiD=BwHpYu+T}7pR#SLgMQ=K3HC%j(*Ug0ngW7B8EjYHfr@1XJp{)EO zbgE@`^kzxx(;mtf8)BPp?B+#uSpCar2<_$XVEjcfCDhgN3AXezP$N4`d=Xdw&yzu+?kXap4z6@8Z5yO>t zR9Ok7VTF=+l+g~fHuzQ#De2HcUf#Ksk5RS5mL)pxnDVUt1)+}v|yF&*|}vl$XpVnXD_Wo18{6Asxa1REkEBCc8)3~aa* zEKE$ua>qkw_m}s#gc1+u1TdsTsIJ&BDZ{9w$J-?#HJXl|LEcr9tj_=L0xY-tioZ=Z z1^^QG_N;BP?_U`bBJA&z%pLLs_FzJ1J%dQ5{wqw17rn35riQbzscC*?rKqULyeiYU z2E{UCY~W6Sr781Wx5F(LI$u5)Y*|1rxbW!XOENofhy7$F*sbll71;oZk?;gAEYN>; zpBfjPTDHwyewyo*HXSP?VchU`_51-Y*;+|*{}ggxLN|vYl`IEKDoK~9p2NR;SL{Y9F{E>gQ5y!-@=CtG}B?b8Zm=`gQ*XB3&L|472>wDt3Y^TJ3Ga z@pXiRPf*XILmdZaRM8gJn{d@CU~YlMN;kMR%PQ75Bksf3)7ytOYeuaDwARYR4_|8* z4{siUHph3bzRjJShVi&jn%nuVXLw_q$h4vWTY%%%r2%AcceZ-I0_I!rKj|0ih3=65D?Wi% zgtn5JH@nZ*U2##;u#TQ^Szec#mcpm6YDYUk%=Oj($&JweF(L|#i-MV_TT(3WjE)8p zeE-I$2MNUDlRAS_MLE>iVW0nR$l&1q?Y{qG&@WqcBMKLQ=LLfrG97qIHQk}p$kngl z9e$c24l<_y1f3&A%E9QLoO09U4zuw)W+J+;7)bO98 zd^=D@BP|S#OSE~mLWpwo=}HAkMV1uB)v;b+8TlaeU&OEb}=)>#h^JhSIsRaA#Gu<;;*LBCwBSd)l z%YT4Nsnpm=pMopr(zQQO9qj^>X zV`j)y2^Y57MOM&VWx>QIn=%5)*eH6TiVl%m9sI-K`E^~vGGS{BWkfxxU+`4b(<^d6 z4+5Gr!VqPx{d%SA8p^P++9)R3w%QPqkf&;jDCrqGSTUbwO&?hPki5LNZ(EJv;PP$# z_=-CX3or#N2XIUueR6$@@K0qjFG2Vp#c;7C ziDdEJzm6heor52yUEq7!fKLIGR1wBTk9S%3ttTOJBp<9zjy;37O)Z}(4JwbAYu&_K<+sUyjE zh>MF$LHu4K1uau=;q-yS1y6m7eC*eEFRDeFLf_IZpP@9`*2;Wej-xlGZBa~e2QvQ; z0Omj$zdJQe^rzXjf`lkaNV0@1eg1c?Ysw4isse&+$N4$*xxK_R3;Kqt>4o?Bf_C(? zY(PO23;rWn+=X#(K4OnQ$=(z{>G$W!G7SBZJ^4|4TtJZI!d@W=me1<|VFd#$_61se ziN*fwd^j2OhY4=T4#E=kKUdK3{B3nv6V){hT9*Zw5E}cQ=Ob>YoIdh#&)3kw%}AutWVN= z^9mo_=woh6!(a0ae&e^_;B-qlt}py^Omr>7>dX*>y?qRfPO-QaBbn7OL_02bkg}?J zTG~%=ti6favLH_RNyeUmmQN91nWV3~n+L;_%&lya$Y_XmH=&Xm>YI;p_TpKZE5rDl z2gNaCqUF;>m&O?E@8`kbI18(r#M26<=)@B!qN=`ywvOYRXm6w} zf14lOTtGKWcI@|*Yy_HrfnWcXSGjn!6zSt98VZ?2l!ftrdU^*Kn_eawPm)ngM4O91 zxRmNct+ckE;7ms?ey0taba0JuT}d$Cf0cLNd6(N034B$@Ir;kc`N3QD$Y1D3nV5!7 zCb7!g&@KM<$5$9%OCg3&@ang}$#=iej$h<6MxCBdu+aAoKmN%zdS{X^)Tj196)m0L z;Wxi~hMHo}zUvb$pJL?0Kj$a!-(+AZ5AfXI<|u0A_{Cq~_y7JWT*7DH*E6K?;3xlz zcW(4CyrS;t9Xd--a_+Tn@*n+DJ8pr;-k*t~D{QY#Gt$?^z1~q~mZKyxI>=6fkxCj4 zcX0Cb2@W4BC*Y9woso3qul|tf;VuAVo1Nz4uW;t|@8fd&cH!wJYA(s<;wb&y_vsm$ zVsR}_DraDG`6#Zar={&UCr`E0P#MPk1gGDQq?kH}mScIMm)@Q}2FGStT91>-8%Rzc z;nF%94j<$E`4iNY2JpRLKNxzB==6O)_`AR5`rrzxJwnS{{{_GKdJUB!`@Wk~F9#FD zP)KjBF*Dpvci#w;bF0J>X|k$`&EX*sDW|@%jkaUQIo4W%*CD^)-t~wqT_Lftz|?Rr z_xpyKU05TQ%Ax22vcp3tQb}#&5ssfc&e7%yympDts$wRFmLsvb#Kb@ky#u36FRZZ{ zPobDHPPd3W|O97u2y#v}~O5_x?G5dUcN3jogm+EdW=^5jx-eRet+h&A2{U8%zvc zC$%xf@Pl4@`-hoYSRdT+3UmhF^Izu|X%w+F%{_gLt zF}bPWEIGwDzV{v8y4Z|Qe0*Q}^!E*2WqWm$!MoRZ`)Bvr(0r6OUE)`M^-WGRmf+Z} zmtz*zh}hyF-5*`!z3Y9f=Uh~^f1AJe{mXRJ7e7;$Y3dkyo|UoNTz&5fU4siGq-xH* z{%wBoJ7=f~IA36||LS3yI!Y$SRNseOy?UGe$u(4O2XB4v+kE$}4ua2lIi{hLOKvbf zIY58^07Ij*tjCjN6#?1lAy`yFU2{9fPqcHise*vZ_BrN_&h+iSiDjB{Pfvbi|H zP=6nNLlZ14M@gjfn6eX>CrG5MhK3`@ICJ7KHRU1P^5;w{H4T(}lIX%X1O2@Wj7+n% z8e==7UU_ zxx(Vi1QQb%ID5X6&ckIm4}jy-&=qpYD2o#Vbltf_&)_8UD^U`85zUt(uV@(0f6Q}a z|i8x!)Wfo?~86G-H=cUV>K3Ye_WBbGiHw}$c zY=N=fTim?U$JqQjiF6J{efS(9O)42@eR+X=*5$4TkPq z2ZcfPV?rsUZJ%rgx9`PgVro$W+_=RnamDO z2bdVThN^1l$WWF=(SAM>3^m2-%mDXq-QsTl6sub)@~ZYpMv6Biz)9FAdS%)y3WZIaZP?s%N`!kIff(tf8ak6GWG$=d<8$;-ct z)9u}bC!6GwD~#O#h?}?WGd#0aSi>Lg1!5*mIuT=Sd5+1+87{u@I;W3R6YnHkx9mhF3&MK z)X&hd3tYH(f~LyC-nC;%rjC}2F*9_ZJGZ*%A75Z2o<>m%nZgDj2uTuKQC1hH7#|s= zzvCRQzkZt9VlVDbqO~S!W}TU#9zME$lcDKVHWL~0idx8kHw7}OB-@+oEX_?aK0HL* z$+KL#bc&`@_W^K7eKAbaAfH-iZm5foZr){Ja)r%A21U`(3==^}lSwAnTwP#pYJ$mg zuW;$Y37X4%yvPAL6EKxL*=&|{CcA?#=%|W{s_A%a3DS9;k3-+4siEZ)%=TU9#_b*k z#+QgC(&QeF4HHNw5^P6TS)QL_Z0s24U%AYgjygilCk2c4H>RPX<`S&UkJ8(9hpwJs zCT5q|&Kme_2{JkL89MtzoguTy+-NU%?{v{UP;fft#60%mGofG;xxtKB+v#j! ze=|%VLn^UNY-5@E=@CW;J2-jnJQq3-Q|@~)-3Zel6`N+T>lU}V9x%DMNjj$#PEH~q zkY_8GA-T26{M0am1MQr zo!BC}GSB?%6erJL=5l8nmHXTtwZUeo$|Lw(GJ>Iy-d<;ZYMj~SDF!#UNhx+*E;nb6l;g9BfQg#j zVs_v*A6~mo*T@Q*qnN6?4jSqz2zhPj+3kYTIyukuzy=vr!r`#vIN3z0cfTGrHBmF$ zEcCt4l`A*t9p6BagH+acP*+t-&}+w3GHgc|nVOhnWp0G%W)jmG#`TTkv{VMz+0`im z&QKMNCtl;bzAcRBoXt1&EV0!oMn~pYPl^(>*ZF zMq1yUv1DpwwpW=M?&043UWO(XSdFXLY$B5M{I83$gFxkB&b%T~+Lpz5rsZd%=VGkP zP0&BEfb8-S4hL}9_NU5cnktH-p=u_ww~VHiR$A(co>`Jf@|02CScdI0nflL^1mwx* zRa9NX<}0VAwS~r-AP(v2vTXhu>YGZiJ@zbJ&9Xk;#q}#!xIM5)k`Pr5N2slg5b)R# zv^1N`Q;bh6FgMaoR(Im@2k{=SBIJBQqwXbAfA}6{(~OVJG1`+MuL?Na9?rH^5p+H;SZSi9*O?ja zzT+c8=jt0@h8amoT(KFQ|F3}YiB zOpN!iwVgv3?YQ4KK|`r;hbO8`bS25^L@&3lywA=4Sz@Z2qKYPt)>jbryRnNpN;bjT z!ZfpUi_8p1iN?~%Za>aTtyD)m$be~NSRB32%`5No;r$uXf}fJ=Mvl}}P#p3iqmxZ- zvbHe8^y~stgPUxp6ma+{|Ak|CMA*U7d|)xu6wBj1+_-v`8@)3mO+TeItu!90rX=XZ z$ft;{%`rVW!{S6QsjQA@bK-gRBsIaEu3rL@?4+paBCm3oqewJn2M~+0kL<*QXeaC&`%( zTpll{nj?4*P#F@_)JSbDGd`y0*6K9FefPQFGr;)5 z7TXySms3Ddceky&nqgycoT0vM?sxYyxtt=M0jEjxp$A={t*`A zpy?uZyTA^@M_+ABoy_(!^Am&Iy?vL#u{qWfIvN6!B<#q$V451+t5fvedY|{M^)Vka zaR$q1KG{HdB!EjcP|{nhE=)5$yU5INoJ2;)bQST-uN)%emS12kR0_d76=YYKnufz1 zX)M9xc>0`baxk4stc9W_8 z+g!VHjh=~3Om{Jr_07~)mJsqfFtvg%wmdh*^!yw{o7*JwCQfgF*U!}8dcw)!r^zz3 zBvXC2xPI*hJ(F>4;Tl>_wo+eRLcncDFjUgpYb?%;F+4KO@VywByok-=#&@Cyj|2jR z`MEfFo%i0qM(<=4MUGJM&>jzZWXybm=*lc(qtna|-6yM&E`H z3@yH9n3#r%uIm(PJ=(F`3pKzGBD$uqxwOn$bc>u(X@vm}5Qdg!alDUvcY7FHRw-*a z&DmEjajv70(y$jBDw)I@OH=(^d-n?6Bhw7tcM&YBr>5ixA&0a-jYm^QOH9&z<6W+O z)X(geNLkZyTEaT9@!NDw?T)%_sA=L$BV7C7CWA9k>}AI|ec>_}&a_fp8p7)+1Oqb3 zO%^75`S9KM=^bBZtnWUx4fWL37UK=t!B9v>C+O|EN8i{gX`zhM=U(T+`4hC(7LFh4 z`6L^QV+{4&|vx<&$m$-QD zI1N=1{B9elS(33uhI?*u{n{Od7iYP5{T7YQm6VqRD6;QFl7K5zMbn8Qs*Y&SS%VC6 zi6wfjY%o9L!fmVJM8_d2OS}k}7+Qk$`9XTRhnbI=_-oJdtzY^ECy&%p8gS#ViI`fB zL~NO{-Uu$`Z}@0(n!)aS)HT&nSrR1T+;2VcGz<(a!@|II?%wNXAt@3F7olu#e&H-p zJ-f=x;7#8C@du19rErxsbK+t(wz&_uJ-W&BYf8uDw{OrjvQB(?p4I3!4K)#5JFHt_>M7Rdhq-n2 zCVjKpcuLwh^~!6UKXa5rl|^{$0$MiC+WZLpcdqd6jS1$4?{TNNimI|O-U<)4XP&)R zSf3f7`%V|b%L+DMhyXE^U3p6f1k=D!Hklvmr>A#}m5hUumRI=B_gDH!j$t4yT>b*}_ z{}fRrMC-{5yz<(4+8Zl~_?;L^nys~2rUviu?)$eHpL@XlI}wV?tEuQLM`mYhuV`}; zX}QF!bvl~l1s%{7_a8ayVvL)TV<^GKIPT5)K&%Y*!EwUwx^+|mzf&)h`;@t zD~zw^@l>>M@@O&A?E73FOFr|vrlFCFPH_LmRo=gLpXH2;ik6dfl-Y>(yiM=gZno4U z6CJ1P+IxI>>jBGIH}!3ubhwkO4qW5@^0U8ds0mi5y1DYsRk{Y|NZKlCKih#jG0f!9 zATwX{Xn>K6GCgpc_kQ*v_s3Rnl(x}+wiPUT)p!W^&CWQrAJ} z<%^s@-b`88i(M`xDn*ya>H6?0H@k*dogL!Vl?qODRN!)W@$7IdG|fDUqM@i@^F*jW zdXaCw-a^FZc7%czp2Ka` z)VKx29lRvd)KHUC^mlbLG_`@|Yo_zkTfBMsIQ11_d``KLOp)AVY3czH+uOX~HNnJ# zE=sGbsc)>JF(4uuSrY4$+`alC-6JccZIv89^D37wpQg381iw?lRMTv&&M?${m3OZ^ zV0p5iTeqtyEsfxB4B>i4vW>;wV+8}g#+ZhNmW?v@pr6r+IhLadavIp(0ZJ+l(a_vV zOBp-5WKUN!q&F8C9Uft3VU_h*lB}X5$WFY$2xXP^G`6(RTocCru$+pat3)U6a=WXW z-u?#+-d`fGlMa_vWdL}Kt~cymFZ{CtE0W3V=Z_xykC>B;%7aEUs=Ajw2JP8dsPtcQ)Z2><(RtlAGp>%!Mz(-7@Uuj&(F~H-oNJ$w(k@4hpFj!lQ&M) zQXF{trf9KusHtTpMkbh?-$D*I({|<(uUsexUbeQqxM%o*T2+8a_qtD31h%XLuduW3! zA*x$Dx%A3qIuDmUQY+g}FciXThwR2Oi_sC*)<&6M-XxYjM9~h*Er_xmr^klV^X$LV zaxoG!lZ=fmk}?A{bzbIlTQ$XgJA!FoWaDhD&9l6jL2wpR+kT!i?TwTN?T8Q8S3!0X zD6XZoErGV&!`-PdGVvvr*Wx5I1`+4M@TllYhV8{}u3fp!$f81|;V>nR9CJNeOiV*5l%~)?_Pg;0!h}O%ypHFMn-?w3W`da`m)Fq@0h`l@KU73G z9DZgnpdji|SteRO#p>97dWL4$)QUOMae=qK@d`(){Wv};8Rx?nD8lb{QG95bXxdIm zO$EMvnw`2^fq+6b{T53-@6kIEC1IXoD_b_>)SZ{>T8_qs3iPIEn}bGPbeJ3Z6t}UF0wI_W_x3vsdbHdkBtMeb-g&I zNn&Z3$>~Kll2F{#&go09apBYC^+3X2%)o8>RDDIVE;> zbW%|e1Z*xJ{^x96hMFN3A7f%s;ViA<_hc4ID;!oEH5pvzTHms4oidW2lUJu%X8DrMs3s{KhNpT z6C8?|%qDMeTTDLN@o1=IwicP3TqGe?aqMy@=gxIdBCc{{{O^!AcJU>cCfTidre;>j zI_o%dzLRsEZ8*0ExG{bG`CnI4M3-lnUdrIDJ;Q}FXE}AOhS>crHl~Jl%RD)-82K1W zb2CgX>y#gRi?f|)XsNO@cXNS>@tp+&)c7p3QCblrZ?D{WI9rWOF?{LhRdGd-%UIp3V#2W|`3WW*#pX2us_IasY zQ%6rNFg`j>REu!E185^D=Yx3lPSgvO4uTzK^&XPP39 z+-u^)9}E%>2XUkpSyrOK4lw$Xn41dUZ; z+#l%O% ze{PTC#~%z+6n2u@h;gN7o|)l6#*VhoP!+)G*`KzDMS*?jw)*;EXj$TGODwL$Q3Ho) zsq*6doR_HW6jRHPiq3H7XFukrAKc{bg9#Saw#n!MPEUxknr4okzRa7Kj-w}XJUyAi zB%j(~cBqS6*FWUi&HIc_FR~gmP9aqdVN|8)0^F zomeu1qJ!}863g1Ac8+&m;;nCei;G9g@Hym9ls_Z4%;3$p`M>}9+pPPW_am$rrBDZW@0u$W5|wM-jCL!fFSv(YCcJzt%8nI9W+#UiH$EJJ@ewR7nCBo z@Rl@k?sbWll#8ZQ?HsBIV1FztKoBJCjsT@)MFjj#gvIp3W2J@2qpm1K7v|VXE8vLG z(AG*_RWV-MqZb4V$aXKml0%&DY@u&vlZnj*mKPUU**=Cpy#Fo}HcbIh@=|%^I3@NF zji)5EHmV}tLTMkfP#;rMawvw0@-2a$* zj&y8}p6gfX8s30N2OX!55lT(4(kDDu$$uWA07pZe2 zJSV_qV(KZDMtkY$9bqx+qyEepPPErk>~rp`O!P-FO@+Lop=uQB%i8S-qVU}D`}xR| zS2Q#oY<3&6&4wVnsH{TG*vWx0mNpW2Do)XSq@9+k08aVS2CX1S1S(oNQPPBAf+)$z z^8Q~)wX52C*>WM1o*08Vybx*ML{({wmS)z6yvl#z7Gfpf{feaAsh-I z3iE|PpQ`UDsi^P-5u2xkhPHFO8B_>XHgNQCIZo+un@B*C-GswMl$Qk%%@~IMP?lj9 z+Ttps>DUG2QVoB31IJp*@Vo7gjV}q=<{=V^P!jPWizy5}Pc~mTvAqAz7w!(GX%JhS zCmK(X7yMK&51iyM@L5s!xMAN4X&}aFu`2(GQkoVo9!7wKE-qP zu7~#*ObztVH@ZyLRY&K^;~a0Tz$F!W!7v3R*+X%CD~H_~s!pBaa8o5g=VR-sAR#*< z)YOy{3AquMw#cTEq|-XjshGI05M&oc70sM^y`8pGCpdg40*N^m#GUvDL~O1Q)vYH9 zcGPg}_+jcRyrdSQFJ(l_&JeXnIw|+maO^}YH6)SJZ2xsCBTk&Q9o2&PoT3dfo3jjk_-FjD|KtBj&#DIg zGAiqia3t)-CTQeR>kQxc5tBos90{(loqy8BKPGxU&iuete)RADgde`$#flc7qOy#J z_GUZ|5kt+ey}8En;0HXocbgmcXZX+l!4LS}<-?TwB)rA7965QBD5K1cJ)nDX8@s23 zhNDNQFAw9iS8}+v7_VfKi!U;G?a%n5fAwcv9b8BElu}ty&yfZvvS6a;(`;?5FnaT^ z8R+X{Xd#d5AO8lY>w@?`Hug*%HJ>4!NRSZI45Ifok}c%0U>+n*T3mlue}w#f+ripwe~FAqMs zZnYreE32WRtb~Ytob_as`Po&nM*^7ceHaW7L?mAWXI^i^=JHbHb0CU3+q>+Mvblm( z9lk_a^94+kf@9|?o*lzb$z}4WiUE=bx7&r=DI#E^YbsltF>njneb$&1 zL}Z7D%9dtI`~%Fa#@O80U~MBuQ_#(R^SFu52$6>K{Mv7{pcoSV(wagB{*(SzlCeAN z$dZU)e(ZVLO-t59Nv<+Ga+eS9&X9LE(RTbK9fwNrKXU1>V0Ys5_;K4L61qw{kwh^J z45Y`7^P1?YN;;jvKtQs2@Oqrsca*}i*BIoIYs?OH@!s_jHjPp`Po3vJqV&_qc>6rL{2 z)bnJM%S_B{5KjrzoH;~wbqP{-lcmKN+o?2p#lS?w=5*r=gb9ZOcwP2=8<5#m^c1PB z1$u|K$QwnJ)z(rT_MpaBS&zj@rnBTV6G4)3x_$TqA;KXa?q}2#ej52~mgIH<)etdl z6_l0v@p){YeU2bvb9yPSuO;lAU@;bDX(>uPp+M+ykEVg4rdc1q#fR6snclQfbEcE? z=Z_&wZ}H$DENQ!lfQaby;C6d($pT4LB^ghk8a@mjFY92Ssw$aG784oC=E38(f7UIFndJ6Q`Csc&z^$z)X!iztc|5e|Ji@uh%(AloUftD&?wj6)x1 zduxUHr8I{_UOcwl(RU3!$Hx2+_j^WI*pjF|+sW~xjZ_DJK9@zChoYJjeDjy8*-j{U z%W5f&xS!akf*@jdII-L0eOq?qc}UI*8jeM%I^m}{=)@+QBvLzbs0yNtFVe`FS6gs+ z`~*EVBvB*tGTgC(fG5(-xz~^4bbAPT?TCW5L-kugu=%KHJk1;RZbAVMF1v(jWL{D- zz`;XwL})yAiHZ&nuz{mz0~9wV5S&4ZDeG)Rg& z4{`{iL`ma$-aK^np{`l5kw5z$3ilJF(>WAHLy(*}-5z`{0bz#=njlKZ-XgqCJ2oLt zE|Vdf%b}YNK0SC$OhYG|$)Tz`h%TH?H$Hbk2Ue9l$?a|Ont>q|Q&JKn9C(u5Dj>-& zN^5H<2@PV?=Gj=^Ai9~uEZL2Fs4QLSh-4 z@p2QUPHJ_G8*l%RKYjZyb15%J-})_n_Xoesw=cF*8FHW{R~fzg4uA6(f5spG=p#n1 z{u_Q6si3kf!naOUQr-D|{$b~@@LOY7`SHK}Z}_kO^)SJjv;5{i`ltNPcTQ6J@D@2! z%djxi&3k|L|MEfaDtTWcmw);9`TgJgHl2qn2-r2!8&h=s>@WD^KluxOc7KdpfAz2V z%QNSx3VHArzwEL+g)HS0fB(Ow>9s-H{*V8G|NW1C%$U8MU-*yz3IFsze~XgmmOQZ7 zTXbU4D9KC~!5$$H3K8^4Ppr)+2m(05ghD|g0g;7dme|@FS@jS)&V6Tm2!e?0ucFfb z(ghWq*iRkm1?Qfo`7onb)xass2xw%I z+hh%ed?rIqF%cb3TuvtrrxT~cf!+RiFlq;KOat^hc|}LlMO-!;B08DmHW@8PE|(>f zH?cY0xLgG}PNxIA{OLN=rkW!gTVo}jC1dy~iuiC#aVGkDxcSi?9*oYj9?znSPC})1 zv>xl^{P{Dqw^R~z6-t!s=l=Mj7`Zg5=rXh0I)*nuDB!@zF7e<&7q{+oGd#7zR#HWB z`6#Jrq5Z^J&YwF*Q%wn8`-_~KDBLxrYC5JVfaJz*lb(9AKoBKdfgoOo4be=o726_} z&SK#C)L1g~Jel|$H-Gvb{ZpH`8ot5l&eI&L^D#dEHOy8OMI>)2r4?0_g$CH%+G2XJ zkL6Qd9FiZGO+pd{3`0Xx(yT5oGC8%1A-V`eYN;*{;Cg{un3#rvu4^dS z4Q8gN7@1f@uz3lWHc(mY{Y2KYp97|0plJ%(Q%ufAF{C2GWrt|4ka2vaEo2i_ zRWJ+#BnLK|4V(P5?0o^7H-OjU!6oWsGijphF;vZk$!?T9Gf>i-O!VDjWIl%OKgy}o zM`@}FeX0zRAldPR%4i6c?cmqxWYQ_JITc;>;P(3Pcn;2e0RWOaOvL@@zr29XAj&xW zrBr-M=YLs0Uclimdra2O5p8b#MQ$Gb`T;t?@zN0;0g8$PkLZps{&r+nkkaZPrOz`x zFvw>!WYSqQ(}wIQA{4a0SW=IkL)8lUoFqv|qDd~DB9>Lj=Q3n+I-=c)^J5*$;lys2 zK6Bc5zaa<`vZtKN=agQ39-<`k^lhmSFwq{~9rs{xlC@|Wo41j&iW;hlM0R>0M37`0 zC5_aSg&3QUvoSxz{Oml<6-^X-o!Dd%OcPzplh}?jIXTbPb{3njk@AX4s)`G`m|+;G znucMT2(lBqT}FP|-Y5vzeE~dfCk{~~8IKc>r_jyd=Xg^VUlw0!RcAkA>Kd7i1*T?J zFiQ?|GE~a)#5|cVLAJI%%f!%q-nqAmAiFvI%5U>Kzx~U+d9oUxLqxzwdGlp{@dw33 zJURaRfAKSxROK->!o>V^v{04(W)>3XCVVl@|AJq@~;vI z6%k;YfA+(ErtiGN&CAC*(pW}QXlFyv)Hhk*SYmR)B=G;U_h!v;oq3wy?<~3RnE(>| z4gw&+eP2Y8QmIs`uI`?8ciR&&5srz8n3%9H?C_1hg2T5CU)Xmu9qt}GdZuT(tGiTE zQ4&Rp`woEEcO;fXCURfT_WB}0iIPAOEU8)~h3AH3@|=86X1>dReV*oF+E4r$|MS25 zZ#dr5fX7zLUOJkGxcFx(l~R^?>_2idvChpa_xYD+Tj{E=-<#}v_zqY=nOv?!rD~$O zJh(j`9M5gXm5?MiZnq1sTft0e6f+#Y1H#g%lu8teWi+iyIiF%9HqGNZ zcNm$CQ*pO*>huLp9_pjsS*rk)WCe%Ig)C*U^fJYghOUE9cW`I6scbA^A%sPxT%uSk zVhZuvIuydvNGD=U&#aIy3;fLo=x&cv@B5(=iUKV&!^FrVu8(H%M*2B)>KNUPAskRX*t6OzdXtQt_XI%Q~B z$Il$4(ILI^)##R1K{Iqr1VYQO{Nx({_0A&WQ}e_#B@C-3pzIDb(9w5@qbH7XWT=~l zfb%Q<`Q1Q(RVkqvCZ=U!Rkv6e{fxy=CzzUBCY~!5~^y$?yw*s_pDW+mfT>pqq zM&gvc!<;{NiW3J~a7ei~JB#yN$Vf_WrEGozvplMI>nij2k2?7BjA?N z3R}cxA9MHC9Ud-0UHc#>-a5lTYvlWJ?+X*lsF2AN&~%+jIZq}LV{+skk4L9jCaf{hI-owyhH-&>u+hHmsXjYTwpy>!WrI2dq*eDVf(IxH}|lIpCp8Zsi#?9Twr!# z1K|h|={!nbvlH(Q=jrocRco37x)5L#h|k^SH%}Iso114PkwZ5Hl5E56ucxJZKSz!q z=kQPuEp260SkIKXH~oZbzcnakPIF|ao92iI#j23rSYTr0E;sKilCkO-K69QECx&TuO30Ex zQ4|~w2eK?7DtSt!DpgH@Yv%_M!m8O=LQpA{C>2XD7FOQFkBV2^O@DJCDJq_5FGtQb zG9+|1XCIPYSovp21_+9YHCE3c@s~mdj{{g$eAM zM)ggHu+R%JMsHr@lh2=!s_1BjMzvg`s>}Erhd6TRI44gWrl--1eS70jR2$*?I$VxT zwhCLUE^o3m)J?t9{dEUj2u!U^a$$*NzC_sqr>>)G8s_Un4*Lu&vq~Yk$oPX>j4fuc zoKX&+J4tU_9o`=#7a$O3k=XPEqodQLq!3*Lr#aByNZ7Xny#_K4e=~z8E}~gBu3Ue> z{L~FTTpQtYmjk;ZAuOFrsYpeaa5N2Z=G?oSJJCl|=+*0zc@{z#RC8<0jNIh@_y&f% zjZ;6n#DUH_f(`|=ANvV+31L#sCzyHsn8~G0On)E!`-d3r^1l`VEmPCb4FlaY*jjnQ z{oD#p#lkee?sQ`l7KWiy+*)QllVELmf!OK=&YwTVK(h~Jx0Uw7!mO0h3=>VSusQdT zJIOh0l2#kb<%aF9q-=bF(bNX9#d%`qFLCzNA$l7@}%#A$8=lA33 zJjwB)ep(v>xMZDjF3#-OT^@}su)aFZ&ClJqJs#dU-AjYV{(7~@zXS|Tqg*Uv3J}#4 zbK^Q5Z;+M)7umP3o2G~xI~tkz0uv(-7@b@pKL3zUKJpRpx;VbS8UHRPuG8Zo7z*J~ zRw-83h^-{abTtvSe^V&b!qiG^#nwm_$~6s?YPF_o!c#V6fmTeiJoS*zZ%&ai>KK0e z97hlIyhMWHO@)lRu7{&%-$BR@KD+*irIF7_%-_Z3vSX7aEVK5zR}Gb5*D+4Kb%|4l zJE`}5zs_7?QpG7$xl9=?vR`A3e+J z^c_C>@D_8MIds!RtCXl{7K*Ep;j>3La{MSq`Wtp7jQd(ck_pw<;qf?-;%O4`IGc$g z?LHgI*P=}VVQOU8)<~o>6fIHf%BWPnEV%eyUzMd%&aU(L`fXOyIp5%Hmc{Ow&YlxUdO$R~YpT@0|Q5tV*1TyI1+`Zyt~|%o<;Rr9xE)M|dA+kDTV%v4ae?`d+fIM?#Vu zH0?Xh#dkq<++<{SmfOEuW%Py{r(Ho37FxALxuRpK^$fpthI8kRGt~CfcaX3!Q;X*t&m*wRDw(x4wlaCD0_?huuIm`DsXzWx!Co@pM}j0N*xf-I z+(CqurLtz{pQriQBDa-fBeqV#R8f7M^z}Cp4tz6cBO%+ogqnsJ=x)IGc!R>TsXfai zmsn?Ua+*X*BIFLy+GMAc*&$B^zN4FlzyfROG;<>(%=EQT=j|ZkvZ2T|j&Gw{AiKH9?dv0~rt%noFl$EV>sN^& zundh{Vu8tfpK|5;81agm=KW{5cxHh1I?oRh*cHM;%PuiBKEe1x4p(?T2Tq)zqu!76 zIRi+tio@k25b)t~*+9>c*(#A&6cj~5SSF@nA=|tJLv|c44^F#^Ec5+?1%E&o)eLL% zBiy=vpS6;Q)`O?GaH5w+zXO{r(0}X)+$AidOlD(-k&#(eQ-a15`xzYUp>b!m`&SN@ zVS=n;ce${HKye0X?;m8ax1G9x6Ui)-O|G&yIm*cR9P4wBD3(nO9EAVm6!i|7U3IYw zurwXXX2a%mQngGJN06SuLHfFysSmo5%`&NtCFUka8Jk!jHhrIxreNYA^!^d*T{T*) zYNd*4nqcKfZuyAz3~}kbiwt+v5%4-uB@?q+q`$9&u;(ARe0`LqxyOt=ZlkBWnMjB2 z4do=S1q&Yho@IS`iKVR~6-!`R7OKNXB;dv$3=xim z@HoDEEFlak#WWkSWfs>m7(!rKU~~G31U>kJVL|~vZin(ppIbi!BxFLZT{K1}aV;zp zo0(*Cyoa{%AWZ=$>b7yzM)LpwAOJ~3K~#-p>J`fQbw=(#VQwXX1}K(=xlJ4KeV2q; z$&g-o#LWjQQLhU)O{Lirs@R;K%QEp`cUDl_?f-D5``cEKI{fNGk471iQnH%V|ed zzVh8{E-#UmHkt!2;+Y(aPo6N<(?)ZkhtRe^Uh66;Q%W!M_~9hW>nRLCeQo{mpB7#Z zPw`E~KfAKJ0AWzb=SZb`{y8xFYqu89d6&WMB%;Lm2W0P~N zZluVS%4mA6EeT9g%M*+*WNKAuR_*n@0PP-L3=8peqDVFF)E7}0N=QiCYCggeyuQRV ze;`N_inET+{b%_=ZX;i*QY>WH+FWIMd7bsy2jnwbBr`=WoHZyq~0O3hZ`X{G+|15W*lEpXT0` z5Bcqt2gGs?S`VD$z4tG0uq%Ss{zF*D0%2)v&W$oPGs~tHpsQ_=OaYub4TcIaN|&F;4Sr`ee!EAUmsz1 z+irMBBn8>o$i71-aW<7u{7rQB?qgqfGxZ@qZl{W58B~fx3=Q_u8v2mm-56zM;USOi zhv**c=R&Wi79=ywZJWcu(>Or?!BdcDS*YS*dQYz~^dK2DumBNp3W?Ou%4rFoWO zDTZ5p*pxR@M@U!#!>sXJONvaWbw7uX9OXc76Yeh!J{4~;O84Ml^!zG|D@l^GtISR> zu`;-i{`$II1t3&+JuO`W9P59?baI*4#5F#3nv@GCI5^No$R(lWH(8k(MLX~1XS%LIT$DLKc(8=vyo^)Z%G5FI$n z!2|o~XbRzV%IL*3>x+|&jZQE(|A1?HnNsOJ-Z{IU_B!|P-zBEFaR&Q&`;Y#V;X;{W zxkx^Ih_nuI;e7}Fxe}Fffpl`6)z})F zn={yXthdQZyu6?tIJ^Yj*u*@>6Q#ZK!*;PKjGfm0S!QoSv`1z$HbcSp% zy>29XgpPqDoK@Qp?l8@r0}S-G(bN#a>$0O@QZ4669T=di@e?k8c7w_IG*9k(xOMm_ z@9p;!d@k49n+Mq*qOJcVAN+YeS>2#q$gs7!Ml7~Ya%qHX*%XP5bG&`&JcqjiFSR!c zOJigDCZB)$1$W2R&|GaCId+i2eQh*`Tu5e>?B)t{Q%@M3TxIO$Zzz?@Xz!lq)KDW% z2^5E)NJ~E_hZ>pN%#m2U&li^^jLKP#ALyapuOcd0;>%M!zH@`yBP(o`Eo{%!bG)(V z=o^Ap(?{RK9}qfPwMw~c)I`DD0bGvf3%4kWg4^Rp`KHrq=~T*Pa``HjSs|ZX;QnU| zyLtl2?nEz_DOaoL?9#;&7FuD0*@vIpObU-a(%owjY;nnv2TZQHh| zZQHhO+qR}{bDB55x9V2C_ufBJsicy#E7|Alv(|c^{aHu8H#&WjE850%=2uTS?ZYEc z=9~?E;CY8(Navuz0h+r8UOu5A$8fXbO!%OX=TMbb+15xJD`?g%?*9%hY)3I^-#TX> z1|aPnE%Jjx<8j+`2Nr3Ml)hYA#47q8wE4RECwV7i^BH93x8$F~_SxSB6=fNjzRv(_ zHzV~RUwAx@+50yT*>%`?+4U}w=j0TWX%Z)JBs;<`?yX9C!K()>`OznXJe{{ zRVf1^ivP@&__3whjGBywc)n9Ub9|+R8KOqY%9Lk8bi4k*mR5+uyNlY}J zixXrM&4SJL{Jqc6YJf(lmC(xNlNiNK6W0fdwcF`LWaQ8}{l9MlEQYW0IRxQ2=Kkcf zSL5`xzK(Gj?J`5(dG}L@a=(|Cq;&g3mMDzXq)i}S7B+OoTI3m>ecykT9+7BZl3ZO5 z{xIvH&Iu^tt^4BR_0203p)Rq}jNnbgh*A*jo~&LY6YOmWCFyYB^B=zTiurKg&rC4{ z!uR0uu0`76oN1*v@y(pP^Blg~JAQnl8Mncz$fP(tF=AD!yQeqVBV6TDfr`sJ0~$o{ zM>+08#C`PEP3-8T#!p4g$REz>6C-$TR`oV}`}8i`Glq9q-s{_WTDELb2ohTsHI=w^W`F{e%lN@Ps3FNw;S%9}`DgCJ_@Z3D1dsikG9*GY>eBd5qOgLbxfxLpR zL`P3yRv>Er80Fj~J7$h@!nTI#!6IQv7xXP>mhhpdcT?eu)eYg${%nXzw%IB|2rx1F zz=~L>e>gjgYIizi;Jy#5lTTZIQ|T#c!9=B66w7b z8FDmDv3Iq2Wdk6(kyrqFzVQ|*&CfG5_l}{Q&IEEd^q1U?_3*$AbEp{S?A2G?+w0Hi z&rF^DY=fnTB`(kK21^d>3iutz^7SdJ#5C{8!1G*tNBdfObJ&h>qAsv1RH=m;zT8an z?(S5GbJi)>V)f^s|Hi>c{YVSxs7z1f4UTLhbg1OO!PA-%D!{_Btf?v_e`&Z{?{IdR zERHaGesfh!ycj!+tboI(86o!we?qW+|5qI4iRO-uk&7(^@z(v@5Ky{fb}=IylLy=% z@yj+g!nuWkp1OHo&>|Yx8uQwdZf;HV2OxAm%sT5pMLE%oZlCE=q&Z3K+QsU0k8c?Fi0}Z8t_}VeIV0Ox zn9o!1x0GPx|FC6UF7bFWk15#GKI{F^9!G1xV>lPNw|hD#!#4#4mF=Fq4cJ}uyr^Gr zx`Qe+Cg@}u08$GqAUK-);#Nz?Ye6dNU{uQTI>iW)2i(Srn}vhog6X)S+@F?q?&Cwl zmgvx(hmEU_s%%;7VSQmF1>GPlZJ?J?diH*&8a*nl{g$vl1r;k(*PJt#tgcgL<-VU} z26W+TrV2LhKYQML=*;PsMY2dR{T;eYlvJTfjwG*K&GMF@Y7E@jU&jb)JG}RD;L265 zq2H?S5)KAs$OepK!n91X4ltb7M-O3^eD#Zdf9h{q^s-MTWso0SF4@qfk5{7F=f_%D zBbLd%EbZ7Ze|M3u0-UJq*xkA!Z7|j~u#Vp;)idO`EI3^PVa-FWTny_LxZZ^anBgBT zS%9@;Be#}77Ov^@*S*7|051@R=P73a*LG-jSLc4}_$M-!M|FuY3T#~d{)TTepV-s7 zgxk=->drez-K`%Cs0AT!bI2M+Mg+wpet*`1#W!9tulF-6nEe=zKDJb{iFG`NPq($S zx`|Ioev1w`CRAa>+wx&b>DJ)-_-%9(sWf^^NfGIooEk~<-y4_b9Bv_ zfP}?bckl)k!Pz?F@yaG0(^~iPh^fi2R4I#GIuuLk(+@Ap+%a%9j9gF!-Pn>_>y^V9 z+)dMR7ULXxKcHf-^%<>!WEq~a<_%u;Xn zx(1+Dscy>(cl+L;oXW#5tQ?K~^IpW7bR$eCk8_wA7fQ@Eo})$pnb~o9c0u)JlIBu3 zGPcafUX@kp-t;o&CnJ*_*?%%}=Q|{2Z(Cg05ObC&)c8*KR)&q{^^kC0`)|Qm@pBdv zGdx2p<1LBNgQr2L@}lJD33@h{e?p)Nv#hbleTs&`pZEIX>Mff*6=SXAckA@@5l7KS z=vfTwezK{G`kzo=b6}TQh45y+qlGuTs(VqfRkH*%Zae*W31i41ObD#)Q`2L$)Mw9n zPJ9l$IYYROA=;oGmWMJ3Nug9zGVEX^jZnR+KYp{vLK*&e$i9qhfheJ*6N5Sw;*vSJSi{JL(k-Gvw7iksf&=h6N>0%SnBu|<~ zlB0^Y?7#eTtdOF|enHJ;KG<-Jye1l0ON>Yi4vrqum7kku>M>RZZthRe&^C5u6MVK{ z0aTP$9XyDib3b6f$J8{t%QLk#O44YLCgZ;eD{gjvtgo#}WqIfRUdp!`2R2^W)|*TF z6{(Is$V_FvmOx`3ar-!i1o2NLaV12QIa4aXBIEm;!pH8TEt*?0(eZ6?`4w&f`wf1g1|_TNvbYi4 z<#XM?e(wIu&{#;_^Ie#L4EeQ-CTq8k+r~5t zal#Ko1gFbQR1BatL0^|Z{j`MPSlE5%+xonf{R>Fe$HK}sv9Za>@JXx?Z#tS4jd~(a7`U7dziq@SMH8q7&LT z_)Sq76rg#2mv`jqfJ?grM#%919x%VSGWPeIpgRQ_r462@GkEK8;L!25fuj51e*%*u zgCR5L1E=y9h5)13MmvMZoXb2}Wy(C-eB8bGzbUHO4D5b=pc{)77)`~G?|`ry#O||@ zfzc}tQg^~e4X1hUzi|HVbwBh!CqagTH}*E+g92++$+Rc#U?y$1NQI-1y+xFaKm`_9 zwtR+Azq{V2HtCn6LhHY7G&XTMdf<%A3?W|^OqL^hqU+GfRT&sOaX=}z?>F|&IkWV$ z&^TK`=~%`%_rVr^QC>qLIdi}EnU`RWqz&G?9k314sgP(;$hU#%o@-8`0U++b7|ymK zI{TF=w(yJ`V@2phM4FcUMk2#|Srv)VQ-z9>@(Vf_|DT#Z-|@E%hW!*1B}4a=_ic7@ z-RwOi)>5&S91B0DF^gtDI-h{CH0;doY1X!ohRP&);|53|l3N;Pp0udvE`4HTq1U}P z`cblEiAKIgMIr2ZM9cnIU~V+>o=l_aD$`Vw&$m19QJ5vwRLq}y{5^((AfN31v+^@s z$3QS}`gX6@jf8VN2*JW~iN<#4?zV^lkK!QP7-d+gnwzHy8)$NM5;L{+X=lm);|)Y+PCP2^xCNW>rF82aT!fu2IVgrfchM2K z81(REm>%S*c*d#%M?wOj}?)ogemzvi7K%CZ1a(FMq`~KH=F!xjZ%l}EX=|8Yk zCMvWCvMP`mbglMauZ7pVRDpcB)O7`NbuTy3~?@e)>H6TyUB<*d_BI1 z0|~$rfZ!`zrA1k|`)$>)PywODYcL#d&eip)hPFQ6ka{>8YvbZZO{dV9KV$O3##mYJ zAG59jOpi9Tb-(-4|I13UcqN)KMC_UZhoYk&n_LDu`!3_!UktE^_C^}oc8?EASn$r_ zc!eb!!+5U>AOe_ZO#r1GzQ=7opXa_9PI6oj^7oJWUxBEQT$WGY4u%6|4Jnx9;9zXZ z(mtBy_obscU_utfhmMUSG&l@G2~higP+h}rB@)Si%man_pgriU6y|?Ap^Y6`CK3It zY^{mdtUDsl9(V2d95&pry%LGh)n0dAcpTUH>NLr)oRg*fKhqkCCX|bS>5W#y*&EhM zQzXJYvK(54Ry@{FAu!?Hp4mU@c-|9#)In%~n|~~4wtk7(g4k6ACRC8bQSts7jS(fyeOjGcMiJVT6t;-wIVZ8`Eh65^_`8A;gUHsL%069%=XN*j62XG3>&B_+mxbV?%C9wll}%_g6)|#Inqd1 zxpE5j5hB+cZwiDVEyd(H6}-wrF(;H#1pZ>QqLZfSm^e|(nElg40eFK8Mp9wHwV^;E zgF&f<;E%DDZNCEeb;kUn0A^F-dA`Fd3E)l_e!Cwl+}XUl(hg%-@dD{MopuHqEmAs~ zYOTiJAXBX6YE@^QzW|sFVW3-Wtr)Pvv?#cFWV!SP92XJGE2uTj-JKKv85*jvO!I#S z?)kdJG^EfB)S~Km{qWA>5f-xnx3m^urizib%|3{Qx+nr0sR#%g55ZP&6kpph6Vu7` zM4D;v@Sj=}Ps5nX8fc49sojxnuvsSzjC@`^IyeM6EzS#U&&sf0N! z8ZAcT4$!BfM5eM5L5o-N`>&CfWKv{ZQaEKf+?&IdK!>Rci-{9BjA;PU zn#jBt2bODDxvMVX+FeT>;`&MG#0Xb4WeT^hsFNFpPrK8oD9hjwOSFyj&VjL?H)QrP zK>P(Hr}sYZZihqo&FJ4M>yK+gM1B&WAA*l>s%MV>WT~pi=7RV=u5X0#=M4q2s|ajo zkDW}T>GWa3)>|&g@tuSf5bD6YmOG_9Za$GhXCgX+4|k}x!p`bpV~EW;+V=)&$E!(h z*X(ff^~&L2m^L2U=>RfKlWCTpMKr-2+5KThDG8!kdtDA>c-ekza@#cy3Tfc1R0bG= zR7TUSH8+zH*SF3^N~r>uR0mG?hcWO$x`u{&5g*z(yQ-qzg51t}V@zEV@3-F#X>cCs zM4T1YgeNryn4!FX=KevV(IuID?lUcvLg+lul}v&xDPI;NxG!8e`r9V`uF`B(BVhiW zMx?$t@HOo}2@~*6!S(SG-kv5=oa*V|9Nf~z<+!o4hf>5^rHLX<>f_`IW3J8r1sQr~ z7x8yPl}U6tSWEU-VxU!&;8S+RCA;ENvRh9zHjhkx6$SQ*~ zRi!M+$;{A@kBl$He025*dO0RQQlSc)<9*`#i+6CjE5TI-W;a6o9l&*QQ9<0mD{^Lq z90POp-2P?%jt^B26(d#6z}79ZBn2KOG0Q?1w@24d2jLlB9s-JPYM7OdjyN6-UDQ)+ zgqjo@wkX-a(J&xcucV|eZT3dZ=Xus1+g)fG#QEMN)CWBqUe5;@21|k%Doxa}u>6*$ zOAwEEV&Perbbiw$kPN86oUoa7KKaym5GL!j&18 z^3X8>lqOmjAynQ!p=ic^kw-STeZbV}a3u{nxoUs4Wsn@A{>*b7? z;ZqSZY=G z8mjsysJ~s45(%z0k>X;5jotRRQ0E~x~%Cl4`-Crf+~a{346w|GTevq9I^ zNty;3s*AMFbU+76DtY$vFPtr{yG>jDoW0ZtyG)JLa>XwynnpMjkfKcE``Num`8JI8 zWgHHNZ{6Jvk6^XDYi;8Ut%T)Cx~K+OW^`zI<9G{eQaw>I#q9P#`X@ILEX{2LXV=h? z4ox+LmU;AduX;tO92uK{b*(@b)e*u-qzc4+4>tC4La@e}ApXVK{qO#`{9PSUj_ z7uK*zE?RtNR+%R~6KP?G6FsF$b81h-E-nJ~IVpvBn&u+xubl@g6J=|exH+esc!Y~@ z={~%(DiGKE9M#YyYUJsbp2-?-0A1C)!*W5K8a-fx0lnS$;SdyZzpq3VCJ3gb7@!G1Rn{Tu{UpLT_ zd5Ls!dKBXBdAs;~b10WEUCR-%#Uwt$&?ja6WAbEg$Qsm8NoowM%Q=NsKf1mG@{GeH zRsZXJ4(pYI5wW{B(#-#jdA@5Ig-iU+VW*^va8jM3OPAZr@{o!ILO(&p+c-xRlNFFR!; zv?WI{))8T>qvErSX7l5oy$rF`=Ru*vO*T+1?Fo z?03R8^MIil6MS%yzh}``s|pYr`Okcy&qTo zA!fFR32d=EIuv7_uXvM+w1IZ z&xkJT?|lqzG`Ln39vQ+n3VllrH=zbj_PF_`~@{Wree!v**%)mZn{ySoD5RZ%nWK_;j z-)!R>dvS(cSeN+j{d&*T;rA-Jdn9Ip2Ys~GW#Y=LHP({fVwHu{6<=yL4{Tcm)QH+X z!z!00N+WGaC|0L)1StZWyoYXB^8$4vLx^qsqp(ZbgVBN%_T4y7QgRn&4G2#1c!chiXB$UzI2J&(oS5 zJj!hM3|wcBc}~sU_5bI~Yx}lBm|cAZ3CszAyYIJqK8fSZ4$p4%VsmMFA@?9k!h zuRYnNoo1l7S}W;_gc#5%G3E-h{#u_AX<_!i;w=D?mJ@ci3AD)zFlBx|P{MNjAOQ4l2EDSYshxUn^ALOx`Q z`sHgp{;vz1uVvpg(Ls?q4v9Gk2O4J8Fi3x0+8tir@`p9g(;2B$5vQbQ6KG9W6uXKJ>@K^`F2nvOmW72U8y%RZT7rTtEF)VVN&c}=ic%F7)eanCoPplat5)5QLJOKHD zk43FTgo|%%DC;#tV?Cb)^33YmMBm;x#!RGf-)U{hKR<7^LKOveYC4Ahz|I`Dmh?K9 z7eNI(xI%Gy)WgR=IOCYCvnTeX6=5?|czy54BJ!yJ(*9t$LwGxS$DFsR|7>WiStO|3 zH|7m!b)tjo5i#=2977z{ltfF|o_Ts|U0i%qOx-B0HrK-E3P@mKg{vIN;&ghZ&zuN`7RLMM{kXD*+Et-7olwi2 z_v3ul!cd@SMLlit>U0GwHXXvWEH1A~c@N&4_&relRVCG+#j-4|Y)85K1b~I(V`%}dO^K8_+Xl8((N}lC0!b

@8N`|mO(8clsxTAlH+_L;yr|Ex}vF8ot7y|k?U_z#)nNdYGAPn>AeMZ zKC|p>RN!pz1@va(_V*hz(2>1@v&jRVjd2ipuvs9bdc=8p#*Rl^?s;_enojdB^=V&2 zzQMNo=;<(qMi_^5b*1C#GFQD^7q~dk-pTl=AVL~w%+yNSmNcpGWks>0<**;@RpY&$ zd8P_7HOy{bEOv3TNsXC6yE0grJi-EsLp~JfR|iCLx9wCf1FecdCdDedErje?y;U9b za(`D8fRO6%`er2^t9!b!E~IKR`%pad1G2pEW8iltD{iATGF`kV7s(vD_LS_ zMr^V-x?VH1Vv|r23ZE4>xw9NLR7`Sjy0YkMN~u)n@PPAGq$qTwCEjY~ytv6P@D)T4 zP;b*n&orwn3;O#_F{nq`dffm_(9(BJJZ+LYp3yv~_z#hY-Cg7a<)zMfp${-NiT=7URx`hK{CCKWcV%;+;QgQGR6Vm}l>GPp?b|cv@8F`C z!y!>4_0$C=7P{fZVps@xL)=6qd1GhToohdau~v;v;CSyt5Z!JeMZCz#R*4l|g!lV< z{=+Mfmtb6*4j65%RiEyU)xZ#>|Jcc>Z3+wb_etq!2fHJde;neH0+d)_drlo2|+EKOU_>6_E{ z^}(2~%edfprQZD-mFHZ$1~0MRgPi$+=v?{Am(`)FR%Y*{IhClvJ)2NKP-ut=P$cf^ z7+&we-S*^|STw`l*b>$M;d^lfZ|gv{<=A!&?g@0V3rbm$udjy5n6{LIYe9B7D^@f2 zaCwDbzm0B8t_Air9!nq~9q$|h=X2#c$oO>F*besNvEcqUCzwo&W-(A&T! z!h`#}XLrm7lQq5b5#RUk4q00?YUuVyo3Gs?{d+X$2?7jA$eS{uR;|nj96Wp7b@q89 zrjlWs7pKgAiJyBmPv>;F=IVSvswf^T{xgPi10X$Y)>nESL>X^)eRJmd0K~M^%dIa> ze+(#NkYB6RD;OlZP?{6bJ5DTCyG@GApfl{ZE6K|`{QtRsu30~>gUDw8H2oyFBZylz z^RhM2O@_ez(+Nnl^L^H0kn1cq)-b?Uh1sBARX0XEx<2ZvE^HTK72{!}+_x@TP5d?C zfwBX1Vv6_Q4&T#6uyiA_o&Mf*|C9S7X@()Lk<~dvDHd@w3N1&lE6#c(vIs+Fv;@SK z4CREO0u2Z4MPX;W9+`(bdfTmK(9AIpleXXc_H_>?9Rj|4mJHt)eaAX^xOKu}4c|~?vHWouI}H*2KW;KzfpeGsN%W2gS%b|5Vx4&2M+gd|CbwXz^t?U z)5mMhF74KI{p;?s?NlmVReN63X*RF9`)yAa5iD3oyWk%%!3X(2L;{IXpLqrW+uMm* zJ^eQuyxy6%8>!?Q7a_&#k_~IvPUDtGPi;qtN+XRnQ>o3x<*%Sv7-UYn<|i4iuYAw1 zKF{Q9AC#I?XH+&k657J#$F-0VLnX^N&Or6nes0&0I6PjkHRyiJM1($%1f#ayCT)!0d0S#3i`WP&I}>dD#1r~PkI?n9Rd!n4ZT9xG8*?fFL0^=bViN0x!GQ1^!+cIpdPyH4)_= z!nmD3fBsZ;2CbGNo0$p0)yg?MM(s5=v<~;)m|aZ5G@OwENTjEucMDG47>AZyXIO5Xi&r1glX+o?8Zso}!|jQnA)YAM z?aCm&URm=~bbx#m!`@E78AzA+R)zjdu3*x)o!lt~)MQ6V%@TCG3Y+`6^6JeNA%~TGA=ze^(R< zEl5*}rLiMsXp()TsZ^d<6hBKiwQ4tRgd!0V6!Hx8TX`rdr_dISNEbc9 zgvVllQ8h%`ZyTJpEMuG}3T}op&@4~J*D_P53a|!^K$q{`;6FlKy;7_Rg2@8JQ)V_X z^NS=E-p}PLMeN*Eck92;S&s^nq7k2$xLYHyDo4~6Bj!qx5E+x+YNuc~YedoIU`wxS z1U6C>8T_B9PrcF_QdsXcKYp^=x1#PeTK=RSgfd)IQKqMB8QRt6G4ju%X!8#D&O*@m z$~7xxjz5r*`m%R;ddF87fCvk+sM?BiEE{sOB&QE2L97&yMc=v$CIWE5T5S5f?JDM)!F8~mR$?QpQ;GMaHDVTMg*1u(C5 zDp-e%#AMXi4vhw7GrAUD?HfU5CPA)m>TgZ$W}7;E0VmwndoWcML?>pdld^MlX;)A% z-Oz^Fdxd;q(l0GB&sA~b5tH|G+IO@%{4*k96Ikc>v9{gwjoU2;%k^LaC>&n$%2p+G zs5HubJbl+#U$+w2&Z|Lx;sCYHe%sJ*Y$blM_jgYDx4ZXfujci3*aytW&yb7pCf;!N zQ_zKegUe6JznTAR%yF)&MjS?{E5dqMb#i)Kp^Y)fJMgkjcl^B7WpsZ2C|)s>m;oe* z3q_K|DiONp80At6Wxf+&)664=A^v6k9Qx4nBWkhFD{QTGP`zi+`+QznQt_-!h224|Lb6BZGkml9kD>R>N zpT_d2M*o{ra-XoBi$mVx9Uv@aYt&tjFqzGU}5mQHpjLqGTA*FxA--7pL zO~>ccLLe~pBp*Ggkvs`wMApPRsvHW`BTbUGM~NF-mw{cM(mTB7=Nu|{anjjqWcE9y zwh>dy!0jBe;fX7kt!Mf~@6)~-`Q)WN_|Hal%;WS)QO}lMZ0dy}CWfluFLM1YAdV^sLE%3A5q*?i7s06T;_n7{|9-GSC;ZTfupw^9BzKs&CMg$#l^? zt`sZ7EXayNoEh&3&c*3=LjS^+w!hu-e1Apt4=rnfNm^POOBv^2;<`KQ)t_iY=JwR* z`Pfx#_2z4674Uba#kG(coSIwo_8(iRca25cDIu#F;!CCSXIkF{#oq=V<_Yq|xsr$x z=5efrtm*Wpy@X6d%q9$0hoc$P;wH~oeL_;!9dRGi%m7+IGz9!O$;L7T?mgChaq!UI zKmt(ke9Dq-hZ_u<6HQ2HgkBvIOig1~*j7x`{P+D|kXX^!U%UNv?lNSy({=~zz>%&t z$zY1}9*Y5s`GRrJ#tL|p1~6PpaPbYn*gVdO`!yVgb3y_rfPstJ!zA}@Q^thz{t1V4 z5^uJCUcqTMc#xa*v$l0P7ZcZQ!YFI=b!Eumfnjj zL$f<+5?D|lQt%Vt$f1HZGVS_#j_EJZcpDY}rR`j2XDie`>j0G%;j&OW@c z(UsPy&NZf!ri3HQlTARoeZq%%d=E8q4=7KzUx4_c1_ zZTQ+0OC1RZOmyPL>aI`Z`yDTZGRYqO!)9Y(!B8R}rshau8XQU&Jy4-$$<99OkNN8CW{)#dQJo6$DO@xxyKScCrnZ`t< z4`#t^Yx+qU!eiJwS|sE%G9Z?t@xOI7O>AIVNDn8gW%j#79ZX7NvLl2bJ(EFO#XEVb zSld`rXtu`uj~5?187+!5jnn-GrDy={bu{19(Hev(F>!)L_%>vZY03NL`&Gc4dU)>* zr|vDO7Y3lAw=g?R{^-;8Oj-T`4tML+yFNWhPGddGid@w<|J97`9ma%UVSZp{5OxT;cm`LQ z)1QGw_y9)4=!9&9hqZl!i|p}F9mF~1ip*Z=A(VZGZn{rZ=F;*!df-3vrU`3Ux@vm8Jp02yh64}S!8xKO?0gL5AF`?Y)(=R$2cBes1a6iH}0fA z3(ZsI?c^E({%O!TX*U`;k_!g3b|)#X-`GF0yOV?r+Xpu`;TsF&A_L(&%0jZ2$a>z7 zthabi@n=~Bma9o?G*pdFeZRDsE>t_q2agI#3ByfMHSRtt<%mM4*d!1Hd6>ykpxIk1|{ z_t6HFyw6wSbX8CvA_zK2?NtcS-Qq>to5>K{V?BC!YyNh_`Uu33hn$R`n4rZFB#p#Y zwdaOTa^Yxmo!QtISI)o8eCW>SFKkE2;}+{Ft|$u3Na6Q{n%j!Eg{9WdMgX=f(yui6iq|1OMneMWZH+hO{@O zRDEe}b97zWQuZ788Yh*JdS9j&ta>{F_08RsRh;7ye{@RA&EpdyG*i{pGW2H(p}e9o zAaez{@mpqGuJ^>PjXA*qLviiuy?UuVe*IT#=k;DRXCBvZX6}C`1BfZigQ}|;8$094 zDFf8(x3zw0?#hX)0w+DEnN>~Egx#0d4QBAmTcv8j=g>hgW;ML0JaV?^*5DyoiH&vg z=!vAt+ED0{(}~2wMa%|)Jzx~0(kj#9`YgYvBpM`Zzo0jSz+4hPNBkKp#}7h$G$T{n z$kaBc#38gB%Bu*wY6!?I=2m^4X>M&>*i?yhWoIYLMHaN~S6%EMIJ_-zM{_p!2+SB! zRl`slkIZM^bnue4w5u#>F(%x}iBZAWAmn$rYw>>S+8mlxgW*#YN@P2G@`9s)_1gc~ zns1~^oH9ZB6{9B2fNn^RZg>p6Tg7`wj56m#k3M5pN`*4vk^c9SRhc%eDc zOGcPkcobes_nV(Z*5Pr%+O{MTh2^)9bVJ=&6tA|3sdA!?Vc^QKrdesx7B_USo>~o2 zqExUX@3PwJ8NG>2i%s#P_ggeTAzs2>1d3sriMQ`x`aLMU7W430(C`}JXU%RZgnM*# zI~zx~Y{|s26O|TyWI8d19?1)sE@I3;Xsu0D$@@~*ujpy|KUErvQpeJr!Hml)d zDsYXN*j5T}8E2+F$7{?VGHE@0Qd`_rloghS%)yUYPUUjH&MyuOq&t?Vrf+0o8L|0v z1my(5@eEoisk>ET#!ROw-xS#-5LmpZMpJEZezIk`5r7{$Oq!mB)QketoH>a{$A?G) z@2W~J9fi5b+OoX0C}|jc90y_8Pk59H}LRD3@K3+au#IP zL>8SdWY=``imcdj4-Y+YeGwEPr^s8F&j?7t|L9CHbEW?75^b zRDi3INIpbjR8=AAd*aK|%Ps>kxC;>`(`9c}Kbta_cRUNx2vu!?v0p1_>EJG*AT(RC zk7c6A%WkhMO=uK}<3vXN7c|9<1wpB$S~R-U7}5O4b;%3>Ht?$|Cu0^H-lr!s{uyz; zzkP4^){@+`mh1YFejl=yE@s;)9~@t>pdl+C9bIVT8EXbkXo|b_aTh{c(#%+QMkrwL zV&2Frwsn6Q7|IG<6Gl>80m_^v%~*5@I=d*7RWx^)9Syhd$Hq9#T#)c}-9ZW|M7f?1 z8&o+v@|v#y@ovq)27$YaLfZFOmyqTT>F!FEsQ0Nlze^rGFfhmy$G11*QeO zG5Tzg>h>GlE3AD%+;-whTzs;wq#1Y)CVV4%F8psV0G*(5zov?4R#EsOu%$9)khXTe zGPYA;bUvFwxwrcJwHpXdPL#lo-|l-wR`ZB>{_NxWFOi(Cz|tVf ze@9m|>Hgd?1F;3=5OE`KGnX)4)i+8nIp5$RlAtGn zR+W+0SRTI~Q(MjM_v97>IhVe zt7uPQm&+=TGO5QkvuiMV!!W3?Cg_=e*I>GP`IIVT zwW(JCyyV|kJyX@&jM|GWerH~{!%9IVt1D<7jGDcl#6s6hgw*Xr+52lq`6w3`m%!yc zUOLJlxun~SEE94CE$K@yeWK7_Iwn@&p>)<C-ikb=O zst;~_UB)(j#1nd87+ojUZP#5&_Ryh#bA(mc2)Gz>je;yjH7jTe4X=4ck;*}NG zxM?)KWeLs3g*v+UmF?4(ej^L+Zb^zxu;a!h{~x?oO;V}4TmfTT{5YRymD(*`S!XR; zT-zUE`!6(q^$TwIHouy3Ezp-jt;)!@*)&fTzEV_oLu^<2M>>eL@L_gfexm(lvDCA!B&L}U)i&e64}NGzmM?1Vpw#n2W{>HH zBFpdjxu6AX6-P5xys|CtXv)+@ZMz;;R-FBw3XYLBBw~bH+(-h0;{w3~C<_ZrRHC8% z^uRYG@TG&+;-%1s9NTMM!b5d@!!2iE&i6JM>^Gp#?|eoQ{r0xKtij5gJyB@A90Vez zRg|PeLlDzuhKsURzy+h!Zi^eg*s@2^mjQE4-8jSz8G$2~d z-9N8R$Y{sVq*KxiX*2hP-|s&K_i~uWB@~e)Q&UqMIda)@ zr*fF$&v3(sj%sRZD|(7oRd_v zR?y?5NR;Az^ zA(;Z=o>(}a)D=xkB*heu%oQ5Py8Rf!lBY<_nCFh4Rk@{S%@!s#S(&LC2^3YvqZ+-| zXAu%ju@#lZ?bkxAPLD*f6*u4e)M}#e$)zS=e2I&42ilt+3ImDqN6YXjA|GCyg?!bn z&^;A5{7$IG=PGpT-pfdB+m69v-mf-kTW=KEZf?jC4{EjYyao9f{cGm(V=c>7=EAtJ z??9B;#Q$@7Z^>bpl$KRQ8}>nn0feem?VKN!=l+sRM0)g$9#vF;WYY7AY(!@S z|CQs1{=D&guocO~O+OCfHZ9F=9sQqr$K zbW_ZQR5u2ex%4q&K_}n@`U;ewe*Y;>v#@i|^yl!6en0=nI5`@XMLi7z+J2O;W%+(h zK1HQJ0w|Uwi@Uk*o0j1I`}yexrOFg>T;e8g?a@DgmR%YwZgeUy>6$Gsu7Z3pCTdY47r7gZ$v;*VFW z5-wXx*bD!U2~le;r@X8*e|`us$EsP zs@AMIE4cBEgk(j{|Eagv#um^{?Y{*LW#(r6`TaYxx1iwY_N5evg}}tdeXU36j_sz2 zXn;GE}T32HWhhwD$eOndnJEIP(c>|D1U3f{TY39 zEaRA71iB!MZIYO?H{Su4#{amrt@$Z428bko#vY0SXqYf!5x5gF7o(tx>EewB)C3&{ zZJN}U|C%^t&APXmC*ly0OKQB8z(@4q627SRGlcwlKV_^1IvrXYjbSKQu$i%0c&f*d zNm4MxWGi)cP*%YVYo~Pp;{Bc@|7!`|em&pZ_86HIN-2jM7k>3=vQX)HMZ93edF*B* z@*-JG3!gnxQBGf*0Y&vGcC@l3KX3S3t^q7N`42ocv9zjx`Ohik6U`5gaGdywnhm!F zU3^8UfhHCf;ip;ju~KtNI7fxp2}4ofrD;{25^f03<UJAT<;ERsz$06=PBu6j8Yn<7y|?Dy-&L#OYqCN&(6Ue_{vt(i5Iwh z@c?9wKgElb1WABYOH1>p)kAEWnwPk1bt{_nncYp_p=b^`)}MwxQ}wxr?&M=DU)bhH zzJRk18Ye#@bsIlkbqGL5%C`D9$0}>aeEgtN5+)IT2VTcae9s>x=yOT~T?yM^y8#;a z@8;4ch_aBPDtmLtbCKlyec>Ys*ux0K4@W>>Hb- zoTzPN;>{;ROGuG9LNW52E31Z25EDl31_x`qR@mH1owBxscW0ZOq0F{?h-Up zp@fCTVz<14v97(o*T*l}O;ZBB9#;W7C)X6B@N0BO{E#6-o@})s+wjJ-20GqzRHda; zimHL0qIlusKuK~j)tF4CJ2p<5HgW~pnoQz^JghDSbs3Se30zRE8a$EI{c3UMXF8gz zHTRNMW0wFN_ngjc(tk50_BE$g1UkkWRo&hG-&m+#Y^UE7UF@W^;2efFB-q6b|8GfH zP~D%<^#``9FY>UYQw#msEou0aJ%1YC_6Bm~2e$0YZw_2Go%7~)$tV8-%w~IB_bp8$ zc(5c$|0?`l3>kUNM8zvE5*%U*^z5+;bvdTQz zrk|0BRxlL9cFSPo77U|$dJl+R=Z<|jx-m$Vl@4K4K;&qz4jQxqRkueC+K>=ufA|LS zVCevSOtZpNQeut!v{c2#{ppzNcA%mhrgF*6N9@XLc)KL5m`0`8#g%?cA1i8~JHX4o zK|&08mA@3nrYCgp*JhYga84}uGxk_P11loG`wK7?aw8_hWx~4%i<=7dyRi13`s9EG zd@~z-FtD?UnwlWHx`Yx{I2i5{bndhoflifEg*3<&(Eh5F{dRhZh-Z5 zY7EO0OOm_|53J`?ONfZE0d|5I+F;`3h4{ALq2Ife6W3mHI;GXF8T19)exV#>>P4$k@bnLQ7MrSsP zHRevfynH}L5VNlwnJ0|uE5rx+`V`ZpMI?(Nt1zE3ZLatgZBct?h*THU`(CGbv;=cq zkB?R6_UNjn09UrS8l;;K1$H(@dJ}F}6>Qa5@J`7K4GTw@pGC;A&9A}()U%n3sZ1Du zdn3}HRnyO)*MBWPVy}OQe5*rKYoR$#K;W-$L_Z}s{Y&R=^5e`y>%U^E)Id~poH~k8 znSFh02pEKRImwI~@0c_aBIP)^!<^sVni+rTu&PJ!7lGF(_p37IZ3%5pCfnuxgR|u| zv-%xbLAK6q?axiS0rg{0V+nBbQi(sS49<(mD!|FpKyRsw0vd?+F3(pMAA~^6ZMS% zfZyqx0)4TH%;<6{S)dD-YaM_gRWdD>MB!h~~9k>6|iVY&~6xXk{{ydSfsUH(UCEL8^nr zA)#inF0+f2pgBDmb9)Zp2AFBA0yKE_=KL6%Lsml!@NtXG&sUYAIn>sUN8M1cA7BOH zMT~`1l}8Vzaj&l8TmOX@oORaxo+u+FJ|2t2&dJ&jOr%Q_Q#H-jk$^2+U^zCDQ2Q+WHzNdO(0#C4mcZrNLy~fjh{X{sn z!<%i5CJE|0b;J1kx3CZtb2+JrPajj0={9wLm&lHWE$w(cv-O!+7s7z6FU+s}0k0K= z)1>(MWJ`yx#yq0ylvdM8p#OG?9fHANcj`yT_x|Jng z(IjrNE7@X!tXe_rq}8B?ih_m#hCL8W{4gWaZ98y}NaKyELy2Wze0<9HadVCoo{qje zs>}OwCubvHe(Wx&R*at6&p$S2hKPvB%F8}--b=sZm1JiqYRS2CkGacIRa8Az#@G?Un}E5G2Xim>)+vdOp*&;zll4xu(0i&JnYsxFYYW%uDn!QJ!PPE!3&UB zdl3MGEVKrj{T@7XI(*W%izHTd@@{Y*#2}#3XgZT})&TYazhb&xnYudp6`?5>q=om> zC(++>(`he9$qC9hVv!zPivuHf+U_9xoVhvHoR<#r>uVhtE)KSi#-%ZQcm@j`z zZHvsdgj?52={$7VP7ULAH=^5;5$_*n*Sd&2&FE(Tvu2M0*qZ(v7r+g-CZ6rUMQ5$i zpAui<~!eEDcGE`&Q{daIUt`Jed)Ffsw`qW?0f;Qss`4)BWbi za&GN-8nv~uu?B%Eg0fsllEfR^%;*}?gH22 zqPsXaDTZzClgd)0rN1!9T%rRndqXL4BTn<%vs?7_IIH}edhAp=SXR2&yP^Uy;U7#T zq&j7aesIZJ-rZV4m9wp2EP&OlPJqtkbec4Isz?Xe+&6pAsqV_~M})U8pIQVN^zae- zvmkQcg}fFqcr$p+e8^(<#!BncWHAXMXVDkfxuJ_Q6`5m3A=tNlp!^&d=pSY*CuLb< z>gnx#+CXcXYsWwMW6FFG1}4+!o$o4#S3=sItcc`(KYgT-T;aiBx312}#oH@0XE1WY zqDR%ZuM9&)B2mF6IV^E)o#-6oX&jCc_`zJ|xugQv>R_-s@QXg4#Z4Fa5Xv(Ik~Y(s z)UG+>tjt({$9DaLPWHmW#402-^!6g~KQE;IG+=wXMuNV!d%6MP?ZeZE9bGP{Cw9W7 zaQa9BA@Z3qb02?C2q6|Jft}qw&yb0`0)>~k+k=n0kOO)pmRt3ev&7~Gdn#_G6{DH4OwVPunOia z)VF1klUtg_>OY5W1uph&>m&96dMxg??~YM16Ycm%*0+%ki;6M~<8P85xBhg@#vEiK zn$nUUMKQ-udzM9vQJCZc0yD{@0NhJDK$4@=BTK$O-!x-43{_Rb7vf~{LY-`q{nM7I z=YKSwkt6(IDB(jexgh^nzB~#dgjrAL+{An^y;Rpe5XAHYOQftZF*qZ>R&aBy@Jw6* z8bjvRbEz~Vo>jyzt}gH`Wh{hD?YLUI!YhW*ii`As{SS{OUI*9I@-VNbWx`!@Uhb}O zh3A#>11GeA*Y=A{Wb9z%!sYM&6G;`y+ZDu`XEtVqO>;k=%%|5YC(}Tr zOG_@R;z)qHt-@yO@V^gl&0Rdqi-gGZ=;6avLNkA!=krCuk@CpFCzlK8FO9-e6Qttl zB0D^J>$?t47(I3ahu7PWr{6cD+v?tzGO}|37JQS+TOvxfEd+OUv26(A_nW6Xqsz$y z26X9^f&#-@B>v-9EOB*YXEnL=+z^AHilYr*wB24}P7t zk_s5PXGfz)d3TR_$iIHMYoB`%LP>hLL%1-@(>F?74e&`t4CzFF(p?eS7u8Nb#A5H! z?$4p64f?it`KO#rL)RAg4NZ;dVKgpH-o1+Gn=hP;N_4=rfg^rTG>}wKXn1xU z)3fRIUsZkDZlm9rSmclqtSt5j;C8q+cF=fmr`qf_ej_n>@@M{ZOrMSM5^~JnOW%>~ zM*0N@(&YGY4wpN^qsn-UNnP3!d(*9+Z}kgMPMJ`*QCNqAuPqy{5m5(t(9Hh94XoW$ z@hLr?LdlO`bjHz*@DEQ1s+!lEz7K8}6_td6q)}8ZJk5AyD3{W4udWWHrf^*mDDqemn27A%n&#DZYYH^jDSP$Gh#VdeIf!&k z%8%GBfnh0cw;Fz$?;HjuFLt!FYH1B^MmGaTOD$ZD;e%MeJL21%-1KWaOAaNwTDv3#C+df-Qkol0DBDMvB)lW zhhLJ%IPMJvV>>fRl?p^nMPp_)$OX z!k(j4eH{LA@OKT~Zz~En`TVW$#>tbdR8nf#h#NWuDTgnDbpv>fs%$}vNs@H zUlLO+!6{>&lJW}bJX<;;$TBfGhsLSUEMIKmTRrW2nGYd@f1bym>+{#|6jqX0G@U&| zeSD!D=b_zCJ}Xb~pCl2!FfpYHVNy{Z>I7SQ0sUHcIyyVlV(6qLAp4_Dw8$ZFL?;5L z?Ep0{;8op|6bmeG!Y{tnpr?OjL~6-uGHKcQ+Cmybxpaiv?3@{cK~_Zb255wnk-wPIOqEhKF^?4UaT73%5Lv^$05t+4Rh5Uu*;x;{LdL|V>1MVb^b?b zJ57uB^I;Kx@TYFK#dzm=8rP9fe0CP}F;TwiOfBRr<9OG9+Qn~@>Z3&_ zsrb))TT1rbA%?Q(NRzCqfe{2ko^Wwn`vn8RE0_B}q}lj)tkd<9Rxs`x;E( z?dC&7E8-{ZD2!)e`a4~IX)p?&U%`iImbkKQD0zftNxS_HFYv8BJu@=2qdqA9{q@A5 zqUWgQH(07|GT!;s2j!cmxWamSH_ar(x#fepmZ>kdGY|W~g)L9ZOqa~2aevNOfTy19 zB$@%?-eK6C-wcQHs>*jWUmTd$wZ9B3{SGNBh%BsZg5CelLKG^eT=!g1KFDdHCSA(g zYW<(fhyN^6H~T+>EuCwuZU(Bai4%`#vo3v5HJ(e156d7t-#e@j9mF|m{x=}adtqT$ z#i_FE^+Lo}n_=qi5XzALlA$XfviXzw^TJsx(Ntl*wLjfR-x9!;P~0BYSJgGRGwCx5 z{y0HpDv*!&_J3LGY#prV@gDT83R)DCe13gW{JrJ=e!L+iimfg|UFGyJcedWy7C)&j zB`*y=L3Rnfv&o`G6jbp^hjYwkk4~`o60c*!UUk<%{tJ1mvftM5uuHsxltfaG{_J=S zM%ArcS)SuY28Gr1u{|a>mhqy{oIjxS==*=S4IWwbvR=+fADd{JY7mvR9-F-GNm^?R zH~izr4Wvi!DbRA){0df`&ArA>iJMiGHC2;}HT83j+umx!mIdSS@oa*E@(Q&oD;~e* zu7JjY?r7K`;tDBIdL$K1-PnmQMt*$V_q~`xTE13g{P6?EzPk~IF6LQav3G2c_xXoZ zd=Bpj!Ry&|%LOiyE+n8Iyl`47=S%=KX?SkVNoe8h61y_|RghY!jd`P-oZO=K-soiK za-CiWl%6K;=ybS`cIxMFZXu*A+M}hWpc;fx_khsZ%s=_I%nCAdpVz`htrp%PEl8rl zLUBHlV@Z}*bvZ;p|Sc+2furWpP$J_oxUpr&EpQE zd{f8q`rkX{!ke~+#H3T!(V?S)@=(Y`nv9pwHp&1n*XI@ClVFcA+ri5bFit5+lnTDUg6c!2#dQjx~djNM9Bpvjd4^0GD^WsuA4LZ;U`S})J&!! z&@*=P%BeYVr*!?w1(be%o-%NnSomKoK)kBXcDKVK2o2ExovsrdMKh!uM{5vnGHzyT zORQolYU1f0_--JNHd5FdyMB6fc}`E)ksV&S7 zE36F^i?}qaeK2s!E~NPN*PX29(cp0hSGT_YpXwU4xpCf}`DCDXt>rKtH+hWy=Non1 zjv{9zJuK{)Xy#H#G!aYzM;4qE-8n9teg5#RnyT!*L$Gm0-61! zGlhSTPHlnFk%MwNW?xK9bEZ87MF7sp)8j;y1|$G_a&_&%pA=Od1qRKN6%25iAdyxX z7GAtRNWmN!v9aUTS!hn_o-QvmSG8T6%K3eOf?58vY27?t8@w$$Y<#mOY4c1oZx_TQ+>T+Q@fcj5QY z;C!v=Dy=e{IG;l{BXYJVIXT1}r&#Z@;Rh5Iaf_wl%pXqsF7<}-(9aOo+n2}Ib@4$> z;GoOho}j2m@wpr@KLt0#p>obhV-k0b~G`YwK?HnTYv zgOcnu?YJ4F_~hA%_g)k-w#RWnJse(Rh{s0Ze_)iwN5DcQ>|Pb=QO{g1MG&hfBzyNG z6!X{u)tUF;{M|0{J%1@o=Z+7@QISo6z2C}=iOZZAV$0WJw!?O0SS{C0Q!EV&k(;Hn z*5>p~u1nyq*CSBBc;!y$7AF^cvtovcDND%`4Zb0jP?h@1sVf8>LJah%s`S&`y#!7km@d$jPuj zi^oY#5Eex5$7JB<$)$ecX51NliB z+49L5j(QnNI<@H)1z#@#*ubcNGQw`dk1pbiPDtu*@-@xA&7kj^T4e4jnKDLPHz z`774rd$l^DfMOZJA#WoiN6v#;wjGXJ_N$T`^MwGjHIdnk%8->ZF;+V%NmKuFGXCr` z^Te7HfAjTrlhASYs5nMFP6{Nr+RaI<|8>}veJVY3>T&hxU^%}7(cLl^z8N>8C@LRz zQ^-GWr>jNY+9Cyp;_e*pm^v+S#flDUn~%AYA+pJh9rt2)UTszRQnPvYhVXG-n?*Y9PIoRqjR|7 z9}ztsn{elK$%c@?>>T*U>CYrv5H*ph;?XDdmpXG2JQzcEx}7Hrf2sSEyC}`0Kwi{y zxgmht=^4>Bm#p0&$l*;QQcMO&Sbf7ZORi&_hp6>!ay>rhLq_y49i2_~wZ=sw7mwgm z&9HQ~NHbd30qo9*Q!Aera1gAyLF{RSz!H}C^733Mu^YL`UM^1t?G^LZf?_i0MOunm z(R!8}^FY!TczBt{mz$h>6n(LiB!D$78R*FF!baY~4hEc-2ik<3lY@H!n9PZU^mFzx0dQv-F>Thi*E`B~KGb`ke#aB1rskni7 z2VgB%YgZhVpDS(f%H?L)op>^${&I7mX9JHoR>;((V@Txw#x7#o&SYprJx9Pd$6#$X zmd~^0->ms_mt-hefPc_P4VqN(7^9yjr5pBN35my6oLf3%PQ#P}@x02Gn|e6V?@r7bEzKOIP7$6(P1N%?M( z!o=t8ZdV4ZCJ*8eI)a^}=i}WqR@i5Fc$TqYml0G)9Kk*+Z#m^}k7|4{gol@FTDkoT zUvTh)LYj|tUh$A_ZFL%{UcT! zm=W-MSaBz2f?a*MH2I8&L>Y|G(d}Et>@C*JuzcDSrL!R)2SoOMqGs3{y)@ zy1+QI$@erCFla$k-9s=;)Cke0A8HIT^bwfT$D=b_NXsyAx#8FFniOr?!U{DE8JvY( z0VIA4Z(1It3*QjK; ziL{AUIWqlkK9)o6JqUfC%dP%3sQC#7;PCj+nEZU;c{@$-+D<3&8!uiWW;1ejdSB9i zJwVFso}8-T6&g`cBu}!kGzQN>-Q3Kfip!J7-Dd=*rG0-;S6g^JdF9G2c#|!?+kX%J z`ma#O;t)(H%+5q4WJhvJ)**H&2C?$T-uP!w4>P;hyu52{Jd0}6qBTX}p}_3BwD+gw zXYA)g*DJ@z3Q3-svM0KkBr2HrlWP~e;xv3at#>k_(e8F_A2Zs|YW57RX*D~uHq>nl zi zE0uIf6mnm08TrCxQGAq<%YXs<6;|SSyZNgqm^$S*y`#%gUSFBU@RS0FmUH4i#8>6> zVuo~W9dEjlj413zk`;03-Y;dt$IFb*New}VN4G;%a1;v@xpkjEMcy4hVntr(@@_6W zk$1yuZ*|f!-TEk#qsTfS;0S!J)1EW=4)K4!kuM{9chu0jyxS#@(m<4G5dDK4$- z>|liBY~XzXlPQ8wWth*(H3>>m{7ZejCj4F5@EI#@JFC^rPEP>4{O~f_of8ubny%%aT)0SK4J}0!R5J0*ENUdUSWi|P<9dRWb_Y2c8z?DkRa-rfX10J7 zXu6o`7GAuyp%=oAWNI>2EUYe%{CPQDQ{_13S8F2s$CtvoW-sBA@XDXiUBXk>6}E35 zd%pAagl$SWI~77i{hcxGdQ2)AgqDBKN$V-sJP@Zh5)B8KQ`nN3?k|_6wD`jhxi5O3 z3s1GS4f3R%a|m#%T)^N^-6es(`%(;KfV zSv;YaC-4Hm(u~$dSKT)}UNv4A2Hs?-PljPFC2UfII5+paCkj8+S=jtP;nS*|tc*xD zRx}`b9j~*<{v;UztjQ9X5Lc6k+#0A@m#h|2CLl}f;=#;B?|!K*C3vMB23xmWfxf8u z%HDL!HQGa3=m1?^Ysa{9K3H}6`dW5fs7&Jw(8~AraUmp& zthb6yh;OLZ6e?dLsu(QEx-f0nN{XQIhU_oK*@^@fLSdBN<&ZuW>^yo~|IXs%VmNypLiUy~@DR+W?tkR^U z_>P4YRHEyCcpVMDZfDV-2iPkC=*kUqxiO%s9i7rd$dfe9)>-I;Qm(^di;{Uy^vL5P z&cX(-v`Ou>11fzpBq(yL>iXvHdpk57pj&N7j}nqWGOALfJs)p;!Y`0S0h`)QLuoPP z_>XV}Jq9|-X{#UF+O(zu9jN|943&_%wso9sGA#}mHWl@ahsVPeh9@kt>^|*bjrs^H ze|zl;$9Lb*m3SlRM5NWU<}-;pC&IRj_MHcQe=fsK5^YKP7Tgn+H^bGOX<%DoTZabA z{E3Tyz#QQ!od#&oq=D}usYE5RO{^Vq{W?QgYNs?(E>^sW4O@l>Y*FZrg>nR(ljdMv zRgSQE-pc<-4ZB^DZWfvzeVd8fkM;-Z}Gp!P;%8lWBk z)1n`4_rs)J*WAMfdCZjR%cBehce>Q?&dGJn9o8^mO%OkU0r zaD|^2;Fp;wl_DgaaI<&=tRGD8Om1KMo1&9p*p1FUqD^3ML5E(`;I%}WW?f7HrY5yW z_ilR2X=iY%pd!}q93D7Jpv!!3cdZ?1Gj;LUm3?duWhpmg(A6uEX6#eGV_20L=9Qz5K<2{N?r;?4%x$@O@E zba4gtV6f2l1!rsVK;%t#+R1pA6UV@wg&BCMPp}|{@c5)d$Siaa9n*#^b2d4Fsy1V4 zMqXxNBagUXf#5$wc!^`xaUAW@^c%JjN`AcKnWg%^t!-CM|BJ8_DEhPza8OM&%x3BI zEv0FU1LEV;5KAH@@>PtT1JI=JjqPkM3jU*rJ}l<0~{O2;zf{q+0R%Q}Wy30#=W3vzK%eUh_!QB+C&OUZAlyZw8z zv$8eQ>>}G#67y*8(ud5)Gattx?wO0D!r&+DZ6@=Dih}4h>6OHf9b6KuJ&?; z(1xf55_Ob&ss*+UiSp>txultq7+hG`HX5g?avVP?;X;pgU%o<2Yvk?De`8j{%*ZwR z^P}$O+w?f?jT-~e#y7jIO>sT?*2A{Dm+qk&f)sgo2+Vp3gbHUO`-$f2Xq)<9vUpbT z^U;zvanQ)Y6VV0bh=vHEU&zG7w(?cMn_pbL6=QifH$chIL{q0N(eM`+%3Lj}ZGtfA z3bjHo$pc3eFNj?*mm;ZKZ}flZx9P=-P^9wp|ELqtY`^GMQ_GF*hQ~1Luq+9 zk#tDVVx2WO7xv3A(7_T9`g!n5>i?l5+KhZ5pA~I`d;ERHoi@GfsS`!8>TPr^7ImwR z4%>#eGJ;SxS%EULYD9=V8k+*B@GG)JK^Mv90DVElc-XFnpXm>~d!Al8i|c`Nrpyvq zJdl4p{t_{ZHjt_7azQN8UI#PUUF>^|x$Gc$hOPS_dHT{s%G6j>EA|GpDBXtWfBMnB zUt{`~THKzQK~P~IeM7v?UNk~@Vb9Nse)^g-im5y<1Ips0X&2RU;4U9-Tp}wiV?0Z( z+Xl05d^%}1(N;K4Evj^H2cc1W8`Cu10XbA@0ZE$@AZGx}63%fB(8;>iK`>O&4m7(GDWh{2i66UEDB#&q%>PF6lip<5W$Vkdm1LgUO#?qx(XYMy-SY zX7EQoK!id8zw#$Bv%2b^5q#`XO?8mq2cX50W(stYoH1OPzDa7%#6q3`Fb$IFaAM|5 zHO`N=4aoekiH(kC4}4=&F`?s$j-K*~+=|VMXqH|{pEQ9s!pb9P!)#C!!0oy%zut~D z6faipF}0fbgRsBhvgC7OOYaea!~z3rmJc&)=tEv7@YS8nu)Wh@II3!eHY`_Irc82F zYk!;}+n2rQbJZOG{=yc) zWLNngHrx)d(GKYHjnf-E-Hjg({JQAJRUIN9KHG}y+hO3ZIQqWN-u_SO6By1P2|iMm zrP~;xrV~4ij@S62yxK_FSqBs)Z1vhXe@n{^7RarSTV(}Hzmkb|#2)x$BcFD-z}n*@ z!HmKEnt-*SjBeRv#UJ_3qp-_{h33WEK#w#v6sSZOxC3rWl$_2EX|bmI8f{Xr!R(QF zfX4GgT;AamP_ft1y09+NKdSjU6j;A(wE;3%C>u_xc}_M;ZJ~M=vJvQ+zd_dYp-=?H znuWw-a+|{^2-iZ{J{#1qP;!E@{jAyo*oOAgnnZ4^*7nClXl+` zj;c33{qaGtwa$vlguoi}WjCWr8lRqN0)|8+IN$bzXEm!b_*J&%QC|f0mkJ!bLu-Ta zl+m>c-E$qGWTVg$POPFyt>*u(F;7+CQb2?X4aJqAWEwEeToazALewQ=C`^ELhTC|Z z&tV-qJcEgVc!r~TWQ3}}uVixc;dpFO^6V8_6Kavb$jV6-jXOud31R#q&ACejAqc4!m}6TFC61S&xf z=#cActQM28OZ42BWlb0E?5?<>PuvvG5%5d_cIdd7?*W<}*XGBt%1I^WqhmMTLdW{* zBCWz3iC$N*I7ppnS-=o5p{b3SuA`ehYdf;L5Ds5ly9CElfxCqeQbeIs_w4WsiW6ul zMkPO@&D81Xdfc1l_}Cb&Dz!U^U?zP3d;`y; zAGeBi;>j&H>w@dR-#k@@91NgfejwuS9l?-ZUP;%JOnO2xG-)I$^4QL!eu$vG6}7j|-Cv&tQc`LGiBs0FctAr;l@qa}WQkgzfaTg~4e%3{ z`SSLs{fNp8CzAa}BR7`f!n8Y-SVVV&bKiE$D|M(AST?u#?V#(8&n!(IR;D(XSbk2R zKEcefYiI=nW_hL4=lf-tIA_C$-5L!dRFcDQW&v2+ihRnFs37}hBb2-S#Wa(Gck8br*NKo^&(;(ol^|M=GmgolN0J^pJm#6*n09Zl% z1@?hLDk;YtOFysR!sxMt0IzWI5GE^I{>Cca(1a_233n+;HU$M)-E*F~ zLVjqSxg$S|y_vtPuud-`g~}+FkSa>fnP2<+Ee)XQ=>UICm$5x=qX#xSCG52KKGf0h zy4r{UWid2ry$mHUvPrHA?x&Cuo{x#_Sbvu4oNx7ltyW8NW6r{5Ma%ltOLhjwdN! z8@WH{LnAJ1kzQ|hi7V^FO7e&CeuODr*-WJ>fbYyrmp4we@OHZ($6?+uuQi$W^g^Lg zz9>9ssI)>9j(S^*sC zN%Q%ek`NUknkJtyiHUWM-UF4N_v>C27AVer&M+;NFF->1AeqI*=DmiXge#W2N=mNB z?~;ajp5|BvMu!`Ncej`12`mBK&u19gQar`V!2Rh-;-oq$8q)_) z1Z1x84{w4XrYg<+ol<=tS?-Ppp+YIi$WX<^)HuKSS)y`>le9)JgUuG*T*4tUp@j|mo&=!uHUrAYrl|rl zi=aKf)8_h8Vkebj$R92@x(c)&?7k9L?rn#&=Np&=xTNgZ1vj(F_}WyE$r_3DP7jqV zIYHFye#j?ME#{Mw?nQ(oqGKjg>Ic~ZHJW1{i$zFPTO14Fu znsU8J-ol6*vbOh*+1%%^Wnm$L>@+i3L%u9Uvw)k3G|j@#TIZbXRpI0lSLIHV|AJYl z<4ggO$NB^hQlkPF!_%8{Ln`9MyS@|OOL0i$i5Cj-!mor#nXin0GboNfd5p&v#iqwy zG(R!$s)8>rIr}J0t%k`d5wm5>6sz(XdAytWCLS4X;FIJia|6MW$dWR`FWDi^tqFwx2S&Z&hQT5C#)Y~S@=a*86-LtKw}`XpEZSg3d&@e z5Q1?mdz;ug6XoClAjZ*B*YeML)&Ahb_w6GDVI64mYsEQ<<4CEtOei|P-61{!Of^q9 z){7*Z-t+>IL+M)=B=L|!z5-6$e#c$KWio^U_9 zkul$RQbe&}rt3mjq4QbFCKiL;**MwWbMDEv84_1NQt{Ov+YAxDP^c<;Is21^TX#JX zI4weFb2Uf2mYe)zH9hlMZyz`ztk+I<2t)Rl%HYQooE{ggq@1HqAiI&JZK-p)MB`G4%WA_v3xg)1x{jhX%!n3t9seLx!0)SzaRmJSUxc-R!a86cyXJcW8@Kia$pXF2YJ$;9-_;x8(C+G=AR23hm29b|BWr-dH_mp)%; z+8MMPtu=*tY>l!a405&?2julT`QlOtw#O3!dTW9Z>C70w6Pi-_am6?e_RM0mzkgO+ zPZav2h7^9#^}8~jF5tVbQHXF1_C){zNz`q=9JE!oWJ}Pn-%yHGhiXy8=F!Igp$#KdZ5KwN}4*eGV`8f zdEj9Z6V7aG&v0`)RiaKpPuD|xz@^)Q!p}MO4TzgdPsa3lT%`HngQ`qIA?ugQuPrM- zQ}fOm_}O**d*_+gBhDotD04(sYN*J|X@`PZibnhI+b@#b4QW07qip4$5zYU|DV9Xc zIIoOfr*x6nYZP$4`69Dr*g8BI36h(ti;fo&zq$N&LkQ0dz3(ro|N|a z^UpEmny2fFudK(SP`!kJe}{oveNkive<`_W26?7jvhCE2>C4+zSM#KmNs=@Q@wM@1 z0RMxz>Op!vyFU~}^jrdNfZ*s4bFL7*0{3m$ws4;l1@7nF5g{xBm~w zF%~j|7ri)ItICvAU}ntn3M~+Irks|~hXKH_T^78zHuMgVkqb@B?P!0UV~oJ(&NWk| zV`k$K8aW<@#NZJzckl^+-t~RkzXBEr6%~xo`xImg!Jx46b$q{gKuq?Wy3_jX9L)D$ zJF%8G9VY(QO9)CJW)n6Vhz1M~5HLoupc7Y3I-u?9nh!eaZ_gBTBpv-?O}0lo7a4h2 zEV{H#F3VDlq<$?=IAqM2^1dvwGzCpTF*m$X@=OKx7W%qIE&>UKor5U^)*@}jh^VVH zROo*2G0=s?c+6MnctM9Su)A=} zXnV9?d??YA*V|NNtxeskN`d`pO-en%XJ^KpSb;27y*8Br|sO8~?r1{1jNPaN!mMnigQzS759DS4>ZaI9v-rke z=|>W9Pe0;XOQ1PYX9$Q~t_A z7#OSoPIZE^+l$HjD-OWJr?40;;%ZX%b3vEzM`e^>@yvIZ7Rm62Q8xlOPse?C`prh9 ztHRw;eG$CPzCSM;AxkN%%e)V1!dv|JsGCTH_vcV-_s5WD@;aoI#om!^CSZ8~LG&## zv+7Ck3@0(_6+A@4{e6bquB z$~-`Ox`Luj##Rh#wG+mcNu}M^?es3N63YnO<(B_&B~bj{a-4@l#mMx(c8C?Ww>v*A z5AZYtTgL@l4B9wf+vJSzbQOFe3ZpFfTiQyvjtKY8QtH0A+SA9{{i^?}qoMj|sRI6n zP6ofUl$1fOPQzZ@I{w!*%Jn-cC7#ZLN|#(}5IR}zg^6-)9bYvE;(UJsaPiV`b2E|bIZhq~$=e`#8F2fRM2J?+i~5>w1imHTtUYg2)^pIV5yBQ8 zefIVa%VFAt1vdC6DXgfb3a5LrEiJ_eeRL_QEPBw@Ue%fgDJrJ`O0de$0`f8&S9S2s zw*4Ak$|VgfRBb89mi}}u@r&eOB(?QIlk@pT@_H-Rq@PLJz={raF?O{_A=^?;=_|YF z7vUICQ}cDUax<%{-T`i=kjVHihqFH%bQEJ?*=LHVU(=7*y-0|nXuGcyKby*J{*G!* zAEaPXGKp`+Q*MYZm#e_}txF}AL}>AS#u(kjoPqR3suHd2Y0?#E(w`5dU0#&pN_>}| zuKUIikAPU8Bx4?~`!IMft!q(d^rf?Q2}5g$SKM20QwV72GFjpDj_dzwsR41?t-y;L z&ED!vaM=q}Ry#aAf$(;?MB?hd&z$$nUJ@kq=B1qVLqc>0`@na4yc*9Z-G!x8FcL*+-;P81X<9M2MGay(pi}1#;QR~XCSY-`#+q$Q*>nC7cJcB zPN!qrs94>xZFFpP%!U>JV=bGkX?<`0~Ala0f_;>sG z*G!vh;utaLdw&5Lfy-3aPdB^@`$gWiHB2OT#vup)1Q`YBT&}E=7=<_USl(l3v8o+R zXDHepp^K*ojcW!xt6JprIxD_xR@MBp%a$hc2K%9h#Ps~}l9Qi{_Z6Wj(nD-ydUXj@ zOE=Aw!{-dq)Be7K)Pq!~)v8-u(*z+Dw~V8tunM_R%d#&9WKWQD?j_@DU|2-O2^F3) zm~s~rwHd?Y!n?OPndq14(2~aq#}LwG0hzgVZaQ0kB_q@G7F1W;RSY>}-w0YUhqG;n zwv0#ML&JpdmQotQ!OV}Yy&WSj(Zv!Ak!5cwgKwE8Vm#%pUN`Wl*byOzpe_PlctiI<^M(cYo)DCQdEt$EKYs` z@_5p_u^}Zw3$wu>)V|WUX&<765tf9sCZ+wEnn>4me3+))vVRs|!DTi+e7cOLBy1+Z z4)$wr4yTJTknXiaS0E&y%%bGx0JS!EG3V#|-!ZUdT~-R6KJ6wmxO)YhPuoxTi0t2I zRQTH1e)F;pPb+O61|K@l&Zc$GB^R>2|8@s!+na~yx^^Apm-nr~qPITaZ&Uu5J(|8; z`5-V*!ECv`ws|_TbNcQh4H9~-QhFn93*LyBIdjx)bP?WM?OrT8wtUTgU4aeD1G;C& zE60nhei2vVo$$R5i>l(^jV8+%M>PxT@r@70A;>hgI)S)lW*#4BFd#A`YrGeA^S6Q7 zY-lA!WbQx{4LQ_Sd@;hIN9_RzI(u0mRb|KhQr4(J z34l_;#v>J0*!aZ8ACof@EXHWtlGiUVx9M3##L(Ze#R`RLU`drqe?Am1M0*I}(rB99I+IH$nm14frnlDCDJyW>s*Dl)_#yy@0}(O?ZJ85E-wRYWi#Xv01lwcWkusk?{WSBw=yj&nCI zbNJo~RG?2DKBO&w>yjz7-u=#kX4D#LP9;IwZNpO27b8%?3g8xj2DgKEetcbK`NirL z?>ogxOkI-Z_o578OqWHBq9P#*yx@ECNu`r_#6 zC>^h`2dCW&JSAcQ)n-@s6{9e^5;c|^c&I5;t+i!gDzTLaD*) z4LODdzOS3bNMvB3jt-Xuun>U{1=%Uwv5iKWi$@VFD^cs)T`6mKI*P&9!Sgk9h{O2; z2$qELz8Cp2VR4WeoD62R{|wX9bCY2WvAgoPyp1R78mc|#Bz-CGkETU|B#hKd6v~yD z)*MN8FAUm;geD=QRv<+|P>F>mC@z)lEZQacTjbqx4k=L16q~-Y&uU(L&y3hfhDZDdMj=Os@&I#avYeB`RgL zt11hwJquYF5&(h@dx!`+^4Cp}Etn>FC~}Xttp;bdu0W;YIohg02SXQ0gbZ5 zVqv*d`o~qi&dU!OAUPCqgdOyCp5jsy@2cvOlZ7r@K2AXvO-X?*HUNWTUJ?wG>J2P6 zq~fLIw7URCA(>?Ry9gg#ZthH90dA89|MlqL^VSAmGy-BNak7f`WC5|cHk%L+k|bQXnPu5-sDY4%a?<&izmHayL* zU&K)K>;u41G3TITay=#S!68Sh5gIcQT5GgQbnDs>cbV33eZ%H-NeqK~ncHAhe zxeD0HdoFDcb*ij93@g?e|L~x?5|4Z96yE#BqvC?q`Bb#J&9c)X=zYid@#FWxy9z!B z3~w4BT^e;BgKi!Sy33(P{hcqCudg5M*KhyteGD4LA1cwpzZHWx{TJy7JWQZ0_A^tO zNt{GVNtlQ{I7_t3h}n1Gg%iY{D_z80N{Ysh1b3!FtvSQU{EhzL!lse>5}`hQVBU4< zu>iXNydHN=WnXag@oN`4VFL`7!Gy$V7!N^&Bq;0(A~@BGd1ryA%JAO(3e$BnS(>Gvgfabn%~%s;0`?qC9rE%5#O))i*J`U z`)*Vjg7Q)Up!0ePBLPax@VF535Y8WMs<{`ev}9_mVFBU0bJS}10Ra61=6(b(G>EY& z{!io71lC1))qlJ6^^Fbj(l`-Q+r&oq9m{qJ6`>;?! zd4^&JfLZe$8HJK$YE3?i89?Spj^(Cj@ZjQ)M3FJJ&c~@wzi+HIDp^Vs*vnB=Fv7hm z2#O=ntrTc%Wpj84xVgj~76srY1ZIP#zk8oJ6R8NQq~hqH?0v3MF$d>(Un#j%1MWR7 z|Dj%F_TeVp6v#USn&5x}R@o~1CUW!2M^Q2waA!zed|s2^Y}kE%_p>a!Jy5ng zT>xHJ^+e564g(|d$T^NVI^ z4td^Oewd1Ro5xw4?sl*G^dm(9DbY0ea*-jOvtseGug3J=vZNnPO3O1nKeOK=Tz(T8 z$?1*JW!iO2q6kG0c6dRL0{ znPcu&Xl4PvdNzqQSZudKSg^^`VQSUc9)?c^J{58n4Gv;!RLBDZ)?S`JCqM1I5jH9l zQ!AI$XL#6sZf#QAUf8jNMlPB@QywP?3l~{J$n#3V0*D}&qM9ai?2e@sy=O2BBXxO< z(CJ5FeXgdC-HLr1!loIhaYq_;SI}@l)o9V;p`xrJJw2KS>kF)|YMzsA#z-W1*dr{G z!t0QiK`aMiIC$v>t%~9iy4yCN6I56q{JS_r%_D6C&*Vubh`x_tKJAIm{_{_CaD#0s z*5xzglHizvKf7450mULighpCgQ9NF)1w0L1*aaw3EB;EXxlqhX&E2`^!_ra&xgq4l zTww1E`F!x(kHV^L+rW@zQKW~XP8)rl0K|volruHBgAZ)@c2rfb=V+FL=fMdQ5oR=! zLi%;2idudJM@Q~;w=&JyE<|4E#cux9C^m5rjF5gmYf4nhlt;;}PJcDgqRG)vs*s5d zZF&DUniucXa(r6%7ov$TBu^JXI5eBX)S%;P&NOhdU1hdCRhE{fQ^t=`*5u-n=qF9k zBXKaJjWNn}WRqpW5lyR5WWXFw)(%pPRrz+GtCFLvZjif^hieW3a_$7xhK}YU2Mk=z zkMUrq=WkIiHCi(McyNqoQMDAbwy-Tv3o8Oo#n2afK52wS*%829{n=kN$x#T=7)N3O z4;QL3I{8*uRG8uD7^d*EiOI@Zj?e*Hb|6Fh;dBwDge|1li&%aYGUv_WcSCI?-xm8KBAH;QOWv2$$eGs z>KwMt{FJFmGu4z1rWpA<>=vMh`aLDzw_I_v^I=q0ClPWmB$ikY=Ga1G zAPAMjJAYU)S0MMm&>1j%pcyiX=MV%f{B?>f#)w6S+)6nmQ@t|1xOC^FjZl#4%EI{I z95);kl)N@LIar?1n;Z&oxTA2mvv#c@Mh%a(l*|9>Z5ZpBD>VTtIiSYpL+WT(=7t&0 zYK1fd1R60P%c{7Cbq_sy35klTea+~l+YOwrmJEQ~;jcB2(UI+tnIYN)2h;iGf7 zx0_4vp@t#1gvQLby^hP?XUGyC;hD@4wVSA_Cg95h|9_iz|jhH`Szo@b#6~bk92)Oj3RR-#U)U{l~53w z7#&0Bx`utAjc~pfRkh_WARXYWV)m3XU;wb^RD2P})DC~^MQv=0{Ap0(*%%OfIZv&U z_PD?zOB(b5yZkcNzS@xKxHu^OLx^lPjUrt(CnDKg88cP$?pPzr|+=&vs}?9_n#i^XpgHP9f|fS$N1 zt(xG)^`1w10CnG8pn_gjx+-y)ViS)<=xf(;^ee>Cp!-KN@g0HH>cDMpQGa!n4}GSW z&DF#<7=!g)P*sL0^V=C33~nc}r-f|=IC07w6Xx95Vht9lD2!Z~M4VXxMBebk$4k#O zHpI={n+~h~QG=zMocyVFA2WyUwaO(qNIuGVbkb!m0TLojCR82)Cy#l0>9}$z1Tb#-V zMX4IYO4ll_T3W})K+)$JuF8fWFit_NsLsE!M6y%Uz{EYOWdQeE>0MZW%u!o{2}P<7 zl_G+2-RTvC^IZeVY?h9m?-lP_FM3@#t3{Q-)SzUM zl8Ev%YhqZ;&mBokZZ3(`-2^=8wKnFlZS4e1=GHvFnL10lC?11GgWd99t?pdIMTS$5 zd1}=kSfm9CDf=IvQyU(vBeBMA-u%hAqG1x1P83YBp#e~^0>>9sS?e0Rbmr2X|01;W zaUwVWzCpb~dTxJwZdlL^jAvc>9Vi_73G5c z?d5&b;ezuqYgMheHl|N+URK|W;5#AKO!y9WQBYPGD1F?tz)goiJM0F=dKc^F9$qRO zI*b;OcS=WZ6JJF?Sj>a>RyQKzqOPZ5NCqUO_2pf6;%DfFmc#nvY0@r|JlNuK&(*ie zfa`9bFt4^neZT9*z&SI>#8jXp8Ha<02Qhy*L>?-!v{WQUifL?08ASbjg^{R$>CUHa zeu!GZz`(@ZBBuI)N>^1tvoqxNm)>5(NkLshO!D8*+6u#Ixg{OFxH%)8`|qyG3_%0K z#Qg@@ydaT+nvk$CQ~pPTOf+Sp*g@;g7afw!+A|wS9|Zds1|;v6F-2{0YMVWI59Wpe zUD&cTa~ijE*_Bs#h-5|q1!K-ahExJz@cuqRqswf<>(?oBP^xTQ9jJfhw_nA1UMVO- z0`NAsZGlA^7f7+PmFI3ku33%H3wW*_2s zJdE&RJTReuw@qfT+pCXkqItm+G=e(=)Cn8PL@>rX2A5j%OUVIa{^$p+3>tWPjIbmT z8XCL*rRCS#-ss1)mqepv^c--}BgkjkoBW}}FAOOHOG85i3kL5mYUpSfI??}D@`Za& zHTw%p?N`Ip&|TGEjDZdeFDa+(sia|SfFoK#_T!eQX-w~Wb@67Ib=OqNCKadXoD})Q zW~Nn0xWR1Y!Yzq}gvL~xRn+*)=onBvfZDoS{Z9uN{EBr6O89A;$Zl8C5t>Fy6gWS@ zB8FIX(dthURyInl3Ke4NqOQHxKNMW^f3X06iYt?tsy{i~{*4zc>FSy|u?L#8m6p(u zDdM{~T!fLvbtN2R)xG^%k`eoi+zQJyb^&I6oc39T6H4KN#y7ymdY0023`}PbcB6K%Mw1+CO{4346>`&&O zqf1Y)8a^lp1RajbKcF#^h)Y%N`WRLMl%IOG_AB;qAk?2>YPlj=Cz>_#=jD69r z<8OQq`gEXBgoB|V?96py6ZC&>dFcx;OkWvS>j zXZ-0F7ZgzROIU!SuAE?OR!d#BvV(-sQah@f*TbL<4`fpGt2`T?pWN(fZDW_xKqmf z6W8hOY((_LjN-Crs-BxCUokK?vicV*)4=!*Vrv`tEzzWv`$tDgu9BLb7&Uk%{Vgad zDT8yGGE3Ix6Eb#kRK=>PsT;nT3d(|3hLPcvxFa^&dt@9!W^6G87Y)BnurUJ~502Y72gPPY=;`uHJ2Q4_POl&2 zS9|A}jqW|Ce@Qy+s@`gx`sHjnw_G(_p|+*>kHfq`9hgTvQ6uoQ?NWe0x`CM^=(;vs zDBWJsfq=ISIVJ~b`jQ+_Yg%isotVpFDj|VsZK2;+y&g1EoYf_;ghpTL)Z)4v7W7BoVs#vTZU5pO2K9pG#C`In?-+Nk*bj*_?vxoG zDTr)$jFhOViP8RQgshCv(-@&%6^p5}d1CO5#jp>}kv$`)pO!aKTOYul zl9^)St`9eXQB)5~dl~(Q#${@_&jL#G)z_2=gHusaFh)_hR#q^%B{53h3Yhoeg8K5l(=}7Ot zw}5IWJX>*Q(yb?{B+QwJGKJ<9+c)O~@<{CjjYUe2WIHjuNSpE4`?mH~FU6Xk|Hlkh z*=dI=^mp_@$@4QfzFzeSnH=U=R2-XwM+jMD&JVWC!h#A(ju}VIR6@+A}X7~@ra?9%`YVD zd-#_EuARc~Z&yX^N*Dy}psGfCs*$}xQsc=_R=JghB;V8xqjsN&)B$=&wGau>Z@>n@ zwP;NL8{d-%lRtZBZx;gdfu!Lf7e8}f(B81-hrHW(8+#sRct6}s!|x~1H%=HPy&nk< zSHh9Mqe#YeGZd8FH+_Zun@O6U0^s~9r96gOcDl26`O%%4gq)Yc2=b6ucoRieVV%~n zOVq-XJQx&9v98Q*U6Q`SS(mk9VB+JMuwd~=F3D@j%?P7(S{&8K#?@Hw2MIX4-8kn` zk$k5$<5iVXx}<%>w+v4G7_(Z>CMFLm0Sj>Rzio5eqfC*lW1M~Y9&2%88IHZGt?ywS zg6GeR{*qS0aK|%=*d!a*b}EAu!Gt$vKs}J4lAxfB%uxe31m1HQ%JRxu({BF3=eM0k ztaXlg-Y(XceV9734}!I7z9AiiXway{(xh3Cxn^@jjWxo9!I;eU(N1cKD3B<68r+nm zmH1wT7Yw&`sYYJj{$|Y)56nJ8{24UlTd|LhSfs`%LV`#;7JlcE#+XTYEaY*XH*;25)4EiVPY#~a4G9DHGJ#?Oa1ut^Ex8! zGrNJ_s~fkc#i?2w16Sw@Dk`GF##`jx9g+2FU6=YfYck>*xSbRH@AnYp$3JO{A}Emy zI@UhNFA%~rFpaH^5{?5AP=h4g+;EKd2V4QM-#oJJA-Z9pI5<3wL>gjdPE1<4EmON% zhFAItsFc8>YJRm(_P?LLu@=~OHl^<5{75#-C2!Km#MxTJ6ON!Sgcid+=5Y3VF<_K?$r-$$ zBg>zS7#F`rSN^x=7H|+oOsE2BG@7<*UY2g`>=f6KDp;ilOKh=TzmSA>(-IT-w%o^! z2M532F8KLGW7i{UZcd$p%_(N%xIwEH7vDCvkp&70Oz>s5_BteqO-X4m(=9mx&3`sHTyEdoUXPJ`N<8hs8Cs02UT< zdFC*GK#oWkfU=^58zSh=KwMt_v}#|W#gKpvD1L3amKB_NIZa$=(I>lGE$j z!jic}(KPya8ar*4dD5BuH=tY|I(Atfc&!oUwCU7jZ(@|;i^ZrU*)&)`~v=t1!1 zjiv98*M5>RQj)c>$kZ@U3&-TSr3-dOB&l2Y5rN5PQr}ov)OBqG&?jOO;do6U z+!Jj%hf_sX4rMiM5iovT$JoR%WaJM2R!gHd3ywtv6ZvL%Ni1#YfT<4*KYIUQIpt)> zKp+4U%g7%+;;R?qd{G#{D9L+O=l)iA3SUY0)ANvtKhW4+i-wx^E*F|&xgT-XpS{K1 zBjH)rKd+TyWkst5p1-R2&mjwHIocW#7-LQ=Tk?WD0VdH-Y`eu#ii@}@3pU47AMMLY z`%4`5Y`Cu+sHR4-bU3Ul6w5W~;}uftb7pF2m!P%S+bo*-(2Clt`<*12ys>2%{HCno z8Bm$E=kWQYJcKz>F46RNt^6jQ6)vLaP^D87>a(}y4apO~!$Onh0d7W{!y1|@y{Z{S zB*j$G=Q=uv;~CW}jhT)PcDMY1rjkVsZwgq>h{DqGAwwZj2l;a&94a##)eF!%bBK^eZCoRgKW%oSp+ zZ-uh;&W#FNQo^a@>Mxw4Q zX=zGJ=D;0M#b|#!M0BkM69slZ%mzYZ+8#E7(&_GhkURz*FAE{fl2f z4yMxjoRH-$Evd-II`)U!r_M8M z9|In5ZO_aZV3%3Czw)O_WrwFnZagR__%1wZljkS2L|8Ov(Ahn@8r0|!Ub_#&@X0wi zX-~;YF31CtbT^Gmy_TdnZ2HH8f_P83yEbA1+i{|#wH=Yk8Dyh(Ah&o3v*=_PkX8}} zc~$c4@jSMAbgX0Gz}=G>iXe8WP0`xft?WQg{+-WAW~P>270V-^?gWga2T|Izzo@0S+;bz`PzsOJknyHf}kOkg(G&!xG^65i+X^s8k; z(em4Vpe{PMuoW;ib{hthjg_Y`GK0e@Au5Q;6D*1scaq;;nVeOH;EXCf&IoURJcK<~ z7s;ZWjC?b?2a;@5!%E4@Ft*o68&i@Qs*T4#H7{lY@NZn(BBL0+iK^7!-`RTF#fLv0 z;B;KW9aoZ@;FgC5Xs46{7cdX7ak5NU>A~tuA^AhCCA0{<4La<}p>@CPf{8wj6R`C) zyBLaVixR#vKL63qNmz->$Io0Qc5?~aU-o$0m(v<=VpUX8l^7AVI%DFqd@b;{^pZE;3s=DuxRABjtYq>(BEPbzryojp5uEQU&B zfIwuY;Hazf0DJA!X_URlpfTadAfIw4YA; z@gS9;y_Y}Dj!TOs6cXKvzAIec$T4caL{cC4gK{!sTV98R?_O!H=rJ^;0;=SgYclkh zHEvnKr1-}ZIi6`lN9@TAGT}6!wxf4=3meW7rXWw#J&Gv5tuig=We<@l@@W*n?(-hl z7SFAm4Ov>lM+EQsEsGJI9{)|?%NM4sKQNVgo+H<#I@a*?%*!r`j#in=MYvKz)*{R! zgJ8lZGUkdw`d(Io4Bka)VK)ed>toT<$YXEsk1-%-BM6_#k~%73&mW?C0uEO8f`Ii7 zJKoB`KlDQo(`Cl2WynX5P|Jwc{7*VH8|GlMm#FDrGXJb5GI@JoLwy6Qq827k&LKV= zF%`Nhn|*Urdg47t(_nJ*`z$}2R%%ghYrxlR5w^z3wLNr0v@wx^FS0rv`1~tkqPdr$ zI!0{no{`5t7N6w!Wp_%=b_29!O?9RnhA=-=9b5%{VCC*hW$m5(rfbb9)XrrNt*F~z!%3t(`OvR=}dwjm0a?yx9!EZdFW~3eY@lCf&a4KR%+{bIjM+DvHmlJ_F zM{T|2*$XtBQd6_p8L0E0jE)=h{3JMC>g#`EQ7Wg_9&mEZ<{HQyv=^#Y(l*&7{hI^U zBb0fZ?yIowZ((leuFU>OJ-T5*m`CZ=jg@hfbD>lV86!z+i?XjTPMxWFG+&RbVp?zs zzQE}E?s8*Gcc5o+h;JFm^6&3j9tiZ_1EvL z&oCtf!FG_uiy`~xH?k1eDtUSx%Bi?{*#Jxb@rugn$5SRRq^Wvz5rD=ZUR6Q)D?rc3 z#rHyL(;+G(b9NeJjv5NEr}4KwfP>`|xkjIz@xUCzjMa9*)>_lIbWRCZ@|VlVPMx|@ zR>ms4zsKitPrK~m6f>6h+HsAQgI5?N;OswUoK?>oFHFy`sQzu|VCQ$*DEh$;GhCJ~ zFG?2t+iO70)T1Q)DT`Z}#q^{=i5h&v(uk<%afOMzodLAty>udjoaW|-KVgvrzp5r9 z|M0H)(S%WjrQ6EFtrs(1?T;W@z^+F}-ymc7k<(|i$55EUt$F^Ouy73A)*6G~sDGI3 z7=QFH7=Dr}E4kzvYTC@oZEHbqa=aqoAHgUBwIpx8PZJx0a}x95!fC#Ppo@b|b3p-g za`dL`(IkpVpHBkHwiD_b-a3`V$=KPt0!3<6Dx>F zN?|am`X@)5q@!_|7ToUInuj+VaTqBmPf>kdLTk#r^W^~0Ac*rkU2}zOesZvfWrvz3 zyV*}O*2k`a4_ZDA@Z@jiNnm%G@p!@C%(g6^tM|1;QyV_VQlj+FSQS5-*`h1N4-bjQz|0N5Q z@A)c>-s9xYEqrSwb63aY{5j1-9P+I5r!aB?pZAmX(Bp&(fybe--B|www^TVzgjANx z(m<0ak5NXkO?vJ5cuG5S3Gl#yD=_)^gMeEu4h9!4PaZ>9oaF^uJEK4wn(r`Lt&_t$47cy>DV;tDt56Vl9#g7` zMuGC8%sP~vTWiV1C9uQUeDI8P^V1z~W>JYvtrNp`tNi6%LNgRl#OCmpjEFqZzb^SGIxYHMkfm3ZF3>$B#q z94v$^3XmLB)0P!JwCj9(q2r||cSZ6fo%uN2(&R)$e1#T_xe6%f^xP&YDY4w2Y_Qbs zV(%YcVWTEcwh57Nq80z0y?YkQkS6u*#|w6XDGDG^;F*NsEgdXMq}lBJ48=|)18U7A zwS;jM4xD3gu|Mej9_7*`uXD9incv$7FDU3KxIjTH;Tmqic?0A`(BZw?Y#qt;AdC3T zSVu7RM;$4=Y2lyq6G!nBeqr4)d7vX7t4N^4EVZ|uqPW8;kU_6yqWcN8TuYKgs{pJ; zoK%&c!T0%nh}(ktuG7dJIm<1GakLi|BTTDvZ!?i?X2s5bEcud&rDfcN&Y!vr5^mJ& zn6D?0aSB{q-F$yUMOGogsHA*;Jpm6;*AE9Hx#1%w>Y72)Ld+=2?17>fa}D@A{Vj}~ z%LnZ9k_WsBD?(GurJWplbCw7k|ue&%}Tc>Ax;7W;5=$rgm zB)+@zEW?2;?`d40^};((uM@G^HBrg^4PK4`1j-bcrALp>mX{=tB;d{9a`MZH!iDV^ zWj@plm$)!knSArj8`WH~(cRst)IU&l4k?s{oR?P6pwASavfW;@}y``5{<`+etUf=C`Qh})y~H+v2M899L}S` zj>S8F{EiIpD_nevSI6pBfRwnDFAVqh)zFM)+NzDi{SEy^Beb@_1)$ zQO~}`wmU&UrNn&%Jktli>rA-`_o0d6zwxH+GCj$BmYe z#8V`&WSuExssBlCNqy2}ele%Z1tdWO${XWEKPK{ki%$?z*XNBL197X6a(&j$B`x03 zN$cdk<)iD*&f%5cuu96*bfr19yWqninY&hU7=#*c5msI>dXmiIofD@Qh1rY_Z9aZ2 zi8?zPaB?+&!-AZnvU#VL!L>d{r>2YOHo*fGA7`WP69fvYy6j;Ks)c47cDt9qmKRtN zts2ysF3<$I*7-%WaGu2le|s)<*Re_YAR5WD4b!V=?|eP(pzcjR?eVl)yK|zuAJwvr z+R;d8fV`fNZ*cim&$hnfVBh<_F70`|OVT0+%*gQ8_xZ0swx?~a-8=XPSsfi1qI5#x z2j1Z1#dO9$xNAkPbMl-+8`ol1SNrG99x2?Ekx`OLa`MQXQ(H zv(gfX0Vody4jm4hD=HLVF-~e}`ni&dl2(GpL2tf4y{E#X5=KnBEmPr_D}qe0_w40N zN~oH(33&+F8Is@D0!%e99UL42`t)Jp;P}VuT%`$3f(vGGSa`ca^daI3w(Q%kUE7;= zM&Y8tBz|aQ@kZ=fLd|10mVXhw`g;nV z%5ceYfthA+akTwnrkK>$3EOq$I-ici@gbEcy_p=QONg;4le#`X+*Mg(pC&nEOcePn3&Dmk}EGlb`^j9|BD3( z&xj@I#3QRr-P2vf$AUCUj{ZaZcPd_QJY>M2qPlu^X(@%#)BRr!y?v1wS0ZWr{4W`} zvBvCw(s~=ey+&&Jld>o>Wsqf$p+Rub{31)2?*4wAY)cfSt{Fz8k<@KhPjJw$S>C}B zjtS~KlA1ns2_}MZDD%YR-wDw*NR!8ETU*1*%FwZ}d^8;vJ$f5u9O;F*GR0T^v64^8xyP;Gz#V)7**I1@qb4FBu=kO7C}bZ*z=xV;B$yDl`UUv$wO6rE zXn69j&pTx{G_Zmtczga_AzaoH)zrdgTCv$w^H#ReR0TWdl6Hu=IDtwbr$wO1Om`8{ zQEohJJEnh6;k&bmTFJTSbRy?stt3UST4{0KS*6KPNQ;euGcqloDYhH;>*nmomM_lE z&P!m=YH4{!SZR(1TSqKuPWbZ?W?cmx%eopXdMNTG4iZ^fE*^XYz8C=#{DETSb%Tu~ zFqL&NXaI=Au?OMl5zG90-Dyeh*lJ0Vj32q^@JBlT`Kv2k&#O1udtrlBHhzEK_|2O? zFfcG%UufXe@Gye+eKO}5s>t|qxy^o~`qAC4tAEk^Xia#*LHHA?nZV7$EeEPE}Yy0H$oj>1{6_&QmyzQzBnd;<8K(2pV*4FvI!Icy= zDd?o9+WpGstkE+p1hs56_~hZ5ZHyw1R$vK(_-$0~AUf^}O563Dja|MRwqSyt+qdS8 zonV-}h!Z%a6OVheaUb2Db0yo?jfG`YWJsL(b8#nbvYi2F=o#+za!?qhvfp9iH>u$+ z?yN5iQ@(iU!)3{TPxgV{sX4ANnC>v0Vrz0S=xd$G)|*;uM<}FmJA=i|Zl}3U|4@vT zqlxBkF*96R&3V~ z>!>y@_q=GIU1JCdxj>EuxlBt#NM55xx$5=tebVEvPmmGQFtm@ZE(iJ*?7(1dyHUOh z34w=}d`^qJpMa1tJkO!WtuLe@5@pFb;Q!Vts@wq?-VUk9kXmgapzG2%(4GZHMLa^Y z@z;Ip?MMzmP|?;6LwkeWhneu@p1gXt)bDAS$VEHazpqEy#`b?NS6E8yt^c`fyY2iS z5dY`;f&c%!$R1gg z>~U^oNIfYqbu9Pv#iOgSZ)k``_Kb1^Z?$n6;oGmrk4^I6#lA)$_$Lk{+M=WMu?4&{ zIJ~ayM)vKOk|Oo7q5aUbKU4PXIUxmY2m8e-lE?OeEaKUS@GaVitCOeN49Txc6LzlR zbYtL<5j(b@(Q^9tPg+ra+mDFg*3-Mgo~>NqoxBUd13PD*Ykj}D23uLTg&+4x45bIN6yPuBd#lvV`+K8OhC;LyKexA+%$JLh-t3P_YfSzi}LE-+f= z-aj!hF?u~=icoeo>!rGHXj?xnR3E#4_d0qVKlt&lc^Y<5&&kQjkabv}M|UHTMV2gm zf-q$ue2QQU^p6Fh?;% z`1gdU)>vB+%>8YHKOSut@~f}cdmdLiJ_&|6G9jZqO_&ToF@lPks8%JLJ;}JXu`y`# zk`f!<`|QAT!KhAyDHR?Zgi6X@YSV8u;w1p!Ck2OWZr{}C@rMUCKVo@x^{4-AVwgs; zy1M%0$@k{{`QPJu5U0w3+S;TQ>`>z36KXGO>B1{3>Cr_=&|x_p79qeSr{Fkx_4@wg z+4+BrB)~&RNf^y-N$>-5mSuTmrFZul86GN=K;spEcDSa7-KABVVRUr#3RBr^-XLRAMHJj}wlDC{cve zml!&V&&x<=7JwPP?cA2x$w3U3n4k)KYVQ>9^y~W|Paeyqf-NiK0{zXX0T^M z%g)~X=bOIWEV6miM`ZjfFi>YUGCF(uSfd~rVr*h$M4vS=&M&_q^nd)X75pt44gPU9Nj#z%@Zx2|%ueYX9!B{X{u&c1h_Kj<( zvk`}cfc(I@Ses5W#_{|5%zyncK)g8%Suj0KGcVXb*yC!DHbuCD&CQ-oOVU#~;Z~sp z6Jm_N&+iYOtHzRFXZoZA_kZ5eX{rjd%gE6BFhZh8CK25ymkoE>G2(HX=9z^#{H8NIY=Jwt z!Ca4m3_uZe+Rx6t;hOq4$mCRSl~hq=n8Hbi7tq0{qRejH1Sg7#66iHU)EJpK3nrkG zo&6bs&xt1>;CYwTs(^94?h_B(9||bSJsm{Dr63LiA3WQ!Z?h|90zGkYeq}34qKKc2 znTDqm?AgEGer%K1J$?Ow4z`hn5tD}FdiRpYq#sq@@W}>uwvQbDu$F}ub}HnEV^W1a z$tXkn2QlBHhimXhLyi3r(!C`61B;f=KW?zkfqSw>A zF3(B%feRk3X-=V10W)q8Iq|S{uRebn9qCz@#w)MBVd`Lh3rn>F8!@pIYS~!kV%B4> z17nNN@2NOhN=YLbWO8M>zkk{J5%t~@+b4>R>&#lSh=!hF4r6s&b*$H{jXxvGA47q$ z%=hA4rU&-XRt6dhwk>PT+C;w(t+<0r3ndF@j1b@iowpyLU|e-S5SNoevnI}#ktj^O zK@&|HN!kAnyb2O8(ZWbSKh`cv%TP^qD z?;JBkG>7VS4@bd`)ZWwE?OPg&Y}rk|^0ouChr)oe*3E3M=eXCyJGxZmIHLtf$-(_= zw5!(G!lB18ABx{nbv0J6_l%6-O*r`PRQS++DxER!%sPClwZYkO6>-?`jp4eA9$R(C z>G?Un356(ArXcg}L*Xh`|0muD_F-yPodGP*E)Q@eMKAuYKz6=y8y_HQk5L zZC&Nz4dik&1Pr%g5~In_J=C@Fgo(q;o(kVA{s>x6dmO1tWjT%rGKUEX3zlCBrtzA5 zxcJy(R*?S@+%&|*)X#2$b98EG>lw5kNkzRbB;Ssnpgg;@F%e4^Y+emZ(t-6}H)3v= z=iv2r%l|ogHN$|T_D#I&DTt`^G*2RNW7g~A{^vcq7981H$LiG49;)Rk3{z|136i3w zhMdQgf;*R1DV=S8`))Kdb6bTB()1#G|K1x-`ZPMux|p*Y64gn;lUYnb z!5b`~y0L>J$Bxm_P)?Emx9(*F7Rk+7Mh70y*FVYp>JCZGLiYG5h*VJD+RgD3UDTI^ z@VtAo|5dOpgT&T6ETpownL}M&bhK6x33zz5-I-&1u8*siZgF#PfuvMU@A|F(_)NX{zv|DZG`z9gVN4#_~Z9qaJ;$jH}7ZLIWoIT4BxuU z#p}Z?#zoXf5C8Fh{5RAW`|#|WN#gxtTNbIEMJ9#@xIZw)-10WDw2mdJ1dB?jZ|$O| zw}-ac5`ymcmr(JT9P!mrZvXga{_*w-a-f*j(?9UT`ED9YJTLx+ks+};M}Oaah9~A& zT-za$F|kFJKtY6x+D1AL_j0tmhM+2ac8;%Qq=~Oia_9Cvh9?$S*^HCYa>!mkk@8wv zyN+jn3-O|tQIriUKT zKRn6I!a7^A6b2$Lx1YjD1+~rXbax-3p{fwS>$eg`4j{ITncil8e2~6-Lrl!BvK32{ z6BWF{B1)_3={|mvuI6e=L+S_7T{9bH=+Zy(w`*f8L=DOgf6w22f0m<-;V15AlZ~x2 zarsaDzgH&Mh#S0Wc}tLFl;SqN{PtVEJy}oKvybfccfhuCB)8@m9~$Jr;5c(D+r-lb zmgFK>SVBYFVS0MIX{(74_&~ZFTN&o&-~NSvy1R-JD&f%CKk~!*E~*RN4;x8hb&MN- z`zL-J*dUqBy|ObMd+BPcrN}3LMuECLY#TGZ#oX8+eSJer%&)Q)&0tFk-cS+c zwapwpdYqo-DhdN{r(0Go%gC?)4}ZNr#_U%1wZ@mLw2QC5|CT?TYr_4K;a z;QD1Q-5O^(B@?bb#ee(Xe@A_xmv?em9sbqX2i~EB!^cBUZZLW8S1w+<&EU)myU7$8 zO~cIXWm3;iGdViQz=Ol|e)UIwI9^S_Exo;AVrj%TW*E46nTyx@7@J=up2;Bwz0}0g zm^QC%EPWbSq}L}Ix^tO-`tcr%n=zuvEZSbirzk1R&de|}G)P}tFBiW3iW6;R1l@1C zqH6;Nn^X6=edQ{@-kxA(J3%s&-OF+!A8DVNVRWRQzB}z4J^Ll!e9=K!(9PpS3Y(lB zV`c0fS1w-W_Q(?J+i?=I&(y>?1NR?r=o3S*u&!%c8iDtc4s@?&_ zCbKom@a>EI=O6o+TaOY;X30L%IeAa#`gzcQlyhHy&B^vM!ru3{uwv;cVv7&><>D=_ z-I-=RsZm5Btx1#IYi0y}OzfOSe07Xlmw)Bb%`xWJcZnzS`fUjUlB_U2InMBd`#d;) zfv>*)f};)L_v%1eMw-ouOZ;-_F84-Oh?@dt$u5a(?zh{nM_CxV$JJjhbEAKT<&78_ z!H3_dLCZbdnfBhAxsR||8Tyf*e!j__p*hxf_jK;zT&m{h(!mD<^q%{g@6L8o5q_Ou zG*=b|F>VzToJohS=f&S1#Y=+MO}h5*k6nPi@k~vhC;k)Yf;H8@b1& zA1`rla)r&^B&oE9Zkky3!z}43h6nF)`(_h8C%@p^uZ~goaKZ9`V;LD@E5ls7c!{fb zCs^2sl1SyVRBb`nvv)WcU^St?^4fx=pk@l$iD&k9BprM#GtKhgul(i5>pU1+Vq^EQeQ66K ziffMPiE#$|`{_OR4d0(RL|MrFUUgU7o@V6kb^iI6L8iA;cnVEQI+EzmZ0E@78Dg7j zEG#S&OB=6!eNpwIhgwNyUmXzI|JbCrrWwC?jsNs7x0zdy5=~~v>IRl&BS z57Kw{Fc*IR1E<;|@7=zPF81@w#hYBaGsQ+)r@$_tHECd5&-Z|BrC6UD;M&hWb8TRr zwe2{`JzcR7kdy^xrY0D;f1j?C7x?C@lXO;x_uWqWx5YBj#FmD*{L3Y--!sgw_;hiC0S*o?#3q;7W@YjgSFT*=?&uOR zD@aZAA!;ilgxnIg9%o}^j=A|&=0@%i&q6`y-*c?7h$7z`W)|5NdU}WD=^^glxx@XT zNv1Y5WJyGkbG&}O#HWOf5np7u?;3yo+f4>%qPPmnXzi_~s;rQJOCX!rVsUnk*@b0> z?qm>M9^CHp9BYi=R$hM*+BS9KtHa#5^eaDK8)jxh!&6jB=ixfaih_6*8$B6iX?BMB zG8o!kG=WNp^EIA1Jvt$mE7jxV(nmqt%oZ`S3_N;#+IXOwY5t zJjI<$ITTgFec=errGYnc5^N)lwmZeezh30Z?MW75HsOjo4mH#e33*Y_NbamLJu%D5 z{5ZD_P&_`=GhNgaxt|CK*yyPpmPT*!%THIhKCnbu4pQBDh=!_Sd@cbq9b;>CnX&PC z=0@&t*%!v^^YTS^H6D>qGGo&=Q^XeTaru{P+`2!@wxLqiaESVvatZ@3FjDNUFEcs0 zz|!~tDa|Gj^7BP!HIX;T4zV?&Yt!`o^cVj6Yd;II9G;?5I@)WfC<)d$=38;#QmcQYLcwGAc z8zZsIc>fLl`q!I0nELtA+EsI$!yIt{BVGwiB(bs<2`)y z_lB@da$B=Jd2pA1-F(b++`tvC=FHg^YAgIWgibcO$pDb zJGob3=E%gSx%AL3E}7z?Q)vb5icAkcFOriX6x?ac=ajINPaeKd9S&{SVV$g3jsJX>qa%+If| zvM@z_JBKe4M7w^9uDW*{AbtNJFmoGB4L{$LU&^=l@T8rCWTCj_2s3q9Y6krT**f9`1#L2_27{?dIJ6fg0Ky;@fim0-saoe z!^|fPe3kW_>usX0B7kZY$?Wp({MsCYw`~-M6SwCIC#v5S?`F#d3*S6oVsV?iVI%D+ zHE1JjgF?~376L6;$MNH>wAF|AEWnav1;t-acWVWnUrL_uJ%X)gNG%WX?LThuU}&Li zUmiR0gMBGm1-93hnVDW>b@C}iQ^xJ{bK^`im4SD~yW31ZeayrDahB4>AF9+}-Ki4p za1C9TuJgC*3xtLJmR1Kc)-xa21+1C z>*-U}*F*`r74+IF+&rpB#R~pi9Kz8 zVUU;|q5sx*{PXTJ*0U0U$_CE$Hd0p^M74|T#MhXeSzvKxivBwS&E>-FxkN|B>$~+n zCJ0L>voX!1JGc4n&Ik)hi$G-~y%(COi}{hQBAM+C7H8&}Uz_F8&3}R{;qzXhz0!4r zJt{!xlu9P1ka2|S>FR3bSZxq(AE#amG}C=7hT|t)0cCqPy*|aWp~pPxA7*qeLAnTv zCL{gM?cEO@pOOKe@CmPhuyxX#b3A`|hbI$jTKeo0O%e*q9yU+rNLy;N&_*S2aD?dho2?;@R9fn;%@9 zt$YY=&OW36{t%C+(>N-Rap{X2TsqUmv6={8CzLWVmGr8F|9QD8`u{dc^$)&zasdh&6R{^~>v=JKju9)Q?9KlyWInXP@%$&O`3?Pp~re zl*fZjv^G}~@;K3CFmkJm4GnU?f0E^#%CVE@xN_|h=et{}4117_Jjsm(rl0on-S>lx zFHbOV&r4-}GZh!=@M!O2_}RuXvdj(M=KiBmX5to=?Ps`p{VL~Ax4Ds-}vXXgh&JCuS^)`2=$Vx4HFjoW+zvZFetMKD)xXu0~=(HyS#* zZ%H&fd+!R`k%tm+1Z?7@ZKZtJz1a>Y@zq!MXp^u#j)Bb zKBtUPNVBy(!|Z?Mu#Jq1=k!Pdl63jh&%)R~z;*zN35mbtK4;~PR*3$f!ZoD#Y z*A_2KvWX=oAKv8Kfkm>ahk#E|c%?G+C0IIodV#^)|KcCt4zjcZ;ieN@im7Z(4l%y@ zd-je@3YkqN?|j4E$Fpo2URusv;InHN>29qfx*L>AZ7%R^;2yVb4Kp|QoSQdmsjm(b z@>k)0t4$%W%>s#q=L|e}!t>=FT(JrQsV#DQeXU&}vpK`SoqmQVHz_(R=>6<-`g*%* zYpf*bQ4xBM#Of@gL;c*mImr0>9FOllqPd}xx~d?d4@9Ew=qPtyZm&%7_|YH(6LEyU zj`LrA#g*O@wA4ijxE0J?lGXW99^Jmnod=Ul4Lu+jtDzkAVM+^^-_<&$&2pdp}`P*jZ=v?swc9nkQ-bX*+j;&#qnI#If4l zWI&$e`aDku?sMz*2=g;f`R=$`XCp=%t;EGk?Pi;|n z-PcMIu22n~7r&9Tn+kqWA6DsZE-y}HKtQ)xDr=U7f$qO&%HCQIZuXBeMaWNE92 zzwT67O6Ynw)&3W4?g2vKFf~;{L_SM)XNbAwS%wFmbLmtSb*lDKHT8P}tAvqTrvLsZ z3mX}5-;pJZ}khLhbboQNJW8DN#jCYE`0 zZ;aJs9!K>Vdar)L*Ef2obSpmu=fjZ-Dk=ilJ4w>tJ!5)ml<|oZbhK3y*wyQ`N?F#X zM;RVpX3GrHd+~Gr_@_QjH@;MX84MALR#Fpj6KYu}V|l1=4DTLn@7Z&pTm_fen&aN> z3APFlYCXxdFTUXV*=7RH7v^1vNVI~WN5$CLVe`%;b59;Je!hd|`Uth2!#TA2PJ*q~ z6&80a+`dXqUHOt5pP!NE!+!nK=qs*K=PJP7lBOkuWC74ALi(~XZ9ARq1pr+>}{^T-CV{_!+ z(QW?H(6j4IjZQPYn1oORCog`+*I!}3(Mu&!(@9UyH zsPHx;5zKso#qnYO^{*jTbuaB_+fY{*m|xo3^E1NM(Nl8_4UVx^^mFXo8LoYHi5hvG zd)t%DY-RbqrUQgoAiX)yt#6+b&zS^TySVcC7u>kmPRR8m&xIo~!T~2nI>q+gDVClM zGCtc)b7KV!Zz1(2ER+295+e`$c|5j`6|UuEYbDt`_n6(|e71{8wwA_uHnl-sxT)^E z#9#jUHQfziyxNP;M2Jn~eA-*^oNbU^dCuUY zCrqsuiFI@m&c|7um?O2vXY%nyme&((>l#%}om~FnYi{&567~LA0UZoQsHmzSpc0`(%3(PMk_PAsl%Qh$$O>7%9kDpMa zg35~6N8Q13SO_CSYIA^mkpJDN7KjW9WX{?J< z|5m(fkV`Bw^579e;~R)*9VeS(WbWN(eh=Q2RVQx0lY{EPt-=<`nGMFCFOf8zoH~7( zGbdZA3_9NUdf$5p3!x`ioSI@{dYyvir>Xlh{`}`J=&JcC@5U;k_!N`ER-A7p63mQ^ zGIOSbx~LD&TS(XmTPL~noWV!K%xvn^c6SpU>QxWsyuuANt?lHSE$H?GwzUXVA#>xK4y$=~eP)wJ3cVT@8HQLUZ zzR&r?jdL^xU(8zz5{^Wus0^Xzl5D32m|mV??CB`y&K#pPpm4Z`VgVE=>1C;8hdV$x zQb{Zp!>t{SxNWn5zCFYJ2V=yI5M7tfbMNZq`tL{Q$0-tloILqBI9#ON(Z!z{s0?n6WozX z8rwTKcm5o`XHQV&QC?}=m(&2&H8nIgL{Km&6|wo2$%BqV%Q!iiq z>973zUvJQRqKS}Gey94U?+Rvio8;0Y&sMTns-NcLCunP|#P9f-D=TXRD;nrLag6Gq z6EX`-&aAP16oX6k5v}jw`qy9a^&h_C`uSFBBA!E^3t^+@;>Yi543ZpCT2G$ii?6@p>l;@%+f{?#^>e8`30d(F zi&aov89-COwsdlNf%up;=7k`)KEvW_oMb_!y0w$eu2!mjKMSr(DvGm$EM@M%TCt54fiYc}h zCK%r^C?0-v#0Li;d;<`>yWl?SStHlX@xK7Nv8wPAwpBkIn7!aIT>pH8y1woXb{2>L2% zZmPiRQeTrjlhAx2qIC^41{@?38P-=fN$%vat6dzn#zJ-kscyT#mknNG(EvV=iYn_L z?DH44NqTLKcp^zoxM&R5(ApZs<$U#>mLvsFq>}1}Ix0Mq%;(Z9Ev!*A8u2>i0}n1q z(QwCFIDg$s)5$D~zk=F^y;>t>R87O_)XL9Nl8|1~Mc+xK$rlWS>?IV65{bA`Um2h) zAuA4|bv0C1h4HaQHod{Za)z_j9&o&00aCMAAhEbaJXgd}!c-`WYO?AeSX)m`MHs)j z%+_X{jm;$1@d%1!P)IMcxVlYVSE+4lqc-M)%qH_&+oUsjN~T>N4(IaX55=g62FiQ% zy){e(#Y~#`{1RJ+z~_$8&{#zz__~3a5~|xrxTco6ke8{|G^@*NB(^hH^`1i+U(Qe+ zZReuYb(;uD#qIUtd~NXF#xhIf^F>S>WX(s=@4)p^5KPj1)V7`BMxBF5G=$&dKo}n` zKfNp1mPuw~gUzjNGM0myNDUnwmAEwJHESc|3Pz}EXrRh7&SHLt<;8UhdK&@v!94dW zOiGyzrXSzs-q0ciXB9ntmpRi>!PvxyWIG5_>#J;~GL&R5Rn;}rRtIssQq3kI$tu2@ zdTOgty66CAUv;I^ZkDpEHaz3j0`^J@k9c(vXjsLaGm3^4YGs#^SGoq za0HvV@I@nTe~3uXgVP~MzqkDJYe7)TX4qO@C9a#Op$K(#RYb#{*9Q3%mxpj|JvCuJ zE;+&K$~y6Q8mr0sMoy+>=2)K{VW9sh({YK$^XIsD;UsnDv6J{N;p_WS63Bo$Lo2{8H!TX)J(PK z2@AyxYpZc`g%Wl^eS->ai{j2Y3&Xd#`CyhExr$R4FLLg99rG(s_pNC2R(Emfi({NI z1&UUdK6q6txjbaCSS(T~=m<$ga|MV7Kkguhz-D`Og{@Q$UG`I3S3_-e;5ByPF7MVh zQd=D*tj&{5ZL=`HL9xw^c6|Ta@vhCf0stStyd+QYt6n0WL+2wcG^4Gon%`+bSdDMUyGDlfnGqg6dd6%*rs-mtcdH7cZCvYQK3hh2SJHdq zE4rI22)jSpwjJPweYwfz<`!8?BO0ovtFv-X-gSp!R5mqH?HOh%pJ8=nlYCLf_9<`7 zyK_Ug`2Nv6S+$y;OBXrYQO(4Zy3dhkv$LHdm)8-Bi$E|+WrZ8ZE53(>q&NswRZ(3V z!#lJ_ZfAp;`5n&1!uT8?X?RjtY_F`4Narw=0Cn{>)KmptA7@Y<`0JXes|XR+)<|wA zSX$gfZ}%XahnVjn$}&Oa&HxFQ!-2!0mSY~m#fp6ST#|(B^y3f3i1;+-wu)?T#>rV0A)y_- z2V@n^7o(vyLftVNWEn--%Sf~-6$<2Xh4K(jmzRK7rF;$x4Bf!81jrf=hZEijo;cyjQd;&`U)&R}&O;6UiAQ91aumE3f4ck5Q zxg7EJZ46{IPn1~Lhuigf=T}mkxcw0-!(JRJq_^Uv(^+(?4s5B0a1!q)4Z8Sc)58 zFh*U4gT3fScKGmzE2s!)EF?-K<8iX4NmMvFs)B~4XV_XA=k_;`SV${0UO30)bDh*h zicGzi@Bix{0F&*_1eu(U&?3A1q`ltBkR%jWlyEpe*sHQyEU>k{LBVLi=J3h)@=x2C z#RPNDpD;K$K|+eqe(5VdKUtYMQ+gk}T~eAwTU3uqozqY;C5{1votw zL?b?Y?mc);)^PbE#6mvY8tiOskxcHOi(1@AevJkBWl@kj6qnCzVK$E$P^JkKB%K>sdAy$NB#6cbQHKnl7HyJQzuxw1DKrX$`)bt#)%PDNlPqem~wrUmaW1ayaOcEOjvUvl^ zQ9&dUBIMhLcimAU;Q(Q;!g?W3Vq=4XQI8Er;$0zZj9i?Vk;e=UO|q@T=)Ck5*H70Y zZ725knS_mH>J)VgTY$r%BFrMGtxfWU0>wfR-2&C&!tHk9c6;!6JUAW7dt4;)u3%Hh zW!c(HV<6-6#;Az+@a}0}I(B*2i&KMiJWeXLgDz^`fOl{ z(;Ol>@iyx&5LS`I(hSc>#+XY%q`ikPKkK9_=>B-6WB?G@wn1t;O){CoRLXIN+6o8i z9ve>5eE33@R0bU^CQBr@5@dA)o1+g|w)6}e3uD~+ulvlT;Mk=zTsqrDU9`l^p35!( zfo_;smIaavRdeBR$gkxUNs@4Qz4-h-+zKR1IaZbv7^nU3nIHYGP=2O~%@@2IAsP)4 z^zD&ckz^E4j9A!D(4(-C$&lELQ#2bm$Qv)i2CGy~1_)3!1=}ofo!@#ii7RZrg8CjB%C4r%r zNTkNtSl+MF;_s#QMq#Q_qJP7`n)R{O8~J{9?zE=5_pfFew&uB$EY@Wi(#^pUbg# zBZ;J*LDRGjudWa4Ku>#cm zQ>3uHP1YzoJ4aE~vy39inI{Z9=;!G=)So%SfB*OMRQeP$nZtaMgd{6ROF;ZCU{TWZ zq<0DkK=Xz1x}5v)oPwhH@cUh8nv9uAlgnkxJa?quEq8jX4Bz6xlUY`c2-hxOYx(Hwq40S#r#ptO@Ft(zD&uP+GM6E@k+ImRB|<-eZB(dsVIcjYWy%`sd`{4Hos zfUqd#Q>-maF!Jyox9^WIv0ft9-p$3&`)K#d9JS{C!$FyM)9E}V-9q;G@Or$s6lovc z_2Too@p@FOc!7K}N$w4J*ER}l%?$JK;bWd{NHm^1%isQbjtZYlI(5Jo**3PJQ?g8K z0jgABW#SQQ-;L1!e1Z5*0o@cxib}AuiSFLZ<)P&*Rs39q4Q9OQp9uID1uihCMWFNtR8?Rfz+Rl?trN~(} zmf+xm6&vhg0mHVjg^fanv?Vb zWqbEiO!DKzr|0^cp-h0PWMdj73b{0i&2^Tyz}FDN?{R&4IKLG{3BxE+DB0!eKc@?q zx}OHQjG{X6c^pWRgwTtW41@PjKK@sNjj&7P3ndKQM$()(+-{umUfnekprUFHTrL$! z6fyHT@|Gyi&Uh#Om_S%1HpcGK-~WWM4TESy7d_{Ds13asY9tYgMeuo?NFu}5)&?8# zJS{;N>d!q`VUypCv$dTjX79!+k?xY?OX9I$r>)F1I;00XG@eyMM^eUmPIy` zL)UeRxdg+vZX<9JZSUj%IeUuM+At3CBvxh_9~tKU&@9QhLH_x7AF{0Q$G$ea%3k;Q z8$lQtx=uE4f+V52T{zYKf{7Bctl@TR$g+f8$WhdF44XHb_G1@Gtvut~|8HvtDX6Nm{7i*` zmCsYKEX*VEoS>APW2FBP|L4vkYNUzFfB1rv$Exvb@(1Qa39t*~i#nzykUdVE&T`;* zuZ}Dv2M(tbms3Sp7J4CvZiyq+C<$99voX%yJN-NyO%ZK5$CVp>bVZ#g(wl4SegYs& zOhYH1FLy~OZZ|GX-6vouBg+~tmjhLiu!;prdI|kV@3Fwrvt*a<@sFF&S>Dm;ywJzx z^CzedI8daw(87NCS8S8a`ZS{h54bzIg{1^Ib?p)z&9(SG+N@BS=SsyQ#iE6zYG^JO zo;~*{fP$hr@pv>8bj)Irf@vOc7Meg$Ein4{5#K#r!t&Jc#lQcBQ*Ctw9B;;RLf>X# z^bvpmpZA#9+`+UAj8d7uRc{S_e>unb3+Fh~S^E(u0sw4;RiKd9F)V@NcHwmFQ<$*J zyH2MQms3HQ7Dge5ZrewC48kgsUU|m7y8{ePWTq$#Zn3VNcN?`(lhML-{qTIqpW5f9KUph%e`Gx`?a^8 z+hrL!R;R`p9vmYsLNv7XaP4$8?w`*<_$X0MvJ?tB#o`P5(#;+XcDpFsmmar@B8uf_ zYL>fbj$~h^=6F6>=3U{h)u!Mv0PcVA(bTflplVjB{5OgWmWgE=7(yTpx+`HL?DD&h5XhQ_yzg&GNXRH^S>F}Y#4;^Rz_x9Q zg%YM^VpuxygqxnL7r1)mJUuP7L;`LUO!CJXXsoZoFaICD8(Ls}<|)sfHPYGMNJq?p z_A3Nvgl(0Ls=c1Yt{$U|jb)qYyF>RRMMIJ0ef%y7Sys@ra*Mk#%4_?^p-LezjRMK7 zI4eu5WNaJTwh^)ee>8;0A0QA6;B!0nkjMDFKww)I_CEY0D=Mcb7Op_swz;nXJ(zls=KE%M|304gc?N`3w;;CjTgH9A#@a8YbyMqt{+b*x+ zYax~2ZAC5z8V$q7vOtp6GRqqs6951p07*naR3GfiH4>_-pr|rf2DYwailYRj1f|Rx zlOw|njLcE+HE`)%FK0Tc@qE%{+!I3B<$bZ=nWHGkSlE_hckdc<={<1Oh(XPWjid zcJqi-4w#&P=g{AA|^*j94QAn>bIyA)4^JUEN zF}izuIn!QM?o>U@9u;M2Co~PG%ZX(PoPi3CwYJjIP)We8fmI-z++=2Sl&SemmZwIz zWve)xEd!m?~6ML|~8L-DSvDoDG2^pOJV!ot$iER2rOKQP9+<)ih&S6n^QOm)bOD%pp4 zrV_#WCTc356P!$vSY2T3={POX9-1ory93_^wy9Ih#+ezNV0>zgtZpLIAN}YL31U}& z-`?Z8C8=EeTjpI8)3kreyL-l$b`=YD{c&MgyY}uOeFh=0N(Lwzs#C)j0*9}Hw)R$< z>MDr%onRJ8ZLTmkJ|t&P8Xib9YkCocUt@t%J`HF_>Cb+3W}nkIUG1N z8MRPkCz&Q+5g_0`AY=FmzYqlC1=;Qnm_2w%N?Auu5@q8}h!3nl^PQvYWR=gx-8J0z z@1-Ay`R=aa(Q1zNx(o|Fx6R7r5O;3g=Jvo0IY$*eS8nk27rnGp`f$8d_3x=_qqDt< z$(eOV*JpWr_a+(zE}rh7CgMdl^Q1PHnHhV^!~QWAw+lEN@(%{|ud`hRmQf(Nu}Z37 zV!q;yNoZ~#p=c!`Px*^BiJ>7ICxEd*k3}FjVc6S zW11#H*vN{Ev$Bh`7cO(D=NMtviwM6)FjkM(>%nJjvaph5Xd%x0+$=N8DO$oYv^{4> zyc-B%QOqVuCK6;yudb6ME4choBH<7|$8OSSw@gQRF|g@?1$wbQLfGYfv1h;S0gx2j zfohJQzl2)RLe40W&!pK-B#0+6tV})SzFs6(viR&=D;0j{2kvye8H8<;-C8A?DN-j=qYOTL%<~nUK=WC?`uZ|$ z)d5_p%zKduKw#;4(upmS*}`l12{gB#KsZL!Cn011$T5dHYs-7$ML_3=^Y&2NLV(a& zn|MtBz%yo(4qE%pbFue0^DAzZB*{2^VIq+Tey2d}p8w_l zEc4v{=^cK2?n0EG>0vKTSQNHbnHjpr|GGUxHq^!Six)Y2yn&E=H^BK;ri8#U3#3+O z7@tfv8VKeu?Ke6wmFZ z`ghMbTkOjE9rD_2t4MNrlA(u#j4b5wHJs&-fBlU1Y9Ag==8d(A6&IoER?dH>Qn*3h%79IeBr58vg;-s?0J$N@jFdQY~FY7(q zFB}#5Fg7~8IKOzw&pBMyq&&!Sb^I}p2F6&(xaqihfs5z5s0}#}e~XfaJ5WjcsZ+S> z@@TuDtudgENbs!%_*XTEe zO(~aRdn-;>e;w~CxB?L(;V?eOuKm2b&!j`~?u&oC5%1==SDAi%kH6oWB_BS{^-C8y z(^*gOMF8Gou?YClk3QUE5ZGpsd-@4)gipzU-x899>m>i8nIMZoW|L>P|IU-8EIXy21^^{lB~;hJxodymY?E3ZLiEBo+;tWXGU;qv zV2j-fqkXH_fAY)aO8;F4TG&>(LiiBBC2X;4=)U-^AD@e&I;m>uq_L)w;44EKWmKn+ zniD5ERx`-dN}BX`f{pbpO5Ks8jubsIgsqcU9H;-@L&i6Y7(emWBvglon&X$~yVOg2 zMcLSW(P1KN>&JxI9AsLP+`$G;U5e0l#=x{n6tfw&$Y8c$Ta0cN(SN4*BCAfS+k3fu7h?AupnMJ-{>%ZZm}F^kgj?SaGoN#D>B}ozINe5V*!50qFk$9dn;K^D-d(=G z|BSV~o7xkX`0@{5a{Y8YUhVML`u;#*n+29e?sEUx;_G=%b<%O;|K;k5C^5%NLj#3f zmTNg67$JoHl1;1}&|Uk|=WLroa+&9Y{X808!VI)A7pH~K)CHPmoJ~C zy)KA$1m2Z2H=&v?KKr_wf?=ciB19u00v_$9_d-Q;dhtghXm*zEM4H6#GE4Jw%q?!w z(;PxmK8(TQ#`tLhp~7O<7d39Xm09`U*_`V^K?{5yB)zV0>Rb~g*khEKm1ss zenj3i^Klj@o^bQ#FbjDPm%qBgg`QSw!p?WXhqfMPZgQ5H`7PvdGmR~6G{w9hc-QJK z?+)MQ{^$y;ui;(I9iZdd|Hbu_F?`5BBvd6K%9Y^<^6rnZ2w9O2zejD0d~%7W{g3D$ zS-}dmaqj9BE_Fun9FccrXB8c1&vQAs!`3&CSzdU~tz44D$q{N}epI28Np7*W8mHt8 z6KiNdU7Ta7Bq3`K)ZJ_TFbXPda@#A6-n+xV%qBVg=N^Deq^X}l})nQ@*pHWB?EqS z2sBjHfm4$~SeS;sJAh@cfh}dpmO|0QMnch?I8^m_JXladk~JJo4Na2~rirN+(QR<; zxhOW4WndTHF*kS1+EVvmt`xH5QVj zIEgl$;L;6&;`B2(I?M9GQ`Z%?$H+X$e_Tad|wbyKT9@ ztPvwHiW!#2pE5X_Ad&xRW3MEuRCUT!cYn^Q1`S!!aJkBZkuAN1VU!0-i9PHIfr+k{ zr8`hHRHqZip&WS`MRDM8C`gioSt?dWG>5jEppkGmw6b%es02d+ z+-~RVX8_0wil>r_um`VGCR-?w&t@rEFFI3xIlQPMpB#C@!-dQ%K{Cx9pj~UAv->P| zOhHvOTux=TeY1pN?iV~3*p@-5WMbI@$>GGIsYe_%`!XbCtbJ2-WMLO&cLyEYcG5{Y zwv&!++qP|^lZx$hY}>Z&q+(lB|E!spnSb8qd#PHhaM!)(eD@ygv-e~K{lP%HmL>@} z3jw$2SuM^Fgs5)6x9FEq;!C*9{4OTx!r3q1Nu6hOBHFBr5a?{)Y(vBH=drJH1bWTk z9FBDbiJ8*985U)gz=RMDYK6MqcEstlWI>5$Byp2$03!4AhUoNQnh)DZP=ExABE<2O z-j1go>}NCF-%c;6d!h8C6VTKqrQR;(-+!mdQ21wuLS9hHn6hD!`Qj!X9Q{2TZu^>8 zp#ipuTE{9S<=VYoGbAgJMdvvE&0R%)&iI?#1B>OLKCed5S5Ot(JF7lG&W7p3IW^1) zTaur~Pl*MyGC!~>TWTcMc-UyMO|5&6iwR!v?tZIwb@i-J>|WkFljAg|B(0Yo(i)LFY%J zG!uaGsJUr&{LTfv>fw_wd5US6dvD7Ww-N~q-NVh(h9L1X4_aj5q)d)1m@*OrT&_@q z+jODB6nz6AWSd12IYJiQLcg=@3RlqtbzJucWzc?x_$(XUqt1@9)!}S;hY5TMzho!- z?H|fj-3WaNSB1q5S*v}eY`Lo1G|7Y&$-m8-H-v}meoE>G09@%fp50lYNAxX~EL|=< zc;`&6sDJV^%9R!4bl}ChTmn^16W>j?8sqU~SuTjM({GP!V5}!%n4ay!&C0o4O8Ad8 zwmKTq@c*dv zI}$QO>;BWfJ2QjFly7W!%GLI5I(u91Xj5@iNSrCMKSGI9{IlF!$CS9Y56FP{I=o6U zHtKYI!hKiVQI1r0wYOpRL(75r**di7;Wr4P>~0z`e?fv&m0SGDaXj6SOK$4X&=hP~ z=I-4^_zpw_3siK?C>m9OgglnO^ve!TDjjVLZ^|CV_j%oczjD3R8*iX09?7KS9 zQ=>^!G3%e~@h-YF7*{++3`1E%qvIFK-`rs|7-%5bg3Z z1qf5jWt`oU2%=DNDYKTJTvn4%2O94k1$kZF`As=Zc}zK=p5YhLdxV56>eRj9acg0h zSyH;zKd)VY>9I%a_c#g7<1CClsERq%FRcAbb~JX298s@Pm!|gse?JsKqE)wX%|t*A zEF)SjQ$D1`QfZ4OQKLe`HE;7DJQ^@)>=+`?1_$pA9k;Mz^{7}fPoz<1#czJ5LTrew zVz*!^Q!Zm_BQkJkcgPr^WWo35N!KQCW*l$i_nji_Y8kcs{?5Cf>3jCWPUdkI!;y~| zSE9%GVRnf>Vw@0!%^u!6#aMq~f|nUMc|?w-Jh?o{V^-eFcsNr&qsB-2!{fwP%wr+IU{d_!a5C??VQLF_8}~Q@87)g)9(juF^-za!aWrD>kmSum6yQQ*6Y$hRS9REc`0)J;Q4@u0_3& zLvfS}CsD6(<*|irt0GmSS$G6vUJ~2Vf>0?{qGp#@#veWFv#sYpsuv@;2||&7`gziW zd17qt9n1}q)*H92b$5%uKk*Gsxa7Zi)8zvnm27bfmS7d{c(#YonYAwH-duMy4#&up z#dXbq?$j<(D3zae_Rhb?x=65KqfQ)`VG-;*a@=QSnlQ|~A~#xirap*tp@pn`KqJFcX6Yq2OrghaHqDyB9O^zidHfJoov8Hk0mUxDVS zo`ZBv=6Mp!#VCOS1?rv9sMh8KT;xhB3)FWsd~mPjtwnzNlp8}I z!<~QMy|Ykl8t33vF5{Mx_Q^7Nox!wFeo|GJzEV&^OUxp-)%(O_y%^kup55XW?lT*@ zol8u2#|Y;La)6|e6A~+5y%Pinq>0P1Bg@eMt(#UH+JAqeIz(wKeh=1Mz$sHKP_!T# z$4Qt6q27ldSr9|3@>Jc_TfH*Mo7F~Hl~H6-*YDU{T6mpSzUQlrR&ATK=gkxfxgN5m zbXnKzx*?fg6%_Cat~~5eIyXubG)!(xMtR@1)3@?Q;(X5 zr{c+K%UP57eElrFqGRS|om}W+lhLD`luQme)2sD(+d*9vpl9ezEuK*}Pj;%1@f)S| z{1!JXMz;FLZ6oeNLG-zEF6Ze>NGRdG;R%tcqoe2i9K$V&TUsZ}=t>zY=gh=o>W6Ac z&Qu=b7K;c$d>-|V%~=Waxd4hVcx_QTM!mmgxnkvVPJX*e*?(*lsqbp&;#JGvIQ`9h zlB6hR{rzYjd&$*!!#2dxG$6xo!uxDf;n#7B#su0w8kpBd5~UP=v8~&^>rjg;Y_eTe zgJj`gQWH(+RD9oeK18~Vh)T~a&q~pcqEl(=T^I^14iA*tdX=vaqWo1!>)fEfQXmp^ zT2*e_6bNVdBJE;onvu9hdKI)H(bhQuRcEqh-1bcemd(mSjnvk`#dWLm(H|EG@e}Xx zT~j<2?d#=E=PYPALTML8TH5a&L;1_HM5}UcOtL*U7xW9?)9&AStTH&M6T&{5WV!aT zKRoZ~nSTTt6KCR>Dn8CWLT$3H>fDp*aQr68uc>ZlL-lNxs8=k`4>)FQD?gJtFbz>` zji44!&9cobE?G|jay6clG?x^&cD4ke*w4~lF!)_aEg@z_&k1brFDZuBRm{;Is&_q* z`Pron(x8KXq+VVX=s|*?XA|iZ47<@tJ%IdmI9~>+j zmdmn!z}6FRFALFYD!7oY48v_*c}d~{2@SciqNitf>ogR+c{H$JOKPc-zDP3oy3d^H zQYl!kYh1D-u-tokvsd?3D%+ltwsbUm=Cp6GJ~Pi+R>T`A1I2F}qgK991`%n3y=gqW z3%kP@A!jl4!qBE!(oo;iNY8g<_jQTOlpZzE15WsUKb*j_y(M52)izV>=e z>B)IBvn41XP}J%a<5)YPt2Aurh7$YCm?7;K3iys9>zCl<_pyCT5%*m8v0beaCojgl z4i%~y`(RlqUZj{uefCUfLVSvou9z=RrBp_p>P@H3$4?heY77~kI?2|Nty&{een6#S zsf>=lP1;>v6jY=bA}KS7=eqCgWgqz?e>8ahxYw4A7)T9z4wx!^Cs5IQ6jY+n0h=Ww zPLl~I5#u6wDEZ3~#fd|S8`}}OJ6DwWHEe*U=@WPW3 ztV$Wdv>b_y1!+|uIveuO`HB~4fHqrVDVvKh04!%aVv&}2j}r!p0#{Zq+u=l&K&(#HM*UMt}Q34UN`PqKf z*SX#e`*(KLH^dit5$#^tsrP?D^Za|YPuGH1;5529u;q)vs{iEaQvR_u4ku2}%`T!0 zI))gEh&HG@K>TTumUCk%o5WeXhp9gy8MF-P+oX9PUM-LNc>h?dxJ!9C>_hjB5U%(F z=l@F4@dmPVn)ZH!jb8xgzvP>W+b!iXYh1hW%nJ8c991Y=ET!40r$ahNSA^;tWY;H?sZ|wft2)+E=t)=l)`ZL@WLI-hG70 z4~y!0QT@A3vY?}XY(nI7zxxAyd0A4Ogg4Xk4b1nxH={6c>5osSuB@;yAS%G^Q|Wd4 zD1wU;>W8M%(4pg=>pBwK*}|CD0WOzYv4weQW=4?uAKQ{*yg89u+s2$;j#BAxmV1 zDDtsGCKU~_<{R+MO2vv1aaEd2eWYV#XSMQ_Qk&n506L`#_SN2t62zy+0){gWbTMD|@5l%cPEl97Q8-cljelo*IfS;o5J4H7FO{y>ecZT7EYi zo9GbWEY_~vd^xBJ%kkr!k&BS<=-P3$^hu%-LbakwOEs_WEjo1BmN@1(mJTV_6#b%I zLXB(2m-Bwp?`Cmt0YBTkp3b%zypWM9GT+C)Lc2dj4tDkZs{+%_EDVA!HenK)!_2j~ z72;md#s8wkOVfpJz2QP`AO3nIr*dH?s76g$5B*z(Kes7nJKVq(vqsPw7)`fk|LpBf zdsK2&;F2|TNs)1a?@H~`aEi~j-ZH+QJon~Q+BL-9ZM~ZE+2l+2{=k21w{@e>3f&-S z$#p%b7%irR=XIw*Umcjx{ijj6kjzSb17R=X8^-*&v!YTT?%DCi^cz7ZVVKXawq^d| z(CK5#6Wc1`TE#q)v*3!jmFiQRwz;~PNOXwN%N~5F9Txn~4q)CmuLyI<$DG5QZ$XhN zeM5>k1AG^|D8r6NUMWktM^iE=_%CB&LC)xxqhjnGs1-!<9Y&Qb!+Ng~Z}H~qi$}sR z$hPDh7cCa5*XsY2pLCqbFp+Hio$TnMyeY(h(tGUSQ(f_>1|h+O9367~rY(NTHYgOj z=nRN0L?3U)|IrqzxM^f(7G+%@6!+fV{gDnoIXIK% z_VPl%b!_YhSMmad`}~oX{N~OMV$Umt<{I@kz^*xcRt( zXjsb`?lR!8YD$IX1R_1H^GI`F=xat42c`?vxBTJCAk|ZGaCwOsG*XXM&X@18bVG`T za8Q>%D8rsx_i*&0jsTJ##Z=8vS=V=Fl&CLXL;eWv`#vE=GrxcwgX+A>X!5wSwP9E- zFEopv+HErd#A$02tCBBSn)$2Eh9^tOwma>#aBmJj^j#Q_0P)5cJgP>#KHbEsUAVMt z?}@Ji&B`(Bc8d+Sl}Sb<_csCg&J)3Jfns*?X`Q|CZNIU>A{a#=+Sj|DcaK2E7h{@U zrRP(bDVG0rkG&sGzA*(7^xjiDgN22p7j`lm&V8{p54DM6Wy;8vb^I?Dqzl3P2oBlt zS!Y?6v|4T*_l_+}f{&l@ty{UXiL)Zm^^2j4)~rGEidGVWEWjZ^X0O+`?6?|#b*N4(o~p$>tQI&*pT zJm;YnQK&?xy0oroUH;Y{X3rA6ZhA;{N-BwAjW9gxTs50JD?byQJhe(op-uNwHOgNg zt(E^1tov&ZM@ogT6GT}>$C>yISGPrt4o-MsolNwvtp1&Hpe)hfmU3t@H0r!oZ zkygDDgO-9>HmnmJd`1PQ5hunJPz>i<0+uoPid8u?djM197-Fd-ShrTQdck7|`y_Oy zxIoxi8R!L+ob1GMS?E${i;>sGNDcGiTX27&TooH z0xSkioY(HWz#~dtC3utzeK}%NB2-WkYVUDLp3QLcOq6fUzgh)FENuKx~ z1JBp?$GU5s^KpGLajJtso_4{azXl!!vUX!r1x@Lil|5Ti6d55D`Rk%&7=sq|crtD> z80WH-TcqnLV_iNL!N9^y}ddjC4XfZSdsn_WZZQX zJGpq&ukA2CJ9k^yG$#ohZv1wlEu{p@gfBbaKl@Eb|H5Pl7>UQvOHXshOGp3T|v?wr{f;0*Z&xFmKeF6ehKo9 z#@$s-U3#Ydk(&lylXX+NJhWRxyT(6lszm0B@G-9FYPnH{O_~T@b1j*QE?CN)qO4WX zYg}h$k;!-J`PH%RRl%@S+L!-60AreURlybd;>8of!=TsZ&_I)H(v!>>=Yytv9oX}U zknL7hv{O|H0CK!qtj+ft$KmOh9SBq@d`e_XD@%m30J z`wZ5+AC$CbPZ1~vRF9@eSyxupwj>r)&TLV;-0p~oR3)uys++QA6_Ie9L=OWm?+NWy z30!etpVDJ5^n~lUZz$FzUUZCMJ(g0E)pc<5*b{qP#pj(DMAKqgJ(id~EEB>4nm8^T z=<|sJ^?P^a=HjmzJG0H)UJ&kRjP9Kw#64+$M$_R}Y82J5^xwJ$l+tg| zP~ia+NM;b#6dx`Iy*___#MbI^L07W>M_oGkk1V>5RZYs4{>>DVhQb^{^O9Ri$8-?EoJ>*Nxnzs-=9DIWfD54zpz8!>162PR~{-W&Q#_2hB*oPN& z==K-m)xMEMLFV6j!PBxTub?f#j^wQ2KsY!!8a)zul%_=QK<^#%zj{iYfg zC9o23H;sPpBf;3t^9;bh_pqjAk*uJjt4}*An8fAM9@ks`mvUP%`MWNunkeJL*=;Z) zY%@;BNt3I2J9=|@Fe2^~dvspK_z=3X{Q>1<5cmDo?~8T31<3KjN7%_JYPJ$EPDqTz z;BYl?`I<%J{rV=gv1+?>!8ZsZFoxaYn-v3^i`D5$fczUH8bxjZdYyd)jcKF9Gezmf zpyJ4m)2NZc>qG{_b~0WC+`5V(3m-W%?C92aE@Uaa;OT->uxIfDk{@(U-S04CD1n(U zp0PCDpZGa`jFVO6F*mSZ!8y{QH!WH|S>CP@_?2T@w#iAAI>K_eQYV7mSs0ngcB_zW zqV)~qm#(4Kwciuq-B?1;T4S&Zf`Nb;$=IU`llt6%B{Du zj7)sO>dZ@iqm|I3_gMNwUlP>7ikKx{-{jo#zfT{_FHja?Q=v6q-5yr+?e0nAyzQ)e z-(OGMtuQ4!d7|m*q`O0Nk)9YAFidX#a!wJ5HdbYx-+Uc9Th zJZfT7&&;MQhic(9XyfYVuoj!qQ5cwaO4fT<`;+-KUIMIY>M!zp#?SHQ{4=^dT8j7? zi6{!zvPtLN3uRmGPlvgpsbOlu`bXq`Zi!jgZ6oHRCtG(JJv|A|ss3(){-}q5XoFM0 zPu!FEX?7Y$5Y3_4B_3*WM_1d_#v$S`iREJ#VPmP^>wBxNfzJ_L`3aB7tRQs)(cAx6iFRMFR>&t{{s}@5+ zk{c>IiFaFxG)Q`KP+-bQ9Byijz|0ng>!X+JcWs*jDK>Nfg<^GO)N%&d9_6uAOz&jz z5C6^{mpBCiK-EyEE~z!KnYMR&;bK`9B5>>g>TQ8%A{Hkv(JHO2n~-V=GH5vb+z;-E z{qrF0qVq>(5v2TcJLV}hzFs7lf%lDV#Z^`s~D z7KeDbu5^RtrK!?8oTK@V0dEB91plfLWvTUw?XCfK_9G3NQ*dr>Y)(Guflr_k_%!aU z^)SY{kzrv>W2Xn(@=@G8VS#Ndr#wZ8odWEMhhYpej zRLxXe*7C3qE|!`&s^H5VWA*bokYxW1?W9}&h3UFFh7qq~4}lsCW{Zab&9Hm(GkhpW zy%Alq)uc+dLv+BRFClWT;qs|)Rt2q9mbiZ8;%vUcIEpGECR_QZLHC=l#!sE)8Rdt+ zOH?35gv%7gSr=y+k$98z+W-nXAuHR6YV!jnBaq9jYk~!l}T5gjF+l_Gx zdt(_6zeu4NRC_8KpP#6_Bz`d>^Af|7Tp_3^YKzp|G$93)Xe%*tcRc@5c$Y0*+}J=R zKaAvg*@&w8`=s1@=Aa)hOj|{C6H5U3v;XZ$jwkV>*y0IKyYk#nL}BI;(@{rB%c_Z% zbXyM>Tv$RFMUThFQ#Bj|@zb6Dcxb<{+C+SMbMLj1%-{;khR^FPYgy$$GvMJxOS`p8 zxVUi7lF)!CiRh9)*GV!+(jaBRHomQ5AFc`cw%uN%XbCTZ%pok>5ZuD!{1$@_5FU)K zMkFg%mJ$$LpOi`rlgs++qQd?o4zsnkMrM9?CpeilcUpSRY%(PxejSN+-L9@+KDVcTAs)Ikdr zUfTozkR3Q=v5K14?plc1W|9^giLv1?*HJRTY5bAlR?_O@74NJ9Dj&}C&jqbp3Zey5 z8jp2ttORY|7p|qXwNLe}>DX>d&tbbU%^eL}#%q?ip8ekZIGTgIJA;t^1jqOJ14m~4 zb|_$eVoN?g^hj{n7P@*uiUqUpBpyydqbe6opmskRG;89TWn#MFI`P()0TgHCKw4YY z`Nu9S+}Zm$1PR-ICf*ChSN&7U4?JZtkP0TZ^q(Z)bc=eKesgE)7J+qE#Lw#|{sl2D zeXh=P#b0Z__Xu6t7}1ffvBvZ9Dk|b>D(LD9|I5o-F25)m_LP-hRxN;jxW|ErH-t0W z*1zQSTKRbm&g>}m`!(TEs+gbu!0Zlwfz3IpTjKuSOsZ%Jf^PGC1;%ca=X}=aQcD6h zAAZ9mag_mk&TdeyHIVdnA8u>IDWosixZ0GQ$&W^9O+aQ-s(N(in8oeA;>d0HDxZ*+ zxtWZSF$PtX&FFn3_#fY}c@fXYt!rb=9d@CG!(VN}1N~Q#$t<7vHQZbvSTN7F8_vhm z7bO_7^Q-v-$8Fo}^iDnF54BQ2v9y*o6me{4o*^H*u-43?=TDUoPx9&4306A24AWoq z`%*3pJfM3dwfFID4?TKdIO&3noLgY&D!gj4S&K`3R%|LDuccZ=M_^tahuks4?fG>N zKY8ASHUOc`^9>lK(VFvCSKWS=#!C$kA2lyWgk}j+svsfSt)V)Y%a}NB`fCH~5YVG` z8t@>%QYZ*7t0bBxy&wHp?rs@6f2Cuc9TX7z*;z`J{DF%9`blslsKFBv_3kIC-D8L$Psx@7J&FDqK{GyXr?4r@Qvb z*Ric{zQ<;LVe{wIoPT)%PA^fGt7RGM6GdtV!y6iro0dk4mZ^A3MYD|ucOQ|V+Zd%P zx!P>QpgR@xJvhTEPDUO`C`H?#+sIBsY*denTVE&9ZD}v_y|}QkG7j#=;WADjVscIE*B*ydCC{w$Pb;+++c9t~2A9e<=5j*qGJ%=0xpNpM(MyUd7YS$h}X4BT;x;?HO35fjVG~k|LSU5O^H0D0UV9epJ+Mi@4^qB`!Q)(L$^w$rBzERp! z4%Rh6;me_0E2Q;IGsPEHP(lNiRg8`!Vh{Vj-vr{#-y<)FspmyctHw~EouMfct& zGwHpsW(;TMuB&1{DPDKe$nvw%w+$?ZZ)z6?zkzkudwFn@Vvyn>0_C8nBw5>T2h9*YRdP@}_jdYttu z&8;{0p1RuxvSOIJsu-ubo=|07K;sM{q-;v_TD`j;Ucb+CjsRpQGZADel}c-qb!t_! z9fTIDBeph5|JW2%ASyM;I-4RZ_uBNbr5ILkUO&J)V=-UT-X+3SH+o&Cyxl{~al6gf z>idf1_(dx(8Tl4OCd~dQj~T0)f}GQ&YVs;q{YP{*->85Z+?8Nf`9&?~9jo8hiOrlB zyyEd!C~OHNR&=woEE0HO39pji8sanT)7ewx+^$*KlItj~t{vw{+0L0n0-U-$4EEBv zT&jCu`06Dw*7dFfPuZ`&a(}3V4EM5}-FOWQcDtG;@1*VbEb)_jj*l$HAF>gi#FKLq z@N~Kzy_*%$l(XZ&0W2NH?ST0tuE|bT)2`1lm!&9?v!Cyt3Yzu$97Q$5KN-^D5wbS;O8gVyT z0D07H;;wMFj}gM-y$?Yf)0p4C*YiqGUlRp6(G*r!I6U2AifhJf3@~gu&?jh;cQ;OK zmg0K*n8aVCryU$Hpi+uPtRVoaNak14_xAO4OzCvUSDXUb>Aia*WVu!AYY1t*#_XLh zO2!%IA|&AX+FYo^8~tDn`&6XfEUX3+a>05gX$gXa`(w%Yq+5A78frS9ut z*t~3#)R#l|WtMdQ=KZMBj<1`5iNbDuSF?bq9Penw&HWXDp9(qff^_j3t>cS!RrWRp zn2Q+3=P^of&cZi%P%EX4cr>6LRz7Vul5Fg`{Zis>Z|bkSB1sb=>FJ3&@6|>F1@)%+ zTau)BxC@S}j219?P`YFc4j=>#n5?g!zFn^oL+LvLfcW~x#<4|{8P;^VAn*{qB9BY- z=MtV}1 z^R{-q-aX$LEq(s9%Nn0wsXXqPreuu+YjbQa*v>@*2jc8E{`f^5<7<6z%XB)sYgxaI z%`&^<8D- zt!FCNG{?#}adY#%k8RgiwY!R?)NX4BWF8YfCDH}ANT;igap4lMatVPt4s+bB!s9gx ztyULRTc1h0M(USQg;y@4=S_@z(~$EcCO117hr?4iEpiAu$HduMh0wLEw>NWql`4g` zO=2~R>m7!_LKIm=>VR1mh@z(9rBj%tggaksn%?t)<0sVnwVeJ=HV$f0hMt}s1t<#Z zPqtTzX(!hb>BI62+UfWB?F(8a^y|F_D09c8&P^NFTUKy4N+Y|^R76=f!1X#JwuENE z$kq}HyPfXvfy^GzE2Yev=)H=4q*CT?(2n2Kvn0TKyEa#0WsOM5GQZ3M!}dL(TSjlt zae9_C&A~-y$9n9=to`>kJhYs*ztXW|;<(D^&A7*DyLcUO`cD%%v*`HW%@*C%Om=vj2;p5JW~+*{1y3} z6se-0x|<}dquuTbUN#UED%PB+Z)}v(v7cr2O@KX?W16`fq{e5VssvyE>As)!qsTF4 z+OCSp?SsZq3sxJZttJxZVUD1EU1RPA=kkEVY@2iXDhX4Z z?Z&z2eoaf}<^LD}&G%{%u(s{fx3C7;On0=Zo=O39GGvVcN&+-Xd!`-{21CQSm&QwB zukMEIxrxonogrC%6&}BwHs>%kc8S^W^QtbRM{;A&4N|lvm^qx%eD+UGd?aY+uLgAA zaS(R7rN>_qRaa>hxom?#jmaCf0e;Vh$*nXw_3f@<!_5Rv4wSX-OwS-!+*HoS_ zgc7lKD2|CRXW7!rcnuBx(<7ARU{UjyPaeNoe%yRx@&(SmG$)8#FB3XhJNvtG9<8Wm zD9>|os>&x80J&bs%FeGT9rq|^u-*O)F&U9xHuW4{VP|(9By}m-0GKgme!gW(Ca>f1 z?c2jjmAXc+JJ}M2Up4iuVvSXST*K90n_ofWuen3zprX!b{jtZBG-7s2rT;@baxKS? zf#I#=em6%dzm}1qUrEgecnnkjkq%tmv^~CjC_xiwVVjT$xe=@^6>UGu8 zd$TnI+jhwVE1cO&Hzb#n2b%IH^y43#d#I+e{%t>c)n|bmZ$<9fTyK2mGSMq5+jaNd zY*g+9c55>m#tEkb%q1t*o1uLorKfjQ}#`br{98=q| zxa|u86z4?GBq86FbK8LQ%R(Fb=;m$y=^Iz>N3{;^a`QUWOPs^XI}ex;>J&4z)<=)* z#Z}y39#`;6iOPoIsYg05m4N4K>@Ck@ypmU;FfVosYDvcay-jXyJ?aD`!}~1xOG*SD z8nUP;@nx#3k3oXL)2o)QmdX1hdhzOwUB#ZDMcTl%Lfu~ps}u6pP%Z1B9B*6g9WHfo z;p?}ZICfn;;p&-!3HzAteg)zmZfa?IZG&bnGMCyn`%M`FHVw{hCH|(c%p4xEh+BB% z*v{VLT@^|oPk*djw?4w1c_ZEW_cdc?tgPH9%cqw|OcRcQ%a(z^ZnaiYve+!#hkknW zoR)m~`9V2PtNoGCImt=)qRl}|;@CKFDVuz*i!b#r18~(bomOibIMpw~VOc3)YLbo1 zj^W_y-(0;$E%8!uRdrBg<(vTE2C4GU)zx`N$-!!Ew4M&1)ig-XonO{u{hnj^iOua0 zduJ9G57SM6U^IF_w8lI3(tL*&nd9iLK0 zySacoxLBjbD-4&097PcqjB?>^TA5|_nk>%g@`AQ#&CHv*esm&GBbI%lqkvT^5l1{O{wkO~~mMMKj+Ee9pFnlI7O?_bks}a;Ej-1$o3~ zws(kMY+fTLfkkZw&?A`{8vc#H z*_V!fjECdsQt}a(Q7KKLRxXD}(-AAhSka_S;0$!y!UGCJ!OyN#v(tuCblmXCcEOsu z`Ijrz(^g*9uyjf&&Hklj+vpY3J zYhtpD99&Ze2M&;^*?&whVneap*{6DNukO^Upm>#<({$90c(Y7Ays|ZnsI@Qk4ydR~vzgFq7)Z|EOvSjg(%d{Ndj$sI>&Ob~cYwul=6I)Zh zh&G#>q;ml^%j+3Rn1LS*U~lztOIw^&DNe~S4-B5%?IV=9G5uoLr<7%2%p^H**Bvx* zNi+?~N+P$Fo2=2`vgeXpp1uD-^*yD#o99GmW1>Y4F`s5UFuVBWHH$PE{)mNY_XS~U zm)K<0+|pjt`*_PkBZIEPwCns9jwsE<;F%dQY834ZX`h}G=6N>qz*XcOADW-Xf{Vsn zE`7!0;|oJU!^qlqGx}m-|BYSi&TiaVtrjXUo|TYXjM>6X=2X4JHD1KtOhb76M> z>>vxu(6L>4sVMJ`2^j(&iDkRZhS4pJEKQRK4_QEB9CPC?#wx?cwY&CS5fAv3i~Iv4 zK&oL;#TLDvKMRQrT||J`{KIm;Z4K45+S;=*NF>!SWPi-+LVCVpV{;EZs}qif-zCu@ zI}^@EPXdf@v$}f@pq)OB;M_1l$Jnr5^+t$`Yw88S#l|o*Iz;axd_C3B`+akUm$8zs z9QzlEfWT~8j}5rCw_99>?mZ_-=9=Q>Z`y|$Y-Qw~9vh;gN%PqR;jW(hqq{hJMxMbb zDMW!#oH<5U65rJd!;FpvYCKyUosvTq;m(}aC)iEE0q8080&g?FAVr5c85u?W)WF}) z82G<~LzjcjXh7?IVvoYXCUV^^Wp$*Yrg1?SQ)VU0HqhoH`T@~tZ$U!zjSFg}>+Ay= zY0}q|V(P}IJ+A3;eIrfJloZr|as|0@fO+4gBXYRwykBwL>xx9#x;1A7pQ9PiGa)Lo^z^1BwM4ox~_QJ{1)ut5YdYLEjO00-z#{**iD$((rg_OzEj=Ra~ajh z;_!3G?#ev^0|e)W=g}$lJQ81hOt`DO)U4Pl3`TCA;bdGVCs%pD&-))*VioeS%ekdb zQ-A7FiOPL3Nu62T7U4wF8921uKomGX!u^#Dz2?$AK*d2sB4hq+`YziRGyvFy`&|hb z#Vlo02K9wJevok~7AoSC1z!GiIYcB{?HG6+dI3@rjJYJm&bkWG-8FX&ht6+L0auA? zA7vrc*wwe!^5m-&QyQ0sW@Jh&C1a8suPFT7)v7QXDkIx z_Vc$0|GPniDIQdC+9{%oAj)g8b@Qui6B`<-D*3!T|Iy0&3)02z zzO^H^5J?&=eHTw?VU)txS712AH3xw$PK0?M%IWUJI%YWHvi*?fNrXDVeGccEcnudR zT(&zH??P0m&ELnKX67Z$fUzkfK*zCU%`(U9qRb`7pHiR_^OT;iCIOyXN1Q}Tj=2^l z7>EXyOPENY!6UqI$o-0xvQ-fPY9q@=Y81 zQqL;|KG~!Ta0rUIv1i#JcTA=9(|NN&K_x)g<>vtC2qR+Az@)5<9p4^{jC&8Ek>p$f zrza!?&ismQLxEWt&FDpV^skMz&GyX8A~d`O$Im|nKqn`bn-#A_AasME_#tI& z>iSDL{mF$LO)BB^tcdiq-@?mX28E0{S)AWadj>eddP61#gh@l>R}vi9m11!2ld7l$ zd>*1NHM_3RsFsf5fZTrf5ha>T+|^}%5u?xMYw3+Nd?k}u5m55XF!Sdj+)Lmapc$|` zC2#fHT_xkH;|Elmt#c(W%%mv5@1y(EF4zc}@A)L`Jp-2VpK-JO%b$*yoG+S$ebnu@ zHGXHX-EuWLz&S9tp#JS=Ygg|bc|F6pncrJCQmejLLu7E<5a;Jsw{T*Ym}+w`v*0{S za!Sh0i#Pa>fMedwWe{9y=>46?$H!;I8qtmp{?q&5&coHsO`=G#+U!pYX1Fs~3=x!Y zftQDflAiJ+%tt#c42zKY7~+FGAsEfP#f zbmJL%?y7ZyYzgRa?mXGYym&!o0(2=xZf+@EU0uh#XhCNF`Bc`{);o@^P~bnHs$~SO z7KJUAp7*{!2`!dz!Pkbcy^sC+@bP@N`kDNfiQ)%){@dDN9fpF$`md{F?>|BJe_KIn zc%)eR|8-qQ8i9ks{nw@I5UuYY@ZVN1P3(yW;*N<>vWaRkW~;{sb=?NIfCAcF1}+ud z@>5q;)fte>|I-@s_4jEbPLX2##l;2T!7Jo+iZ@?evDMQT?Kl%RH#by1V`mO#Th+WZ z+pi=^s>s`puscoCaVD<6jkA`ST;t| zj)%(JMdn)I#E63FEGwuycpwh%$O$Xq05!*_HLBUg?QG(!z5TXNqJo#t2G1V&t_-~G z;HF311eYyXa26~ZeU3l6=H(Rref`R4A>_cyJ;5o<$Ce#cOSI!x!^hW9K#FnVpN>)W zuQutyy1RS>uiWvniu$R#|t`Wf9J&C^3|S6-{(e%g>~B*Sm|j4C{#-hFe{ zvErRKy=#p<(QvTif2cDA2kQbejSBgUC7#OU9j+J*giDKO!K#23bIy?20y1o>{ z%4STGgvi+zBZ+?&tg^fIj<+-s-t7&YH*ESFK8#F$=Y+R-HrW{snKLa$gyg=}?@yJkz$Pkm0lPP@lBRk(i zguZJeM-1^p;CjW7}RwB~d0Ld&})PF zY`#d;|M6zee;x+%zkc$c@BYkGWyt-%e)GTng=427@caMcZ}SJg4__;F3q)Z|b8FU% z7Nrv7z#z*Mj-Zz>;8Fw0qfNQ#^!%Ir5#wY8DS6iG7er$e=>%C&$g{=c>D5ZvS!SZd zBO%)7qxg6FkDKzbbTienm;T95P(WRXhL_Z#NvfQdh3Ybaz~9%eLE!HM6_ErV%<%b= zm5HS2@TjrmqeoK8mhkE6{!>H-OzZY-ogkJeZ3I$J!JT-y`Sb-z&V*X1c=br>DuJRU z0g*7l1jck54qo3MzKF8rfx8-%pAdx_lkt%v&>=>Jbr55Xkmy#qkw=OnhBt#A>8UjRHk+ROpZh za^{1m!%nv)?7uM}NED*3pMUOlXd$Ni#3@&e`6TtBcEV=Xj2f4kl_gLFqJA-8cv(~{ z1G9b9U)J3E&zM#d3f94;zU3Qe=pNr5~Um=f_h;D8~ww3RRYp0ENj0!$AYNnCAUw zO$Nz>cB@u6jfUxygBEN?5R$AedUC9w+>>iTqJ25?6MO4Z#L$jV9A(X;1~HL(0T+i$ zVaV8F=cf5$RUMol_4Tu(j7DF+HL3CC#6JXPP94eWN16>u*rTW69!oO?to9axUz_EC1 zVFuec8iSk8&i~Ps-?bpzKo2)p@>k>d&>CcWEv-tgkd_-E*oV!E@eM?+iLZBqX_Dio z)aIljmCECg1}M`xcLx*v@tt1wuKu)2v_O+6CA=0lHh%2rmm1*;O9FD#ri_*sQulIz zhUcq}-27>wTe616HgS4o9!JpqJ^T!24d4FDm&l(24Vr`qG3by2GLY;-(opv07)6CE z`{$$U4>}r(m(>bb8JqJ}gLtZV_XO!K;i4t*EP_Gf{*xPIsHWZ8jK5uWF_zSeLg~V^ z(o~s5S{3p(|DZgP2aN|W;E|x*9o8p11Z>N4Sowd_l!!zTMr+aoVk_$F82S$u@XED_ z_f~%#rbp__*Kl<-xFIqz`36VS_TN8Gh=&r^!C&EfqHxpDPE0bfcTcRzrYeIrcU7S8 zH0Q3(nSs80bZsp%0%C&^M$S`=Qh~x$!io+^{Vd^RRfWyfu&_>qS_Xd9eCWiY;CSYL z0AfL%zA&TX6O0XZ6L6c6et`26wMr(o%f|8oGc)rnt?dv=<)i)JBp(jm%5tadlS?mmV_4l_L5 zPhW=*llY=I+@1}sS*KP=u)Z|Q^wbP3J4cc8Dai zl&THTOPFj<+PnK185?JO{4j?)TqvUcDL$1(DZatX<&XGp7guOJMKnOr8!!+4mjB)2 zpxtYJ@Jx+*B}Xc>$I6ZB2_8ns4=rKlzdT4W*kPT03;A^1O z$R{GKFU>JOzrft$7SUAxfzItY$t(^hZ5@3K3=K0rHcU^@gViWL*N$jSQ>hh`L^hU~ znwnv5evOUYIGI9)rl3bQTXA{Y=o=nmVtky@LmhbS@(Sd`^twH=T`|+Mt|{u(mwM+}r~5i<^Yv8FHm6 zO?A(?K)|p_&8&S`)T)Dk#s+gy#h3fi7i%_W|^FtV_|uVa3V*s(m>N0Fxecm zb@nklHo?T$Fo(Llm}SG$kB!!(Uda;OTxD){mbt|>Hh1ErawTew2LV=-1-G}2zQMzc zj0`b!s0*LN^pFEtqnwQ~dGS3yzQ0SnQ2+kt3Id+dzvjP~tpq%lCkBiT1{#e@o^)h` z`ROSpXO>voj*`rjDA$`9WD|C`kFNefM#qnEWb_aLrxE$7_O89>pw%g)B5W=%GCMoR z{L&WTM2148PNNArgNViM!r$J-q2Wx)cJ%`mgD&UPqCrdUA}49FHMPH!6n!(&WLjB|LP1CQ;8 z*>h^GKq9=!%HkZevrDXRMTw^Jl&W>B?YU~ zOMA~DjvhbG=uj`6KHKAizM4v-Rv;bOW^wu!SFcVoyB?!tXyfdgzrz{yVEtJJ12h`t z9I40#bJLSd&8)Dt9VM0hT6Z08KV1VujE+xmF7Uy{yDUbEc!pl$H-F=% z(`WhF1Oqg+LA8)zcWr^Gsaa;{*V&Gw$QCPm0Xwq|PoSN?p)rmf9cQqo?T71bqf92c z&D!ED)3b{#t?d#`<|vfwXnGN=!%eWWm!Z)KjvgJQC*Z*P*r0ENYLIXW>+m*0W%gM4Bw{{KY(&;R_-|NK+G#EU?)*<|w0easd! zeS`f>{h$8_^-=-JXrgocIQBr>GyHW8O?w(s_2~$QL)h(h><;H&>=_3UO|4RhuX5|c zyS(+@XWU%aAy?JV8zf{_@OP+!QwLoIy9-qJWC*Jw= z8q@0$3N_FhWMs*JfhN^ripb6~ODmgf#T&S~d+}H#>bVq~3s*4rhzJG&lOsT&_ZWii zr#F7JMw!^^ZNB*6UH+f9uClzFrrgvJ6&Xbq5!4#lM1<9aMV7Z>Xl6G)j}wdW=`v@v zW{q-ciyNQ3%iC{#%7weD#PSt1L60bjNTLp%Rwti~v9-3s+`<}>oDO$e0GCzyD)^wO z4GQr!?tT6dfBfUeT$|k@S*jx{Ml2RHW}}EsYf#E2_JR)c8^j6%-i{93RvG;RCy%CS zWHK2PMZst^{)I;OCqQdb%}3e1e}RAd*Z2A4>O4D{GMe6itVoD@fo7#ZVt13d=@~+K z4U^kX!2M;W_>X|vpq$=f@{5o7=<*yJu`K0k4O`D~CWg8Qy1wZkY&06AQYqYSHwMFV zaIn`J)Qd6hfBr6idh0VT-&-SIs-Y7_6h%f9G-|~RyBlk)tnLu2$OJnA*iF(?=}ILN zCcM4DYP5(bNyzdO{z(ROs8mX2%9RG9cbMZ7{qzPb2neW+GV!%3u6*QcWc;uK720gH-Z?IN`-Q{jMM2vI6#gwtx+MdIms9A zzs-O9_sh(0rzkZvL|Hsu~^Mm6bYSLC!dP4zO=y1!WJc+1*hMK*ZTEgOj8?F z^I>MMe8~U%Zy#{s#v;4vBC5`SB#TG}9a^JGCK_UWb&2Km7!|#PK%4I&hb5@0N5FFfBEmcdufWrP=*?Mj3zT?i-J+qq1MWzB0DV1&$GInMl-t!c%7JJ z{ev~wq?C>@eeDW!+Zpl=9Tuwzqar^+H%07iLyQl1)8Vsz6%43Ws}zexTrL+n-N8wX z)0$P1n^Ro>^nL!Xf4#`;MuK7k^pc38i0HLCg=CENr6m?tx2Y&Td>#ijqx4ix9!+gh z%ZHi0_9^eY^&y|!Tq2ySp_gP#W)l{ZjHHKZAx&swmD#yP)*>~W!FHTB<-wk#QHUql|Qjwmx|B1+=4z*FIR4P*!WQ@UMynZ~0%_O2}8ihguy2vSGNM7CSuK$Y@31gC$7ZUAB{m+-U zHnl;rSVt#H$g+s2*Ql3r?5?e{w7fyOCgJo2@Ys!C+2^o#rY{r}-(MqM_@?gGidn)N>nyEolB~#h0|A^?`68qHds)b1P?|MkD~ z$4~AswHBjLYa+^fbD`Jj6w`ZWrIqyvb=i*J=f!H0zH^ISYu5K}8?8-q<^8vL`;)uO zuE)riDpXYy!M;Nr9_hkmeEiMda=A>oT*mEo|IpEUF3}oQ5}T7;`{X_T>%U%NZYx3Q zf$ka=@vF1#+R`G6YrE8pK74LFHk0&p_NAs$FC|&Idy)6v`hfQ@&9ENN(bVhr^wXe2 ztCvWIcUfLsWFwqM@pKY!@7?PAeqB_dSz+t$`+V@pZSF3GDO75Rjvxa=hZ*j&V|Zx4 z{L(g(BnhL@c%XE*UP`bvbA>{ZZJ2uOj@(x@_O*tjNjD* ztw}Yv!@Y~|^48m*@x|mO>57U@6pp=))5^8oP7B_rzZMo zvl(a>qbyI|yOJOx?Q4^;-*UtMojd^Zgy3WnT5UY2-;DXtP-Ra^~ zx8+ADr=-!WCfHfN$LE*k2xluG2ngDXGUgi1T8{YQXMFJSZRU4!=+QC+J-p!TPGc7D&PA~YQ0Ek`3@I9 zyT@XrN_S5iPRExef>cV0P40bhfe$Xv5iY10Jw3ei>N$=a?jz__XciN!&EDhYjVY$q zV}#}}@yP`*9;c1t10KW!ye2@SnqKDK)h~GW(|Hm#0dMzV&c1w#qlbI&Sq&5un@nE6 z%B{OgtZmM7{bLE6-GcqhA>5|@nqex9dY<*WSGf4ubtX4+h^`J!|LQ;R#_18d12&9$ zjanhe`s{T+{rCzuX0}Arf!lGOp`e53@iLj#tdR}Pa`ob6KEJg=UbN9ZG{*T~ zyu?_K7o$)nvAx9o>o>VEwa)I;H7+P-%nlE~9(6oL^D7m!0<)Js;qy!PS&7x~ADZC& z>%ZjXV}o>hEeL9jTx^s1yI1-6lbg(Ku5#tmi|7m%g8%6ZPEkV#)Jqw5?tRMJ?_XhZ zEsf6NWnkBD9@!6CnC|6`-o zN$o6hRx6O)Uf}MP3w-eT0@1Z;K6&4a$L-+! zLV~uD^zPukSsX6j`6?z;VkVg^Ao>cqS=ez=j7m5BGIU4x0t+fh4(+5AzBe| zwjbi9SI=>Dq?dqQq@3Dj_RbBiUY}(xyvp?t{*2XX#&YHmZ8mA&&uP|jY)#$Z;wM+Q zyOu%k=;Y{Yzvg$Z9HGl=!6-t#lwx!CCZAut#us$kW*y}|bV%Un=QSe$O&7)`AZ?EvhCl}F)76N~N3a3Fshejn6Vfl;qdF!)D zR%2y)0@hFf03ZNKL_t)H-YyOwJI(pCV|2J=C@0xnp5l{_uCp4AF?sm{CYuAB^A-A> zhHsUUI%w<#)nkjF@#pt$vank~u(dI9>I`R29;U}@Mpw_WwK&PuOShQWiZXrWV-&X^ ztNAGXzWv&lfYu}zTH*f3@ABU-E>qRXxI2e9e)cq{CI;|X1WJi5X7AqQi_6pOhF7`q z*+pz_FZQ#Ca2X%EEu=Lm=Rz#p`hxf0zs$Y$B&yMc+ohvYERfz`#kK>AMlHL}y=#|w z|I=AwH68AbLC(E$j-w;p1neTE#1=ERZ*cX-9P7I)T>ao3>~<@*Q~h`?;=Z5Ls1=FK z-{j&am$*6?rfRSf=sUujZ=7YY(}hJ>A+^20^~*Q8GrPt1{2e}g%Y?)E51i<6Vv(Nw z?a>-#>X~^ye(whJ8%b*D&3Q5t zRcPi}otkEHYK^2S(>{EL-~at@IDV)Nmqo##2Q?U^qa%pV^(h~Hbc^ksbtZ33GB)62 z$Zy$~V_mCPDMpr=oL^%zQN|J+;_REh=Wl;8gv)G1k@V=$XmFnrW zXt)R4zx*p#XCti5OmVNLmtOxdyhg(_l`2siMM6tcT>1D4Yh^u-&Q3h31ly_NkM}wM zl4unQ$!#vbf0fO68QD9)%fI<8Z@e@{hs%sC>OpO%qoa#}-^Iu8UgXANg4>^6X1Lph z*V%)8pI#?}V#OUWV)K5FKB!f);YAigA+l8gN8f3Fd3KOqp9ujCt(GLbF~i-d4U%OY z&Yq+E-GBZYP7MX|*o=Gq4Ad^VyF2L&da?cS13q8N5nY*Ob!U{mPB&iVfUXHtXckzX zondlvg?K~6+k2G1|HnUYe87+AL6)=H9;Bl)NJslc-g)~n>(MQy?@Tk&=f~dV+Mgp) zty9bGu(Y_w%60~WtCzzs|BnCiyHj{9rahe#z+^Nsa{5gqRP^-{AI>HTtesJuyw`_G5z*14GuTFNZzpcsdwh0nft|%! zZe8tTV&E5eC1HO7C$&x^v%t*44%^8Z=FV}>z41GK_0k~%PVNmXk%2B%9W@OQT zPHWKK-cB&!#s24yxv`Yu{^e_o9SY)g_2LxwH#llFO>}pSyK_-$O^xo+SNYYOzu@%Y zc5EgIgHDHLG-5QGvDjTSOaH{E;7F!W~jFft7|V9pf;;iYbxj@Os;kY`UmOs zJ~q>My!-~g`OSGIy4)CLanGI$w$tC=jqB}q`0U0K+Y2+? zzTU@J->Z1`t-Ceq$ysI=c8R1L*t(AL>YKmi_0#h7bv)5D+t^f|Yd z;!NGWPj`10zSG?}j0d>Pj8-9++~Vp7*Vu@ckbMK3`_->_D%r`%jgbMN!3j1L6xID2sHGh3ipjQ&xVLQ3W&1;h!?(t#mb|O6}=cQIsY)oC{gO6^qoYe3RpXZg=j$zoj z!L2KINN4`C!}k25f?8mEX`bonRiafL-kziU-T(BroEmJyV|&QH>}sdY@8G>ZUtuY_ z&D8Bl275f%P3{Nd{C$sVP|a>JGdaV|Qk;hDVfe&r{HOo;1_M4DX4!yFQ0eUGrn57M z`~463^ztI1jXAF0SfJB+6r;!d*z=vHR>{TIx%>V*++NS1d4u#gD`X5b$Sc48HE*6Dr_*Cak@N`7b^?Jm+Jjy!f4;!Y(z@+~MO(^Q^_{w2i*R>%V@3^AjD|Ofr&Qho-g@?C8Po_Hb=#i%`ji z$)HlJYjA)ry&gnb!GPxlO{Gz*P^mN!BxSEO%z@5ec)n?tlSFq`SlCQa7k%^`KEau> zemZ?-zV4SJqsZM1jf@lDT4iQylI+$bD_chy?g?PE?=Q2xSxl2lB}vr`*u5PLO`K$6 zxR17PY^*Xyqr#!VVb&MtnA=^Zkl$b@R-)_soP9q9YLj|yhqbjWHo`?DX9q(kUuI&c zi-7Z?>t~XTBn>ceBuZ?1i}2k9kRDi z_S?R>Vaf_dlfuwo9}816Oot+r3K=r_I?X1ahk7AHI#-}jQ?a@Ow0CzCa9h8w?JWrC zMH#crOJ8pX0j~|+T8?rdMLb=n(edLC<@18ptdfs!v9cZ}RcPQDJHnBp6O45Guu5OM zOJqsHY%y{E>@>TH0{3=zSYKUbD?Wmw-HiT+rckPNa-k)rZr|bNVg_T|A%+h*$lfmz zO1~Jv0JV}O8(!x2Y@DKIqHFL7N5@C#3%XIhTI>?Ctk5?!&e5$6mUmKYZO^c{cAAmC z4(#szW%>v@J$juU{gZxNYf{O^2`}Aeb~Q;u@p1Ir>Ag8s^q^@p%LQ`DIJr7lJpl$z zz0AqcJ~~{+hqCNs6h)^0&>-1~DXwi~spJ!Tb=WH!-h*lgs!bY&FdJ)ItncQL9DW8) zy~c^*Zrbef*X2$m8ATajbUexK$_l$TqC~e>Slm9zP@4mT^!<)cO;u@@a-_0(a+M~g zPA{DUL$tfB-_SWhFJiR1>FVmBr^AVEDnX@~C6#^9jQ%;Sh)~UJv%0p!ZnAgmDfFhA74K|n7m*qlE4`+|5~CKkg*p3!3*IdPn! zEZ8hv5wm%eiP0(MR(IK1&X7vRN#*LOK8=H#b*xr%WFl)^pNvpw=;<67S!F$vWhu14;#!Eo{!X0U{biDCwKBzAhFHD==sb`}kb0w;(fIrYdS9do) z`@_v^1@xlvYu$C4SdOG9VUmp>leA zy4yQA&haB_tVgn}?9Q>cc8-DGb{wAl>25U>C$hcGda{V1H*@INNybJ7X!qE@p$D?m zhbYuJwYWz5ZiL9nJgbqDbO!8rjrzSZ^=h43tqw*nBWDLWb?O*{y-v0(b4(rlD_4(4 zZP3Vv*n+s_l$vCRo zpb!tUwH+o}P_g%QGk)qc3vKb9mbg0VmcnD_H)`_HI-6wgVpt2qS-q3o?%9h9A&h(4d+Aq zqbx~C;s|HYth2He4|Mvo}w%uE*~2;#3R=)zm#O9B5PLg+beE%9Yrj=f>qr+*yo}F4Uf? z;Z=(tms&1KY?Iev(M!}wi;RS>b*oOs-JWCLhwkwUSt=iqtHP}L@-=r+6I7|F7L z!`;rv#2{{q@|_@;&S1jZ)y=?AH%>#7Vmiw5dYo!we|JN51{rJH2AZd072XP8_(Y~ z{HQc*6*A#%b`yC@O%vTigY@T!CrtWa%#u6#Ln~_uJI5OCd-MHUtus=Pue45nO8ms9lNOrmh`{@ig9|{CKK+t1$ zcJD&~nH``U4uzO}9e9XioU$KWA)I(=BQGU@mZi>pa0 z)u+&v2NDlDL|HK+Je2XT9rP{!v1n?ON-{!tCq%rcVR8f*J$V?PP3AinICRRM&W#P=5jASLIGfvX zisgMYWd7=bdwrKQz+e!O6$PE}DD@H$B?+TZ-qS%%d+J%LmlLeaOmXMlDmlqV-`H_Z z9d1MU#@ru3G>v>{uQ_PGArtKFqpvTBP5IU#N6@2_EOZPH($nF^qLxX;c34_V?X8vl zJ&dmwo1jCKWJF1PL=A8OL8nJnNTER?<}v?eq)|(AnnvZeJZikJ0X-`%o`! z4l{;YlC_O6k@$Y?ON~-4ODdKmUl$MzJ_d%m@wv_4(F4JtVDWS@a=06}Nlz`a!|HaL zbm75wM*u;u;OQLUP1=rn!zy!|udOZzgk8zx=^vopZxi4nZkN9(Su zt&_pgK0F4Mawf*wR-96Gf4ZwR8{|`IlIbiJO~&O9GH|Hvflc$RGrR1dYoL$e!8YVZ ziEMm}?MQ)A?a{WrTFVjHoag$LN#-IoI*y*_-RyNZ6K1ZvKI`Pe2vc(#RHah#d=xYD29tb)S zv%}BuSU*9x6p>aAEw$+-qoRgH$3zCR;)k6wFp1Z9WO{0B5l@Y86t^7`ajnO?1=I z?#AtSe44T1>BR4GV3#+ErPIV>Nh%FDR-X3iy$V{H&6!)=xH`#NUZU&7%e-=C7;|QZ z*%xNWHOhq?vF!*&O~7UH5DYl5KBlIpPBLO~`v|(s$eRh`;V7wej)rFck!tX(6yh5! z-nqf`^Dn~_72s#4vby*+#nMIQwr$30_CXy_ch=ih)YIU4u!}mI#1f3p()rH&X zz%J{^XR|~@AES1vLxbJRGo~;;>PPzke<7S0UDr^jzr1iOEg3qUauFQ z%lPPqqk@3s^yBlnaGP{&6!V0(!jz7=P!Yd3yG79H5#2$2b|YqemTWvhGLfRv`_1Oc zpwVpBNF}o5@?|u=6`S2lz$2p5flg<{);7r5*E;qZZkw%Go=}@t)6@sPFax3}?Ul1Q zuxM0@1>&I?c~!%t_y`1?IING+IfIPZ9U$PcVl;$EL}Db88S0u7X&*YLlg(HhE&^7G z^=z3$C``66KwVS5)gMEp(WsD!rzzK(=w%mvj}5E&OLs(rW}`;6t|FjEQDpSO-giQ6 z)@jrmG&KQ(C}Gg+IM8iSzJ;nb$tKby;%O?HjMMICp!@MUr#ISg_&aE`Nu){@;?X$y zN)?rT+_De^3}!nnrxS;wC!Nm`k3=Y`K}?U(xqL25B9^5o7?90gJWeypeoHlK4HD~f z+`m7^azaPP$x%+67^cnk9A2OLQPI$}Cdp8QY@tF^wBz@C@VWN_VBbN|Avps0ye?cO zfvrN0&~}9KQRhB&*MQ{iz-u$2=yGHeaZ;%?)h-3eVECr)Hfp5e8S;fPn!$?Q?#1sG z5d@7!qfV(*q0!V3^mgnvGbYnx+=+q?i`R?OZb1=3WYQ@TsUpoj2M4oI(4K=nz8j^e z30RF@f&mA%$Jv*n@<4YjD26ccaFk>+Lql`y!@kt0RjZUsRa8wtC%SOhW#mVmTLp9m z8HeAG!z7`Loq+m7^M(!(YO_H$mLQQxQ$@jJ z576Ib!SI-KrorU+N_R80GO=)sVx@*^m%dkbHBF^bu28Mi_k0T`3wGP%Y#ITh(}m0L z#jaB+ma;_S87kE}n7_3iwHleoI+HhUaeqC7+;xW6e|d_Lwj9&b2XP%fi9O#zG8`pS ztfGnz0s#+Rm-5I)&w^f$}JzMc4JhIxv^mQ9^KVY)h4-YfqFwjCz`QY zO_)vkM>b;CixSp=AD7jHOoB{0MI@R-?ed^$Wr~?7tDy|#hQv^35U*WNW^0b6#TB;0 zDYB&+nqI=<@Y30Lh(mpy1l*RNK`*6)K`R*WlcGVhOe(y^)=r#)-j3Ijq1IYFKQRr8 z#RA!E5mhH5o9)<568gs}uTDlb+VRo3B@d-m^Cy61mSUR zp*s0&ig+wVwW-Ho?xE9f#3Vm&R+EOR*2tvu6pK}m92jjboF?64$57B4F`DeyEfQpF z6jCX2^(JnO$7H_l|6Me-NuydOpG~s6Hp{K6cbVHMV)b<~G`82Y^~>7|qP2rV!~OKF z?s7N0&dlv=c&#c&hq`fFjTnRml|q{M&NA0;&a$$b$Lt9*c;q+(Ug^6TN(Tm&M!iBN zU7*^~(3xF0tR_rPICKl53%k{f*{GvdDv-}+C^sHBil64mjS7X(3^%XcWoom4qvr&# zymp3uzlBWkMH0&fl~R#JJdY;mkjxJ3W*PZ$yRaZ4DpuSM6OuuokWP{>6sTzYC{19s zYLe}xS#I83BCEG?^zbpp2HLS1zZI;}i^wKBk_jH9ML)(7)}WZru(=kc)&!%)L%?Ih zdSDwzX{gN_`AnW-u>zt6qixSg{kZstpjR-O9XPELLcUHhohDyz($L_0{Z~2zqQ%eP zNI!>`Ho3jC%hK%&eAc03tS^YqVL>)LxMdhx<<8AX?yqK$?LK-BkJ1;gVSMf^a}B7G zN#!V28t4=YR;vw*tbfdROaOxoo7IfXBGSxN$R!h$8V#EJ*(-D+dP@(ZWBshha?FMn zxOd|V+{V+4_O;`-8_{bGO1T8PYqMOtwZLYyf}>-Mp|QjCIKO-^JqFo?T{2k-BAqIt0tT}iyIDbboM`C`7-Sm`yAeea zNM+LG^LZ-!SrdRDS@CuBa{NdaQ=u7ROEciXN>|A)gAfxj4zS$sMva zk+wtQ9PV$!^`$6c z`UVFW>RaQ+MvUcqm-#3tacr;?ufvR@heoYHGPK6zt^3?vP9d6I^o<{*Kj?U(UGgx^ z;tmUwGt93g(EA4%J#v(xcIRFnoCA#pR7s_Bl&cN&iVeHff<=1V-Yy`BHtaStHnV|7 zp-ldP?yCFLU4yNk(Xl>O!dX^#=DBm-gVk_?(Y|(Eb_Km!ryqR z7#tg+%b`aQvXTbW`q8=p`9h6fp=Y#X^xnu7Ikl9L%B!P0FPbsdN$bL4uXT z`efY|6&nt_30c&UO{d8{m3{g3o~LQrgAC%w{G?8YK~eTf@o7!c$uy;M84c^+eCkDH zqX7vX>8Sj9vUiToW{c!=6*Pktqt%7mqaGq!wBdA^u$m0i%O!HDB&B9^AG*6YdAbL4`sK~m$IYpr z)1j9Y6w!bIm14d?CY`0JdC=D?l+r2U#TpGPSfnC53s<=}KgsO!HjzY*Vx@tm-%Doo zcl0tmc8oJ;PcYo=!T6mUvn`%CTET#y3=K`KQB3Tzxg8^`+3D)@Q(4$1bYKsOF9=$V zO0`0V2hABDg&-I(h(;V%2|>_kmI{=rRce4~Uk?->Yy^)NOifd%6(Vdb z&#}0fplPttF@Bc8HXGK$^Hwi?Z^J7T%9Ja01W7@$STXA!XR-?*$VjpolgWUfmZ{}) zJKh*KrD3VKVGc&bGx>TZ4DUr*>*;?Bqk}4y29Ol(yr#XN6Fm1N4OET$2Cw=25 zd8JUHab=3o+8sVBMA?|{#_Kd8(x8+}5!=~dWiyH9>gDvr8GdB$DB&VuW)l_hl-__S6+IV zGh=O7ENI>s8q{j^HmT8M3V)hBtAZKLeOC_7_pco^ag=Ou|TO(p{j!Qna{FK zvf&kGCuf-4u3+yv&ao4R>Gawj-E8cu0Oey9idsI-*2)4`rXnFSS%tstx7GQC*Ro9x$j>SI`pE0?y(b`&y}cs zai7)jJ>L1Z94iBRSvZOTYULcU?RC~RqhysfPMti>tLG-@beW&ShP8X1mXhxP03ZNK zL_t)}@_eyEt)`+=Oc+f@Wc}mzLIDILMxzn4QID3WQ^{s1*Bk7!s2u2BjGTUnOjV!oLjwftPe?9!(a{>zYGv|;DgdIzicyxHu#fA|8;qDu3Ils#wx2N)6r61XocQHy>}H$HZ$+58@-eBMWqLcjSWE`Adinoj@4cVoIP)~WPulXn zs;k-?G(6z}f}ppvyL0PK?(RbRMIq_$QYfUj2q{9VyN$b@9S(;a4h;xz8$frXy{UHP zZQ55qWPvbk!7*fG_(U**fzHax$~W_Qzy6`Rk!OB-hQ+E*&*9fN|L!GT8_W>yRI>`( z#%>!}j*DqjS)07dr;By+i_0vn*JznG0#I~6(PS3`qenS;`W&yHJ4SCROyDQib@RuA z5GJi=i$>Ez(tP+rA;QWI!3ar1)j~wV8ZvFHMxDB4WA7yyfP|t)={s_Yw?3$0eszn< z{C)oG|65`1$Piu0Fab?qx9hAg%`h{!N>R^o_N_C#|K3@KGLbz96$`*-b^Ho<9?Xz$ z`Z;js1gB06lM3s9U;)a0fIx^AwOSj)6es~tA7f|U4H5|W2?kU|(V|@~)3hBN_7X^t zk<>ItFI-}y;UHfhXa4Rt{HnOfN_=)Jjiyw~W8<7;n7&9&esG_&x6`s!A~A zM^z<6vrM^Cr`~kgQrtm+-D=V@O)LSX(WcdEdwcDx2w`CuEowE>>!1rq32HmomnbM| zfN;o%s!G_6D$Qn-_MYrZ37_9bFz7>;T!dAiRBn6X>+0r;DB(Jo%_c3&#&KPm^*U|C zd_JJLZ4umGD!e3Yv(cj2dcwP5LObxTgpQ^KiG(y{VPVzl)GY@a*i8vSl4Se=KR&;X zB-%6^HOf^B5?c#?IYt|^*`nnNEZe5lXkyy-GsRv4r(I%c{0>*XyT?+~&)|iNeDc;I zG7%l8{+GDgF2Ze6s~MPA?PVQ-VKNR1Op19(xzRl(z4w>*t_1ywQxLy zrpmaj29-*kdefmRx_O4ba2@Pclcs55BQT9N%|-*qb+Jv8R<%amvT=aI%x$hbZd2N5 z6Uhv5V%U#{gHbQBvb4y;gPY`+*C;du(l6fNXkQHfPtW=I8PDM7WWbLEAzaL6nWeco zHkvB&!6AksH73V@np1uMvS4A`25r;zL^yRFUEZn5PDW95`~ekN5(vw{w5&g#(J2IG zqsa23TU@_(lc@qka))^P!}IjVgBU-#1iJvv1ZTOey1ny#bEJ7uzER8>RQR3um6 zv|AW1{NM@mc8%ifRsQM!_!Z-8Rob1k&_Z!~hmUaaoey~D&9jW81JBL&mSmM!_aV+* z61Y~IUw?UriCf7nQ!X>`j^6)vu8U>FXr3$o9T zrmDNN0IKM^j;1PL+t`MQ<-W{BUl*%cWNG3SzrXy5rACnBADrin3&+U@6cGFEe%si# zMXTk_q*i=>bVb==W~PiRtN1!?)50*YEQ^%!wBtyC69s)D_6`r$Z8WxuAA}cDY&xcRiX%ClC zRUKVdkc5kCv}ijn_O{1A4@p)Dq(?b@QDB>GTED%{y?d9LzVq$(PM83YR3hmfj+{Hq zTOYi~>CqHn-^-5Y`g6b=0cNxvY)2rg8k(l>QfaNAYbv^~A{-m1-Ntmq9+Lq864Acb zIDg5-YB%}KSN9mdHqV{QZs)HckWlmh$?jp!o_m{j-Z;V0{_soHle%`BR(YA*U;dUG zkCv&(ab7!pnv=&zi2L-P;9C5#;PKoO9S6nlM_1Gxcuqo=RD8OZOc!kf%QRn#=d@6o z?!%Y(@BY!`|NG}JxqNq;?Q3({fP$`T=$e9XZ0vUXf(-d6W!8Y2M zVlVctgraD4_4N=AEI_r&(!w&!D^>c!F#_^4%phE>W}VfkIr60%Ek_`Av;b^CvK`v3 zHn!s+oC?zqS|qwhIC}9t-g)yh!?_p%*`&HU!~JXD@Y^qMF|oYB)!+Y~bXS^m;uO8n zy$O^5j2{O-Cj)*I2wba0B|p#nnt?BOgaiEvlxqFQzObKx*V^W~F18~Ol7uWP$U9ao zc%yw(ML`naIu6cD1t)fbi_t8y@bDYH`1DhLe}5e{cbYTr{55}bI!Q#8S^uMa&t4#~ zO#`bl>SZgax*t^*2psIreL#|t)!pXXNyxH{qIfQWYuni354eMpg6a#C$Ykh}{Ineh z+p>{#KbquFFBe!_-5?d{A`$jI9oZmU%vOz3p+KSB#E~>Y@f0zij;?Dcct(%WHgMcF zrPU=C=9d`CMaX_Hy1IYhIySatVQ(X)hY+)|=-!mi;Li72dOIZJYd)kQEh8Q&A8I*X;;? zOGt`>Eblyf+T#@&Ns_$4r{i?);UDmvxel$hamF4@FurV(92wyCcg~WH24A`hM+gVo zsFR<##^;}Y&KEb9kdu9!|M@OaL4T(;91R5Tx&>dm`%To>072t`I# z)Lp7dB_!EByh0I!CyU$1Bd(dxaz`sH%pl3MAp}72Z~%c$~4zb0{mF5hX(4+7_-5FVS%% zu$mQ0#UjOO8&~lYN%%(@LJyO7KP;n78d*IiU-L={d-6V2pp?TW#uvB zSAWC*`JeAlaDxnb24fkWdIjW5fxfgpwRS|0b6%oaE?8H;JHvRo`G{>?T*fy~5WwCdjWpe zW`lBZgN;%HQz-bO38H}jx~`(h-Z_m{8%uJjt*@{+J4-$rq%R%DuWcnD{S=N_qcL}t zZ|*L!-q1Pp#xaf^86u+Y&OJY6JmFo-*?L8v@UEr`5Dtzb5UxP#tm$st_QamUb#ZMQ z*L^wOH5wH*3MEQ)1EKnfCj4FkUDsaV-6k8$^DHd&l8FUKcX(F|Mo13~aWETaxv<2{ z?d#m?&yq`=r7s@z3VU1|+iX%iAz$Ue)o&T?j}Zxsk_r2~#I9q}t{2Ep-{h;y z+&}o9f@)<6DFvu$dZd=8Z^rbT)T3MD>vt{TClMezztN~J z@$lw#zWQzoCv}7qm)_yR!E~qi?$ug(k9SS1ZC=u+yvz5z>$=a_ySpfcDT?gHC>#gZ z@pyMH^L7-9(=x7g^rj09H5C*2w&xyDGnt%A4OAJPzCKW=FI9-E7gcY0r^yw|`%ug`(V4TB8 z4$vJ*y!3tj8Gk^Vm<=ecC&MT z#-9#P+W+DCxs==C$t*VE6)Q`f&;LQ!AVApEi+Lt*f6Z54f5+{q3W1)JoO}BNKDcy% zup<8%CtrGP)hm;Cn8_EZ8k@}+S@F?(uLMT|Y%IhpmKjg;syNpj><<~2DHp;)`AO7kL-4T5sjS6yURaTjQ zJi*L*bBpzn2&V_>9~osNBYpo|1JGHk-PY6#(h2Wnc=q$VUYbp#FwfYvYuueHBj--= z)*B}|KAhau82)oYxE7VwS!SoES*bglg2%GrBbFOxWO$ISFkaWE4Bx*KVt1qN3I9lv z^!_0BY@lWja`E-| z`Nt1C@6EUbr}B zm8G%E{N~dyx$HB%$fbBOoOp629{LAsM+WMNV-t}r(-#?6~!Oy2)J|6DAxTKbT`{ooX- z!1f~p5iXWdWo708H!pv~=U?BaB!w9{_ckAWbcvG(lI$)O{ZoWXZDWzyi3##GdsARa zl2xKzgA5-yKrRAL3M7EeUa|9n3V7z2m*hCtppu{9_Sc{BfB)B;G}So$$KK@h>Ej$8 z$`K8y2&+MPb)LzwyIj3B$=J8QW^JuR>)(9Dxg*`gdT2e zk5nv(-{*~W(qdT-o_&j0GEPi)`F}otNW1u$hmU4Bc5sN~U}T?6Bk%Cs)Lo{QHmDc? z5JB(0o8M7MR>>ZEozd?sDhh7@z-hp7p}t@HZcy=SW`y-*$$AuxM2`xckj* z7RxQ<Kym|eDS^9GU4J{WyY`khF^bvod?S;qP@rX;PgpO92ulL5khiJYQ<${CmwL?#(gI5 z{Eq)r@Obx^@1G#;SCEt-@vZ}0dgB;##Tru^b6ox6S2Rj_P9Gm36Vbq|QOwVA@77%w zN;YyRM8vddOR`sR^l~@#$AxgHt}ieNqI5$`Q~!kq%KZ85`h zU-1I(?)43j^d#MbM|kUvX=XmXOJn6epZ`~z!tx1@kM&=?%};jp9EW;>D9`9Jcn;U@_N91+cjcGyqa_tR z+{4im$C#O0rZ%?1?7gq}zy9|smo6Nmzssxst`(Mf{9ugn`65+4MpxKi!-kky@&&BX7~9EF z|BN3Wui~4z58z_8>a^Nz8g-NW)EK2Xu#7sTibcbiXD;j~77fsy3jh29{kb72D6-nA zGVv-i>|F?32nWk@5JEyyRn$FH*=&C@7u#%5FD`QX>(9A-bBxC;ZG5@cIQQmzymkHv zLz&Q@IVdUsi~0MP`TXh>^JR0>5t={3C4GcstcNaLK~ufT6yZ2H9f3!&ZIZ;r?Npv4 zN#1CoKO~`|_z1+hIrLf@$8m8S3)5^(cRNSSIm#}>#z83e3IK&zomD0h!0*% z6W=!mk3+q%$k?}E@ay}lTR09fJtyAb?NC1>89$PwqID|ggl+FwIsN4Pj@_vcl@%0K z+gs;^aIjh>X763$`n`E7Qi@Y=UgGr80n#DuClyK)u0?Til53y;mYd7XO_d>$ z9VHi(H?`UCa2AAPP+pzm!Obgt{ml&?E>!VlMmc}!ZQgtHG(+hy+P3qDf65TJPK(9+ zm-*fG8K#Syc~12OIVTU1Nd!r2Pk9d4#d%WczwHlqaa?b&_@3u>sowkk%3O=)#x!@X z-Q@b6d762wL~yxZb9oxMVqku?of zmiAQ9D_oP->Rql}zQw)C4d^<~xpzO|-Lu2=q#^`-Dv}Ubxh%PC7nzub{V(5e@9{lu z1Y`7%jPUNE=$4~Igkxbe3M@?A~EqB*Fo-PG^AG-9t}LFJaZ@*I$h@H+GH7J%e;-5=47~ zNLrY9&k-)fM{to*^#I|Z?|GqTRVNTm(ld03(-)VxetnklYJ>dZ5^IGD_COeYUsUf1 zT*qK(>2Ef_`s2q3c-Wa@}Op5&Ysa{>#_%Jh*Y0 zo`D{6$uQZ-)*Xbd-K4TU%e7kzR9b@GQzHxw^bq&$ztr{f5VWeRj9>qn&u`CBX>aD; z%;-7Z)N=G^Qs~n2yt{ieKjp@96Y~Y$ReeE*&wYYF z*-Iwub$4iLCt+vXd$2E^O}x8jzg6}T?>@k(ci(5d(&p;K3WfY6S4vBaT@9eCGBR#w ztZ0fur@JUUyiKE3#P#{mcI_5_6(Mk)HjDQz^ToAkW=orS*B6d)^52Y*OZrJFo_(o$ zg!iR46HtJ#>LfS~r7T2~T6P<43!W-RYhcJJf`^*tXYAfGne^d*@w{k@Wpb=C zAaJZErKN{l{o*rzd-Xm`Rh7)>1>X7aBi=eSL{}`ZB?Lq=9~{K4lP!gM-K zA}rA?Z?L#2vF9*i$={!o^XuCXyQ&g9e*YjusoXOD8~>~V&A;`pB!F_MJp3lU5E zIeh*M3$wFKO{}oAIK}PzbDTdAB^ua2wMVwurdBSowz|GW8^4UNuTIl&@$RP&zt3~F zoK_Q~Gf!|^2$Qy9Vp=Y;uA})qV{tcMOgK$y>l1wQyX#D^TO^OY!RseS$wf3=%jEkf zPZ*e{)wynguq|xMz%YC$vW%jrfAUH{A-uWcm12Rl)jH;L?fDW~piQLe1w8 zfC55zvmYIM2VD$-B8y6YfA0!~ld)g};t4(oXhDVdLELQ|0 z#}9JhowFS1i9S=HDWRx-!ig*gPMoA#T;bNWIr1y>JepYG;;~+mp+9{<+Op8W(k?G|RI7+^d5$#qN&!^C!6WWOJM*O~NBud7*FV{USi@#Pw>n&rfW zvm84zL|62g`>kmBLUFnVe4My&iplXM@{iVd@Zd2QPakBoJBTK$X#U7{dWp|KMhnJB z^&j9+SAf|@jYhddrB=rf>=TFA3j`YV3dQveRyVfbIXytRVd3R1HFTd3pDshq#%{N0 z3kYw!rVh4a&}`YbNa%h)eszbAnrE-fu_!OkGchsEV%eqd%m`;Lp5|a*`nh*pR(*ux zT?`+8jap%m+gE3qTU}s$Vx9}f`pHD}EjU47H7cynPBFGz!4Po|ol#4Co- zLPUFx^7h|`=o+}m^&9tiIJLyu`U__=g%{eYcc-WD&w|5*M0c?{-0E5 z>F#i`jHmXcVLxwQs=g4hYJ;{VK=Sl<{C*W&f!*>1U3auEU5j?x^7MNA0d!s8Bky*; zKae1I@EpJV_epxMU*+bVM?9WiV?AF+_612~dKf)^g43suk(L+u{po7=Js48ufnIsxx}lsIrLgL<{Z z`q~DS_GaEyGF2LejSw<&hj$ePT+_fXO{{G*cCN>}Z4<+^k+mRNAb@X=iFE);Qi=B* z;o?U@QrRAE+`PwwsU_A5t856BNHW9F!DE~}b%dkCIyW~a8FK_apPyhT==pN8g3qUY zpAhf|{GPt!*58PtM~H-j_D{M59510S!@Z(yCRdyMmY^ZCOkvTmz$Bqu#J^6%Ai3PE_4}F6~Q0 z)(NM2=pXE-J9>}tW{vgLHL9jX8d%S-QK~j^^aROthIAr;z-rG?001BWNkllNyTf#E`AyC3V;sn=VyS`LaoNH7v5sP0~U=Qc}}r|xp|@hYozm+IIz{L}gv zzt&$EnI;@s^)jmq>zJ-f{?5PhA6KvPuh9^>gJ*d2-FG?G6Z)YyXHSsT0DZ^briV+G13H;!9 z!o@UdEKJU`yi&#q=IH4inZPUJRoK!Z0UsFH|5Qzry=?YG@Nwe9&aJI_^xZpOa z*PGOv7Lp#uA5Rj}b`!sZCqb#@nI)=C14+-&l}(dLzEJ)BvJ<>%cogf;JS*=&u z$gk3H4iZG>*{S4KZGrpWeZ{Z-;&zb4cMK%gmEIC9h*+oxg2c8SWh^Mo3$8~0kZ7S;6?qk0VVP*x2=DyE|HQ%fHg_q4gg=rXl})273J@R~ z3!-Z>Zlg}K)xvPLt59`8G^p2G)SEW4?jsOO5LEZl!6R_&HcQjXRGTJ}uZON|nsj_? zp?FDA@kP7HrsG5cGV8Sp8!M~SolycE-j!q@@!SDUhLZFjKF9mjIxWKiNk;Vr2uEY2 z(n;Kn8{9YBG%Z0e93~Qpcmb__0!i}Gedq%J_`mh?ZgUI!QdS8ibL4V5vJ8HIkXY2` zby?IaGz<&Ng)Qrogo9%>sMXq-mW!Hr8Qy(zfij97Av1W4OVKV4oqn52y@hGJAglNS zA)<){$(YW@qe)tA6C0UaI!Q1X*oR{z|4_&%TA1U%_;;kvHMZbg2}RY2_4JSltH`!S zI2<4p)Dfkpyqnn0j}``&QS*3L_IdWDuCn(Dpb|(bfmoIUCn99}4|49E3XQgxoKRGq zKsZ7onIa-DbAP%)sb!-ib>fK_IyT1Q18zQ?XMVkk+nVO`zx+ogzw(~XXII;?nr!4( zST`)3#WBA4rveYY2oVS+x$w(>$HhZk><`UZg?P_l-urLFX4|SNq41C z6&WG?L}NjGnvBz^(`>cbVj5`&0z`vay+xyGBl`jbVsU~mscj>x0TQ_pPDU~e96rnY z)jCbnK?oVm?HV=Dkiog z@NE^fv75AN8!VL!99JfqOc4!-UUIyXz%}cv&fMaw&wk6-x2ITjdbse(U-8bHXE|{o zM?COj$_`3^N^0ORsezr3lO%y_swC5KB9QODcVv`Puk{n$Znso5uk%Bb5r%_hn3%2$I2bJh z%W{w;1y%7J{q29MjG`#0stk^UZMHEx;}G^oGC(E}P0=4o(ZAzy-hEVcKgo2AfG#6S z>ueMo)Y~rUZ7fZvwMMC2quO=}b~(;#-42AqbY&CBZXUBypjc_rG6j*X zBK(elQ7^Gps$8`CXmGn$ox;KxzyH;* z`OPbKUw@MiKYE)}qrJp~9U;zr4oTKY4jdu5E6;&rsKk>oqR}AIe2sc_ot3gn ze_Gj+1cce7R#|7gVt^VX-jyMu@2y>42-mBcH#=Sg%kim#H)zdc#`;^8~o<5~XsLQr$)m2S{ae1hw6S zo4pSUVbf}v-smz_K~)vhZM$M5kY&`4c$;uK0+&yG8wqc`O>>!>zyB@2{o*Qj=bOZa zPVw%??{n$QQHHuAsQarFbsNY86Iq7iS%!ByOp=fg_=6$RnHUOSH`ggu8Z-<+EVvcV zS(uFyg>s#?DTt&p#A8wRMoTWXZDSZ-S0=KKrb=uZ?~}Y)_)15(-L(u%>v<7x(Gj#wmWQ}CsArgJN94CQmsl?(D63H;~T$M(3gM7)M zKeM$9DXa#~$|`GR6QM+ircy+FTL*tPeO5S_rpI$a@;dy~U3gBGJ9d~5o{*#MY&~eq zX;Le%FgIVqv|UnzqjaSb1YZeHSV9lR=spnJ6YmP4k;)_q1vK13iBgAma{+Dh{_uo% zOI1n@2R#}jnavW^v_0^yi|bl68U~K*B54YWDsP#9eR_#;b^d;POnQA^yv0>mSA-cO0L?gZ* z@=g035|XTw>OVqqN2jY}UkZ&xGDbWRLSCrTsBW-QcIZp1TicgbgGObI^@<58bB(hsyUt_UAA-_V=mIwx-WYRHwnuOb|Qfr&E9S66v!CbY#_TF3P zovxQyd|YM`g+Q!}?CXEWsS&YHk^vIFaDv{033_)qPLjZtbW-UALBEPyDpD+0s5TvP zesy!FjBs#U1=fpo%1sx4Izlp&A-D%WdegVd8vaOvY&gMIOX{>s6la%NtJG<^KDy%x zvRxr$Swhx*1mkfMew{_pqFk&{uQw2$I^?Ev3CF-_nOK&K?AOtKKD2$syMK9jB}|}K z0}^^DLC=wMgo7EP!Jm}^emqD76G_rN-NdyOTD5g%=Qn5`&Jt8N2jtCqnZn{c^Hmd9 zj*;ull89}d>AzD9#lh3nEPuCcl>&ql*ROT-u$>?WWon~fMDHqGB~ z%qFXk@AB2>*O;osIq~+#bdU5h6y7={FYGq$W}RBo21!BF^-krc*9xbqGOpdG)oRi* zx0_xq5KfC`t4*WjAjy6-e_+pZaeq44yQr_G`$=|plMIieE*F`d&9kz8kby{Si{I>0 znS0FAT9KNqkVzrilm6pi&q-T}KqOArP(Nwy0j<^s^YiPJjtr3r1YbCZ zz-l)rEHAQDY+wkTLj&EUQ?V@q?wjx7RuHyDtGLGEYKd|ix-uEE+4SCKT)S;bOXFPq z-Ix64n@6lT3C_LuF(1Bvk<$me3G4gosoxEI6)=?*l}Ij2CX*l}7pWBUJet_xWGsWG zyqL@sv?~Qx=jK^!xTwh({R7(R2+>lfh}zZnvm4UD)p4I|l7`gId!; zAfxC$bVdF%wdTKsSU56?o*vSP5WcxpR##S7Ua4|06+nFeit==unio3`m9sVchPkN)I+7dCdQ zz@w{Q^4VwKaet{zV)P6j{ME<2b@m|LG5HyKT#+%B-Vutu@e zqB|JeB51eOntBN@O;eGCi))mrH7!gVw#+677u&4U zXqi~HK#BO!H5E;AsckGV^WZMi8#Y>`hht}s(w7Qv>BI`FNwb`1uF%GCC1TMikx=jl zb%Xw>*yG+M$tvND*GUsm3e+pBJRD!=WULF{CXFOPyIf#xc82A;jT{ft)0-t6^li2i zw&XblO?$#~2JKdZ=JutN;F=gllWN08prh(K`Zk3mPPTGesozv5-zscqFSj?tu&Cr8Ip+@ z5&w%%mcX^k%s-wZzgEQwWXR@v$R+&yPbB&!>`Q+%L05k_Y4tv}R)P72HHwD^$Oc23 z&SABi6qXiQF4kzfI-~tLy1L?fk1vL)k6%x2<^B`*&eCDHqGs8V2}dBocAL zz8AafZHz{VnMZT16l&OkG`a2``ZGRc31mG$FqLI69bs~%N?~!1{OTIDLkXgr9zz$S zvdVg~Lapr(%*KetqWEQL|19TUAbw5;{A3{G4<#8q@y3sRAwL7qA}O-HLkuOxc-UBH z=HWx;&kPaqNAW*H*urj7T%Kcce3tdLi<%r}cpyV6_O$9jxL#Y8VLC{X7nJe3K%N}o z&@L}Ae)Ai?zBW$5O>_ACyZrqx-{nwO7~ej8OC?#spBbRPH%l%w$NWZ~N4M{DZtwy@ zJ^b9J=Nc83XJ&Z#aFMFe=}Pxz%)Q6>ffA#%whyrE3>I>EVHn%#7e_PNd}0gQiN3%8I43bK{(_?TC1_Xw!+GKo#8~l zt2%oY!o?`Au(noUy82+-%VZ(XgX_1+A9{yDHTYa7nJ}xYEzI)p!2)GhC7bGIbSRDgnP9$fZEVxR zv>lKYG|h*uc|4~mI(6m6?Sy$Kolr3Vj*X4GJsEtkzBBu%B2eMcAkR zBwO=?U4!&@r%66qVQpcC>8W{+4<_h;c7VHUIm}L?KEM2<693~v4a7+F4RfM9%;oha z3saNKE*@eqGe}r}W>0o48pUNEKb$6CYT<^uIWXK!Px@J&b8&1F!*X!l7kN%55Q>mU zM$i>Ov%SRJ{05bw9Ep@~)3fe6Ce_tNR!eo-u0$lAAsz|ilU&NBCB`p*%740EK+7KG zV>QCRdE?;bj!a?ED6KMc{}GRiEi3}0yR)Q|(Wi-`R}7LY<4fk~>F*;OonoTA%7bgS zSUU7Bem#uuS)16Zv9>tF{W~*MT!nP9hv9(?A^%fDR=75{Wno$#M`fG>H$l4vYS zEE+_fuTmnwXs`89^ao}W^seI7GWqi#F3#G zK5Yx$b-jI2)AXmjtNO_HrwQCHU{}iImseTcXp-p(p==6(Su{76$*-5Fv>p7J2#Iux zpe!R}Q7tcW|ME>9%&egHo#p(6)0`NJJ@ae`glkZqzsLQD^W;kw(VjsDM+V7+_tMF* zf1!mFB>G1;P`5QQhYm5)ogn&yTU`Hg zASo*TbT7SqePkmuOqN!7aQ!yR2j9m3f*&oc8mkL4jNP51B2>ClJ&X*d3HqM;X2P{P z_NDujceT!&BLq&n#KQO;Zry%NRqtZt#3kN8*ZV@jkV~^L%fkngjLnqMBVF{49-=oD z!tW2FcAw%GfB)JJi2wjWt1`)#|722F*r1ge=G^;#$KSm%h+maaH4Ryk{`7@hKLR94 zCY&3gKX;et#2U-flT1w=-F6PLf0M z6OMIr^k9zfrdQcmonmrglG($(yw($b=6x5qc7y!XW9F9&)NGA`Y!}(Cq&IH)6FF}JQ? zjn`j4L2nprqk;XRR_`;A6dh;hUH8X-1zV152B-+p(K8{kOo$g#9{-EIg5)@(K^HUgP@hDT+d+JJZeZa1SA$ z2FP>`kJ8^g&ZGHhmZlzY`}!c6zzK$ONrHYA8G&QAs8`mRzIu!Mgj%3?x*vC&sIAXsu6k|8bsT($YuDDU_)<4O}@wG!`Kq-Ss9T z>^f^R54e8iE{_Wq;oh@+{ELeWWdcZMlZLtNul45tYU;ic1A8e*3X(s^fy1L58J}Y6 z>JqazKjU|!2`;@hNM9<9PnEEZ28D%tT>0)A*TxITp*{uxlQ(O3dEA!<}0b ztlBckWR{TweZ)fkpJeBf9_{1s(NP{wF0eW|&Al7nkxB-5>v%u0kPjIfqgG&T_6}cM z9%FK`L8SXQhfbd6P+I+dbe3>!?D8CAT;Rsx~>OkEm(en?t`c=iDAy?c=HUp=BYeUB?wGDL$i zhkFx*d@7P_(k!p==;md>Zdz8O?kD*y{p$5P6zQH?GTQ{5y>{c9`_e9gCY5zO;7ltlx$6#*lgBEC6EZ}&a!j_)G+ zil}UAr=dKG_pyv&Be}=M@*-2KhseGtMO6(nm4{Iz0Z~+ml$26cRZ4U|PHcUi!R`SX z@)gSSgZSJkvY0D0oH~xPIyTDv!D%)%2ow}jQ&UDX;CXKG;7mG2Ja$0Zu(9QQiVEC# zo_nDBhk$@PR7GQREmhOY3@lAEeD5v=d2T*xDkbD|BUn0_<2`nkhWVy@g1L2INEeQx%WRo$LhVJoA{{nh`jEpJZQQ9a8`%pv+ zBa`4Lwod=QentPx76~~_M@Kttjg|O+vgqa6Ku|(Nit4#>wU)(i=GdJbq^CDRz%9^N z8pi9A5v(l9_$HGB-E{K7J0RuG*lK4_2ukK z0fR(roynftd^NjA@tS}nSqL39krvoQ25nN*6T`snyTK~hi^8TpLcmsRx*G}TS9)W6Qsz@PcH zCXCTpL)l~YWqf0To}PR3Oza~0N~mgTrJ*#0TY2=J^~4@4iwn$e93%VlD6VRxsXTbH zgVDw`Q|v8GbMMDHEb0*&cP*mfkEt#U;#DLtG9-`onCbhGp8K<`q$NsP8@OJ z5cH`Jb$5MsfIr`zVr4f=sIrBo)>dkx(!-r>wq;=KFETp4PAp;I&8wigwvN(>a?+<3 zwv}LMY=9s7mpKlslQaaBYps;!1#rtYdN#@K>I?(7d+49tA}L3?+|fo$V;SCu2C9rV zSU~ILbJPwmbG*FA`2BvOkqDj}%@hPZF_t{!2CVK9?y zObu{*!}VgrRSh(?n5<|;GelT5ECa23?hb)}2*E#-Kn z$Bt04433ru_|xzEnBLMT>-uYc=Px8bpdg;iAv$;hzSGB@H@$>&G9C{KR5_ zjcIBeAE(GFK=WK|n{0fOrO9EYSK?$Xk$`HkHF1xg74^m0&ytESuacIA zDvF~|AA@vO5CDaO+7>!5Z?n90%=pF%Km7AQvNP96U1cF5k3jlhn}x|qrsp?Fx}wy! zU*PhEMhYJbTG_TmI<~^dov-+P&kAaB6W9KxnC9|e&S8>NJcYHK@9Jc0_lUuTEv9<@ zz~5)LIoD7@alRk740`&Q-PL(UhsT&&;hx8o001BWNkl*jLyqfxPGY)ufU_D zXH1>!<~ZN{%XbVd9+Ka9g)jcDnu36WDhauFSbm<%mlilm4KcbtOYb*2$=xNI>&hsM z`j9b69_+BbIK#-$6!SYe(aKiNcU`2jHh?4wn5iT7mL?dOT4V26LoHQEA8az#{XNst zi%T+y-h8TR>S?UXI|GGcO!s_CYJVd)Cx<*pW`dp71;)o_ zS&JD&Dw_HD(=O^tqfgXDG1CWZO!e}g|GA&FScaD0g!r95e6kn-vOk~7rgMCJX^Z%e zW5j2B_|qSb*j#R+uDpPNM+PI!acq;NnQ;b&mWUf(Dw?{udcL00yj-DUSGb7kj*qxJ z8>44@jm`1z`F~Sev@}*zQ543j3h1c=HkTKfn_XmaGle@^!TB4vINw}F{?Dqs`Mx0l zGSTunIxlsyv6p0UVU63r{|91=&D2&D67kApk9Js^nPy^og##%_O>VGUa zZ==Q6nCktS|NEOcJf%%s{31e4aR@~c5JU-2K^1N1&$GI5z`*<-Gkt&J|4Q!A)mlwa z)Q3kFFtQ1D*A|!@n_zT$A2nP`)A=iOG?ozdJ#P-Q$Y#?V9i}kM+;N0KpYmSryge-> z#YaW+IWDbkv41?m=JWtxrQ@u&Hd0*_LNrqx?5r|BHN*7M9)!y|fB6bmyK0`)T|+0c zImVy=<$Fd~5)`%F;@92^3PW-(OI23!RbAxD#Wmu`_nFz5=I)<04z^oqt}V;i*0w?N zV28DZ8AgUDS==+ot7_xI#V*cO`;kNu1UG?5C0*CfF|`$EYHN<(?@W$%muapp#48)5 zPwsJlbctj9)U;pX`o&i2id<);e#?uk}?*X6T*VWb*ExNyXM^s;i(NnwQH++u(zl~Wj$Px@3r@>J1& zp_Rq$L+&rl)BBAr|!bXT)WspZNZZ@JtTL4a9tOl z-B?C5N0`}};qKRI;#>1HR^}5>EzyK4f_OZJYw&2Ood@5$CG&@F-u@B@&gaE%VkdiO&6}_&MLh#%+l^IGyOlZFm(6P_E_7*GEEFiAW%|IL+2HK z_30%l!|J2V_cMy9c!`uXbL&?rGN!=b6MRLroV$99n^(_K zlka}wTwdF@F|`y&2ZzM=Gx!o|G{ZiNrz<^$fT;M0R9)iZPmeK#dyLL)u{trp`t(pP z=!=bITG*nC!kT(IuYbaga}^Z$pVAe}L`$cL$K%9~4UUspbn~ZPpp9i_Nu{&sx`m*+ zak*U2oKgAARklUyFwWM>I{V2C*^I@`+#p|Vj3WMI;nkC0>he?6a*IGDpQ1Cn7yuyP z3YOD!{t92DGT7e@vl`!I;@&os10tf3dyl4Rqqrk9v~_a*vzv6(7U6$<@zA!h4UKf- znEm|&RQEB->|?1kf{5bDqyGFye3CUlz0c&zJ`4AMWMx!FI@ua*+ZL8-V4C16sHD05 z3ZHy@k-DPL6UTYHO9-NZKfjg>SJR}kI(P5Sv$?ZC?>Eczizfvytz1EHB~nhyh3kBB z^CHb9z9)A9**2D*;rQ^7*nS-8D49E(`hl*BL7W7tYRL(}VQPTyy1ZsbXw6IAl5o9VoEiyNJ_6b7Fv zN@tnq=@bVChwQ~t940li$8=7RJmgn2bM*^@WL9TrahLtIN$zaS&?`x~8Y{MiWtmu} zfvtq8u5aPW#~*W{v6Rrs7!;KNd6n(l{QL+@?qg_rgM+mx`Zi`6c({AV#SWD+R`++A>W?u!_(AnZ>SU6~#P$#Hd5=kE^ha~QAfmXV)U;pXR$4=F4KltQV|DZ{o0EMHbq?FY zG!0A()VvDnn!5Pa=T~VgjpBapxH8bS45^fcg@EMthY@N}&n@sdRrMsqyg+yL;E0=D5!i|sGDDpih5HI2m=L@2)d) zcZ<+Gp8$Ri0Xz5-1y`M7n;lPtM6Mquh&69QUgS*y7=^qV+^s6vH5M*CkNS> z8Gg#XRLQSy;QaMZxY1cnVc<#K&Doa;;`;~0;#rQ8xjHM49;FZ{sHElEExz15pm%ng z-Sru|H|M!0PCmYx~%h`iXrRC+j~ZnKd5sxdbG|OMY!Tm#)P*&e{yk z@31!B!_G`UqR7cSYGDa7`PJ=oT)xg{H(DqPsAsG`(l3i3xd;{2bLD1Ecl$<{*jb;U zdm}e?;6%r45qEwit=B%|hTc?N0Eae{BDKEk0-W~ zkQ5i8a1@(djTOr>uwHW3j9`fvrj7LuM^FVxC0y3Rl`rxrs;Xn4e}t*|HMV2NqzyY) z-M+k*){gUZbhJ`a6vqGbI}`*2MaAp$6N!fKg?vwCGz$o#iYHn{*JmNh8(Ntf9cE;5 zk+rQDhlw;<17w$nyu2bRYMW^9I7eG^H3cCr?#GJp2x87Ty7YOJvf5_GN5`0$S!87+ z#!)hZg@EGq6Ur~7vaXqP9qqK#S5g@Dzq5h1Q$-L_y%9>AZ}4A4ifI@bVetM0^Q$`? zB(m6&i$Goh#Z~oO{OBXv>MJPC_v3o%JZ?b{kX&8@p&-$;n~>j)D*v3KqW}Vutl|p> zh(<$%d@718JX4_ZokI|j-4PluenzOUocf_*hR0@E+1lqQt%KqrQdmNL%Q-sFchFj2 zPJYn+Of3LGlu+DWB9SnbVi54UUTlyH7Lwv35DJhdM+kb|yvlL^HUhG$5)22i(*^*R zX}omHrzjd2hWSqG)2ShYErJ9cOZOh4t-y zj#6nXL|ncg`2{6Z)wgi2qm8E8GV()S9+ZHvPiocpg8`z3a&okRg`vOvfH=`Gu-?U^ z{Z1P}LXiE`od2A^&99(#c$ndl8J4zU93^#ZStVRhLQPW}=Pz{9T3#vX@>%!$sq2u8~&tE!{* zTnFdc>M6I>QFr0zp9bcnL==Ji!PaMf#v?dw_uK3Q|;mkza=jscsly@cuY6 zOPlN+rm#g7U$l_oidxQHyhLYnEfs|!+|TH4uBMbf6eJoI2?c!5>aL&=EpO%KZ}O>b zYGG`2oay;BHg@7q>TYQ%)%7iObhgo0Q%ZjDk?uk+2<*+PP=7M9c8d6}-x25QR-9vZG-`CEl;j2Qs?Q$PWZO2Tp<@_2`eSpbsJQScE_@IEU>Oe+ z=>%KCFh3ysvZRrVpGGLItfBwjFcWjDIr~zxP<>$vOCRZOeR&=}^;vBbBo&W8Kr|A< z8}jFl>wCfml~B9|G+q9jKz=FJgZCMlm}g_>kfdgU;w2m{qNeE_U0oftHk6U~)cAZ= z1X04}^Ad`La0Pw1Rq5UL-A)Yw*&U>){xW|ZDx&5@cW0Nk*gHyNODeu-5oOg4oa^f1 zd`oWZxSy_FCv%d_?sxD)eQ^{jW990%FaQOtSR8~MJX$-r1ktI zI@=qlEz862Rz8?seV-9*`$JIDH%H5A{2%|@|4u=1Az%FVOa9MKFOuBb#2?A$`hW93 zP|++Fl(2$rHic-=O~w|1*W3dJtVA z`PH4A|NOs4l$1C8<)?^kVQ6WRoV`_4oJ|ug9D*gdyF-A$;O-FIgF6I=;O>w>kinhc z!6mp$a2VX3!QI{UJm2}(xqGkvUUT!THEX21tE;+d?_FTHlE{#Xbh=dREI81zJ=OS7(sdoM!_u^3?s(H>R51>Ds&6 zbYc|ARCHFYV@;5YlPenhju4XSLJP0*B_3Db9$mN+G36-V>fBU2xo>I;Ys2xk6{j~6 z%Q8b27vfliq>JRAur9a!81g7Hl{k2Kq{YQy?HixyPH(uYsv~Wcv{VUeTH+YJ8Ny|1 z!l6ffM>m_A*#_T!>BH>0ZpJPcBlXlcAzp#u{KokYV}ux;JUdmWf+(9l1_!|fW$obs z&5rr06E^Qz$DAPdUN^FEANx+|u+W4-WP~yO;69U?xjCwE%L$=IMFk;wsyK?wv0TFD zNG7rP*jen%EAOvae_gnN>D%9r?a7Y@j%s-7ZFv20AB@6^I7N}y6TvAy**K?W!Dg?) za^XDXcY1ny9|A>HR3=%@saD?&iw@_@(5mIL>!3_Sq(l?V)PZ$bi-DGJBgG3v*%_Oo zEv_iXPAQnB#C+ooUtvF&b~F1-Cb1G*=L1O?4}e9~K5_-PJS z1k;Y9c&ot)gES@TyE$W&vh=0MmGhzFM_y$U8)_*wve7Zfd;;kiFCZ z&M}uQQZ-{&KB|Z;qvy*WI_fGAT)XA7X7%RxVpraVv?z`h#hT+*uEmUR4b573jm@SN zR@c`{@{-UJptLWx`p^x|$_@+8R42fpVfJdxtf+7Pc*)}ovED+%!}#c(+!!AWWvS>d(c&{GYyBEcYER?YB`1T{;qCNlo*z^Nc&9F2tN$=SpF3j568XaE5 zHhEG8AqybI)aaEZvJBIinP-3c~S zwd>?|3%ssc2Di^fn+}d@iKy!GtZ8PL-q(H)Ju1 zD$tlNfu*93PgY5uJ)ZP;>%4{=N~_E5hlM@Os&GV;l@I}bc=i{xzac!~s^e^Y%YMUT zO8BHZCwoQrhW+#39FOl$w4$Fti;b?0Paguq%Dg`o8@`X5ZvuKo$9SK=NhoMvz=6F3 z|Je_C3N*i@X}!Ypu`PdLCKnM{rVIs$mT#?Jg31a2{yM?Z|``EVR* z7Z>|khecl0{VA-;uafna1cQcVR-XRQ4>c1T!@$2A9(b|5^vi@JS8jT9WcuJ^nyWit z%o0C8tYuJ8c~jvewRI;2h8_ z{NqxK=<8IE!`=-hMggKr`gGU0Bu1P%i`cCExtp!YtTgNR9g@prx}SjZn!Fq00L#bN zx57sLh%k0$2aI_eR8`CaTsJKY8k`h-AZI<=qAqa(_rd2qZ{D@nc1=jz(9y$}Kp?8d zZ(kyz8)$mjn4ggc{y9wt=YHgH$_1cgTgl@tF)N+lDZO2ATM(A-c^)eCtg7~hzU9L< zE~ckQX5+MYywk&%Cd1*6IB|k1;lqYxLRblmc3t|bh#VsjG;xdQ*_lJKv{8;^CZRVM~`0L1nT-^zo}`?0e|iTvfo!U zmcAMgXt zhd3s0GX(^G zCkMal-MVO8!3kCCo?NNzgMD(gw?DPx>Dx$TRZNfo`XWtQz8juljmlVy;}y1WcE%b^ z_a83jCuLw@pl4wTfR1|FW%T{X{+U}^SMT9?brti__;wROnE{>(;? zo4aFq>__T>_2p%5VzS0FJG!Ii-(wwq#_l|j9`MexGKs{Djh6;Mw6(mP2{^F2zMb3g z>;=)LkJhxeE6K`!EG=z6+4Y?uAt!fn^^}mc2G??|Ghs*cVZi;g;(TmKzZ3&j%*V&) z-dFh9{|#y%-SatCffn4qm6(`FA*-Ycd5SjIIX*d|9A@8eTu5yldlzDi5z%-4^m6ap z-nc>%saIqj1T)RKxU$l>b%B9`kSW=EN1`@fQC zw|w1@?#9rxa@x4^i>Dim_liOzOGN@!)mMF-=){-A44{yqNqbwmt3T1ln`Egc`a_Sz zoHESjIY$362JxqKLOzY$y|1B!tXD+&V->Jqvhf*CcWCFGPIsPyXD`2A+ViZ5a%ncN z9x{Fm>FwU%6Nq7u_<0Wl+YmI|v|?YxGWH?FSdc_-%%t-v#yX8YJg~HMY}rj}f^&3o zg+q!vT@nXdDF9gM1u67rD@(TZ7s!MJ?}4~Z@&)31xbBU{Wd=k?qz?lBZJS>IziiV9 z50>OV#~APb>e&A^dI8hgZ>64&@@H*VC<~x|BP1* zR(jzbQ9x2}n?gA4#JaY+4rfHN?MEz7DlZ{q3Espea6&sxaJL|-@LA&WUJ*t~c=_ezw0c@+C*N=TH7oylPfqjQ6W;<>85 z2NIH}bsKSl_|_xCVamF1+<7@Q)BGyRvWIF`l&7Mk*_-^furK>a6`wK9+o1~v zx4XA)HgAfR+)4OWW@~_x4<&?&V#watfBf_QDYkMKyW6!bFn#^3C0Evp@PJ^cP_FP3eV2yM-Q~e+GkL)<<&1dfe4(T=pp$3hN6QO zwN`0A<2a@;B`|k#3>jF?TWxJQ@FNDyYJsfPR~L9OPn^528tNL}#=~~Qy%V)&%DxC& zG=&%R{_$6^MuKx|2DZZ#=}J4hv_RAX7bL8%!9V-39cO5fJ;ATyixH%%l7!zItORLJ z9tG4>TC9yTeerXD*V^C!9V!Ya+P<;?S9sv^N9HgL`?SCP6fffXv@g{CKXdeixs^TN zakLCR06STv%q^^n(3b0chz}L5`!COg=DcuUI?U{ zbGjB83%0GAdAxSL;c{FnJ z^lfjyXH0)0DRM;->)t|F)mM>s(IZCH=mTzOBI6i!ic=R{Qmp~ox999nvO!Z39UH?( zdsd*Ef1TD|{Z&jTLZchID0e_}O!nHb9Mb%{4Wy1I4+9)TA^MKQpSHv#Ws0nxduVGh zXF0zvt()#Y8~M&C7z0wx%@EH5DI>hO85(r_=qM)B9`KvUxa(C)Ix=ZDX5f2C{i z_Ha?|4#V5YngN9FXV?#Oi^Z(Nt$u+Q1zXw)BfKy?I2z?&Ez!ij4^G4dDr-I%=lqi^ zJxs~8j}IGTaC)-m_&isGDLnhdjNLC%*x7wkZIw+Ny#2@ak4Y6@b8lP?+lL%Ptb3V0 zSb+&5?i{ZAPh}g>Yo9ZA-f>kX56?SXF7^@mR-pI7H8P=4_e{=_i2K1VXX~3Ad8lan zB(1%id>W!&<(c41-&*-Zd+OU0K(_2zzzEkTUR9TA6yOxqkS3@HpXc>fxTO{Ww>Mc+kNE*}f!eDT-%othgGy zu?Q@>ma~OYq=(hEviH5jSts+D9FtqJ*2ltFLTp(#%rKmxRnsg*yn zJtK{qQUHm4aq}5uq|YgB2k%0NYF9KMZ>m2ptncwvVt*By5Vf( z{Axhdcc!A`rm~&V2jO;84TUP8ujB<-CEvi33M_O7+{a{3X=C=e=z3cp(wH29lwvrz zn|mRrnBX#)_;3-NoU%gjZZg6lW5juDRxQOhy?x#IpmN+@vgzTiI)vOvC_YVP)vxd+ zsim~PpTqB+J}bxEEc+=?i`&}0N_g-rfQ6a#`LpH6@JzCD#*lS1ZpMPxShuG@?b>3lY3Qqo^1v5GW@_;T&(!P833rpq0 z^I%)Z5V+P&`MZXPJH|TA!OBvTM z%f}K>%6a^v`z8-5Jp7LfEFIH!M*YyRKi9N?%_9a%kpnyIl6`w0SyLh?tILKUH*RHi5Xa$n22t`xR9dHe@x1OQF7hN&dg4lz*C*Jz*)OLi(*w zpTk(%|H*00L_B%9M5pe2v&q_6wLiT@<6y720NT z`Gnlk+bM$6Fr3J*&d+rt@%Rg|nt+Lo{jV(O3Q8ok|Rt?yD6e zkH}ME%oxwtZ690TMSj2}?pMh7PsvT4of0x%sN+je(tsW&RE$VKeQbY%RU?X2zttmqG~fA5qPd1JtFL4a#?!3}SkuBaT-PF|UloO_NWcXiLE4EfsHfu*f` z6!39apHX|@R8-FIVI{6Y35nV|@dK_tpK!s$&GzFdje<(<8D7?W70(u^B5VYD(c+s| zAjwe_a`enR!U3^48<=T;%HQtjFsFuull=I>2R%BMy3yqqveWBj%Wt-EQEhM`tt1{! zuqm!rFV$z{{Zq2XOdP9g!b}qxI>)=5VcN9E?SW{it-JQg9qy=oCn)i!2&1u#Tpy8ksNO3{V-k4;QlG1DTKEj)4=1w?EBD?v_y|~3hi|7L=8(BCT z2d&&=g3Ut8jDI?Awmt;?xu=h>AE49kAL<8Fa(t|aSWzWc{Ox}-_0|ECM)SHMWy&1v{=CORsCjKU| zS*I`|MVi{sd1uC*Gq-05RdwsY^#H}n3T)(8(w7Um*qB&p<^YiU-*8owBQA# zyMX7k%64)K3jxKdTri_n>1W0dTQ2h2i#Qi2xE4iwzlq3ATsWk35f38dIg^7`R&~TD zq?G%0vPlaopU7aTYeyU`W9^79yv7b~Oo4kX=jazlMEcU=qVo2z*t?<_B5VW9@bBLp zBhY=3h$me1eBF?{uydN~(qfi|V}E5|3c$f>gZnt$nC6R0#Q z>$vFF-jX0JJr|UfSB`-DD~heZ(%Twb6J8aGn}Xz}-yG{&$ELcG=qA09^O z%GGxevyeiLtN4W^?pFLyl|j{b@>GLoV&Cpre%O7_N8|oYNcgA7GIk>swE>N5xl}?* zWCh>sz`DT_@nPf00oY8*O(!{3HAxY(pML#Ave=Dn8|AXtoBMtE7H6i}E3s2qF}scl z52r9C4Fz5M4WGR^rpNUOacYIdA96DTaNX;HZx*tor`3WS{fCDj0Rf+5Iz`(Hmx?-^ zO_ABHXeE3#dFQ6K&hs`y@3Sb@YF|;ROi2|urA9{Ex^3Zz9*_Git;Pc~gB~OtmBl#) z4Qn$06wzJJn42AQJUsk;=rUy#@s2~~v`Tu6JjT1so^mgU{Tn#oS)9cN5#f7NZ0W7V zP{h@F36%x6n6G7KUo&npZOFokz_v`n`RgqMSMY0pe1L7_2qttm0p<1QFEfcwPAuDTl*=CSj@_r9UJVKBET!As56jH& zQ_ONcp)cqgS{SL|s@60)V+|i>gdH_e<(iKAk?RqDj=NSqg+&UV`~1IwReEBb-R#i- z>m<6eqh0>(nw#*GsFw!g-Y^mvLI2x#l0I%716^}#uaMCwyUowY`Qy#2hLH?{6Dv%+ zPwg83&Y62_*vZu+Y%0y2ISC(wcXCC-H*{ywOB0`NadCw@`F*~gzAb$xW5BnM*k^?Q zAMK;+WLfTYTa>3~+J*#*NyKchw>yhmH;adTE32I<&W#Tt*gq)r@Ql6zLw$XUGP^|) ze}-$J|IjJ1o3jjUg7ORv{glYh4H_mlDE!;@b1D$S{&VArgNI#oPP_dh0HI#V%GqnR zA8SncdJ00wAZrNDS}?KC53THYjEmb5|K<4EfE?GDWzE#;B?W!ZFgo&4eT z$zMt<`XXs&LX$dHH{0BEXEvJIiw{qiVeD|iz<)p0#Cn{nqdham-f&OVhqO z<=Xd-Y0V?1HcOrU`!UV<(l=A5;9xCzO@BpOTSj?XuZ-7rW7Yg)R&s5%bZMGFmxsjutyJ#|}S9EZqM2hhH|^Ibh^QX(D# zxcJOseR`yKF^zl|8t{_VUV@6H`a5|T|NMB_^82T;E^DEIxd|>(#l~1600&iZ{+DHm ze*Eesf0#Oqy=FK<4@ap%3EE7}LAKnVt!#be=6~mbuar@gEt=@q?04^1;o&hj(l8Ot z^PBW^TE*yzRDMLSk~ z*^nF^D;ifhb`!!Z%;@0bH2MyTz^N(SL08>87S0nBeyIC>D39K9g^!)%_aK*d$4eTy zH=VXH&Ojxfbl$&lNVnisWrNu6&H_SVPQuvkm&vXv%?f|#ps`0^|4US4AQwovekaTy zw4~tJ#MRTe@)XH(n%9cN7qDeoVI(YVs=-EyZYA9cQbKd8EXqF3!7cReC}^#Yvzie9 zvv7xo$f|^>Ct&7xD=gys0=srI8he4OGQIlCxo+sV`|$H&L2&s=ExXVc<#GBeAAWen zl>6&iVpmRe)%Y`MTvuRQ{3bixJ6)kHGzl$ZVXpOQPmZ^GH!i!Umnx)Lg!nK`{yNe* zf>ziO28l-aSN-{M*Q986^9~zI<5JgU_D0(N`pArZBsr2ie9J9@|7;Fq>mtGH{G z3GNc}M%V*m7G89Jst9oX+3@I0B}_=|H!wDY(j&Cu8Uu2vtL<7ELI^dO^%VSeWR1qN zx8E$(IdP2V{U_2TMR@aYC;BbB?an)TOJUkKz?z}jX!An4i_)=_Z3b`kO6`iO065p`T|6rs492Pt&X88YN<<({{JYO3#BgF@^s}(= zk+SDQpN@H9^l~@z`xP{aTG8Ea=?`>0%deX-TgW~NBHj|_ilkBX#)4=Mws?J`R3+tn zAszP_%5Ur=a!Q3|ISF`N<73CzyHj-c6Pj@|b13L%Lf_0Rh#6-(3v9HSU2}p8OX&@9 zF9+?C3#GjrEq_h*jkP)9smaczXf6!iY-*XQPfEz!vkP6u`k-4bFc+)W z-8h~+nz!hE4?_^*{ghxr+qKjUcW1w1>}mURG+34lZFX{1S9ap>W;`4#Hb}^;_eH=| zp?vRyCeI`fZ)X8ADW|5SlN@bxke#Llq}k_57@am*C)L0E>!0wS?FgmnF#S5NF}Bzo zjf30gcET^$+{&6$GL!uL#Og@I9KZ)DS2&s<;HcRMw)>>C#^5b-`PJQ`JNlhd+1;4` z5=5KeIIbM$xbDM8QLd=2t?e4Rq?}W^vk4N!is9DQHXhPsr0)Z+c+7lN9+#_T=-_h4IHcMX$_-e^>Ertd z;?K6T$}4^758G{qrGbY$gDkR6*d+(~=&;rSaToQn>;m$jiW8R!>&z7sQTvFU5@}zq znrPLP?)q04dqX?(8xKZX`vN}R&(q(JfNXyuGz<;bs5r8w#(5}@g$04c1+$8aQ&D`L zi6({Es42eml3ikhNm+aeA^7DJge;Q1C6R8`A1oh~a$x7mb{U||+UBC#Cr3>GbwVxy z2CXssYgtBk%_Vv78cP^^DP7p%Lj^Py2i>Acq+{UFoy_6Hiy750w~aQ;IX8jM61^cy za*c2!f`x9O2DT2}5V$|f7a!f-Pp|U3fD@3?6;agk9O=o9Q6#`gNoqP|4`PE})UExy z&jfk3&~11YuD!Lb#2JK|F`zo#^1xuEdUnj?^1&G z#t}HaAw#$`NuRWXyPQ3YRZ&K>9`BWmJ}Ohm`sDemHRkS|$8DO2SH`0)y?mUT&}g~H zlRf5Hv%3MsxfNNEgvi`^CBMw&$KQFxgR(?|M+ei9{_}bEy|TzrLCMG!s-+J-4kcccsv23JQESLP z_$#KfUu|RE3|ji%;gMrpl}xd*mHS^tFaKiZkk&XP7YNLgW@l!#j7g8rTYZL)?U-0Q zvexz0c6j`A%IS2{eMTk**!h%EQz{KMcB7Oow*uB{GourV;!T z9JuM?Zg{O4gzN&?!VJ$5`%w-){-Ft5BIOgWinr%^U*G1`Cgqo19F*WK^?D%KJ{(H2ajbLxZ>4gRVyn*3*Ay% zUcjo!H_GU3xUzYPNa_(XCkalT$3*uk`L1K;WRzRVtnJ+#NFOXEijjXm^wd|Hjf*H}uX(A&EOqPx&Nd zzdXVs=uwTUJVA#37CV%R50b{d4D({AGnQ49*Cz2x7o16wws`Q$dupM0npRaaMcFb) zG9(pv77w6O@Gakq`wJ=slY9O1v@kYvU(n4owQv2g|2H@1={@O=fAqxSprOfZl&c5V zCBQzw8Y~)NvY(#TRpxy4i_DJt+;q`*xPNf91#X-OXpaul@}rEz6?IKUySl^(uajCG ziXTlQSoO$*q5G(!`VnGt(7dYn76mib*ozq-A;_2hFmm=01}@l25&7jt<9dzY&)-#L z6Yn<(yGV_Z*kxT46FxDe1gq~SxozcO=R4$&{$jlw<+)eBjM%k*LDBYAHUGLVHF;1e zZwM{-^cJL&%NN-~&V;uw8YBz?(D9-AWi*Yy{UgF*7O3Kn3rg!l=N|15nB7#!wNeee zNBgVoR7Q@gc->>5=oSmy)YrF$`K?R45ji<25zIh^R#?rC`jTA`t)C6djhO-! zm(+mM!9vG&C2H|^KS}rzIgFoIf5uM=3+PnMW2++DW?y&N9O1ZS=2}oSo2hGv;rJJe zRacigL?FeF|2$O3G~~iPpA!{L%zzs{I%u05E;vd#um_vc?J8?$+~}oIOxLO4z)L#) z%TiK-_Rgq+&|ZQOu^DNOKlr`)=?iK_7zwqikt^z6j0y5*i01!^%{!;@+I-H}j4K zH49DsRo2ltqn^}>>3`ZX)PNyWt_qx6#ZV05X?AZ%l7!N7IoJ5i%(&QsK&(8CN@A$f zlau|@FG-%b2f;4VorEPtSKg?0T6S<^qKWx?^t^CgKY8?J_e4Ln@l;GhRiYCO&F{)@ z_mt3bkEzrrWsG#-Qz~v;D%c{cd3?G(s;kO5k(Dj9R|YBimiC(`#4Y{qKM1AoJ7Sfc z?ewIPfr#M%m@k}!Sf?mtBYMiaJyf(@VSd(L_xqRruo&bI&asDw&Q!)c-H*b$)iOC& zWROKmr)(tpig!t)d&OnP8;_!hH|7k(;>t?5+zn#PZ9T_ZI__8RUt3)Cj~sFsHifBH z56>k^`0s?@R*hla=Yssix2zYDRvmFy{N59e_D9K=tN#*`E~r`=MsbjtL92luf^L{9BYV+o;RYRy1;ro1*_ z3T!X%zq=2|w2j&9yA{%u<_SZM+z{VeCy9@i`B|q&T&}v@ffQ7OpDv7sF+^`wHRly7 z4J7L>Nbp-r(X34jf9w~Q!yM6KvJhqJK`Q=53fAXCIdglj+YD;6R@h)TDVkK^(({U{^LObkPIE({YL$HcM6}!+-LJ<^)20j!-LGj1?uhoHlPJ_PJ z!|yABe^LwE2_N0(coya*-nSFn+&Br2ZSg0=;~0g>xS_fU2b)oiLLRxnmGVr*{|^gb zhR0api>`|R#o$AtO~;%zOg^ZyKKKOxWWdAeLjVK02-Xk{}lI+pjRE^hr{Ih zDt@2Q&;zRUFFP3?#s5uvIHHN=+P-eLSHxD{1)X>$_wv(p*^%tTCIV)#UuNHK$^9JUS zl<~M7^?m*L7w64rkBbe5#|y-uU$FK#Isu~b0=)O?l}#W**}N(z?RvL zN4PxrBn+j{2q>k~H==EJ9nR_AT}dA+Qv!qsTg+jE!HwQ6O%)PLo+GLjs+o+|A&0cK z#D3U&AvD|ad!o6`SX!CdxHk4uHAx&vI9po))N_pG2BvQpe6S0U$Id6ls{w7fmKwcX zq#lKZ2T9T$NP`}2_Um7b-zwc*1<6JQEVegyvbDu=a*S7=Th zMwLtPDlTiIHXN%@yrmpKW@Vnxbqy6TiKjWqu%Ff?%eGY;8=vne)i z;Y+@kQkF$mYb=|(*u(@SO4ZMMZLXby#J+yvG-#5`?@^SL{178w=;+w3CJXGUWlKN5 zp!#x>Q%~%h(VJhvRD&mQ2MSrfD*bh0&c(bdh5)qBzcOOWOoT=&V|VqackH2<9(mIV zY*tJ6(CNSeCk7#{$a{NXhqH|J>{%gm6liE{rrL7$RN^aNqS0AzcT+|cV&*E)_HKT=}t=i3ECi5U7SOVC!>_X zjL&>SUVBi99k@-SztZQ^aZH7QhI!fSIPeJ0-fBptOV_sWe|RVEsJb>IBRK)iS~6zJ zq)cbYP3O+t7Ika6xPSf?Xh;%&u1`5eSWOX}>XwM@)yW~Y1gXx*k?NdAzVE;t9HA$oPyq5)Vaa&GF z?I}Ijg%x{3uk~(KW*%*Z%VS$})6CY)c;N&g22&Q!0#1DL?sp>=a+^IVxzI}CVa(XgV4^=0l ztD(8Om9cQ%cMm)3!J*;LXd+cw?th(y)F_~o%LuoQZ!Uve7<~u=Lml1lQFq7$EjGv> zYR=956IvB&=(=>#xK#D%%2B6`tI?-X2z=F`V{XI;h(Z13o1Ulr z#-`~7xq-$D12thFoqTuhL9?rEB(Lx^oku^uOaPkr&ydAXSvK)W;S3vy1i@c7-b);? z%J`wW&o@+$spASUR0|L`R%*PfcOU^@|U$D@On6}z0D+IFKD-ZYjzIMSYuw-6QMfr06x{Ie5p zTTU7~yhD%UhN9P-Q`(eaFK9?ET#0-Gf9g04AiH6SVPrKO`OOUrT|f*Br(a`ZLDl6p zG+44zse;@rvRThE6s5vc=44+6LM2xdZYk+ihzhZfPfx2;us?VT!U+=nokl10;v74k zqJ=&YhSL_WzN-%B*X3{7Kea7n!0SBlG$hb=4F)HMexTlRe3p4`P6(vW^~_Um7ERpl zq1qYD{?TCl=LA&Uoc+m?VJ2i*W*1GFe3YGwujhG+8*B^Hwb4r)sj4%tV5voCr#Rc2 zbwG~?pfpeDe0{6b8D0tbb=j1?15)Xx8D_`5~iP82M=B<$h=CC=achU%m&WP?wb zZbe(^gYQ%{ogUQn+f$bNx!GK!Oqd79hB&d68wd8WeqI7F8dx~}H6pF94JwSky*Ba# zHNWV8+)ytR=5Bsc-xa=Qk%a5=W_m4%TQauv$j;1&`n#-5^R0?cWa#l&tt2%yrGGPyc+nUtm)#jeYAlp6jFoY3YcHp=*$d>GCq2&f&b<# zs=AcW8jdH8a^ztl#f}^82X-_Kp>~*V?!i6hZD)9euAfj`3bOdvajF>n#7!$@LM}i& zE*^brKjAG$w?#_0dKBWHma&m9v?*47_nXLn=zfb3Z{D46;QMa?14Ld}m=kq7=FYGC z9SpxRVD$797}kSJvF|+?Ws5w`NxwUNT*1WtXa;Um$Mh(UK0K6Tcwg{YNi0@n#eXJc z$)MKE16e1&byzS<*O;zk3$QOW1F?}kUUea#(Asd1hh3hJJ-wWg>H)tlm%NDrLp9oZ z#@cJYqX#^*4(!$DPr=(xf)8(#GXA8LhZX}$fD%Crxv^ry`2)LGR@`fU2^?_>-v6i| z)-DvQj@|g?lk_l%84^myTAk5H_P5mskx$7Mtwg z3S1f5D}usc5|j!vMM9f$-7U4?b6t&&~i-G*D_EAMBo*0!0B;9osBBj-gRT*y~IiitQnPY5YI$ zYO+1ui1)^otD88+AT#*SZymL=24{JBIgwTKKQ&~kg+;o~GX;EwTcWm+CcUd;fSmfX zv!}O;Nge5!No4mbu1I0Dyrw;c*^OivV2JXemapiyEX(`&@xe4cw_(dB zC!1KB15G;>t22L&*|cRGS<#%jWo&Tq8j~#X-L#54pm%XAqA2EBC4V@wW9m8{U?M9Y zWoxTbWY_Dh>)N=+0R1g^+B9drt(*Lc*G%mPw;GF@cIb%&c>? zSn?UtPkwd3iTIon;1vV;ji0i$`29x^hhWBSh)PZCkWE8tgSG0y(l$j=jt-icX=sr+ z%YoPd<(L{cN%ryfv!{GDJX5C%=P`ZOYdXs z0|sCE<&XE3(pU`h8;dg8E1li9zKcmD_RZU~jGDwPucFD0cB{f4Uy~R;`^OC)n7dDT z{f}ZM*P#A8bLV1#peIJ_;iTg=FoMY(E;=)orK>?fp{J7-_1YwQ=9M-=nf&Vfl(k3s zuIgXXHHu;3U+xeiuU&?~Fq*dysTk4sDV2!c>|zW_ly-7W)q@r27mE|(yD5#byWv(L zUNX~EtQL>~f>ng-UGcCILRd2XTnLZVr(LOqo`S zbohu*B{2`}lXF1CBblUP_+Z+=8U-S@AucQXRAol~QyZ2k2}wk>{UDK<2cwF(pKa z(yLRfLT1uEXGvfr3dHW>ky!A8l4kMkcj$~j_j_eJI>K}S5!2tXo@ZmwD|E>t*_wyn z$cmCzryNDq>>61AAS)G0?tC^W_|%dLi9;k>N^{}%0yb?i9#X|e|ppn+B7VXcBemXH0q$~_c8PJK)z zSuWFVWg?FiKMhv%4_1-*5})BI6dm6+?Yzx}x^*_fxG0sjQXu_Y`F8O+K~EN`<)?9? zXEZ#Qg7_QDeycBdc#k;DljQj1waw_7bajKqI5{ICBgFdW{_VOtj$z`WCthIjx;ie7 zWbY6TJ>Dfw)&&88+y8DF*zvj}Z0Z6){pXu+Up1CCnMq7;`!hZHD7C$lgLZtLcdpoy z?<92*92^TOgGyt=>3zxD;XZ0LMZco^gQtntSsKaMg`NrD#(SAEl;A^YO!N?RbHXfS zn@Y#7($R%?5Bs=@HdnRah(t(#r-f7yTP2HqH;wZNSQeW>#&Pz#Y`H+qE~K!ls%z@J zPM{McZ0e%R{@35kU{vxK(ooGwsyNSP8*x1a#CKYrf6Qepk#XE$kIwlwANc{jNI^nk zQC%);%Z*&297=<-}Gn?dST!VinIqf1lW54 z8YkN9Mc1eyKQY6(4AIk(i-MqU=SwxbW>LsJH3Kcu+d~ica=%jJ;(m!FnV(n0+S>-^ zQwZ38e_t{x18rjnPx$$PA_&MasFFfnOph-gezLkoxw1!D?B`$UMXt!I(htnI>u*RY zBSx7En{o6!F2kXRl3nZ{;MJlF?*t4fB?i32%AYvRZ29ubQ@8Prt-YSZHrPC-CzV$Gy++mFoqFId6|W%Yw!TBF{GlkEz~nZs#}AJ3YJZ$YD#XaSS#sDv`A&71 zFsVvBq8#aX1}HK7onC(GF0>K=zddo8*!N>j0R(FSiu%{sx7z?eh$@x*>rt&Hhsv}0 zweLNQRwe4xin{E=);(F>z*;wZ_%TZ~hoE40?{_>SJI1|A{oFAol02Bp=|Jm!GY&$e zv=DQsAZg2J#&PF{^>$v&qxE0#I$ngCdvdC;V+_=ExJ*f8Q%(H+;vh>U7p6Puyr+rr zj#ks%V)nz;Ud$rH{_hZ_YVBT$E@Fo*tvA=GVfF7g%7Q}FD$fCrAa3PdbBC2K#%{P#b6=FFlP{@M zEhHMoQxSy8U_&g0#`Kp{WV_#92|P%xjTkm^k&d#n!DCKOuqueum$%h5&Zv;0Z(yK0 zgY7hTv)I}A#vzX==ZTm))U^WaDBSS<TMn zEth)&lxuPsiUO9z1(}f*|LEw|O=75D6D}rnKut?cRuHfA=75x} z%%1gSpDf{Iwl_%l%UCubQ@Q*6#TMYqW;1?E1JoSo;#{YkFRGsq zLA1W#_-tgE*Ml?(0El?QPvB1W-}+UiQ;As>JG^Ie{7uP`%u zpW%TXZZ-$;9Y?NhWS-&Rp71hAJv|;0kc4Af1BlnC06qq*d;auU!;sO zUx;YDoM_OG`#S;!%gB@3+hJ*biCx3Oux$iU#uJL;@rQ`SVnl*ooQ{`I61~IO!MkF> z8-gH6IJ{A6ThHN)WXR<*WKv0X7ao%-7?|yi)WrO+eH`f>j)PrF8d#JL0^z&F7zIE; z5QVR+JlOw;2#%!U3D?sz@B!iGG1!%fiHcv|NTv{sw(5@o&08-{D2r z7+RimVvmD#0sWX4C959%p$H+b`h%RAHwzn6%X6^3NwQ#I9LYckI9y%=p%?+TbgJLW z2CQ$KEAen=de}X9C^o9t9f_P3l7_|*DduvP$eZilHmMQw0>A%#^h34|ZZdkr&F~Fjb+T`iz zeZIOo&caR+e{DNG4YgFn0(eysQ_FF%v&qWxI%~W0Jox+%*xC)QUuvf&b~@7mmZ_0F z*dvk5P&j5ROOjPQfe7KC2j!H5QNiJ-snezaJU9f4d}g1W z)m9oR@9@P}qdeVSVr=LRwcY3WMMn_7A|k5+s+(H5sQJ-VACZbi&i8auR~aSbbEAkR z#q0rF=US+}bBo(|#(AqIb%WD;8}w>404>q~AwoMB^jl;J># zhL#2f>%E9CH9;1+#3u8Tlgw`C5q%9@8El~{`nFHV*c7u#4t94*Yt|8;Ll8t%Pk>-J zf>(Xj6y?c75S;{KwRHFQQl2;PMH^`8Xs5NgmWpT)mqWnRvn01y>1wUzZ=Zd^$ihBz zV?*4jZ=gI9pe61`_CzRa>ZYsVDT(P_mdC&3KmJ2z?_wv-l~KG-&~pcDEzdGBHpcy_ zeH5oizIb}y^+aKtWOg^$Pv?)dmk1KRNEKn9`mNaKX*`x~W0@wFX@PAbd%{$;5AgH% zda3nE-*yx$3T1Wes6w9X?gq1~$}!r+Bg%AYv{yrD80Tneh5V0~kU{fQk`mu8rp-=iy9 zeylGmIYU%6pXY;5T%>fJd?80BdBDzIlGMf=556?XXR}x^23ERY z9#a$$P<>&-p&-6vg*aayEX%^s4J_M2RGb8=ySRGgGCghOc)tY=YI%OT3^T)3nn$-ON${xU^sdx_z(H7-`U@u|+E7nYp3{0$6z_&#;1EV*KVTsq0# zev)ivgQNF-JGZ~$*3c~bVwCQ|_jvEhd75G` zBe#DYDCGxI+Z!Yb<}vmXWTzW{sGN}Jl;ddIF43mh7T5-Aw2Af$SGanymDn@(!l63x z1cSVn-5`<3us*cR>e4(j%X_qzdr;*Ue0@PcP=eI9^>Fj&KK6@6v_hU_BEdl_M{<3J z`+qgaq%JYg+eK65ODLoS0m&JrrtLf*eBvQ}Xm`_z1iOheiPdR_Z)@apc?K?aP#g1} zdd&3>KMe1R0dER|i0qC~*$|!+5R)*^gbDKX8lR{>f z$vdAhwwfWWJ@3T`f<&OIg$sipaK6TKs^3eXv~Nny;-#Y4cXdnJc4_}03W$P;2-s$k z#L5#M4vjIhZ4hn0!j(&1G*$Rs*_C_Ruq}=K)u%kTH_X%B;n(0i?je*SOrGoNA&`5FJQ? zCN8}fqN8XcyMsidUnj>7pF?sJEUUvC@Dorpl8FNj#y417nq_=?i{2VHvUKcFJ(wBx zHkO#4S|x2MMBDr5t_c!wot*;a-v@)_#yk&h-)3s3h;BY_=R`@Rtf`0o!9iN%3gRgS zeuCUkLFkS>Q8@UXL*+T>L@-{M9(JJSXpH!r6b2{X|VH5?dk}Uj3k!M zuCsGGy$TkVnP+X{F87|S9&0ZpS*7XvzjCELMtR^AL&fJ_pok|Nr?$C`I=^(x+3z4w zR!x0-3)O#_WVV=PYh#;qwtyY|=@kR=sV%05@9=PTlk5?@D-x_~rK|5Mms`T8OGzty zy{rO~>>yIzKz)4;VYlOjqJ)U7cqwacrlIB$k7sw-Pwcb4x<#QsjsxL^-++MRj8fM* zK%}-C-OwrIGNcnbEX_{xXn2gN(Yq|K?^Cd3oY%Xl4ZB`*A;bm@lIycP9D2y)dgh2< z2qNVjR~Wo>fwqd5sB*qe9CkY^E)V66E!3BVj_CxJa0Mb%wYAX{zRP|g#m?pyyL$&1 zc8Nmdxz{MjIQ=!88w}IfQ$*K`6tXFHH&&RRe!|f31fySVvAUB*@%p&jR!R7^`-LY5 zQ_rzB^^oDQ8P-xqg`HJzgvOrh4E8h<_q~DCnk|4J;PQv4ZR?^UbTk1ghzf!78X8&} zC>xq5kH_p1tux{j{p$t3sLT%Ke6;Rs_-9`l!_brN|C z)%hM>HR0#=TAq78gJODzwdpbb`sY7!|M4biM~tp3@A0z_207Od!+EOtE{j5Xhnc&d za(_8TPCx3W`r@^8Ui%FL^-f%GWU^BLL}K+V)YaD$Ju>Yk04n9pZPe9G5gJ=z|6rf( z%^eDQCH^D6zJTBe(Qs~nSVIrGp;IhmN$jk%I5WxU@Hi6>Zn3htkA?%cua_#Hbc|M( zfb5LX&^1V`t_RJ~DdsaIcQ;v@o8rO!5#}Db95=qf@bn|fJ^Vsvi#^Y(;}7FzCrxkvZ8HL=TX&Uo&x zf+$hmUL@Fjg^nusDSj^rQFNdv5`rLL6btC4iTR3sW7{U0en`nB%g7D|+14l|*BQV2 zB_neQn^Y@gXGo{@i{?M30BtA+}1?Z$Rc}tc~+)oNETWs!-?VwQc)YE z;=67rD1>X9X*t(M?X79%@>zD*H%R6Sn7DYo zO<~m2w7Y_Y=!#L-9Q%$BipYwOiq;O=8XogxcAK@-0h=ppWX(EUh(|egZ5t!A%f`|S zvukN2S0x>N=ZJe%)VF5p>}4=X@2xR$?=GJ&q)LL<&p>iGY0i16?&zmEcDhw{L3ZJf zRpXCUf5#^!9L^B+=g!geaE|5eHTKrl*-NA-T4l(hi0X^ee)%RvLq_q8F|)kI!ss0) zhb@p~Tpk~hvMQRo&(ql&V(EX*F(()(s*2(`o_G0d!p1T+wq_qQ^yOowj@ZjmAv;_9 zGdkOce14e0aT{wd*FXb`(As7B}t+=^_#d;*gK=@&o}v z@!|_ai1<~+q(*jcm#l7L*c_#F6=WpEOQg*E+<$jl>*I zdvOJiCar95=<<@#$arYUTh}StFOOzR!m@FVRsGd;^WI7FuSXrI8^%AKN9F zKiVu9ZRkdA`8mBcDyKQKAPOR~Lq-%uKq3$b;P-i6x>rO`gitU*&@Ho-FOW^A$safB z03a&3{bAhxXa29bm5%l%8lp~$|KBa1EKD$TuY!1W17+ReW4rnV>6q)ZcF@z?MTKAF zcYhq_(cCEa?p0G!SwUG>?C)-neTUbNcg27=1luww}@2_Yz5Wn z;GNdd8-k$VR9$%7GJEa8M0isBtvX$D1dTRXOr5j5)98SFM66I1MlO|s*qS6pJR3 z(~atO;nY(cERS;Q-Yi>53x7l)yFSgRwu=00bZ-~gU46>hK@QWlNN-FtJ}i)5^WhCw zP+eO`)c1M|Wr8Td5Y-@|kRP8*!p>-DnGAW$E^#3rsRigHceYrX zSz=$8a932*-4ez5qtJem@J1?W@4tjyd(32jtWe(EK$%}Y+X+}vLh*zN1>C3(fmA+A zzF4Gag9kv6@J8zBx$Yuf)4=r1BJ0~pGDQPHcH$4msIG6Kp*DacGsQ?o$FxN}J})lU zsg||=K?sPFLaecai+L~Q$Jk3zR%xm6<3DBYeL)aWolcxif`QHr^FNl39sLaLzeiKOaE1C>OfH(CC#Ct zg=rX=KZtr&KvY6BcAukda-O;6J$5!WSY6vD-xWWFVt|A%T21@Ke$2A;u~c~#owdYX zvwwON0oT0-Eq0Op$_!C@MIe5~4_HZ<*!~)58-LRDT7X7rU99T4OW0!~E0& zTm7x*)n3lBJN7IjStVZIO79@VlSd~5oW2N+^)bB1aqquY2squYlD(v~p0@ppd2B&K zk{u`x5rIP;szaaVdmmtuhlE* z5LtS0BJ1VXk(?1)dd}1ObcMNne79^f6$0^St^-Uw_gD^GG~oz3k7 zbU_ANr;tgoyOG2ZY#obPaQka4*^1pF>UJ4Z2>B$?MSERIbY+h&1cKFRh$ z0m~L}`h$4guJ7sOnB-GQ(y0^~y_CF;M0_t1T@jF+J_4Z#QLlnvXUOdDkt;^tq9F7% zA>s~J(*54AX&%sz)m9KC2dc}1`c@@uBwWEt`hWTFbQ?$cn*l_Jip%9Wh|}q&w&w=F{O33U_v=04MA1oEb1xrNwsZYR_ZNp#J}z7? zM~QaqG+^79nSFM)wpiWIP$-xzKKwIVkL6>M02YQ`Bv&vnIAH$a=WI>hL6TI?|Kh*$ ztB?8#<#HS(GU&EUz~v|GS6(UrCrB!aJ4nzgBkdO{q*G)I1@vP($xadi4rh?Yz7MGA zx_V6TU7DCtoF3e7R9Lc<2zjLjjUXV3BI4JaBX%hicw^aiK5zUCxfFwO&Bi4{0I=5lND9C^|(<5(Dfp@YyrC@SAX>LwuNn37^YRSc~a?|dwbU6 zq#)o8SJV69KhtsjWp-D^>2kk;<{(m}B&wwj>gk!eb9?4t>W*FITYmIkU_bfQ|A8M|uCmJy zez9Ktb&C`;7(p-~;{XRI=dhC>&H)ILpae<`5Vb#5DhWrx-fN$=*LVHa z`u*1Lha}5L0vOFIMtG@7rfy*By67u792xKZ{N~IDt!y@=vpH={5 zqCEMA?Zq6esL=p@DYaW*r8Ce9u)Tk7T z6pJNlhK$=6AQJYXh&xPGMt?8(;p3Km7S7 z3wekPALf(4{*2=j{q%(0C~qwlwun2_!{N{VkulAB@&16@^~M7_L`BBs_u)|$BuuK6 z8uhw{#S2orS|+ApVHy^K*g91w3hmmWJ3gknQX9-N{-?&FQmDK>2+JU%~>Xc&b8wMvHdObyMj zaP443Tg@t!{07VUI)Y6P;1ZWFUgl;}repLBKmXZDhT^^#Y@P{h z9=pW?%QUbo>j${-*&U*!;PM7=dB6F0zds0wl7c4?<_%{%`36K(hl@xogiDdJsvD#; z1@a|>Zs!hDjb+j-rO9LqlL%iRvvopV9|E%K!l&-J9>p{a484hNm^3vDm&b)7 zi!a{vSn*oZOyVQ3qf(X_`1=FHSEv=W&@9Zk28-EN!?2MSF#7VmK7i;GMzmuYy9@E`u^BgT3{yfD^c z+t{@X1Jn9C*ZST=5caBl2}&?bFc82m3*@U+QtKPkwICMH7WB2iYS5^cDOWWtK|=8b zaLW>wR$%eYMgH>THRj7f#*e?xXFoYchx-K`DzxJ$w%PjT_R~9-L8F*p=E@iR=C_xa zFG_SxoZ*-M;qN#$7;c>|eybYYT1UJ5kv(Upii(OW6d~+&;}Fv1GHJ5eJci}nv7oPI zmZ?;$RO<$kQ^nzO;}8wBdWKv7_Mf;sU!d$5;@pov;>?i&JmOC4Vxd(lv;E(eWnvm8 zCOW0e5;wp26JOn3CMS>aSAY94rw;Yu`TCfqb}Un?5b_W4tlswt+Zpgy5Rerg-6Kbc z_D`Z424?$=mLSWhs)F(j(M>k57iTC+tgnv_*Bq%riboGtDNl9dRUOZ499UFyX%deg zvsBixt6%+MR8 z9?!9o%uuqN40U(X(-TGws0^I@Z~31m{~q1^nx&gnV}1T6pa19IbMesz9jE_}zxmN| z4)*(SxP177UYxQ(t^RFPoS-R_{SCh4Fb*iUk)wpA*rlP%CFi=9=g+aO`x#-E5#$Q>&5GI z;Mi#s=UrplLg-1vz6msVbm9Ny*T1{Sy|jb=Lm%<)|KU8tVb}AyPHMU24Kj{mDMkURyU;SVF>e4(LW*4V_`WZhtf0(F4d_L`u-lUdVW-+lrx~k(0 z`-yaP;**~LT>!0+BeTBFM#IF};iID~iu!IG3)lm^z2bNL2>H$)^J!{>6^`H9~GJL@hWDJbDl2D*dXSxAvwnP*{fk&W>P{mRoR z6fM0;ePfBG^)%VKjwj|P-qnFilBgL5=^E(AtEx!o zG)q~Q=O1%7A)$Ms>_0I{-2JRWp@rEfP|T%RFE%kHFAiTjlD+-QdTounSN_6({Vx}o zE2{J#I?Lbw@@Kp^62+z1`&;m0y%Z!T?qD~AJz=IFB}mUdU}<53jpIFZKR3QC>KjX} zt*1y=4LtDxkysR$qJl0`Pc86pHbvGd5E&k2bhHnbS9;#wH8r$KiuFv1VqHgxdT{yu zxJ3!W&?u!=nVES&wwY)6@P39zdhzV!g|#fSN`_3XNV#U9_}#eN9-Kdbb;tJ^+Zph- z5M*RkMpm6I51eU&WqZ!{3X&^ASMLZ125xd;F~`c?%Uqu7<^73HLM|Cm6tFA2o1O|^X(ibD*d19PeT9tCCKq_BDkQCg3C_%5YogzUd($Pg%cMSFZL$YfR zxpDP2-9CkpE`KYRp3w5H8hV}V;zJ(Xn`J3q2iZgaa6du6hm<|Fz9K9v(|RV~UMo+g zY0}QNVYMQR3JAa>?54LbfQWz~ihDCU&}zLu zPrAYa3=Gq3r>$s@cf&w8jBQR7p`G5M^|PfnsFw4j^HmJf!WD=S^0!h$35pYMNX7F_ z=iyB^T4oNXBqB=+ZeN7Xo?iMQP6Px*!NLp&>F)2u`|u&9LV}xDA21bj(H(N3%2Mm7 zsAXapI+av{`5QNxFE%jbARXOZgaf`ky8&%kCe~B=rA-WT(>c#pUl~R#l6-4bEwoa{ zZ1#oOC{rvH$d(%jqJl3RC*V=r=@=9|ZW*IlV|_V6RrK=JP%rLdgLDR6$n9g&mZ{UM zWLUU!iyJo|lc`yF;~kthIfBonB8eIsha!@Cv5-_oZ_cA48>-C*X?I%U&IcULcC+^T`&F?4q`w#aK^*LIpD=ZVeS!C({eQsQPK+Y8L2Rj)Y=)muNqH~)kJ)X4L zc+%$fGdyWCPsX;;N)h&MkKmnjchfGk+Cje-X8ZfmpV8edyU;Q*>UmO`64j=O;_~4S zhVVJXb}9)GL5?yqF+|tHHIhrK+`BbRUv~uW;eLW{wVl?YNhO!y?$tXyTuf0HybN{q zGddhamLyzmADumMe9l>t#U!_{-C&?Aitk`AK8M`yuU32YdY(tqcX+t4M!^&b$6|DL z#Bjc~v?SkvWwoN^w{?YO8Z8ZN*I2MDtM#7h#&h)zB>whbKrV zur2Md;K1YWWNd#ww^r}6mVU&AFQ@4WI62T4!r4AOXy{c^%k$j0beBY>j-^H!9O|LF z!-s%OARM8yJA&)h8s+jL*S?yjC*Z&_5XGf#w+oxp@~hmtcALdi5lwP1G}uQZ zPSC49N%tlB=@}YgWVD037gyL=yv5b)LqyyPeGzXft*2?C)p9J)%y9GOW3qJtPrQpm zQ{8ynDw1px>4*`F_>q>^S$=$nrCXRT3 z?w&4u?p7Kb%Pg~W`x;ljy3T{FMQm(}vmd?3L{Au1urQ6UsX8Hud)RJz!8+R9o}=G- z%1+(nS-sS11+w`PmAa1N_Tvu(3Aox@vVx4$8)0-}fbN+^GOMf1-nq%;eSLg|vvX_IL@&c#Jq-4Ra3~70;AUuifWW;R>l+)~oxaInZw&W=ZUSyc zd(B{B8XDF78uQnunO#Xy)J0;kIK91{I3*d&FkKMboZr-jo7?NY-fOt%?=2%hiLC8hmTD%pS#Io z;x@nkm4kBXFb4)Z3A#m$T9(zvce!!x8h2L8D4rgUynlw#-YDK}IezrQ3X9WU@&8nTASpOKL82kg9*hRHuuPp|dYw{Lqp_9S-XOJ}rcl$cXyxxuClf6DO*VrMM8%EA z>n9raAOdEyN^W7AfBoYPmeVz26Yul>`=>e5-#+dws(6Ck9Q)uXH|EpaSx#{C!siG^ znd1kB=?uG3tUCFPCGK9k#Kqf76ip8!hmJ5gF-X)Sw-)1~^nzmD+Yn`>?S-dA39`_B9|9~>WNFzTSSp|*?nP>_(NcI22KAV?yTBqB@gzqKq};Z6n*OfqsW z$<5^qGZ+7jUpuOtJUB{UJc!pNV>YYgQ!6~Ud6lpJa+jv!x|0u&lcbQ$xkx0yP@pr#Q&mUrPY=Ew)582Ww=aa0?Kj6mI z8{B@J#`H!RJaCMUrXqM8GBQpgeM5{4_405zPkP}lfBubySvC8V6B(UaAA>gOn91bWSjF@Cb(neC%9%(x6-_lgpJcP;j_> z1blC>PRO3aLf2}P(n*Sqr*&>Em8a6su`H8jHOKnuGS0epo6h+N2K@xQt&IhP$T_JoH);?M|*I#odKfcBswt0eEO=eMOdX(Vp(``=A7w^1WBbd*zPKj3hm zs~z+tAc#(S_aA2J!3t~X84|PC`9ikPE611|>A~-?C}$EZ%-rIui?>-w*YNfnVtnc# z6J0IGs^|&PGcv)Ekw;`o^Q_HY<#R=+l$v5}u#2EaMY5XIidmK(-Q~vBY3?V=2)-`% zjgGOeFZ333lz$x-x?ZD{%~Gs3pXjC4WNjl$xoKb+8udz!qV z9^KEr?hp>KNp5YPyEm?L>FPWcLn3zIC{yDD^n_GE#2f8nc>jJ5&aCq12OB)P_9uR8 z6-gZ&XQ(@Z*C}IZRr0A-=I`I-tIM+_N+#~;Fh>s#(H-@)?Q|2ZQK68{wQ`%cb;UC4 zB(o)Int^3DsT9(zuPh@KTY4=BB8sauS9o3O9#mh0X0=E@n}5o_H1#s+Vx2}?FUz?N zRu&d1O05k4f+!+6gTx~~Tx!c+(~7IyzIc&8-(10R1)2Qt@A%+AoUnJ(o>K_-jWT&; ziU;!o6J zGLN`@<0jYdt18%ep}_r0>rL{@_xR$=>)cx^5E(hnd+(p+zL+5&WGD zkB%`p5mVc&vBp|4ZI32B%K( zqf{F0iyJ&j-sjR68!SGYCKmMIkilqFC}uZUPo^j|6g(XhocZx*oEVLvWb1GK3wlQ} zwGxZBzv9Y`2dtE|_NNwlz0CS@iE5*XkX_>HAAifzE$^0qO0FQ?6KDDCgE6B1y=KH1 z7e)wJ`hAVZ*Pgt;N^pRYgD3dKhoh*1fMql( zr&qXr{W|xSiwx4s$kfSg_YzQCK{_YT@ySOint!;?ouwHr6jChS>m=lJAX`l;`4mfw z>y%74y$25S;kn~X^oMcm$%WdhM5kU_WBRxMmD?M2%G)+53hRp`a&^!&vP(Dlw|`0E zamZU6>5h(reE7i$j!$$TBVaZwWLF<^<WC7nj+X$~D2d9}?I1SD6Op7Gptg)6Z zp*zBi9X-nj=Z-Pb>BsRFi@SauhE`(!)>mA;`H3Gq{3u8KfP?O-^BnAHZDWbD15eLk-v1y$wV`w2 z_A)b9z96;ykgj;EC>nZ`Qa(*Gkz^xZLx~J<^4te}bY_Zf-%bS*0W|8hD&=w$B&AhI z&>`*3lSyv`ooarS+rRrYSJ!G!ZN!#RtE^;dpqmud?(qBnlE&v$w&~myr%xZ_%)#!q z&Q-}L=DB|L8Veg$N*y0CIX<{`C&d$G@W4?%&gRJc%U@Vof54?bW>}cLNj&Vw*|wkZ znGF&v8x#!(@qGt)|D$spAMYZ#8PYF0@yCWZa_R`n=`XqZXr2qdudwpqCh?FP1&wkp z#p>!hnTkNL?;t<=#b+EH=^(U6ooufT3uuyFy2n>vUgu$|vXy?$(5hq-%j9bYrj_F1 z^}q1XsTnpaD2NUpv7y8K?Bk>KL_BRrc8;~V87^L!#nW3x={e5%LqL0~5JU;Z-_69) z_sC_6l>Ru)?EEx;_*IUFH)DjoDuP}my|zkXJxj^*GH~z=AANM3;f`%OXVpmDzsl7s z_jr_VZas@uFOyl!QqxR~(i(RzeNJxi#^&u29e!N>@9~d6nZ=lJn^gG78zFb(wlDl<2yxi(*< zyB45t@(fcw+wUgg>m238nfE9ZD|~Tnj>k7IlHXY3PInZyVo@(8ta1CxzcBr1onrHeUY0ZKtYquxO^uC(mR??Qwt^4@QN|S; z;pFL4oIKElLlUsG8rAhjT)%RibkoIzYlOpx4#2hwTB7QvWB3s7pUY6He97h61+M+{13t#($f#in+f`N;?(juE#llP{A+L(nD3M97v9g+`CWjcEJkEz79A_}pI$udtf0VR_1|J-*53xreCVu)#070z}6@=9eE05%%ph-8Iph1?H}P!R471 zl9eZRYQ2tn8nj{rh=M?XqOH!;hxp;e#2RAN~Nz8MzBTT^UK(utK#Vo1hMr+NWhBL6qWuRr|7o5=wZXMVN$y|&l8xoZOm~F0bhlp0v$2*SnX4msJ2-Is z9A{5W(I0iS9F=dfyKG*Hcin=uvH6w=2(p)O&m?Eg>nNT8*KW*znmboe2dc4eZ{?WZRcOoQarq!;^DTBB!4Fp z;s_s{93tY|YpFOaOry%`y=ksoTVkoWbA<`5lH~r)IeEJ^qD@hjb zUgch`iDsAxqJ-*l69`2aJvPO}p%a`wb%^1P0P0@#?^qi7TGPO^1Z35LHxQ&} zVw9oL1Dts86o=aJJv&@nijrO&#O(sl$v7gkHSi zU^Qtro75Wyh%RK+@x!kBWEs@U85V9_KJBh-vpC~k8-z~HsDygPIC)^RE?>%-&40?dw4f^;2|?^Zt=O z!oJp|$2fNmcRsg7l1zF+4uW@%K(~Xrc$dW3Otm zL9?1={@zV4UVcovwzFMW*jQwG>B0xk0eaR%eA`?nOjQo;KmYl%|MV<++H7%z6p*_9OmSECpdDT3x~Wp zCIm#qO?+sI_kS$o4s~$-?gN%qH&}agm&Z*F-LP7zjy+yNT_a2k?&ILGQ=B?JL5JVb zZmUHplciLy(KJo0QkKP;EQ?>;_!g2cPCrxp>~tSt-yTbw-A*;Q{_q}GFWhA={{lNz zPcd`j>0AwJbex8}kB`rev-{X65lQvaJ9&yvbOC?#Cet&ISxwF{z1ToAK~hybz7PXb zlS~{s#`~v_Gtuiu6`$y(DEk;be40-s7r~BO%sg5mkxcRM)&ljWfr)_PaN_j`=^YEwIPoLz_ST~-nmrug!i!*%u13tq+eEJ?UkCs^5Sm(j5`7Pa*RRvY21e#sN^FoVRA}fHg6zZ>jM3TK&){G` zJrN)34y#wm8>f5!d;I+8-AL{bgQGD5&ZkWmQF0RK9OcCM2>qjzEU&Dwp2|_K)@d3h zqU^xo_7RG9(%UycUr(H{Pv)Huq<+JQvWK4W!+fB78LjNT@~r3x(y^}(ze_4VaHoH3(IYwobdDV6C!hH!H%$7cdfRDfUZy=R z{IOw9|MbUnB+~^-)z+dmQ>d=-P5#$-XW|j-27I)gdHzfbju8 z-e;=gNsbWRW5@V3(#!s(C05opNaspaYE2A8REHa1Fib~JAN_qjbVU5P9nUOr1rgB^ zrvJbx{P8{xEG@IRnj~MWQfssp@rvrg7mU!=J3wDw4_#3&4rOmU+CrxF`{L?z^RnveV*IF=SoaVImzGE*v*e1E zwlm<#yWHK^Pk(O*5x;xe0&52Zg-GuRr+)Ma-E}wJ!=uDJDtk1Q@#{yBa0faVKldS@ zjWwwoFQao~jP-`L>70+)@Iij`V=tLP<{R#^Lf3>FA+v zpr66s4gxOu`D?tBv}&J(d-iei{Kv!()?To=wZmU39wL3?gguU}eEhP%gP}vG`Gq`$ z66|JpD1@@Zv?IuFBK-$=-ydUWY=Xy2YozlPs!anyQtci1BM8MS=!+Xk{du0en4nKVdj&fcIaT|`O5kzEnl);1V5s3FNzOck{B1N`Pp=k=JE)V`t zjIO>xhWfjSg?7+gK|*px7(MYJ(f$z*EH1ISmL^xMP;2V#Ik4qa=;-QWpud;SSOAy0 zM{7s{AmQ}JnKYz_^I7h9Pp_7~#LYv`iv5}}XxVbPMXu?KxiUh9;6@)3@J7d@R-bAU%M`WsJe zHMvd7>Y&(lr94@+bxu?uz6bG*`|v@Ma<(NtN&M+EFnA!Y6P*2~R;ncjF82eppg0&=XaXzz8A?0mQHIg=*g}^+Bqg!@ z-5ebkfq2^@#19)qKhQ~S6>*2b+1M~PqL*o(*WPIPE!**>8>x1}Ff7a`GQ4??V5v1G zWG9L%;7Fu4NR19Z4O*pF*${j!!NBj7NUzEXczW_Vh;O_~Ywv^aIi0<7UAK)!UND=-3so}<>#FbnrtDhY z+Em+|ld8-zAyFcY(Jv8+vm+XBRQ>g6Xa>clpvoS4i*rH)uQ7IG>-_9qcEV@mU&bq-;YzUT8q`6|9GlBrPwSx{FWV(UgPp zYL5$7U(*zYrTDe(K{Kx+tw3u`exafAKvg$2$4;?QdwaS-E+#H+%f0iIp-Y>R=RYSf zBiAI!&+ur-q`i(3)G)&I_!`BWw`Dnw~#X1l0`p zQ$scsu}+s{0ss)G`9b1>wJEs`z>B9(ZrGBV-;y29Gi`n!3uT%FQ&5cBmh0TPtxMXW zrOTEl9POol&|6>U^M8K|u*VPJX~y+kITSMDX0NQSrbdD#B_(CQzo>?T^7^}C&!Qp{ z+Y8%3w`x4&|2SBoBG{?8G&aRwezU$V&KA-46X*J;d1?Hf>fv#BS00p*z|qfaAx12& zI;O!wh7E$!k~e6{0@&+I$JbT%&2pLbjtXgHID4Nur;fHcQ}Ha|cAO)JHkrxkIp z>U)Sq)6=#7LDlTMfeHPp10?h+8a=Y|(jr|os=^WPS0I;4m!Wv2L(>rI{y+S&!g0%_ z+gp#|Zi;}e_m=nfqS|G?5R-KF!n7~??9E43x|PAdl~=7H?p#qXyl&HRb`w?&Do;h9 zh*7~D`U^|#1NCmD43r8z7^eW!LE^otN%H1g14oES6;)MRw?4?>y-r=<8Z7dU^?b>EBD;J&Nngi)Jk9vn=;~;f z&qEyTUyG|R(S06?Jia^4Ka9S=iqBN=Bi)l&ZWX*E8}0n7>ihy)i1z3DH?T)+qa09| zA8=iL_OOqYNVT~r1M)R&i*}wU+xI zY{zL6Spo*F`Cue*5~MGM@7~EI0a~pPJ*BcZ1Lda5*yQh5T+Qxk{`YioPQyifT}0W~ z7Px~|YuDckRH4%4?M>dt&m-mF(Qz00^ZA%heW{k6HsadRCW1ht>m41 zU)b~7Kwawrh@GPbMi~KJ{?PnZGYVpbtg)3=@u{rb$UcF=OQ#;BExn{(yI(BvY|00=K1D1zOwC{EX>4MH`M{$PAx)M@G*0~!Qqm$klZe(LDxsNQ|zbHXoF+wHvQOZO;Y>JSx;NW8++zwI6P|36ck&8u1D zJdJv>>Mcrga)>I$*AD#qh{|kf)JelrV6YkczjdzT<71>?2|2kzh~o$*k->sI4Hi5s z3~bOph-2J1^Y8y|x`$_HvWb71S4sZ+bSf$<^U9c}t!H!E)?lD{0KEfr)n5YM|9b@m zXgqP){G=n!3*KNs*TA6v_!bKz+`;PKJxPbInW6n{9^};2+4_@_`O7Ka$j2JH|696V zFHU?Q{$By|B7qP>^XGrWb)1#c8tx zm92*GN1-Plckq`_7MjI~(8G@a3C)4pXT!l))?Yqi!%xdX#J8S?AN~&(p#Nhc^H+|w zQRiaJOOKTcUehBFg%+ISV@8yek3}T;ZPn3LfDgNkqS2u?)|y~umP!l8d2}47bij9V z14+cXhTd3K><;L3dKAcv!}uNA#UMrftfuWOu=)T?*^~FdusMpxZ&GM0#UyV|aYy5r zCQ|4m%~bRQcRvi_+wVT6@Bsd`={zT%5$XS1l|{KY$9ADpK4~7kFKl zjVk~Y?%CI4s43$kW44m7Hj%jYHBkxQMu+LmnZBcg(~r&K`~8%y4D`a5A3)c}I7>YW zXa&pa|0ELIn@91m zBEEga@96mK*VaJTpcmxFr^siN|D&>i*a2!3cln^#dhAs$T;1G>Q9jpXP9@1@)Qh9# zmraf4@zmd!l)5&h#uyty)*>e%PL{}ILWDNv%!rU8zr&B>U5PtWsTgABSCvTp%wj46!RF{9X%@$WAWsI2SWJ`}%t zo@96SEsUwROOzsi6MovRelx5_S1i_LP0#`STRkNH(c+R@s7VML{&2GX9+Ero!cc8< zJtboCrbYfRz z?>FRu-8y5@PnGPB(3+1QAGaC$o=fh*f@W8Gkdt28wBzvSe;w*))@B6p=T{R+eWwcDiWEFsZyOvt5kX}pHb;3E_dUNQU1%(Pe)TNNLKWOcOMoYk0glYblR8288^Q-` zp2zQgy%!z}SBX9uwyAm@A26ula7)6%OJGS))WV`LXjUx`VvLdTTHM+f$r2SG=yV`R1@85GoP+Wo5)o0x zA||+6C*PvFp2y{nDo5=0lf^{bxgeDDse9>}S(ZMIq2KJ&q=n=p5tnQS_u2Exnt)9c zj;%tV5~fRIjXr!U)B*`tdgy2t-t1nM5b6QKY}KtT_V4{I@C{vA69106?PCBEw!t_s z#-WBsxPNDs#Vr~n?S=Kn6#-3>O$aV{S96XZ41p-xY4Gj_(2qouy(qyMj3-2dru*`Y zTy!ADOxh=6wKrh4Pa3`7LK>FapUKM5J0wiJl1k;aMSOUAS7ttLp29B$$5H4z1N@S; z=BKB@a^HPXW9MM9=B-GAptl>v!mQ>J78}XlL{wsz9sas|WAqZS{(8rQUaiIPPhz|< zqLTgWas_tOcO_{74SpD!8F_!&!;0oTTib-J?aF!_u#NmMc|B(BgQt!}G%yDV+Mg44 zzhbS<^|W=p@dl~|kaU^%h%GF*A~((Br)L8C9{Na_L7bi%{T?j3_5fImSsotnDn#+S zFLsL9vqn~|(4%J7#R!Rp23Tp5t+t8KckHsRKWvovcSTuh>K)V;K;OEIx!+@lG*)N{ z5YpJMTU1<}kz-&&P4u3#&%y`oA5u9;1?9OZLzehV;AFGn0O}*sU+T*t$A#-GZvRsWvq1?>Ve7_t~=n@R+r5! z{X%@HF$r^7mwy`+i*HoFU$J162fvW4jSupt`|wOW6cFyE@kiLxlV4YXw~H&va^iBt zT7@%hN>DZg4wkvl8&>$rv6~;CjzKYO_9lzL4S_e9FR#A0iveTJFAB!LEtBjk*||h{ zhiAvAnC(8BMxuF-OC+<(JlExi?KP-EMRZD$AXzz>E< zM%@~nb3l4tq>L#cdb7F= zRi$gfpQ(ZmQlr47*g7uZiH%qYnz$Yv4um#a1Bfd8rw#!l_5Kx>!(;Y@j~Gn-qwO^z zvPF3&^XD0aHU-QXkf3Kr1hve;B|~4^0F~dT#}`f0qI!Z5qQ~PTrsZquTSf=2M7Fn+ z+%dAYzjyhhRoUW4F_4&0@6mRzxS7g*PbX>Vjny}cnGBcz!;K@&Z%QF=$Q`hAuRCTh zZ$B6j(u7ou&`w70dHgoeMHAJIC&mw^$&JL;&EDR;Aaz{JFg7uZHW!Mvm$W`o zujd7<Gu!NB9H(_GKS_LdIp$X4Wo80LgqXkW+T57x`>z;*&X?VaVq9K~46=h!LYXb85qw2Y*- zIZb!pH}Hx50CF`OC%5R}Y!Bhv)%t7ZnF9Tt6q&R#>*(DwPBXjF7DU)hS_45zcfeNd zlgyNx{1-(C6yeF;RwKK!djGib17FJ!a=*aA!!>Ns)T7oj%@W+N^3TloP5>T89_M~9 z`1QrH3n@J;E;W|R_Z;QBV+@B7HdO&CgEoRp;wJ=b*0#|n&*Zs&Z!(pM`n!qn_IFQm z!-5xpAAz`!)X z5x84_eznaJg<1@ylB3uC36ej2GxzcqS5Rz7C!_Rpa?k zj?a$>GH14sN$UYa5^kR$s3be+tg39d zW)5ecy_{A}4mM$rfu!m!u=)HFRM~+lT1kF;bO7 zFBs<(6ddgtZhqYPjxV5gF5KFbRa#)tqyunHa_S^BcjuE<;I7q))JX#nW3k z*|jsU2x})Sm|$Lk*FwO;qv=}8(l-4`(T!UqGi!IY9}{qXYBq~t&(3)LwA(wYg$0x$ zTj`ug`!1^+MZ+mgxQo1|d>XQZQO*5&025!d@UW3|@BOSvjCmC(hKbJkVw`ge!0R{rmdd2-@70HG$$|1)j;{k6ZoI90iZ zv#bB8M+92~wZgGu5)nThtaBtHa-Z(2rK4Z2Bu=n5aBD&~7D|@e_}cXAqAD_T$?|ZT zlr7LLdb3oy&JyT_EB{5Bz60BozI}LQhsN#LMeJ>Z_2Y86vu*$fd69}(ZFgU`Q;WMp zNMxfxSc$P()cQxgIDmD=&@xlKn_>tS6S<*)q*>|fMbj;DyLvnF$M$Yw5%i+SRE*k( z3#RoS9ix4+DBW6vk#0^<-C3njxq+{t8N|?${SKwuDCS?n)d2&&?&_!V(%UYyVG3;4 z#=gZ3(l9bMtVxiZK<^zP2d_F1;cUHgq}XW1gt02vw0FBs?OS8+i-g0Gt|y;WOMrL8 zWg&r}|GSrUi9DXHU!r|D2&34 z)o%Y+{G@Y5i@OnhgFWUqJ;N}WjRUeBPL5d|=579mr|4re0F7JLh{dfI#w@a1|<=wxhT(WH4^G7^h)kb^EQ&`vc=bsdrlaqZ8 zo!ELQGk%5@?J|}SF{r#W7C&NkofePT`8U~zQ<&Z-YZx2~_8d#n*NXM8jv8H5ud4uO zSs%(W1#agFee`WF1eLDZDE9`>xp_poO|5~5!#sqFxbKjz^Wx6FAU|ULuW#aax}s9`A$*3C zkBM!;tvU5C#qn(kp;ph22*Y9YI+7Xt2cx{N0yw|;ftSpFPlL=Wpw%y0E3*x^u6OR_ zm5qgeabl&-Gl2TdE#i#>11kjIJrF>niid5a@F(HkQvC|C*(sczZ@u4FNOX-wsg3J} zTp(IEFRFLH#VM6$m10_a7aq62H+%nW__b5|`}u+Kql)`Cqdi#`Xh9~>e=x<+t8rWr zW3-)UKX~S@;aWsi4j|a$ovssRiC^CXRabLAIEVf@=&|tHz~yOjMQjVpiNnfl=?{Ek zPt#Sgjp(#(RYi05`5k@q6TMEqLP>mQzLCbnn6A^ub~>v%G>6c|~}<-O1J{L>=VO%k4-hTAK#BE<@rJv2heIQvf++HW32a7<7CT;3$JguJ{lOQR zH82q4-i^yTkPL@=h#Gt0@#xyA<;^&|eJj7NG~8_;>ej*BZN~XkHqG1l9;0`A)SgXj ztB7gy;(@`tIhyOYkq5UZ{S)DVO@5!5+TX()h3riJ>399+FT1k>CP3V*QYC z@4~}Lxg=TT359R@!J&Bnze|iG1p}l|0nl|)3|g#jLh zlUtufd42z`(Zq7zvcxv8{BmodTVMCW=sk zJ(I@nn4q7?-HAmJ#qHi5O=rM+j+gJq<UpC#%aGrvrM(IO$#+A}n+AEV+_ z!|9c4ml-pDO6^>mohT(Q4P3WjmI z_^29Wv$v!N+JD>N7_Ajal|VdyU40+&9V9BbSyH2sa4M>83CbLy2z=RYj&Z1PJ)U9J zV_qxn(~sPibIFA$6Yj}_nj@+SCvp4I|vOYt=!goS9kZ4&Qv+sxBB&bP-d z|AE+Ai>nD+6@Ng`nr-^aQ*KNB-OO2t2~JdISW(1Q>F>_Mq|UXnR|^&C&$@~6C7ik; zx?i!4S_it`-mnT#ArXZRFGsJ@@LsY6#O;HgH?*ttT{7k#slo-IKRl67*yk71gZKhq zgI}Xn6sS}LhJHaG47>2LI1Fy6FLZ*}~U-TA|BlV81JTa<`^>yz1??u_oG}--JoZ`7%1*Xn#c`UYV1#rh8*e3l7K@>7o=* zXQTUFd=DI!!+$D4Z><@j3N8gN&nqdq@t(au-~Y&t`=pz0>{*p!=HECg^aoB+EyFhR zVud2t-zUSD`!i1w?O}_m9h*{UFaP+;Z@n zpumF}>!HKGCx^=5hbC|SdF=E4PlY|Tt{1srB7-OCWLwnH5qVUn==ZkkfY-#Y>j%h{ zy9ATm%P+=f>Luv@PSCSBxPznH?=i;}&!%7Bgz62MEsw7H`U)TD5tC+*C%+#TLpMnn zMUaec_O4khe0IN;_|$0w%i{rc=S$k;!`%dnu4r-Vbr_r8r4$qE1*c+tca zkX-txtezj=*(|=56h8rmeCo5&NKpC}_T-aERDSXL=2jKQ!o|y_AR~jGeM^5iN@pq7 zeK&&BJb;JXe+|%|xISL@AM>Rrz7(uvNQ5tnGd%cHUY-*5exCdAbcc3aUOzTDUOW9g zeBDvdN8KB0KsUrvK+Rnt&6Qq7C-wm8+WXb)Q-Ul&e(ebHYJWBgoV;xz06xm^;rSjM zmHZiSxp-Y=p;^jm8Mn$cv~+hw6`h)J3V3A;>JzxHTBW*skwLKxI)!rP4Tvq-QoHq* zNBY-aY0tan6s4x1GHJi5yG4DSJj<;JrTXFHI;ag)ZIQGCPJ!d%Z}*UjJsMlzwXNC9k1@l{(4BMey19z#oK00^ zt9ua*#26Gcp9D>vH_R+MrmHHJ;Jl`p8FkgtbMDS|o{^C&7OCa|>+%5NG>7W@TwRei zTutoZz5Irv(6ci~1<@v}^?*qg(K_uisOqEM=EV53(zx94`BGZob2Isjy7rC%GPc3- zpTf$ZDDf8{d$owUzeCPrDPgMbF|q*0glJJJC3K!K`F6-%g*Kklls5g|EquejoZfol zd&WXaV`^n=4e@O!rlNile4C(u+1qYDD7!UlW{N0Mk&+UP^+*8(ydx}-Rd8^Md@+*} z9iQ`mxP#p)%A_Lp{#VG1nPH&3=_K5bnCsW`{E7}B@lE;MDr@FO%u8#?ww`T8Yfup& zzmE?4tn^C!@&dp{6F}imR)YFvxTAsLrD=4TQt#eZ%%1sCM2Tq|gnA!(_z(({Ti4v$ z{VPJBT=7!}@1k+b8*}2$w(TofxH<$?{JhgM3LW)qN1XwNH#jEw7F&JzPOgXZQh1&f zJa;$W_D8tAxW{1NdgNe>GHJ6JjeU*;-Y*d*a!>v!$zM31uBqx{Srg%KL7)fF@ycnL zEz1Nj{znda*>nX81#{tez0(c+%6^jr>lPMa`J}puYZ77KD6oI*kZ^s49*y*-MWG5&x@^uD!(I-A z3Qt7OHaO7u(=yM;06Ha7Y7m88t2LQ`?E6wu)4A7i69H@^Xf8PLkeBWbT>7OP-`l^(bOkt!ZvX1s^y>~ zL@sBK_h%C}U0utttiqtin#BD-!Y2rEDUv|vq)xp~&60z=r&lcx_o$|Ike_K#qjQ*h zcF=c0g2Cfqt-Za}bVGSlsG0m)U=B8^vgSvF_3y1ZI4laNgU@Ca)fJx!BR}a8SOGTS z)|}ion(&z6u0lITK7fLI4+k8ZFR5`X1EI%9mZc$-=uHEz)~{Mt_^(!z;02vHDZI{H zjdFBFWnupgRHX@)TCt8%PZkA0+XviK}uez&AN!<4bSa$=QTGy(sw? zS&1*ySL7GI{|5_zRG&ay+tT;s`LTEF&u*WL%H92pxfG_)j4;a+ z**hoK#X;V|P`bH0adoLImc?E!-?JQi$zB@W?pY=4A|8a(^30$5z%h zwaD<;VO2Q%xxev_Yn<2EYZkpc!K;{;jUzoaw+V=wn`Ri!=G~ju6w0Q$quvwbn(I70;zJ53|MpD&Ymx(MWsSTSIaEp`&$9Frx@NF^E+|(!b>lgZ|#okDb;scv9nhi}dD^zB@ z(4zsziChB{T9WOzWvuA>q_NOvf|3T~5~d|34DcqE&fcH>6GjyhyJ9BmcW{(ZIeJ?` z60~Ge8mq47YaVs<3tw#rGs%>j2;*_J@st|1x3}V`RMGpmw!3plrdJjmNF`|3s8?cl zw)N_E@BK*uOL-7U&di=3t?YEBo0bcmlsB!2!pB<7BPMBI#ihMIsuHL*fH~6ELXg*p zFhECL60GEQuKO|0WBSJ<+*+d+m?k4jTu^@Jh$L@LP9#fM&fh!1XC2&0hOLync=G9& z*BN(bp2q65REMh7sbkcGow`eLzm&a$eNF1DOPV&=<7mYUr22&YT$dA9MYcz8l^)HK zs8~_c04%KT`RB{9HV%~EpUz6j@;`^&SMgBW*3QuD@ULlfJlIJBjZL!E)a3MG+2_CR zc(dJzgnBugqGkP{#>1$0wM&W(b+KIVEkXHv3F$NCpr}4uD#f$MpyvajgHCU6k%(>M zez?bmPO-^r{jTdsd#iVvhUf%c4+jKk6E|h5Jo#8=WawLZa7}o!C<&wvmhfOY5@!g> zij6yt{Qh&wg0GUjwIYFfH_LUbji4qVf!v}-L7r{uYME_4LNhfZ_dcBD&a1iM=C^)5 zWLoN`dQF)so`1 z2%u-5=D+zEE^_kQHmo$S0QZ%kf{ z?;hJLou3m$zUe!;i`NC^sPMOG-ha>pXK_&CYFlSl=HQh4psQA+lTtj2f((mSjvGw{ zM+a-13EOi_L-RuQ$%14}!Dq57zOf=Q?oMc=0}Hq#CPd2~Vrn5_$jhNrvs^KBg$+q* zDemnslD$z2WiWGD;Bc-baq_@+7*By;fki%~EvCr)X<~{(fdsujx_p4oS}en`j>Ej^ zB!c^$;n|vpyL*R3o-qXy6(1xCJxF=1!|AQ$9`S*Dh;4*eNWg76_MjX(KaEt6KSeA& zhDE|#Arq&S#Kc2(^$F9|lbOTlT&$n=nCH)z=H4i+{8LyTsh<0a7|sKuR*PLxl~-F! z^xpeP|MJs4eNR?-S+~RIs1z6kTrKVd3j|OH!6IX-Wni`P`|^1I=+EE31r%(A#eNo2 z$^71h7p+YBn`0^srP>Gni(j{sGY5SUlcW1SD<^gV!ZtVeB{Z;F%NzYJ=c_L|N6SZb z__)B&Lp`+UKj)5_MU&1`dLS&TQTVP33)A0~RHJ7wJD+0OJd9+M@r2^CA=&9R+2_ifmO=<>bfjyMBtLeBnR>-m0teP>E zbuI1VGp-TVB8pPZPNc|q?YQGve#K-?T2R%N6oE=6-~u1;_W?)2bQrle8lMJDP)Va=1fs9ftEy)Pk8Jz%XanBc@3Sb( zYFkR}7X)AoY%5Zj#$vp@1iiPVxsgc{A(hw3aV zy&u9T)VuY`$^evuVTK$PY#{>Iap>I!l3qs47KYEcE||dx#e;J4k;Ks~3E+AfjiWqY zDx|vTkv*|BkDNc(08DgTm6*P#ZtiLHSbLVSC)tq77>SzFsQI`etBa~%bx$AlmTfOE zs}k3cYukya=hTDNEfG*~W=%OHJco5yQ$<0uFK6#t=|=RzS`1f?)169Nc4WVcE00R= zXcK=K%YW!v2vR!nT@#%}w_urY6;kPv`u;nosmZ78m$vD3`6O`Ri7ZTy;p$8~k;IdT z2xMJR4b6cy-{6qB!{W~Rl;s(hR4GshKfjKi;?#FMX)H~yVI+-h=00_Aztz)*CO);z zM73){v|hjp+}BSsI9>=Iok#w@((T>TJs{(MlSp6|KBpf>PzI`7xMsIRA`J@${<7Wt z?~^oyUrK)AmES^=tG=DF6;>^W-%e7&$b7}XT&uG^^2eL66U@&;x|Aj&-A85N$hN2I zTX}8s6XubdS?(4to^-8iOMX}!v%@z?Ik9NCNtvNoylgX<2t;VgQlM(>dnH~V$XJzR zIo@1>)<_k=2od_$qQ7ttB5YYv5<(diWb3rmh_%eB6CIH@wlrJFiKQ$>*8OK_>SUS; z@l_H}ia``h&MAB@d)eAq7{q+hAvQ1Y+_recNc*V1DKLD*Q7rhQxagz?8q;Vn@~J@D z%SJ9HXa~Qb9aK*XbqrISzU&!YkivCfBM}p~z{tq17?{vbcBhMuyG1PgOP85x=0y*k zlYeFj7*Qbk+XNyzoqt*CP>;V zZy%bhoJD+LaA9EJ5u&NcdZu_I!ln8=v38`18{bfD%SCl^Q*UXJ7#zjBuUr)jQ1VuB zP{E^r*i-Y&x_P3ye+Ju9jdJmUZe1uO7BqQQKd8xS|DjHMebA87v=?9&0z4P!J#jPD zfnx{nPlS9WAF8?=BWQ*h!gm}c8;mb`ov%){EBJ^p%Hi89!pOxj;g?iu@^Za`Nq0~_ zYCCV3D$O!3LWaH&lglH)?0y<%eMG1;IDOv(R|q z#`-(L#=agf{C$=DF>mGl8bS|H8L<6~Y0%BMtXO(_p*Fwy?_B*8{4e*TjV^xo?7llb z{aOLR?l^uO1&7A{3>dy>;jh2T!fcy+3jD&X85Ee3deN2>I&N>W(Wl&5FcZ<6Cu6m| zQ3g>dkSI`Kp}d6%6uxq2no|_XrcDN?-IeE*8w*YIHsa>V)=A8}J#47QQ`8k}IDq9p zOEmAYRVmA&Ev%wnt9P-%G2I9Ye8lzS@7t4Ueh|?)VcmqApH$%r*VM zM@;+~MfOwloQ#bbdtvNkSFw$GM8Bte5$f;1mw((?YAN&?}jJ!&G`{-a>rovGLQlZ1ur_n`KyLrLz>$9ZgCwXXtI<7NvKq+on30- zt9^fj!{9J7hF>?=QQ7L`o`Dl%_lPZ%0akqr8t_}P5?}mbGgUgY?}_d(snV#!8j&9X zbw<$R1j;7R;OL4yDgU~s81f|9J#BwA;ia!*s_XqV`0T!h`+KO(_pb1T^qg!jAQ4x; z2AG7eR|9caWDRd*kG2ZF*kZa=f&r_mXlXGPNDS zvl8oxZaL8jD@sy&Bi8yYo@W5mOHI#Wj4Mcat-@)C4at56zwkVN#7M#bBr% zVjntG4V>3eA`?B{u<3(P(a=>nx`2ITC4XA>1z0V#E4prEm=%UR`C%ZcS#u^t2exEd z%$6d$=GoHbKtzaq575CAtjhxhB`mx6yd-PSs~hP@t~-eSsPD~%%a1uh+u&x*ISI(G zskXjV(_Zb9FydvFBCb%yaH$@NGdRmH>Wf}wGPM;{7ygV#7X}p%$WFG*t2-4iKre*v zwDU2wwho0YtD^o;mq6dnG4X{;)?QeW3p6OvbL6~rou;O(D<$Pmh_Sn|yeW<-y%Yzw z>pkSID(xyc|;@0oM~dfzyvZbkCG zW&MzpYx2ElUHxmn1rBHZ8iB_ikc(PuU@4kJ_c zhgs>w6DRX|g4d=MTK2t_?E>i{xU|F5u)-0+=7DSDg*v)Oz+t7=?hBG+)~^gPopUi{e%h%CkEzPZ`{ ztS|N{!BkKp8;nb^ zVW3=Ed8lM>l|^?Kl@q|B|IU$cnq!(@a7(xj%|0eESTTB)Hfezrn%WMj0gjp@!8&2i zFQp<(jv`GYz(*5HOR_6t*Pz=2wqYe04RvP#tR{cM%&Kn|xcJ$+48{1l+4&7HeyQkX zK&ne18{}^PtG^$&$rVE(3s#R!ribTqu;&T;*8`^uEMq*yH83HrhC3C6L;&Y;X*oSO z#uRGi!5k4BnW_vN-e*iV7Vjg;)CC#=fGCKY|PouZf>=yx}ms+ij&I`SKkTq zT|p`)SN88JIq}r_gxGU-W+VBS{F>kd>1Y*y7Oi2oH-f0d1?1fw)2q2Swe^n~ZiRtr z!*oqh$Q_qxmwdO@=;av^e5@Mz$4WX%c}cO6jW++@F;??Dm_XcIe~dO?vvFx zhyJCOCZjzJc}N?vGf}}7v@GCqMdP0xtNAfYC(c>=x3&4XSxF{csAfpvBcWw#Gbavy zV@I(~ne(>DH#dIlF_BWuxF0GqniY##Rrz7BU^)0;gy^}r-aHBdT@(oCOj(?5dPJFm zq{g%owg>;%Rj=L4@etAVsL6k^vLE1CF!&2o8hN~Kro^XItrU4-ig*7hQyUrKEX=)y z(#PkpGd>-WI7bKp8hE>A?|O=v$gQ{yV$~(n~>LwXvs#87Sq2L=gK2yM>4xPS1Tt zv1+KzZ_E4&HYM(sPclhanx1!H?ahB4UyC(?y@n#My*w!9_1<;5q}`^ywqC}N^8zdu zol1;$w!#wST=^t5Eq4j;cCp;olcKz&SSJo)?$NOkwtVWZ%D(udv@@So&IAZ1Elg3B zl-X-)fIXip3ad&pGJn1z)bR$QO&${Xq&}!%XmJDmR8IJq=dA*$VS|ka4;xGx6$na2 zTFet0Ot3f}xrGfU2O}%0>uLz-%5jG*6Z@KbSjNUas}RA1d=AC@bCN`F9~`cx4It~4 z)BYbzcCn=wtXc$H6}arMtnG?QJ2SENxnY?nJJzFrr*9-o;y!m%Mh)eBz>ry^e^i!E zBo#Q3A(mD?OB~)E0&P5;mFcBE?1@k}hY{qg_s=_rX%wqY>5}(Ropt7PFYRAdsZiot zdIv-;?K+_KD?9AF=rNNB7%`q_`nH3pLEz7oeD-nsmsPmXT!7F@NmJ*l0M&TWB!>3C zY2nWCFwhi?iT_nG2Smr-asUA+;~ykH)e4BhLp{RIj|#iq2@F^p;d9hJyYV=4tSQUv zLC4>ww2A$?^V0rq+`KRl)FJBkuWNI4ecOVXtI~DCwfdDhIghasNcp5`qhWJYCNyq4 ziSk^nk>%egKuU>B)(1tg56jeH+I9Bf8ag5=4aswqc|cYAMU+roqAo>i?jBFs{q1{| zX}#UGcYU8FysDkXINW)x+ALcE1E~=-y3UKZ@ZEiyZaZ2jQePF!h?thLd5dHb33Jd2S~FWN zriE{2(>5BT2-uBecJM!9qothAA90>NUBfkKBSsN2BbM0XNh26(A;LKk z9@qwrHW#P2d1aUS!sgRZ8ADBNS}8X!zR!4H(d@Hl6?O^!ydAf^pE1t-s3)c>306ZD z`~o)nv%VXH&NR?<15t5M+0skz>9@Gp-$aSqy7%wJ@?kZf zM>P#{sT7O%2Z_2|cs))^tG&o#QJXTIOt8B-&)tOi9AjZy$6wRI#ShL<>$77yP~fi^49MlxV$TIxMzPsYg#CJmYyM0vqOAs+p3t3X}1fjWytS&FJxDw@)-+aWG zo>~IVBbpicieMTV`Q#=OcW*NMaFLkqp{=KnzV0T1wx>(WyuqJBSJT8+XBfM4m)kQ@ z3}+SH{m1EPtHu3FGr&wRHB_}gzMx|YB9g<2Ro*9Y0|8Mit}R&9HreLW%~vTVU_ zml4ezT0Tc!(=m!E*3Y{exkQ-x2SeN*8fQ5rQ{LIZsnflbTg8Jl$322D4UK#v%+%c* z+`T_fDDR+QpqIYxW=dc69$*@nMxJy=LpMOQSg=}@eFJuaAQ%5e5ivE5LM}_;iJmx5 zTpTSEVtV*8|M>q7vZWblhJj(2NOlkPZM~d2e}QuY9n=P$uXVDHUPu#LnPGJBF1Kd4 zFkLltpEyQGQzb6x72CR|MnNr*&+qZB(}`7<_My=4c~=s_%w@?JRMhV#)YQquH<)=a z%+1kdGS+I&zWo*_I_nA8k8Za3kAq1*9br7=5xIIohE+2J)G9(Q0*$k=O1fkgn zY%H&^9@-)G@dvznycVmpZ;H;5g{c?FC&P^2zP4vyx@hS+#%?xL)|gO)l! zHglKQ{C!3z#?WOePM4h$$1imwJj&3}4INcCK@bro329%)VzC5JmL)_J3{6MZO^id_ z(NL3YE1 zyk=mN1%8Gn|8X!4bYq{UkAi?GimzU0)ig0R9YL0mtyWCYN=5St&b@t(vwba81RNNd z7%Nj_4BfcF*SDwG3e9r;Yb%P)Nkzpu%3ip<@{mI{3=HGhJzfN{*wf%=(W*7g$7@y) z_jqityj2tdL%w!|72R?ikWrlRU*kDT#MMOzPdQJwHD2hmuSe!q#fNm6nkfx?% z3Lq&K6jQ?GE$8^VzvAMlPMWIyI3<A7pKrhDIU1#p>u6eD>uqli>p1w)31le~!LJ|DJC0FAt`<$4~ok zyd)jO&NML%l~iV z$zqZJG#yRX52b*96krF)6n4kelCJ=9@dq7{Mlvow~rsr>b$5_X_J$K2J9D1%-KDQM z5MW~JI{GsPEeHaL;(;>yO;bb7{{QT~*K=HFn&$aCF1=4AOu`!i^d#s#MTwHCRI2Lg z>hA5`-iY3dy_vg-{bM%vVs;|7FSaLUyJxDZYpO~TMN$;K0Z77o?}1Dt(&w>zaX<lJ1umSqnUwXAiS zBT;((v$^h1Numg*iK*KGt<5fv@aWp<28LmxoAw7?P8SYEMilIKr)hmBll3<6T6x#d z$S#lZ@a8xC`I|mgN)oN7KIP<*-85IY-|`-{00YCY<(hxG_kO-G#yJ25gZO2$OK}wv>!jk=_7k- zt*^jIp2W;B4{u%Lo2&Qfn_i^r_I2{QljhdHr_Lkt%&|7F_pDzl@0PO5Oh5RN-~H(> z!%G_B9Va<<@)&!YLbx`YRr5w+t{1kNSeAe&+B0Ls=lLG%_frx@OvAv`bWAJ^!$4Ct zOv?nTL{2T|Nc)HU`WL5Y3VjzwuBeRD(AI)aQ2E`(hxAPM(c8O&wzg&}eD8~Gwldx) z1KtrVLq*jMBu|9$cn#H+J`^!bB&e{QxJ_ntm29q(sK@hT3oriTII%1M03ZNKL_t&p z@H}1BXT#z^}4XzdYMW$fLZH`ERHhCLdhl z%RgV?YR?kxibjtA>erk+yoH_UB)_)A-1rz%tHn*77H_ngcx?l9(H|@r`-31zPD0gtIQNSXd$KytNFA-sbyURy zxE$-(SgBy!fiqOrHBcM+7yj$zKBiM+4D|KVy=w=j+d{bBa1h!uHPTBn%uG(Ql(PfA z8zD*x{#YG#b=7ua@2ytkX`~khxqtEB_9mAXwGR&gLq@etW31C?n!xY*FV`kmTNt3TYY#0oRrup?{yk=>c@i@dOwKKl-h`iIrse+ebNixcNR9_H-7BA!3T9%!Ze6(J` z?pksNYuR_|Jb|V|2;MScHO=g9DzmG3L9Rv5+odY*JO=FK?i>riQBL$|RZSr7X*ny+zn4DQ4Re1V_$__V? zcoPlPG5pWe`?tU{Q46b#c3kH2r5jv*IEPTajpOG&<>%*i6Ll-^u(;vT@4kE#@UitR zyvY8xFbx&0n4^jN0Pe11Tks1Q;L?&llFa7ZkZ}gO& z4Rb^A|9OR2vag2Sr#|ODG#n+bmdIt2B<5%6?H*vd{}vMi-Q2r>nxFmrLyokS<9EH{ zY?vPelkD;gGt*Nntf^1gg&+{9Xr#Wjn)2Xto;AxvQ!^}&_i*jPS6sR?Mp6vX_QA*e zTEl;`3Qn1LUnyJO*K(`9w&+{A>gN?VGn0wRn*4I`Q!h% z#LeL(3!|NUb^8PU{#Xp>8xJ0vlyWH+hkKYz>8P7j1UUT>DjRlDAC*y_nHgDE`j{W3 z>)O}+?u!nl(-u{GPV(_*pK`Xn8lUp6>`P(8{j@jWb8qQ}e+rLYr0ah+HxP2HwVhqt zTd8?!R*8fthuMB;KdqySOw5lkH#5u3%o2K|?|r~|3*-I0c~=lbL{Y#r?EsQpeXgLm ze7GF2X4utE@9{1mAxZ1xZ`oBT&#yGHFijIpv#T}*Sw<3Hvc=fa$;|iD(|MblLm503 zdpUUQ04-JFEvB_?0V)#@u5#htDATE@Jr>33=h$zm@%!9wF&SWCs2P^WySQNQiH7PwTk_CI|2H)s+DjGZxLqPx0ZoBeZX?A?$OZ z$RZdaLg5IZa0I{SD=yp^X6oTJuC+7~_Iqh5cOg3bl-2FzaI6Ij3B~2b=TYpcy+@D~ zobDi%4J{n{;2^gi&M{TYF*h~K@@krvDmTg-by_X7QikciJ6yQ>fQeP@sZV&qmFzk5 zE6Sqb&65F^iJ|35CuZon@hvy*_Aoe`B~ZVI!>7-3>hMmgL+&4t2#}CvTT9(COpHfW zjvJaUz7Nwh?DxMQASe!GQA89a6mL1ryZltQ=pZ|By1n?^8v{H7g6zO0M`_%(hkXlk zbPX(%%%qr^nq@8DNO@o@C7GWGgJL$p!1XV%r9X%no&O>CzpBSDx07bO&PWJpD@op~&Vzsdb*q zuFlhS;|kYqKV)bwhqq=Y2Tq>l%(30nMt$!txg*F(vS?TOo9h+GFNk26rirGSb~mRi zKl|7%6TOsSWpRtoEDPg(blkYXjgA3kb27F2k8}3iX^!k^AmozYO?M(9f*|8i z>`oQaFdlcxJ&QCf%R<-fN@YX^QE?zYBlaxH9zqqhc*0ef>ocZG#T@Mi_tNq06|UbK zW$gY9t_K5zgJ;;cE+P5mVDs+k>>zh8Ugpkt>M6Sr1R4(if=_*A&rAkbrbaQn#8}@0 zZhU)<&cOvro+|dWALsnJ<7}&XSG;T6G`5dycTL;8Yj?vx%lk1c6XTJ5mn_>=%9c(( zIYocxO*)2>$dN{lojFQdJc#$LS5iM8hL&Zj?+zEQJ!CYo3Gap~*nRp}1jFHH^RAjF zvpPrD^>4U#r<}Y9XD@qqjQ*rqLZe>CpmrkC`WeH z5OBWbBCyAJ#JhGkfMu*ps9D%?s!i9}aV*0$5hMvoR*c}P?q*v&fNbPRuN5AB3cZviTPWHFm!Y8+vaGGG;gm!QCGDjuZT@mtl=4~9 zt7{}zOW*sSfZ{U974=Q458oI}jr{5iJ$LVOuV)4$yn}5!chFR(P|Tz$KK`H%dX|E! zV^|i3u2RfrNT(fOIB_`KI317}A7prBhNY}T^S&MIZQn&xbrjcQ2?=360PSMO!2?W> zPcb&q$-?v~UAj?Hwc~1rgchC*<sv@GHXkVZ8$c?trN->zxVgI z0gLR)91{aW^v`9%TgUFh2iUozf%2g9I~tQ5xP1|-o3>L*&oVSP%lyzh-CZLb*j`6t zxeHlTaC(C{y)XJr5vMOgtf7sjvaeZ~)5s>1tmX2k7H>S@W?3d`F;6FS_6#WoQ%B7um>hh-)o*Ul(K|)L@X~tn zG#{Ng!tRzhQNQy?k{J1+u+Y^KxpbOja&>*c^hSt;vISIa(@kLyS6!W<=k5(|T<_%m z$P!|>j(x{Yar$^WyBf=J%Fi8<_+}x<$chuEOSXe8*$l zy_K3W-#eAe5(EcMhZBb)Viq*CVhQy*(v+a1>qYW;n=fUj3#YtEho)ts6;jNN^>FLz z4X)kkV$H*||_Tx_7` zlFW^E^X;Xp-0PcSx#*Tkn8G95< zrC8F?Gy_3)<8Zlg3c}{+AV??c$)?k+CR3w%KYorx7vcrkf@#=+NuL{dDQ44w2QmIYtOAl@`d3AIDcRdNY zG&M-)jq6;w+09HE%3Jnv?DT0)w6{_j@x0TybAqVgbU19@EtOD9CDdnXTmcy9T8Vr? z#}Y+kmkXyPAp(Nz!XI?K(Ek!d1y3YSb!|1}!9He|O03S!kx}MH5t_cL}P_%h^Ga}(bfFm+1V1XDxzxqA5q9sM(;OdqW$PV&*&W9(|KAnJdYyelDy zZoFPwmb6qVQc~?%me1wgqKc*(;Beq@yK#yFvLxYj*#%&N0B*M%heLh_{|HDdXIH;`AA*Q8SV4Jtl$cLpGLvC( zdX7x76~l7^e}+s@EwyD1#J5@=Vv=n2G9i% zT=;x$+%5$(U80!HQqWBdo?(DlC5pv7*{p^o$~dEC_#M(K2P_5IjmzaD;FS?FCVELl z)t_HAy|p0W4pegBv;Ud$6Qxb7+MT`-RSm99J3Z9gA|ns)@a3Pb@NhhV?u&Euqw}0Q z(N0Ts2(R;9NM^iE2!Kpk;~viab(o#$(kAnM1pMW7RL4C}t+q@ZJv~Lol}lW>beqA2 zBA)6UoIU>`#}90$p(6MLl4GwE_W3zoZhRgGqGh3`6694K&4SHS@+O9!C6g|*K#mM43-dhr{s-0Ec}>!S7W zY0jKI!I52!!~#E*=UyKK(SgU~!sC{)QbmgS9Qo%}m{=-m$+o`{6&zkaUWf8M8_dE~ z)65QaaOtZn+`tpZx>T6FSAG0>lCiZ;*-x zH||YJF^&8(6FqnM>Q7hb7+yg0)v*8E89qLHgl*MfeD6dWXd@&<$xS5ULXicGLXLc~ zNXZ26qhix1U}Bkhve`VvqJijg;|>IDdA^rE5dlH=602{fp{9ax?=%Z5D=aUqkTV*2 zVO_&t1e=#)jr;lNH)ZTjmo}9N@|V|BSN^nZZJ9b+dXl@BFY@)}y9_Or@Yd|)gYzG9 zyuFRO^1znhU6*^^M>b8gRFa&kJ;%;7F|-`HToK){P{JX+ZWnTTj;Y~(9*iuLclena zxW^xpLpYW1bv#%lR+ko-SSZSHVaL&veE8vM+S_W01)T4Aj|vE) z6OYG@$0cK>AMx&UtVOFxsgxs~Q9<(H^agC+eWeqz3uE1G4_>znmWrOwqZ+n-{AQnW z32&r^1HbqO%1&yiPo1lJaXC zE3*$Z2xtJOZFl*|LwymN)!UuK>$5(eha``2s~<$6TIf zaCw@+7cERLGts-ugdh=XT*KLXoZ~Gn3WbtgjU>v*ij4d`%SM!uWf@r(z%bB@1=RJS zSU-+rfQTnlL35~r=68K4&wyoFSeA((h|d`YY=NawQthFGqAVfH$}`)_Unc}nAy84z z&Wids{7bJ26HO~oENb@9JlTO`U8-ht*aN0yNkS9^j8Xwr*Pdt-wyZ}30H4#EZW&l+ ziDJpXu+}9TURE;gFNCCcC~w$7dBcuZSY=^pSr*40@a@;%@a?@3R)}%10R0C*)vDk(;O%2-5TzoC@KVkegZ)c!c2}# zCPgBnLum8QTUwS}I>Ewf2|@M{h(_?coKFO$jADw}p$;y7afutx!JpbqpFSLXU=fu#6jAsgE+PX&xuH~ zlgjEc+|Ct@e2UdnhIGLs?3120(o6%Rm?W{9AzjdMMSX;0Wq3r3VtR?$(Ge!+SILRx z?AWu7hIk0aGi*aqaoJsYvVftflu9bvTM0}__+zzfkJYmM6;@eBkz8Vuj&CmT#ib60 zS1c-84{`33a~$2P4MBa^myx5dA? zM66XxlT9aBTGJ2}C&6e0pX*5pN^4!RPZXcULv|;uuG@od1wlY`I^L4cAmZ?bsoi^m z+E-j@Bru98lBo=t zfFI4z$-t!Wz=kn#OxH4X%$llQ4y~o9P+)?%S;T_v**}( zsMxo;e8oB}Bg^v47()XSWR)mobvtNpisEp3i9{+Fyqe}(KZ+#ca45)L#AY+1ibiz z0o<=tN%m8NfGjIG6dA!ZF-mE&1>M%J-Sh!9(DXdHqAf2WI$Stp1qq$>;xwauJxnG+ z4py=6@E+npC!5v1SZbca>I~C~5}GLx3q?lS^adwX7oQ}g2 zpmkRR9+!ft=2)5>VsK=F#jKOc##VOkYa#NCtg~5IBb{7iK2-uafHxSztGp}S=(hyR z#M0LozIT<&7jAHGB!#DL4`)94h!Y2QQXlheks$UKhNY8Rou=p3RsQ_d9fp%4_4`k8 z_S`9s?{6XEk+(=d3P8XW2vSxVBccqE&dxJFzRX&4oS4h?l%s0sD#___=2tVQIBBV^ zBoYp6%4I((7zL7ZgWR}qfva~%Nz3INI(ddqKRQZFJo=h=?)5+rW&C9^%3~3{jFCz# zFfp0pSgmi9c`X*j)n%5ZrkKkc$WcF)Rpt0RuJ1mnrs5nxzRO?8EWA8=@0ni zgTvIteD746;|Iesv5YmwAKv8Rm)~-GU>>+GIjY@0r0-R^o4QJ7ewx|EBxzM77>-d>SB@eI|9eR&!{Ai*1e7M8bX?o@!e5pX6_p zrY8nQKLxAE^7I75{gbR{BH`u(v^RzcheE`+H&Eu=IG}p#z%ueAW(K(N_19eM7$@hf zFeCKi~OT;p)uvnlTu5(_L%PcvUIaRdWY zRhQ#)I}lKrALwLgY>uV8ld{?t_UvsU?AoMjz_Kv&tE?syBr+<3?7~-GiBFNYW3^8+{0lzcwM3Tlb3ZxdM85x>jsbC@n>u9VkC$gdK&oT`RU9u1kH-@*MCG^^0*|Qro z4b89+L=jnWphzNu;v!hLm$UI*oPKULMF(?+f6FCVTgs4)HL~yQZ}{cGGW>2CNmfuK zi*O`}*Q>x%hQ!h$iz_)ALN0rl-4owup{ABtUQUw8YRDcJp;!!$^8NPo_jnd8T}9Ol zTf@EvY04$7Bn(@wW__td#B&-Tf8!kTg`KXJ0F9>ZJXoVCrJ>87XuaVP4B4shk zD`U8%pLmGJGS_*Dnlvkn<^L%~VTdmKRt~ za>(SHIxPo(ztPU1*^S&hM$l=ltIFwKTG;3ygR7GLb5w%R$O2 zD~SfZZ+Lj{4~0Q4IZgk)TU@<0#Hw6Q>%kNJ?9-EMi+NvdfV*i|H>tV>f`F_zktN}A z;N4YLLv6f*D&I5{D|3wW53|1^M934^P%&d+su`9hCm0=@W6h8WL~Cf@9>wF7Fx3Jp z<2`)y$4hk1K--Crk;=+B-Vk`&Su=_xXD1jN8f8AGBUk#Vh*uEwIDf+YWMLXb)@Hi7 zcI6fw1B+OZ77m~Nh|@>+P#f{QyyTT->o%*J-3~2EkKPem@i~5-u+U3sW{0}Ceyx-K zxdPGcC-~s}IZn1W5#4Ms;xoU>1XH7^u6N5xGRhlBMk&59W$|hn%DhaZml+%AXKGgs z@o*gP#zdK^Qd*m5sCSHowGw!%XlkgWEcD~ChVb|R03ZNKL_t)U@$x(l+m$Sn#-Fh_c^``DUyXMyL!+dAQ{%ZSCRX^485nNBf2(9g`S zYT}_PJWud$i9%|gp}ujJ(i(!difxS*M1w9IzB<~DRMT|ud2`7uFjwim`W3~wWzt!N z>iwVcSD!Rf6Lld*>7)7!*>o40PP!%Jl(Oh_G|tF+Tm|Bs;2uIA7&}O&v|w z(cU!gMk=YPt|aE0WN~SZ;ejC*_m)%Pk)HT1Q_CC;obbJ@hF&9za2FX}Uriq`XVl(lGP5PFhkx!1()7{D4{#gvcO-1Vww$;Umcs4jJ#WhmP za}3R_Au4Vn@g}Nc0lZETL6lG&63TOq1x$3ofkROc1pz^@Wl&r$7fwk)-a-{XPr|}9 z3=Cc8J2^fRwWOjOcJj-@4rrE&C5n${^a_ZQj3P<4lVFgwIrR+Z9%_J%57U6gcHC0i9ZV36+=i4ZxSe&0@axsITxGAq| zB_8qMcG&+H-Eo??HPY5J%Gkpt#va_Dvp#~~*+eYhMiMLxwZPiqARV3ec{sd+<*uZ* zbr1V%9Jb?Vx`@Uigo7T$@ma>nDpMf)XSaZ(#rKDsD}#u+)Etjt6nV zeka>1d?>R0t|+c8Fx7XBYxk#FEl8B@*unOuswXs_?c>ofo*3|5LemY*b;&x@(AVE@ zvfX4Q2;Xt@){97C={e>`d%1b#9wRA>>RmfIdc2*cs0-^AdCn}QS)7|?W+{y!Iw-4c zqqfZZnCHO0U%H`h7^G=ZEU9R^iG>B0iD_t*)DlH~y<=?s8aiYNK@d^A&d!J2>03tfM5t-oM`Kk8-}>=b+8U$x?{MdK zFViJAJNNJB_^~}y2OVgoBF{ecb-PlQwqC`trK9GS=)QW5d)&*#2u=ls=Au0@P_xq`ZKQ^=7#QNgOaLZtjpC| zrh%%KP)o%pcutZe+vXExRK(mIXe`6$QV=bZQa-`#@B^;i z8Dwf9kFRzQ&8<6VjM~9ow?9NpQyuZhAS;<9efREAQywPb*g?$yNV?3z)KvQ&oV+7sO3wYO-NHs0XuGlu$d9GA^9K(BpcO7BMs~c(GQ_0<# zRTc;Ca_?cBkk3JL#d-&xsZ&^+W1{;yHy+H8QWeT~?q*j*8BwnYf`Ft*NY8bEEwG$8 z6nQ;)Cm=}<98MQb=eyS0e>N;V%iKs0x2|?FnugjvyEuBhorZ`LOD#QTkJ?=Lgnd~| zvp6@$%u*Ulc2QQdjhdI>-BL+KGfeFM_I2JZ*}nGEyepx2%W2-$L`(f3^8*Wv+`rB@ zZFQV&D}ybEs$B6;{MGJI=UyxST4#d8adovhu6IY=Vh+*Zr7Eo-0PVlDMdKA_b_Kp z?xM^sV5r4s#<~STL|lKDg3Xu3wMC|87FbEExWiS%tE;Je3Hwr2?e1-R(74UJrBdm; z_tf`z*AZ%E$MzcfCYBhS?BRY#oOsO5p86?IGq8Mf~;cv}|jk zKKdxhCgb&&vE$$lYVJ>vnO>y#!F?(!D+!%!A>?tQh+wEW(#vDqy4l6(Yzos|PD5iI zb@2d_C}6%%25ecpPX@fldu#$ha1e<%vG4c^##gRze|(%P|N2iXj~!%RYaL~N2|csO z_&^t3y(7$~6@pc5od5I?ja6Ybyra=pCm6i`NB+;>cOeJj9Q^Em=U1n<)97?O`v89Q zumFwJ!W7dp^Q;ygStus?)I4JgYm{^gQ%x~5+E0f!hiBc978MuXNHsfKs&FY17#fB7 zey;wHKlA6iGx+NFbNuuFZ9N(Adf}_xP5Zt{<`>rJnjPZih2OKbGQ-jRZB)m6C>Z2Z zi_8r7aP#JU2BuOt!Zoz*J<9RjW%%By_UxO6iCRpvG(E}8(i+7_g7TKm>f9*vX%$Vk z$gj=QcfW&d*kiw71Odqzq&!|reN_;bB4HUiYr|LhZ~t%G*b^Q@IOjREY7vF zy`h4jN5)jMtj>?q+j*DU55`$3IjLxA=hUGl>dM>*qJSq>N9)0(>>E#Udtjc?o4@5h zCq_81cRLO72tFs2(#uQ?_0iou%QZXWiHvye83)V8wk=yCQo zMDV?Q$>@&`Mk&kc#6zw z``=#X-f)t-BcF5rv(Gmq159)^!_veUGbA&AWI_Q2Z zPa(R3R8`kf7Z2f-w$}T?C}o%*?%=`T9IFMBU~?H{7a4w-W9&KW1VKRdMv2$dQd{mr z7DeX)So6kNVSSzj1e=*UEDP~4SSy;mXirAE)O%@)5X1!6gYx-d`>cRBRt4WZ>snE2!bf0 zgd1qBk5Lw|Z7pqel8%di;9oBfqPs#I`VmZzDSoMmN$%~#4M7@J?E zpqiLghK0#NI&T~J*Y|`VIdFz**x6En-|aw@y~JC0ap3R_vxz$lP51D-|MY(`fAR>e zbumJ2i^A$0{SO|}-9JqdA2r+da_012;!)q@ivRq44-dMA=$p>s@K@q;2_(k)=v@c3X~r6 zoX+gXEQ!31Wfoam8mITZht;sh=3N0C{wiu}s;DWqc{fzmz`iplIn=jE|KcLIzxW-= znNjxbZlNORz{;&KHQdL&yS>b;L8M_jC(jSdc(R+{{og6( zP8_DSE=JI4l26Xi_n?ce{ux$9KaJb>bMoYFDg&O!$(m@}VcPdEu(X_`dv2WDU;Yb; z>D}zz(M(N60NE^(TAXIMx0kNI2^O;!k%k?#pE}Et8Yf$1jKUKzN*Pj?*?pNJ08NV$cU1U)&qyxKb<6T zYly*{7bvCX8QHs?=Bf~inPYx@fUXC93``^t0<|1IaftTa^^bWMK=y=)?l{i*qZ4Ra zFC)`kT>3+r<=I2*-BwB1Ws+H*qW9iC?hh@Hv3xWgIL^WSJE;jewq8>GJ)Xc8+;Z>n z9$Nr{faETty6q^ZRtuQY1BPakOg#LS`F`2Xmaa?J82G7fZDa58k2t<9M%44<;AhL! z(TW8!*)*~gq@ZrBl>e#10;|Yu|6RVmc$@y^!sGv#x=KEsCa0O0#vDC2FEZKVdMsZd zd1KV<{*ap57*0h*z_Qz3iv_Zo99FJKL4PwBP;r&fcJMd_%|gD_!_?{uLw7GR)qNdB zwyWCh%D^IpqJh7vndaSxIrq_FY68xmxQv8JF|$bjt#7z+cZg)+yE^16{KRPdUStG`1e(%()XBXsf`rWe26|iq=OE zBoAe^+d1=#kI@|0=^9^Vb*h`o3&Y%StS3t>TlS$;ETJo5np(DV=+s&EHpJGeD+L6_ zPi50SPMynwqm%BjMb@VKxV|*X9YsVE)++-`Dw-h>t!bjA{S4>M?4zkFutf()S!9;x zS(slUr5ad9f|2`ISsHS@Fo`5c4$AlalK=H{A0eMTK+7_9)Ix!DCW}MPQPhp^&43Y5 z0=2a6KgK8NBH!K}Vm>ub&&?HvJM8y~VQ6Toj_EF=b=zK!oj%FlhVX_;O9_XslAT9S zkk?G)JAI5VrkUxz#qwz9y0pW3<#I_w7kpH2t7p&AGn_rrN=4B1BbCK?8CYn=0xQ!q zEUacI8YbG}1P`w!8N2u5fV-n?8wXE+OiNt^MG&wo3q#jzeoAM_7D}kv#v5u-%q1AO zb(xDDqb%m1|TfLhP&i{;xhzHprf@xyuC9>HZnW9F%plzsH1kfpD7U;b6M{W); zkt%*yHm2s%q|-$#9TvwQa$$7@=Y~!Sf9*le|LkL`%6%vT$gVK4hIW4QcdNKBJz!uu z$xQ!U7Dpc^pXv<9i#4`IHUv5*pdnY3^M31NX+0PjYi6O(s*q zGBl6jad&ML7u@{r4azQV)B4K|;lQ%tXsD(aZl z3WJ^BvM_S@vCStsgM?bo6RQZ}bt_1sgyOGe$ARNy^E%?~ekNBId3fyt{fdkz+A<4j zNyBu8*|vQb$IhK+e?x@8WBEFh)wx*~my)ch8diFV!Mhik>s4OJ@scNsf9L1aSNZX5 zp?L~m@6p7}9E-^`dEG!ZZqBb6~lL1&5nnod?C!NmW&lgdj za869r{0bxYuJF~Z0p_#XIrh4x% zKm6cH-qqbyZEL3e#2Jq5s(Ye4?5BxGyt`=gu90H=;Z+hN|37>0)f`8X_WS*+yQ{rL z!+S@7BmjC(jyJpe?(Q4s99<}MtI)MRfbMVH++}K!r)Wgbp{D_ ze?xUm;6Qh6i2g=;F5e_y)UXW9vYFgr{N8uWJkebRNm9XGNq2iMcfS6DbIn0K_NODC z)m2N+^*hMA1>wOITge=okA~P?n!skWAQ(EDs-nmWs?|%==?*U4yu+Ovr|{W0f#+Ho zD5VmKt!;KwS&Ev5w715@y*R7Guh(6BWhduud`U|~uxuL{2D+k9%;(8ua`+1+q!)Bo z%Eee1_y>O*T41lBKFqyUS6ofkHktqdg1fuByN2NI?(W`r1Hs)bxCJM;HxQiQfyUk4 z-PwJ=V|-`N57>3sOL|nz(zz~~Hq>NETA5Nw^iaWlI>`6L2TFMjst7KKyrhrT)#glm ztJ|&>bT0rw^*8EMEs$QB1Cl;xf9a(=sVPG6hDaj1-*Jj`&5O$qB3cLPNSvPQu>{_6 zQ^ydyS|m;EqJUA~b4$?meInW*Sv1+rieFVXM6IHKdY|IuR<}nQq7?$7kC52deZB?{ z#+Makb`u(-mpho40h7a;nLShRqZ@(-&uLV^-{pt#eW&iG!D~{@8}BKd1HlmGm7U@u zir5L#fdc_MC%(eYf@7C0)KEHae{aKDB_;p|+vpJwg3tBS0k0$i3NLxY%O-8ETKDDd zhc2B;D%LG6A{xcN1tn`FA~;~>5ba1aFw=# z+{5Fm7$-@1QEx&%lHzqsSC5Rg)%Ha@090Y?4jX5P&arFW>V-*aZirfiNR2lblG)BYo?KgXfe9QT@iYj`aOZlU4Jg(cDo~t*b?Kx=hBIK?~S()=s z+vu`qtOiZouS0k(^s)tI4|`h2+_fCxm5GXbsXmcmFi~ePvUNdvo?Hc$j(<&k^t&m{??Lp)a22f8}z7Oa_+#!Q9yI1(8VF6xZT z#A|^605ml?mEt5swA_yKf&)F#D+k5j`SD0SqJZyr3nS+k$<=8gFJZ&ay91=~D!LVz zx9#~+eS+T>ROBTQ!l0gBZ@xxKBqSu3y>3j|l9P2r%S3xZB}59i4Cy&|LkBS2x~+hB zF?^o5GxQuTb@E9_VQlNoT-&~e1=}P;|5mb^ zr@F-DRljTHO)JGj_8ZGD+-;a3^2~6sPn>QGtoXfPArRn9N7Xh&)yykR8g}*^P2vz# z0$Fnq%}i{T#e9tZS;as?3@nVQvP&FB&Spue&2YtMd>3CO2fU_(}b z@E;TB1Gtx%HL38=U3|tmKX?GhlF6g~6tyA?-IA>t|HR7Ju%h}neKH*GDN3vzL_SSp z7d?$@c3)|#Y;X*YzarS{yF$DIJ52g9;lZ=BlSg?*&%Pkr3V&DL>@V5<(rqOf${%P& z753?wnP1WuicYCHcje`LkN_PO4o-y?XIR!#d3ykD!e-Nr>B-^8K{hs&nOt8;Tw@!s z{qfeYs~OUZVylIVg@dtU`sL}c22>0mg;|eTrVh^$1tO4JKPo0G)V|(D5wn{3^}-IC z4R6&JzYIB}g~V|wD{!_piS6RA-Dz`!{R=?WO59+ydo$4n>3x%RYy^y!l`GI-fBuKN z!fVdCTnWXDeGMiS^c8K8u;m(ZggD+hn#e&6{SlIeX3@`&r*_XvOLs@b0adkscLyH4 ztAKDqV;}g1G!HLZ^M{J_j?UQ@Znt9x(ylJ+Lnmjl-GD6xgqRQ&e_ZYEOH3ylOHZr3 zl4f|pEB}UeiVlYMOgNlk}WCJ`;G0@hqn{v9s z$8bvvJ)$czEqRJ%@7=!uVj_8UB<0=V%KZHJ7giM2JuaVa(oxPSb%;Z=eB1Bh5?uPZ z!0PTy)zY$7(O6ucK`Zi#ezb)3CUI?pTsH9 zm#EX|3;2PdeRHAytWg-8w+(P2+2k3FDs&^|S>Zu0E{h4!t-~=>7mU&xohChp9h1w; z1idDS(b3VAsW(*S1*2c?&Dk-IghsbS>4Ohx@M?+}4p|Pac>%lQBuP41oerC~VHHRb zmmmjL2U;fSPY`-xrb0ZhFcgpo)9K}Wg4;> z$QDmws;)_wR!Y#|kf*bd6HDg6e6H%3mu!n3{ef8}*`s3F1dN@tfgP;d zyw+C3M%i{1iCfj$gNiytspteyF*otQg)%aJg)m;};TC~BJcG>41_bxLL6)ARG0>FJ<59k0Mt50*3q zjHzxe@%Jf8_{GjS$fAAKKGu@XvL{2cJ#deR7mOU}fvNfVfK#9>S(!R=IN2h>>_*pN zQOGpwICw9WV`~1JwyK;D#}QH{upZbFPi|7bIO=W1M)+6j8>?RutNwG9>EO})A zFD{jZIjYDDaqK6{YLwgkBo|qxd zUfl+jrV$a+Mx0*O!MGPC?X}2CBzEvAn^DHn@(XrQ{=%9Ajre{2`7vCFp9yZaffs7X z_W)5zq4c5xT^CI*6+3@&cWSDt zu8I4{-v2bC`T}&lHU_$HNe^r0)YjQ4_tZ}ZlYb#1pcsGIa-qgvFYBlpm7J*;#>jl- zq(?-(VZsfHma7yOoij8{qu+1*1=dAKAodIXp$OQ%_Wla<>TPhp09Qpophm8Je(~hy z5@Ypaj={{U=;g_BKl;YJt;tKn-6HzIdvuAhBB{}Ca z%|&?14icLWZVnaX&J}Y3XeE|XNprLRRj!jDmlghJ5ph$n{t@-R%7}FQe+QNSRi6H` z=YFR7pM{jaWrw9FBDCgY*Iid_1SY&D<750EJr1HpV?`a+mkB5FKbt)28P1_EodX<6gaZ+apBij>1 ztcsNY!gG#2LgIsv|Jd0@5`G=f%aw$Prs(G6)2h*RuT8|!e)t~HRmutBNNbG`ZY3ls zPz9SFDhH%fMcv(Tqg4-U(_w08N+we!kLF8P>M8=rQvA`)XZ;Sy@>&Ha2|c zW}WP%oSX2A#3;{`#=9xC5Ep=tl@B@ge2D81*rzgPId8qSqqXp4iutfxe&5>qt9H1p zjYGiy#mKBu5yt*1Y_`KyyFA4w{(h@{%-}!unff_c9@g;c@*rl7=vhAkV6MiBil!at{jOrKP3+*E*Z^j=P?qtCzR^ z$sedhnk)^xc4F$iJFejQ=^#PCb6d=vQr*hguwiIxA7re3ju{M|Iw)(XJdR?wsn>Dw z6M}*2C3yRf$YF=y59)Vkx=zCQM*7>^qP{yZfiqz}W$k}(E(nzEzDyk2iS zz$@5AAeS$9a))K8Hf#7O$bcoIy})f8BKu7SUn)Y(3F&v7j!g*&y6NaJpUc2eb9U$d zUjI#VA!kp7(?#zu-X)nd>(wtg@DZUvDufX|SY!(ZN|aYd&)NAGfgs`OmukMYs2H_t z-oE#~d;$*Z(WG$v|6*vDa`p`Tud+)y41oRlKMQboF&^}ZhK81;|J#Blg!rVY!DT4T z`$-I9R!tsF;W-^|uy|AwK@wk+7p>Zphy|BrI-0EW6a!f^Jqi1Zi;*da&URrGC-|a%HCCukuify-c zmqp_@5f4QlHLL$lntL2E^QcR;js;Z+C2C)FwWjM$uyehIP^xjZes>RorSZz6V~gnM z>~#A_IVer)b?TNO!ZQ+BjylY>K1HSl_8iGn#pMK9rRwSZ*ZvMgk^L-YKH8Qa)NBAQ zP5K89Nq;q37)ZB_o}i&vmV{`;_O0A|iA$?%TIjL_##pcC588=0t<=ZxRBMgdZ{$NP z(xOAD7|SceYY6eCY-V@-y3SMbWJm%rp9*q?of@b7F<-`IX(r)yTo^gf|L zkBzJpXOEftrW^4*EcZW6Y)PNh@aF4Iq|d$A-cFv6^|w@JhYXcPWMc@G_ufD_7{vKu zcV*C{(n*;;!e}p%A}0(J51di$iA&3&7-8x!j0Uyy9iHi^;gf;qA!>ntn`U2Sr`cc- zi@-4}rv6>OePr|hxKLo9bH665RJ zJH|(SL;pG@8>kM|ExPzZh1wGw9tud>i*u9L?m%oltGh*vF1SfXK2|)bV+M2BS zfv!R7il#))LcxT8pQy5nMKAj`QZ>Z<&#;5%!kPc|HJ@m=d3T_+KDvWpp%v5q4)W^$ z%ri5y3TfK^Roa}P?==ZlJL-QX_YWS%Bd9c>>H>|due6n z8=F#M&?eE7oj^gfTudyP?-U(#_}8Surh;~$*+jy6ygoj}ON_1#_49J$i-VgTPuZH?*0Wm#)K%w}>{ zl$WvCo9ka{qi2nc^*yiKG)Ze%nZdE)Um_NyEfq1D9nSzQyl5^aW1T&g@(+5H@5dJ3pz%I z){F$Sne=2;CXIrZkK!5&yx{e9DR=)bA`96MDIv6GhXjKTIloKrX=rek83Vs;Z{6xVvDP zAmLYUqP?)#R$yt3998Qx&dF_vZ&j9K^Vg!33hDu&+b3xVi~@ zs>F8&?H+N6!f}s*^H$#PzV!K4&VG;+7&1?>tJ;#=3O0l_7=&PVoMn4rQ&Q0al`sGL zBUlIm>XxRrjFOz!(KRyX#GuR^p{&^Z;+Y^SQc%6`rKWCC41)3(A}Yz zmr>$|g^es;My#O&CBxk0O+sDgyZ zGaV#qP-ATEhv=ahkmKC7sFU|#fvI0Tsl+MLC??mkQ+2f8`r(_Rmq5HywO&wIEW@vs zgk4HYT3<&($qHk`=aIAl^vnB!9bZEM8%~oF&%`DoG#j$rWHg?1qGG{bk-sP!gkLC2HeTnKYcVaQOqcu z0z4DNHdiVo&AyekLLNz?0pJk%M>MD?lzpwRaj+{j24eyv!QPLWZH~Xn)fnJ&%L8|8SS#B|1(;owd~|zqq&?>gtX}luMF= zaKp^sBdjFN(d>mkx&ehp&?xYW$HW-`(DYA(aLBPW;AgMQACCXdJR^)M@-Ge($eet9 zeUGOcNjk|2?@M7#pSF%^mX(b+XMQWUdz2zPB*iJ^0`0QfxBOn&G8kfx?d$j$u5y2G zHD(*apd5IM8gXR;-C`;VKR?3_|NNWN>0VauC71Z;s4>G3*bTW{^(0hKpiK;pCZ+WnU zkhk6UiiudW=0W4xD=vuTAkvYAgNN0rqz zt(bYhNs=B8EhInKaTr%-=VKe#JY=#@!lJH^o*W~uSv@bEc}W)xM9SO_2t9g#xlNd8 z>_oR@O(Hi|`-cP#gUACy3}jPqRA;n)hKzT}GJ5>V7qD$Oo!H=4t%&0Gu*KIXpM6R- zV{wg9iNX_s=}abJsYqEiWxSK3%mSWM33{QOY{3jIR8x@F#XBntv%3d7|J2gMA?*O(E2jw5h;zYMZ7Dv1sh@A%^d~=}U!AG? zJXy=oo4~{Acl%^K9_61X$JmT-XqUvktZ02Sg;HyViY2llv2`0@ zkAb%apuW@m=L!>95z^Bw?8@`sgIsB>7M8}a>b3SO?3{}q94J|dJ&=hNCmTRK!!946 zLMXxGOwuE^C|Q%Bqr+kq8nZX9;ox`rSUHa(%W zdq6TADl8tpv56yZoI~wik&)t57*FL}XJ_D{8$Y}W@TVVYcxKj$3GHu_M`cW#qk-!m>eFAW$P6Uihw)hqx<`MXSeIW#cU~oD*QB03^#;Jg4&(VX zjXHHi{$_~zQy=Djpl{?f1zEt7&7J*&t_sOXP!z9iT(hgK$_j_2dHMN(_?^a-aF=^J^w$l%`| zwqme+wbNO$!U0{X1{ZX7QRE6P!@|X_Pt8W>X#2S@a9f|LlitTu+Zr!mQTgL97h;v) z?xi}I+GU4#q1^2z`fBdm$gpkz*U-Nnwh(i7httxe)8^X|P2lx}4-i(GHM@|~x|m5x zXm{hoH@_l|D!44Vy9c=@w}xW(O(k5Dm_Ogd+%q<)*R>QP&L5TGp`APiA|_%%?Kb(+ z9LEf}GdgHgo&@Xd3_q22R8`3=;Z-FJ9g;$fydCm>dy_0pe^aV1dH619+JANJ?8f%a z5{vBmumulx&px%nirwVzJIl>Es@d5SFOYJx4~l|&crvy9P#MH#Ts~5@e>__d=KHcU z(R`HAr!q3kn@PyHA`x?f?zscupI3B(*J-u^FYuaL;91vj#Ee>(muKC|)p_39m0sRV zqSLZKlh~*w53?nV`z)c}eVpg#EMwL6hVyjCq5xQFk}Df}xpkMB)q{ervXuE}1S7#? zd}_~hDSThPfxovHgh_la?HI{LArs+aXT=SrLHA())yG{P+z!I8d?GMwZyx`b01Lo@ zHk_<$32Yshnpv_8&|_ftH(a&uwcM#7hPsct-k1tlvtG>VM5e313;+*C_6 z{%sg#-R}Q~ef_ecfQs}_v{_7u_NKB}4atza{VK9I@U_SILa8Bh-ZiZ9sAE=MvnQ+o zN0!!eX*H6Aw@I2JvxE%aySqc8S)Ole+5$Fgm!|4Q9qA60oug|~sq)9O_sNx@nDhd6 zG&S}b8=C)IQwulPV8`!BAD4;8AxKN$IAqaS2DhM!+AWGX-KrGtkkrDArO&8CCr=Xy zuT+;|a)|IUEon6*jZZ*e4RlQ~D2%*PT1k*1$2UFi^?E%B^!wXa6I$F5ub%NzUWK%Y z^#!R!f~R?S{}|x}EPg7nLlpz{vBj%xQ*liuLZ1+nx@75iP5yCzK)LJt2@EsMrFe{ zJ#X}r5_*$a_~Rss{xmX;xu1lmy3HiohEYvfA0r9-U6wYiXN%P$H6(LFQy%doP;-3P5q;3ah6+Y6eyz7JG$9KcXW zK5QclIn2N=VImGbrr7UvsPRw>&Ugdj6z6}-BzwI#k@+q+>aU2}=J;zEolG7-6O2~%f z8H;86fqrbAY(iz}=@G(Vl)E!ex|SpYJZqFkRzQP{g$lxuW=A!*eq5qhHy+`K)g z9{~v<%CTP-NtNNSz8#ETea;Hf7ZWZpmXUu`0k)lhCrpCnYd*u}Kcg#mK4*-mB~XBSzlRR~!U-eX2#xTp6Wk z3z_w}b?N4a>@TIY@uvjGbRWzGs|r+1ih{pldv^+ zC+uIUuefEcAEPN{2dT+q4A=c-*r^x3Pv++WWdycQN9#j0n4B5Hs08iZW08Bc6YS*CZ=DH45;KKxWaM#%u`;pE?A*h{Nmx@;x&L1))vWz~`W(K|=%_Ud`s; z2B*k79(w42Of#qazsCYegY*hnw1N&2+VZ=_3Er1)UO+GBthm%* zMjc6eW!$vSygY@SlrHujxodmUrxFh```k?1)&>r&(%U3o#8Z+u1jiNQ**W<7{uX<9 z-pk|RMf_U{A$Gme9Eu3X$0ItJz9w1vj{f!=833&*SI;ln+Yh(HBn_sk?9B#cB%n6` zv~n-azxeZ#bAEXPs#0uQ|K_y^%sDHOhHNW2A#qrC!qN2i-=s@*ECQNk?=3-R+gQcqz6k|m zd%x|!(OR+r!e+109zO1cH&9vXwJ|Cj4tL!Y;q$@aHM_FsPW9dOeKHiXl{URJ0h1-_ zY2HTdep9<`|M$s3G{lr{*UWw#Y2Dlck}Saab#koeWOP;xD#`jW7R^$!WSDOb^iJFw zv7Dz3*aUT;KyBP_*&-2{f#!B1=pnf}2>j>%(;V@_%|7?znvH}m2z;3hKpT&#MII@wSa4KZJ(lJz;l zwlmFmsz*P6n5xU-DnB{hyS}S3I6wQvvpZC@FMD3iDazmX76GpQEn>FW9WfeC(=DtW z*6;b9HX%GdZ^NYFgXJNBXlL3AR@;NIYa(&Qz`~64rG_N5h8`=1Aq%!9i-%?XJ(`u3 z+YH-?rxgv&LFx6gXuS2*+CR$%zcC2WZAvtd$lSxY-*{!BL@DfTPkNkYLp3ST77(Qd zjEV^SAbg0hS{l`@5b_98vdsQ_49ocBb%Q59(a_31+;st$xva3`c)B-K=GErj95HnK ziDf#t25W?dl1TyS>T~R9!T-YoOkI#(+W6%bf<$Mg=f3~DD4n4vT4kJCe`Z3xKxXSq z?a}f}&u*=CeRmL?m?O{O$u;xMXl|DsdXB(b{)?e&NJ$_lsoqR_A$tpZ$X_(3F7&uX zZayY^x<$ic+&$hLBiuBrwb>A&wQB9U)19!{&hsGq;}5*XN1k-o9*8RkN|+?^&{ zt;jyVF|}!c)UQ3&ZB^EAit-G91U*DlrU6xq~NdyhB z*c~6*Wu1k|K3^no)F(^8bGe?~JJ#e0O1eA3=c|94yl8CvZ-0#@zB6{pq|DASD`Brr z{W;<7@{W@WiGF0cm^|R|B_WpSG_g_BWy@3WdLK_--`1$T*HBxfVMSr}&)7yFo{4L1 zXmMo-A~BDeJ!f^!rt6c8jqZGzw70j{&!{`3JV^8nK%;x^YfbZEuFIqGJ-N+3Qn2B8 znR>Jhd=vd}cR7L^aw+mX0ikn9U2S7CyJVt3uY~#%yzd3^>IchgW@8G!PrE(O_2hnY z-WLc>GM}cxa{*jyG$~qnhP`j+7~>(p_;&98x4_k%_Z}pDNjODo)-7fybX|Sx-!6~7 zIeZXJ-$w@XhZp>;bra(ox94S#8l&^#s*-Sod}xSyP;?EaApdB>!;nrCE9bnZg1b7g zN17oFs^ct_UC`SZ{&`?vMg--JgGDvhok6ems)@U0$ep$ai}-M&y2CiqRl>yurw~X| z58m}&k5CVgl{P_D(Vr?dmb!A@WlFQq=xsmd_@HLY>v)H4N$W{7c|XcT`PLsRqG#=A z8XZySJDF==copgRfGa&#&n-In7Kp^rkUF5cG+t7r-R|~|Y3<9@5zgUM~G); zW0!V#&Gm3G2X=1>iZ6g3MxVEdRqL$I2z*H@%w$FiBqsJ}*1;T8V7=%Z%HvI(Ayl~E z*va>j{+WQ|qTT9JGZ@^--v9T0?ChG>OC{zPMa=5Q7J2^-x?GKbFRS6+a!DhAOKZn{ z39Shu%ps?_{p)|-r>kXn{F02@!-H%7*|kgY_Vr~*CD9Ee-n@{Q_onLJi9VeH1A;f)KFMvN4f zIe=S*JXJea@92A#vjrW018D5^^5D;<2{2Q5Nvy3n14Vf9_?lt5_2(vjxB}2WJqe3W0S&f2_jk9T+?;=S*-j$!FaU#=+xb6)5Qw+`Ah5Lr8g5i+gdT0oC zNjEmEEu6BenH8p*t!Dos$!E)QM9_zjQ;sl1L-8n6J06^0Mks?SZUv1+1X~teeSwQ% zyt1@+h{cvmIm8FOq7grJN%REC)Mp)2z3V zYux1{?on&)xu5u$BV+*?dfV~{?eJvTcutKWHY!4Gtado>*0%mpC`;9vfk&ES!lFmE z=s^(ZklS?z!YuM;DC!rZ_$CmwK!y5W zMMton&XLC*QpR%=zp~FKK3-D?RoV>vT51z4z`U*VKKIk3o$XpPKGef+)nb6i+58itJ+ zY+^FYtzxXMXx~ie$`@bTK#%~A4rtpZHir_yw$E8HhxDU#m5%hQd(^*&k zCFy(i#x%a?Rvk$vZE7_nALd_6y2e(*o@q7V2t*OYUdYJIq^1FGsY%kR zv7=fw2HpL8jK+>+i&BYc`P$yQzCv-1N->5a1rKN?2n1L854 zZxce(H>?7zf{wxrxva5?anCQ$oJIE(#5XgYXJq8w6CWVcnodMNc9EpZAyvVwuAq zwDA+VeYrPOu1{-}IfXiU;!jI&`W(C8_Yt1^HXg}wAm1=Qhv!h@>zZ6o!$v_pW>4Ns zkbd;so%=#f-DZ~V(;V9Ybua`aNNei;bd4YHqeQvq!azsl|0A@^TO6Va>AyLZVbNnX z*zx+)6;*$!-MtdiJ%nFSh+V{_5XULh9EahsycX6 zoBpyts6^@~S_*N3?OM*`EkM&Z16o99P6+kJyRSa)(h#p>HGcSH*8e@p{hXC*F4{3P zE|t^iQ1Wz*-2Hggy2`H~_Qnt05I3p*o38|^!Xi9#O|gZCcWErAn0-^IeezSY1bg%3 zze@^xL0gA3;T+Htci`)rhu!Kt?PqS-v!-TVlMKXP7~}e|E&cw6x6Pv%SKH#p_BxN? zb@m?{YEb{{A|0i=eJW6s>*)-OcRrHH4sJxYw?~D8iUQJB4vBOKFnTPP*@17A8G`nC z3u~oP1a{Cie(3j7Eiz6_b=@9GZ|-Nc{Fo3I5z8h0TnleN=Fj8en;FIKw|jz;>5qs% z!{)WFu;q}}ze(ANRghL?)N2Rq@faJ~TRegIKz=U~?yzL!V|$;ZW7ZVwDued-_uV=M zv@Z*ZR%@^+m?l`+n(JbY;lZxwJb#|f%5of$L^x}>X6EN57QePj1P9Ie7sY^?2L6<+ z+l#7=Dls?q_6^`cr=Sl!E7hz&rLIdc3W}EMtSTh>?ac{1En=AWtB*TkfAz>aXk@+k z=dfYP*ZjA*tG~Jr&qghMcNs<$g}E^e=djHqq&Dz@nHR)ZhXALGjuaBU&tnIL!a%dI zG$~Ml&}mtzpJEIH#&=P`>yW6RQ)Qq(lzJ+_HRSySEmmjZ(dNp37CDcJZ~Z!5yyv;J zWMILf2jeX0h+E@c-@e`6ODOiOF2cs5LKW9h3@gY2Sk{R(I5To6JCm$MaxoZJ0` za+W0Tnr{X(v}HD?>PdYvIeSb3-QyrkkV&*7A&;!QZt(0AkuvxL9tr~EZ{25FsHv%I zL8s=xw)S(1F4@HnMnPYZ)zlb3z-<;n49b$p=j z3K(BK)^|~j^B`Y2-p0E|Ve1-;qV88dm_K&TytES@!m^Z-#&D7hMUGDd4?%#W$*fPF zCym74zo9|T^0v$@srL7W;raMv@ZXxP-*l;Uh zsCiWIiw2s29R9JeFrV}y#9tIQLOCNdZqo^1M=|vnhY99}wl>Li&9S3(<;S&LobNb! zvZ^#>@KEc|MozO2ZaaqEO%IW#hjf|#91!F`SlaxIz6N;DU)EQ1;ED7ViY(m5&UOdr zOf1SoMUQ<^~Y84hFZ-oLlz zZJRL^GjsY;j|o}^0A@8HE)HThFt)bm``dGjO_~{~)xcOX_{CGPtd-@X<8muA_e?eN z-shHJJ;xmzQx~!hae&c#4x@2k|3n_c?Epr-xKiGi>c=X*Hi&PMweiNbLrTQjQJ1)V z)!cqj$M1ys`>NOXDtC<+B$|aUBDbB&dKEI{nFTf;7?o8eCn-}$jy3PLa`IK#CT&S4 z+AELXN1U(p;v8w@Dc~)-$xr<~b{=X=%i_ZojKG^g$zy07t9ewP(sUNG4(O&F(8Q8p z{>{XlXXq=6pfq2I)KWqUJ^f)G88b7SW9#TgaGp**KZA`UYwOz4Uj{Yu$)T2DHIIRo z7sTRI+P~OT5DD1uW6w$BE;&EPLt1|@1+0yY-JXUta_(Iu2>YV8A}gQZqoYr>?Es-f<9~ zug&d+!g{&NMaKx(ja^lo6(3JySGk|LCaXe+^%qwYsekj=y`^FjJ$1@2Bt%c+$Vqwa zc9;4D--{dR2ZSFJ5CvZ^LPhY+_}O{##A%9L#sX%%ny46>E9^=8tb3+lzVY7os{F@S zGEtur(Fk%f9iqo$fy1|nz|9yzVXj9moMdrl)3IYby{O+KAR)XQQ|gnwSKN%F%Y&cm zF=+nMy&QkA^y$Per^dK3ahja`AY0mC;V$5v zPy{k*=C3&78$LR(0^aD7Hj4yJOGiYt;-Ua}Wlo+1Zv&pc7#lhc{&m7cPhhj=wZPJq z)B-r55PC)s$Lu+xwu$i5Rq!nZ#~!2nTb-SF8q2Wxjq++?P`@bN)YLpZr`ta;kD*3C zsdYO6SlFs4*qJ#nc)I6ZJ^%fEDVNqqCtId&`?uY;+0Fs*c}~$+uajzDOFDWRhBnsNurXInID0gP0dV4vH{O>*_yit?;rDncCzNEM;Sf~c+Vo-ubc(U?eADa!w&HJ)w!1N2MF zn}2aC3p@4O7%iYY@YMCYO$3G5V-2t!h`zrJ?cme??Z z9)}x141t^%d9x+4BgKXU*1i5`{pm%doqqm=NQ!^N85H^u{^_ub7lT?eO`~)zcg6m^ zn!ENUVq&aXmlNCys?spzxW$r1qY?}LB=(8xlH^En(MP5{n&NYGq6C`Bm0wbNXk=`p z`=rQ=!;SxT!U>}cL4AiI@HQeBuaGXv`;+dXmZg}z_{^pD#s0zvFh_<)9n8Vm;RJkT9;_74EHjB2&@(=`pHCpqh z--007Lkukz*;17vi)FsN2(nSS%J6f}OG1L=w&s*fwO^TC)*`gCzDUXmDjQm1fy9KY z^axp{h47p0>vm8dih(1Pf}H(*YRT1Qs<>69CH&!qe=5IH!c+KGCrcPIrw!pvA=rk) z<)>U6QEaEUL?gy3PjYmrP#I_|+I!K8waSR3l&LV8E}_)WlF4yYp7$ScvH>hlw7z$L z5=&JzXC@MQ&}Z=@X+yk)SfQi*0~L?5RQT;~%%Sf$MMk<6LTvBbV4mHV4VkobHVQ^%*_Kg3nIza+VMP+P3jDt7Tt`04&2-tQx`*UDUX$xJq z$3BF2V*}~`@Q}#7VD6t=iO09NKJIKJAIfc4k`o9p!XMYhSCIXvhTIj+6g=`UXiXSW zu08Gls$Pj2X5$oTZUeQ%>&SrJLwd2fTdSW4RIOwTvAG_~6Z<+~EBwg#{*dRc6aRw* z-t5pmA*pp#-${@plAxnz2i$UxFQ@Sqntgv0@llc-wkOov;Yna0=V4t~Sz!|$EW!V@ z?*xd8Cg_!bJNPI`Q(=;_WctD6P>`?q72SSy_|H43w2f^w8NogIqG;LJVn2JM1A5U_PVs zIJl3cR(-BqPPok03$YQBV=AC<8aRJuSn_%0)Pq;crCV8x8^g#-RX`lOPPD*R)YQiO zT;&&ak`_bUYN`PJExy_Pwo^(`nENTJry-& zBZO00$P=xM>3uWg9rVqTwk&Wh{4_yL6I~*OXR+}ZXT;hHpG2QbJNWsY=h%)hQC>H> z9ZC}1=V^cjQG=Ac!N&`ar;%TA1AdTPk>g(~k&#u9W868)NMWaIqYUXhQH`l5_++X5 z17PokYz_$qi?gIy*|JAP1(QUoV)LrZR|KGILI?7R`AeA7Wzse`NeE;Q-%~i#gzwbY z!Saz5u@uRWlo&))TZchJ%SW27V7_QB{PQ3c$w$qvDRd~9I5iZTHP={>l!-*>ptzPo z2oS}L&$O~~_)%rNVL?%*(tPrX7S%%ymyzRgS$W?y3nzXjxV)fJAdBKRr6+AcXdjGt zz-y5-N4}}2XJ#_?&`RC-I?Xq<#P4@puo6_NM!93oVnGY;F2pHCN1Gi`l@we2G!=Ug zhATyh*;nvYq9(E;`05D>7#?5qw-#t6rg14*X^SHNH@S%bYxRBP69oTT%-ke_jiswc zxpX`B?N%~UV{TfD*uu2*?|90vf~Te$W+i0-L_0yHG=T%LdR+PD_DRS`zK7Jgs98i| zfHmk~3yb3yj+M^e#YhoR?m2??Cw3BH-@liOd?}5x*DW#Ih!|CN1r@(z{QU&V<09C& ze8ymlsEt#PaYX9{2vNUkE-cutd9XuRxla^46v+hS1Zvakbk`@JQO08Asnq$2mZZsY z3K&X@YdpHh$n3=Wrtz){Mi+rm?bevP<2(+-{c@}vt#t!#Mgu) z1^R&;F-OsdLGYS)zX1S``l_nT=(_qlVs|kK9<$jdn8<|{@8H-<#uF-JLkLf^U4cY8 zQ3W7cSPcbc0bq0Qg`znc=6zK#!cjBR=?j^Uxopz?1n?)e5vt~@&YMwwlDt^z^ecJO9iE0T?r?qmZ;Yo|tbR(& z@!HgXl-#rPb86^nft~Ps#NQJ&fJp=bUYh^x+9NB&JCv-WBg6|;=o%3t2}J(n7u5F( z8>vnA%{6_Iz|#GmE+Mo4+!>Rc>xtxT5G>kMmy|%S&aeOCtCTd}r|tywNCNdEM$Uow zym!(3R<;$GUbzS_Ysf2Mw<@(frH$)A_BDdID;y)GZaVQ11$Z#fB0y&aUW4$0M|drs z?c!6ggH89x9BuSg6vnYKlf%s^MyaJaKS=`>c{Ixt0E5k4nmogO=8_hzs``B!*F>^ls|UPDDwTkLzPHVBo+ z#On(>w}ztlH()QVFE}}a!=Uk-lTY4N2~jCTy?`Uq0pkAh5E>LTER?THk;W-D4==%B zYj;u#Dhp{TwWA1#WA2U%_(Yog`2rp)8G|hA537Mt)o9scGLO^asHuJ>lv zZbm+*i+O5VJH#V3c~>4KkF4YI=~Uw>}bk=V*M{{?$}fH6PO{%K*@9kMW54G z1?R|L*nDRy;-I4~UAEWrQs{CVOTF0Z$+J)XL9;AR?%~7slf4%ojlpQCZ*4u~XeV|I0&CPw(*EHE@c1 zXm6+>pi6jWj^z9#L;bzne!PV1i_^XT7&{xkZ)0|G@;S0g%VbPI^Ker`d~^2^PbOwr zO6MsQEi9)z-p|IKF!*qgk*CM`_@g82Y^froZ_N=DL>X0+QD579=i%9T7UyS}oLI3x{ttirJ>7Gl+#RS&7(cSO zJf}n^wZPD$Y4RlpU!sn>>Pq5)4cZPtL{jvh_$|w8^XJw>z0utDTx>JL?DPziQ!6-< zpTtj`yPFL`R8V#0N9?7CYv)*)E$?Br;3HbqMrW;tZ-cE&f~5Y;wWF?#+TVpJd;K+eP9NODT%qTIv zO#;QQK#-7C3Hc4|ZaTTZ@Z%W@mWNT(NNsfm5o4ovS3**xcWQS%vxI4t&(DHeBsDuq z?{Y6Q(=*I0rZF8CK~nGqA|&dX>FVxgM|%U65&wp`^xqZU$nJVBj+JF@bziY1AMxro zI%-t(ZDw~}vqT}8WVv8s<3}=QdDQounV}ITm(t{mCYEhe4wpP-Y;=_2vE7_FbA}^( zT8R5)q%CcDKVXZyI`1(A5lI%2WbizPLM}&YZkq9IhS(!B1Y@VF!;yN~kd=ATXw`3|{)8M)|rb)?hadDX& zxyR+Hhd8+;$#kBQ?NIJc7f^MB(7+H6hjw%7sFF)I|vHF$`{euiV9b$PojU%cU#xZ&tqbS?d5%gS#{Ngi) zAKYi~c@oJNW#_3gv{nW&-Y604f>*8#DwP}rMMX6XbWvDmKM?>0RnzhL6a+7el}?hk z94yD7n9Gtcl(1ckg^3aRO3ztdklAtI7$;h)i5U`BZi#1u{oJ`f#?!&OEGcp{q5uFO z07*naRHuq~s!rhCZt7yjdl2Y!$<2-Mu>S#lPg3|oHMI5Yq$v^JkQn9%{BrPIi|pJ} z9^Svt&_o(F(n`m^{d9yR)DH%I8^NQLU0`DPK9}xKk+&qeyLQphQb%M%iMH(n*R@Db zk8r<#fWe6@TC9W4efw#DPv)-Y+T`Y+GkCwBq46YAsGiP)2Wg9F=-b|2dN}!MhI(&t z;o=}GwvB0-6!Te9=>ooZ1N+Y&;K-2!^t2`jsBglXzSU9I7F-_f<=(&;<4ZOb?H%ms z*+ErE-M0R-Yo?fg_K+)A`WczC==k_JM-J_#rP4qW-Vds__2E%W%`iTEkE?^T6l|IH zoqK3&t|hb$?XGKlZeQ^Dt4ba zMN?G>pJ+DB|n6?LP`T-(C79p03c&9f~m)1>Hn*j9mD zra-W%gX72As7r*R@ZW!b1pfx<-`-EScy@-d{$9Sj z*3YEnr|rmjPV8@^CgMYSBOXkVXng~TSP>DeIrKKcV^5BJbk7b9$_U>C{k?4+fkis+xe zrUOiGV1UX-e>1+)^IX^Kd*5vt(jgHl9}`xs*l?v~&7je$TP)2I>+a ze2R!`=GfiSPJQAVE?&OFgXvKo^xdYVwVr4|C%6`8_I811k(n9d#>GoqxH(Ev3e$1$ zBaZEFBN5WyOrz%meqp#ICkN=ge2I%UMo7yEy7wLB?4cHn?HZZ-yM%|CnPue8HNL*k z$LNwtY{zL%9N$AnU1ZxPbYBmLm5BkqyL6e$y<_C`YIg2F%GpEB@5kKr9MaQ6^sVk; zD`K4XJxBTYNGl;#+O~n?7vY#$7N?%lfBO#ej*H^~h#0XdDq>YMw6xG%pCDq$?}1{dD^3*>lCMt@1ngnjJyr)u3K8A336RZxeQs=M^pQ54!1W_ z6Az&ZCh6rlo{tPO^mu~jkM5EySmZ50DmCAsI>Bqs;CdEp`#Z;p^r5_Il8 z%K4)$1h<{t^>A#PQn7^NxOi@c*;$#cLnkSQY=i4 z(s=ti*KXZoc=j3huYW^pR}*_eo5iE{^xljEk`(e?kKI*!40+K`4eq)wAS-zbdJ%PQSM&9gkP~Z)YC#$)CW$H%+fUD zBM-TL^&!s|a>$B+x%wQNEhZybH3)>G1oSr$>is1l$Y{X|T6?t9iZ2i*9MIo@3)*CP za)`UvFZ1o?yF5+FH0(LZN9T^wQ|m($-!$x8uHy5)Hw{9WUhK!_w?me<|KMM*7FS^0lVm&gMw7RT;!^Xe5YfA^5df{(UCM>unGKke0lxAh7i z0DxECd(vt0<{BM|f`Dp72nGFX3qHSiC(oj=GR^Sa>s+{all#vz7!7;)^z%-A-4HWYkd8yg-|5`-T#G_FNjg_pXKgC0YjbUm>KE<=SS*hZ za_j0vE?vFP^R!CK!NZ(6b%-6cfge&bZevJVgzDxlj-7*)Wl=2T$)(dQCbJ}G#^}E( z;@UQc_U@n|ZfyG5#4!uxlFOt^E^BEv%c_q+IQ9m|ocfF4~*xNJRZe*yNH6Om#I=|J`?7?Hyuba+o_egY4M1ljBW(0vpsy_&M-g zi+p;8bgqcCmfe+Aj6nE}?e4-@Kew-6;oEBunJO5x9XiU{QwQm+_HRqO>#d$Wyw&$p zV=eUTJHpZZJE%1NMrW@141$pm=E@|qi)j`f&GBUH8P8{S(UI_dDAw7+_>c^ErzndH zW>=P2T+ZVK8)&aK&=g^NX7}G42#A7E7WVW!JlDf}t@^u%hgarm7J$`Y&zp{+s3&OX zKEZEeyYN(laJ+_^ir}i?ZW*fTBM^-fiyB~MS-Q~A%*qhA?>(btcbK;yg?0gx@dwwr z`*@1Q{L4G0fTS37o%n)%ZI#3Wo9D!MjzwW*g8myfxIH+H6=~+gsWTkkRY^elK2`H( zkb`yf95}%2!ZOJlBRqR}lg!FI6Qdo}#RG_Tt}M1XHbGhp5{$TtLevWpB||BAuc99i=vhg6UVRkyMG&?$D-8yn^){5cR6KjE5gKKi19yyc*WtEfs; z5DRKAjDm({gospDVu&U3`77KQoMY_qC?h@H>~0943fseNa9xw7smJu+zQfqEiSyEF zPf~nTwjJQ${@pakH&-Cbv(hX)d%%T1{)zv*HG{vthr=gMa_ZioRjnl%sG%rO0^kG_F1=5jBq*a>KX7|pwmb97e|k#!GQ4vv{+_Q@c< z*RF8syFtd&GA(F)b^6!@SlhuFqzE2jv{wmk?aKE2RqJ$s_uZY`* z5_Pof+(%Pb=H)b#AZWxJT50d;pyu)jQ@Io~Q!``>?Ra5rll%)0+sZNd;3|D1b1ddx z9TU|bq3Pfk9O(!V_pjrQdM;LBg~`zY`mSB!!u3ZiI04!Yp5&vC&vI&aHJZ3FJOB3# z$I9{i;Z5!jPcXmcI*HS<{}lUo)Dc~8op?5-+zN9~hq(65e{t>J1Phj*jw2`ef+Q4tVCg+%934)5!tHQ`(TPEL`PnWqf&UgPrR zUIwR2gqn77An6sf>^VuiX&;ttQpl%CEzL3Z=ppy}A2EFE5>F=<$XRgySU2@i-zHY( zy5v%`3}5?}zUd<7E0sF}!9**&j(yDDdTmYd=kjeVvMV!;KIrB8SbinCEUD^lb`&W&rY@z_bIRV zb=w6}u!%iK4QjiKhG!Tl#sR$|9g$(H%Pg$NG;o9wSb|%^| zw9TVHw#_WhAKv2L(DOB88(OfUYFI>O-oY|6}&Lbx|fBrNF zyKC`nQ>vUFmbpn(wsg|c+(f1E%E<#!@>Ac{Ma$h021n;voSS2IZVA&#ymigO5BTYL zUp#_s3(v`uTv;Jm5D3-R5Lbl{%G>W4f}kMD3W_3@MPM8g%YC)#_iylU9S762@jL-h zR*+@+jcFtVElfpSn2Nd|`%8sTRU@rCI%(=3VJ4ep_W3x;=GIMemnSdPT) z;Yk*z2KjcZAKMd9)N<8itg3;7r}m-E5A$$&foUW(-G?k~hWqMZ=9U@0b(OCkF1`|E z6GVyXuH*O`57AL$peyU#=50VyF`~6}MQeZL4+SJ8NMlbA9S_DB8kr}#FwflF0(rNE z?ZRZ@xfaQ(G45Qx#Isw;>!8c33atVjr=h^p#TCSs`4 z+TkHVG0-Em)W>wjawdgznryL%<%0B<$J8-%Opgq3<(uyqUMRf$WCSW2IHI<&tD}*~ zS{L2ivl+SLwvo zKI@e=NNmf&6GcSbhbjojf`BBg3Y;V24+g2IjIMiN6!i$fNF~)_m8pzLK9weK+BkS` zIWhA+JX|Zs^us$`x-`U-}#NZvSTzJ6a#h2F!1S*;+gm=)SeBsEWfh%h_cF#d?k&o zZR;chR>je$M!0kJGGBeu%UDvRwrd}!KK_JXo$4a0%kNc^&2ue^>3N(Q6 zbBLi@b{#**r{_1MHYs;1xHAj%rur5c)B+i0#>^9FcUp83gPZe93>Z!Y)qG%eDy z`zR;QeavSkI|!@Nwzj*XuY&rv3hH0`R|2A>lW6H+M|T_j15*rVvy6{CAzf-9;cZ?A zt8Hc(AH2t*!`)+vy1Eee@M#)t25<;y>F;r=YPzlxq?XZZA! zGwf@RZ)=}O6hvgXT$BVNk!X})z*u{Z3Lo+$ z;9bIVaf@j(=^Q3LYAeG?8>lG%fVTueMN@tFbs536u?htWtHP&i`zJQGohO+#aXpZA zKR#9EZ4_h+vOypeqbjT;kjBm=DViqgFaJ|(Kq6YxL`RQ+KW)DJWXP(Yy14HL9Sv_A zo>L+-KSuA(2RwSdjN05xB%qL+807xciv!?*JI~Z|mV)DA=9A2gKVr~`5)OrkBxjBuG1wlmd#fU|N1Pz(xVu4~lPr>zw zyz6IsLkNO|5vioHqmxvy@XEnJ*8J2rR1!9RoEqkrg-dFFmdPjMELs9;tbv_78>x&N zYqo02Mv&^Zb{Z3djLxKa`uGWRM|WU17$~ZOVdzMrh$F1h*R1z0f`lOI7(NL}EbFIO zw!>x+nTe7{I8jG?R~K5%tM-&m=oo$tO_T7_CZ$}Kf>WlETO-s8o<*rtBv-IN6j35k3|U4IC3K&L zrm2X6i14GwMFmCC@aZx_#>278BK7MhA%1y?l18MqiH>f8K<3pk(SmWB;wrlQ>a6q} zlR|oqCl7A&UteBkU_6Z%ZRX^u^PD@ekM718+fZBYokNsVqBV`QcU$PGwbn@$brk`$ zwbqGal3ku)uGcWBu z0)nK_&`?3hw`PP9yOd^T^d6VKy1^O3mGasGiaCZX{?LA8bI3}5;afbSC zaN)uYZjUVCukPUB>5n;gVn3brk$0L1fYr5G-9USH9<}D>itFH{L+3o4MHu;rF zhVR|v(%09x@pu6x*2vLQA942NL3TC8QU7k%rhuqdvg6=>c8yFhKJ}2<$w|h?=P2x` z*u-RjfTD*;w6wF+t)ghZnhc0GG*KCpS*zjDwQ?-ajB)SUCBD7V&+{ZycJAlM$G_&| zgDq5reA_k=0N`Y2crtj8%Qv2oQxeowgb`AcJRY2XVV-*6rFk+wPr78|IFO!u!sDS5 z>6o8Dw2I1j1Y@&0palsdnxLtD2RVQC)s8Glp{YJjP+ucx>^a!QG}9w@xcJpYuHSpk ziWg?*i6eY;?lcFw>If;@I}xxU2qJc+OM#qBZwk_XceJN)0auoua_`%<4!{=ar6k#s zi90jO%`X=jx};K3-^roh{C9qLpbA|E1PNL56R+#wK%|zggC$C)jkmffs+xgeXo%?n zGMNlX%R~1CNK{2oSF`_bciWTjMQSW@Jua@3M5G0-Ij)VLv(ave>RZdtzl+cVY;qc~C1c6H-pCgsbV+$gN9w8jm z(bh@S34)BO1qu38WYHs+Tp?R1Vj`gXd;}vQbV(p>TV&EX9LI$<(+VDVHn#2Jc>;nY zBa6}|a779zz6k9{KBlt!7^OArlO!wnf>9#IOHbpP%gb`5*rfJ#=)b5Cqgfgh=qE=6uhlm|kFV%*-=6e3!p`d6E9H1?)gQ2M-?Q^vT2QsE-r&tM8TF#Va!^yf&sG zlxdmEI?-i~t<8miqDSdD@hj@~oLN(Etn3p-3BPo9@SGx<#R>YqyTYZbcX>QpB-*@( z)1Q3A!QGv-RE5#y?MV&vA|zGA2nF#g5+Ww~e4b*-#6w+kPw{YY92eL15F`mnlHM<> z!S@g!k^%1&9=7d*q!9>)2>Q0a(Re=~;tz$1SH{qUrxdbF%r50IZ5MqF{t~y8C7YaM zGFikyCQ?yBIOu;v5oiyqn5R(4Qz&@|ibg0DSl4m)TobdDCtI+<6OnX3s=QgtSRxRw zCJ_JezuZg+qJ$O*5UYrmMVs9c`P{3N6yRXl4zB0nx(-$;Pu{aB6iZmnY9QKkacmpg zaqt8QUocJ}@^Yxn!*fb3%+4}5zf8tes0dclP#Z+s6iz?^N%0Y>YS>~G^yNzMVm?Q{ zSi*E90-+#&Lql528T33{D^I>qq-45?J`GLRwpF#SAc$yz2$g}YH4*@>_Up^(SE-E)3;oEFohdx=D_jOe0u&UtyK{WRoX;O^-X|h zlTS`D)OVGyzPZJdWsi85ETN^1cB%VF7j+jnK_=^zs@(`++cXl z#8=(JXMgxLM|xVQjvA<2-;4FuMCKS31!s^8|h zF0SLShUDv8L^;?WsczbUukL|slbs*o=A{c67y@D+-drj zAPC5sPADG3S=CT174vKSp@&(ra8~vE9J4?%?;y$rN~W`>F!S4cW)VFQMc>dOEz=!N zkKE&{KYqjYhtmkrR*s(en2$~!pshNBE^l`C@Y{lmnahwXmN0FQRfAB-_$!6(58>fC zMGD0{`GSKWN~nP#x+HF@*sLi1G@q!Ln&I)Ct9*Om7LOM!!cBYl^tYdJq`QgAu2#Rm39xHw?L$Ob=Y-`sFKJf98`}l3qX8nMtgXhe0>Hqq7uJ=77U$c|r=fB`wPn1w7KqwkV zlLcHW%i`=bGqa0WYMk1}W~w9FOI6)2uAO9T_$lM#OITWnSZxO#RT|o6^7C&wxMY@| zbNAc-;x9KJv**z)ieyh zir_ie`6X5|X1Swht?%pESfw=SY!S=$kOKjHnu;b0h69ryR#jGBMo8U;g7;?oZqJ8}{oAgukcYS(jJ@=?$PIRF4407*naR15RWj8C#q zaL{5gcJFP(@TrKRha9Y?wz`r;P~q{?9Fva*nJ#wIpbNa*^xGG!vhd_*fN z@N4R(9Nn= zE&sld_l%6MonL+NJ3c+VhnBd%+&T1~ z!84b5^57O<{>K#t7on!-IA8qZuQ{=^;k}r$+?^j*Ryh zqOX$b`gXeO?s9!{iSdEk+&$RFsm>}wFYy03#U&=54AJ*soV+dItKUm!Q-X@%-=bum zZBi=aNasxuWmF@GUsqQtB4l*M!!eVLKbv8xq*B@3LL%5rT}1ldC{5YDu7GKKD4K!KFz~5mQBy?}Q7AAyHO)+Rfg86P zsHv&qNPFz13IZ1^H^cqg{R}^uBkyXo*Voe6kU$o;vRA)#;5im%F-Im>rZ7{DAby{| zTFEXDibkofiK7b>ScPc@2gd2DjuCr7K=^xD`3!TTBTOu%C?Qhc*gz~2Mim4Qe8dv9 zw6#@pe{z)6%zeJPxR1nd_R(7PLS=|sWNGFZH^1#;CT}5zYiMe&As#ihsC6=#fAWyq zm#%PkB9FgeH)nr+p2It8i5l{T5&@oFB%jNZD_S7R_yQpeP5x^VQ4TfI)>2PP%`c1gLN5;&7`UpHimVlGHFQ?Ts`y#Tk3B zz|507e0}u*e>hQ3WkCH~)xVo%e0Z4tJ0mPRA{F5ZTAHf~7}^#c3jhz#EiylHpWYjN z+@H)5sNTsJ|LwON+)+(a@8hwwZ$Vye5`R(VN zJ+_O+=mrx3j)hgqk;<94h^V?Bzp)i*OG-=*_Hyg$4Ia#th;-K%7P39!`C7hQruq|Uy$mW7@7=La+?0$ zep(x9NbIYBsmsp8b90P89AMaGM-gvIdGKE zeshMd`VA%mJQur^BbP5yv^-?hhv7HysavP$P|*B@DhvYg*Tp_OaF@wW3=&Wz#FC5= ztD&K>iTb#XAPPUqVg7F6kX@eS{`G704bPBMs`=;-UvTC~5A~4^CITD_vy>&BwQz;9 z-3=Hz@|Ll?0-z93ZE~qao;}HumHgDTHW5D1NX&SF3fptBi%CWwJmB8FF_!W!fvQUO z>~ACB(-0B1aO}9m^rJi6x_X`dnG%t<1DyTzEC)Jj%khLazRzlGBbO&%v_X_Hf)RXM z%I*S!N+6VA_r4}BJenq(ddh?T2eh`-b7p4(`LFBG!6_{<*f+rF_#y?*prfIdhPoKC zDBx|~0sXtjhh)G9e83tIWrNCw4)z`1$f8TBH4Np^)LR5Er#POYVR5*)Fyt_~J z8aNa)DKgnS1?&4=z$LRV$4a`0<9fJGk<{`$Q{xk)S9efBl2P;^@u(j~6!9F3!rU-7 zZ``7HcnM#ko$h0w^4ady##=!|{89hb14O=;_bux#NJyfzD*9W7sFafoc5a!`@!Pm~ z*o7nP?`k3z5Gke?nH(MD&dpogemsX2sH1E5A&%{<#ixi{RQRdP#@+@W zQ0B_4?btzA?J()l1;*}O;Y*>&^1)rS)~|{gIt9`TlMD~s9*$ik zv$#ag_Hf+q>3eKum(%1*E}m;s$|sqdof4)9U zs^HRg?01|x&`DE;1_&4xbu{hhW>5VS?o6i{y73iXi#hU#cG6rMBcRK8R-Vk#G>;$L z=GvtJ##e0AXe)>Iwb57=Tn#SE_+xc+?%qw$lLc;$F7x2xzw;m7GKco=ptUB9?B-aQ z7@@!S7T5YFDTx{_oqO2TQBOr+YqrZ+sYyl#?(yB-adKjirus(eqAJ;?84AnmUnhtn zvK}HDGSJns3uP`np})76i+3jw{c(1m`$vv-RuB)Yx>$0EmR-BqKQYDVS3^ucy2aOD zLS|t%UCq@Psz-i#nrDyh^WF76M&?XH_3i9Gx}TPixLWluAW1rvZ9Cb$=Q&TN(u^!T z<@%rgZ=~!o_IEc?71p7YWNK`Hn^(&MuTm&MOV2)bHpdBU;a*+OwJ9Yh80zn*e`uP# zXwcf;MN?d&kep{Kwf?n&q@d~nqGA7ExtEIzWAyjlby539g;|1hkExSMZCr-8p@ax}y2ZwwrNj6t_L2T0{ zJvUD>TPjohIR%o-^GuFUkov37@c*;-UQKc=S)Si7WNJ}bYXww6Yg~oCx5du%^z`hE zE!T{+p)GA~`N|JKegl33KGBRcKCF>TVaA>2bWh(4t$`|_w8+vTOJruH&d_|wLZN_$ zsDfw|(D5_74>wQ|;Ti7!_jCLlcUMrnLF%e}WD^PUMIB?$n6b8zBwMlo8>5tAYkiI7 zfVF$BlPG)ehr)zB4!P}Z3c9tU%>Wu3$s9$)!m)J<*(B?$%XkXq!`KBuMDq9vheHIs zhxgnsyR^-EY>4}hXNc!)!Yw^?HHJ}2Db`nCUy*_!BB|xy7u-pTFbhdG#;)f#cbXHVbs1qp`(cohjfHOtdSLp&OdWB8)f@3h@~ za-F5r>%Y~@ZTGNZY%ef2^pyKgmMO}9I$AoY3o8^->ny*iZ;BG4Cqhky4^@`HvCy|> zcyRXt_r~Jjujcp<|CXe%|CsUR3{J3~uAUyc+bR!reL6;-%-RIkZ#-pk zIgM1+M{{d4RZ5Z6#tLt!(%o?-67(Vp0*2E zB(oHC8^<=#a!J;fme3{2{+A#is6nEU00FOxAPTQO^Wphd0Z~E}#ofIo1wllVWF+aZ z??mokm6F6~o^XFK#(Lf++S*H3LkPK)Vr}Iuy6f>1*%?;=%tC_r$Tj}Y8*`Mz5FIDK z;mU=6>Lbr=Y#UQ6l1Zf~zM#808>u`cqg*G&T$1?8GE&aBTPLz7NHFL@wl#8@JSFS7 z?rPZ$QkfElY2#2No!Ve!F+_eRup~$_9$$z^$d5;nsp&mNcl$iCDg?hHaO1H?hI;(h})sePoaB=C_k&o5*@T4sXO0XDyG<)ALGuQN63*DoW_eB?`huscQx8d=dlZX zv$(raWF^)_P1KJf*y#BroADKv*S07K5gK|<^4(v3M}JcYGoJVaU+8T( zfJQv_l*f-JSj_0V*Y!f0`0NG+-Nts-n0#~#ZDZoOWA2Sm-F}i^Ul}0m6Uy71WH*_g z7~#(CMFJfrYS(ukrPPwAiq3&!oL-5uachE=$w7Y1Y_Tw2PsA^x=eAj2S!RA|i;`SL z-&(wDvz4{*)wFZst8Y1fypy`%v&j@2t+2(!!#j-5u9MdGI-je| zCrTJ5Bv+@n{f81$A@5F*M?{UbFmUP|=lbjLDTi%{Gbm*@7{2tKbJ3_9i61WZ(oz#ZK)@;_Se_c? z#*J~*iU#~ge#Oa-y&L7rR5bN+>_UpgwG0oY)|q^Ci`4o8V~y4LWrt#VgSF*Vmf~5| zns!c{zre+lZFt2!Ax2R`jW%=S^f}fyQWWlvvl4sEbuGoxWCK-U6|^ktOAE{`ZIKtl zbe%ZQ#S6!2tq!6brfj2^a4eJD`XaH|EUT#krYw@#nBng4<8RH9l6+C>I!{y<>rk^Dmrz%&1d+!-vI^6LAf03Gf#LtG{H*Nz_OoRFR>EaB2&^a^*Cb> zu9I6H#dQ&EW zE4#(q#3;9K&!N&++%J{>Z z6xYUf9aqU;Nlp84{{H7}Oh3BD$m}MmJ#~^#tTMk<#Ia4X8`C_vT4LczV0RKq4mHwu z;uL4v;OUK9Ovkenb`uyZwiahtOY1m>!`jRcKmF4>;hl+pL6QkI9O1&blN@cYJfsKZ zIcV7=tJCAm#?$0W4nl67kvl&zKltXUI6;yL)b(-h>?uxmRU#migUGAX+`l_WRtQlD z^>X^eQJ!y%Zjeu{Fm&}g(}^Ml<9V2S!d%@UhkU?EY!_Q`Co&G6vb2BUAu z{uVuce9ag6?YG@!y>uL`e1gTv5pLg_L5w!zKmPZeYX^Mgca`n=Ck#FwV3%OJNk%fssy z%Ok<(eKS~3*Rk_lIoFC$^;6Y+gs-n`kSyvvoh_gDvmIY#qPdQ+Uq*5aO1U&^3-c^* z6|vMPy#p7xbp8Zw)&9ekar+WRF~`=z45RZKqzXFTV4CHbC;YfQ`PO^oNHYT`&T#o; z3tm~mu}$(@ON>1k1?me6VGT^y2a+=6aM-C-p0Rk zc7q_vs5Jw8duf29?Nx_VFFz0tXqg1dGvmy~(-cY|<>EZO^+#f!x9P4zxZwyFFP!3N zYqYGpdV%!HH23Zfl9!?s!+o4RVY7Q8wquY_E-`rR2C=OY1#?f5!rT(^jD};t%Jd*V z+G~V7@~+<$YCOitPbmUuEW&Pqn-+1#_G=UIuZlPT%gtTXZOCWVzzygL&eqBl%q z*D1a_+e1TT0Ds*PPF{$U%9gk}G|%$*Bl5{LW=89&j`|QBgTi)#wdG}&<7q5!6}_j< z^X+$M=!{5*e1&~kcV}i7SxOeM10J@PC%OC6+S_d+Pk>k#ir9HZ<9d0g{RMLA|=v7&#^Ond%78~EFvlaLJddx z_WMiZjoUn!h%@#0CfURaV+|DqREJ`Elcm{tR#G~i>NZY)bD1*(ZB+TcgjIN7Hiz94 zadG)X2nb4u>eiEd`-6q*4>LGA&C13E4`+)QmV+Rv_<~WY8;;UFaE1%tUg2a*2#N>~=z z{77Hm{cyn1*_<2W?$xUduH|3-XJ&$#;RG|o&o4=#Iy%lr`R;OGIg|X)h#;v{cO2u= z6&pwL@pycJmG~4lr=MV0HlpIeABs@b)WfNxXSn?Jc~0~-;XTwNosDJYn0tJetB)4< z1ZG}D&nz=^clm{DYW;C8iS_*KQU~%|4xj}g=_vUgZj1(`n#(4 zH*gCok-84f{qk=ReNi3^Pcyf?!NmP}9v1a-=Bpqgdwhf<71VYgr+45Km%qM9Z$os~ z&@VqrAyV7Psc%ID$xFrHII*R5W}hrGTrzM336C#8q^g!QY|Nrw$fa)-?L#r@Yd3H^gMrU3j}XHW^87e zmDy3|hD%ru$f}oMq>_fdQye>Ufr}ST(_8oQ^UK>d)pZ`{n_miegAwjNoo01?iNU2w zG{ZuWWPE`zmGzw*?K#GUufOG7e*+QU;mulxa;APhm1aAcL9;BhQi_GAw^?}l_Iu@U z1HG3+oI2J)%}y}jEpNlpi)_qJa_`3<8Qv)F$t2&)CR0P3ObtE1A_Zy~D1>N;Hn8#Z z5kK7;V>SC~eL`R6-cK)SYHdGuxS112n+U$V-|C^mA-k1eJDsOw+c?<-u_p;)`?ymI z)(|<>$geK8QW@IM7MKn=8f#Nex%=aNo^BLh{b$83rk`vv{p9&2Iod+k`4GSPp@!Jd zeXib(v7CMNIG5X6;PKYN3)j@zqv(NpdZI9V=O#BM*Y^Z?_M)>kH_qDJ`0f=!_E3A& zpuVk>-uB8vdnSigD3Dw)uMX5o8rs}buFbvuK0)?S*{f0A)Wz|xef~bjqL7X=eCs+l z=C;|^Ui~e%7RT9I9N%+IplSd@6&@^YiU(JJVrVV5CzE_HNn*oEVtZ{ze-(X~gY+C} zr?J}qV%yCmh&{Qp@3vcUriou(Xr&@_SUaghE}0~?ou%YBIE6HGBlnpbdHbD`FGBQG zJ>Q;br8eq)`wakgiOsn&?)~@^kJevx$SYtZh>awO?J0v4Zlw8CfM0!6$=vV*uHP7E zKK+`$nOJ7%&Wn1f)b#MRr=82ETky#ezHl9Vmw&*P{nR`jVJPB~Bl0CF(oOQ_l{jULv!ZC8r_Z0jS}B$>_^z9X&FR|XK}C|xHnBY6V&A`cmhEwi?{%#)=lN`{Gzh@yH4gd<0bUzF;z4SaLDg__8Ig3J!s z8u6*8-23q!gX^!ciHt2~hPPgvM~O7iayrB>E(Mt#e!#Vx6R-9Cvs;S{ZY{oW&D(IC zoV`K=M~;F-YtTZ4v^Xf&GY}y})WuD6vAe=SP=^MX%n^bGR+} zf;;ynhHxBCtlj-P2r|X=kzAJ#rFkKnQLu(kbdFXRU~(u7K&_}QD=Es#-Dc3S8Spd( zD8|UoYXY;xABKKMk}zuX3wWPNS2$wqVs@iewPHXgysTgDzcN~;$<_+P&LXHP^OTyy zMwS&ic{Z%9%E`(j!j}QQtsX|=CX|#jm{4|o-bmi)g`6^W9-so^G!9*)GGlu@JaM^) zv<=V>c9i<;kkiX3LQr$7TeH~wA{C|K%Q&;NPwn(KlUuHbaDrksmRA`htwEQ@T~VQ5&KFT-k};YxG^+1q)H}bzmO-BQrI8mU0t95&Fd%v zi&(m=D_)W)Mj4wMW(KGfTbuVyTO}lbM(g|<5_k4wKREJ|rtoM*lb$urRW;lyp|w7v zyn2xSiL_dX8vC;&pi#cmbbd`+cIdfql1R!RcqvEkLmhpZe_;riI_PYXrO@YNbBw|C z3Pn_AO6c%*o}OD4wvzllQMc2%L#n*m-DE6eb9H59<{x$T&2lvuL`MJEqjHnKa(#N3 zUr`qQOG>zJrv&B;)SJW;9BeC?>bFNXqw&rxhvE~IGkDTm*!0PExI-Tcg6X^nsaphR zR}vkKbbwlFo@3=6yxhmh+TeDT6?%lMsJ1HZ>5AX3#jq~=T50_y46VH57nP^Jys*wb zv$#nE5G(D*?Aj;Bt0`^h3D3P&;K`)9rTJH|Lu-hH{-GZGkjodX{K+HvuoTe?>|JF- zU9XjjLu)K-x@0@Rs)Jeco>e1Wuj#gR=V*zm@{Z0L5+yRP-du<&rXO#cSJD)Y^?YWx z4HnD1-;6r9hhCRXY+c15aQ+NB2f{G~qP6mN6uCSx=W$0?48jdlKtP0%5=2{E@%Z~S zjrmoIb7yeeW<8L8q?|7sDCi+Ym>ZxPc`bE)EG>F)lE4~d0$DT)KxPh%IPZ<5bSb!d%Q37a(`pj!p3uYWx9~QM8h5C-H<8>OE zX%2`PeWG^#^=TzP++dvIinfgMzUt|(Opdr*?&#IqOw;5QB5zVK9&3Qlgx#|v$!?YP z-dJQ4R?1r2_v<#Vx?s=~gor?Bqa7Uyc%{_^?~JAfym5VIt;4LOsFRI%roXR zvcjzONXmQyBtTQI7Po&}TM91vuOA_U0uVCRfl9TRqfDI3J~J* zCXu(7pBzxVNZFn_kO4iGsBQRNQpK&IqzlZ)smrTU$!&fue{SDG)YMiMHn*icENCB> zh(FFxj8KF6DpN=)XN}cQ5M1-}A)q{#Q6B^r^g*b#M16LkdmAqPkhZukd*6=DUa5hl zR4yCD<%Q1)+maZPtK-MMBoqA?@}@$_yU!F$Tt6Q-%!!R#@5(cNpHL|~SbkO3DTbP) zspL63kfoEd!p@+X?IKqXHWf{5S5S~V=-`9)vgK0B7G}z~`Fw zovsZSZRP8E-v?rIHs9yWtUKO&5dqQ1%e<(Lj;@v6#S7K!_r4RJ?W7QG3e_1;sa4wZ zKU6X@ZHY%ufal^0&vRTwLCRh6Jw!0o9v~dxlcFgn#=DvtSzu+^8DyWn+8P@YNE9WN z7*pu&zWwOCw&ZOab@9FOEp;{P8$pn8{*;vcwzoqnlgC59E!^ zTCu%O$a({LG;~0j0mL_7{hXzh33vb`tXF+ zl>Pik`g1}g@nJ=26Q|Lc>2TLj|MvL=-cHuFFvH{9mGSFpyyB8X0BxwN%RTuF_$ogp zN;XL+;KI@&twcmJz}H95znK$iVjY_P+Ig&H#U&cdVDs@uiR-cSLX% zN+t4vhWL1Kr{J4}gu)y}Qx-g}(D<21Da5razO^Q~y*6K_*H8`E7DDUO^nToPjEglpPnN;yv^Ubih*MpD zan8HlRaPfEv!nczJPO;RCbHlLw=mF3&5P9-Q)3S$c2BEtB24>pA_#D-6v_cROsOc!Ke zymM-Ukqyfd?d~k~xbjTDz47Sl>r4F;zD$k}w>wXU(Y_)MdWUIGBru{;@F^Y>3ihv73LY=}2j+^xoXyA$vL>BrH)5nwv6Mhy5mT@&v)Iss=G4iGGA*utAJY* zp}Y$vYDIDG#?OjiXoN-HRbF(bMS0Rs4NbgQzfY8&GNfk_OK!o`%q-N1Ny^NOe1JGZ z%im!Op1(;o@65i}H?Y2V7hd8^%tN+=ZrJ$DsFQX=sxm(6PgLr3GH40pLlM7#An`YC ztI+o2m8@l__S02?URh%B=*3{sL|4$bMY?xF77zn0$!MjA0ve+K@ZgCd`p;mZgLt)`ZwF*DG>1PEZJfu>5DDkv8a-g! zd+LS7C=qJC3q9d!&Jxb$jj40*0@5nCU?hu|C!kkyiBvcAbin%yyg|#iXS>Wz6$9%j z|AwbSAek}-)u;XSC!mNhqg3>2^KUp22L5TB`L`LG;@H9;`EDdM20xJ*gH~d&gNb^+ zUy8k-xO07b$F`A_Z{91>liLg)kYnCFKTnDG;U#W+--W)nO(fdyR3T#o5elpK5jFk( zJkdn3Lw6aU;w8$vv-e;7CHBXZF9<3ZkvSKZ1bELwOKWE!RmIC-%8fc@<;wSV>*Yp* zQjhTB=L>!~obuCdyf2oZ3X)l}&;vY2UqtZ>lxB}&{B3vNY;PN1W0ax>zz>?^93jAd z%g-=tjIiRP{vPY*Y@-WL0723_B>I1jNy$NYi1z-dL0iH^#f<22br|=(oJ5*k;1Hg7-dobTGXeEPWf{$ce!T5sSjzXQldtPzB%PWrl;w}#;>;XU`Czh+;VI=qRq7PI=KSoPs0#|STe+vlNI$c z`)s3zNx~Y66bo-FqVF-~3zU91UIi=0m}w`=kb?;etvo8~7I{eO-PtyK230P~VR&^QvNVU410&TPH!aJqL5VXn=KnoJuRmI%vaSQ>06jDd? z_KtT1+^tNN(?Af>!c5oLH9rvgoSg8q#$K)7CQwvD5DJpu#Qs}deNoQ6xwA@$;vV7; zDXuJEKzV1b&R0CYrLG&A9mz^EJi(4Eg~y(za*XWgT6N zp1Q7vdVcq922OPK`PWd%8W4AxP9yMrs=nDkoPFHn&K1}W&y`gTqTrVCC?kxxZ@9l>fhYRNj6m0wdj@JRF z5D!Qn7A-_ZH<5Goka}q$&*47 zSk&|abi9l1hV*>RPDs9m)m_j!?AKhq!9U)SKSZYWu7%so)&-0jY`^q+RLp+zJ=X(j zcTPlmFJkRp^_#73iUjjIJ+EG#=bNAWT5e^R$`o(Awl!e|9R>Y6==~KwPg6d)-D*Du zFgND9nzInqj|JZyzFlrh1z-rrMY-|3Unw?*mbOBA0Df-Qq)#=NlTR6Mx_JfHz1s*r zx*6XnAE$jrTYi&G0y_;4jHv&oX@Y^bF)#;v_|K{_lqA#Kcnu)}rSY5`2@Vw@6zb&= zk>s=0E+5_5^dI(JC`zZ*9ubiYOy!Cq6CMTH!$HcoGv*Uls{(bFu?wxdK^wBE;F8;t zn5e+vGuCgs(Zc#3VUh%jD(&}9$v@p-g-dM9VM;@@B?@?SJyIMwBpDMbY_?<$$!~8m z10Xj(^w>>su_DeXo|V7t*BttUk&u&rEG?<4iGN7#%RZiPt(r&bQHXMA=I2|bmjbhU zGFmDE!XTye|ATiB5ImV}U~ZusuL0@>A%lWD)Ca%4!E{GG2&dj~$AzX&{+T`+JCZ#O zi#!S>ijay5Ub&#efWuA2mxzhK7K0=kwj{*E`r1qmnDfBgod zTaqP0B0)nyx-BOhb8@YZA?dgx(~YFdgpcABansj^eZFt8ZIU8RBTX7traHq)jXeki zb`$voJ_?xjlz!x$46Z^2VBi7E79h!5$^tgo^%Hzcy=T^yGms{l@YI7leHgAnElRC3 zFepY)O;}zYtxs|-4I{GzufsOgwpK`)lW9^UoQl?yUqB=QO1KZx&Cnz?L|H0HjzZc( z7OVU>Elouw%z>&vQRilV1AUB2oGpbchoRVle6_QvxQ1GHFHwPGME*_)i655kNCWT; z&kiLLts^m#{w+d7Q&|;VWK9y%oes1nnKWr8_3GE)fb$PwF=h4cAfi2`h(9}%S;cD& z^3A@fa;+bD(@YKcAi`(~>WKaU5lUQAf2(@iM!vb7Mn7&&O1mTyY$-%3H1mtk z(oR$bq0WR&2o*{13N1G>?G9(t#> z2Y7=H9sF(3%J>`_t2~ytxlWR@;s}NvV21jbBEXjyiFmn+;q7$tei)tXin`&1BnB<5 z0eA)F?Yt2G5?VLWb+Z}fPhsH<``S`dq713+*T za#m}GHeQlMmdGuW8h8jjKc^)>SJk`4u?{G@2S&^`*I0S9-r(PsQG^s%;ByVIu&y{7 zxA4d<$w+SvA&M9yK>QK{&XCyODxwbIpxK}Qw-;-xN}8qhibiDL@P}DM0^6wv2&A*gY8AbwEe%mV6HKb-eQdzmsE6c}I|>->Pl= zHBb0jCb(&C$=z4yQ|!nJREVel{@Ted8KAu_n7WS-H91SZ+o+z2V}02Lc@8htmdE|A zQ+I3ldBDi!(Tu#qi@1xR;~r8$_)Yq~@rb?5I-+}nL;LAT4I_u# zSfnoI)Ygq)X5pDwoMNHHm2L#bhlO?^5)+pPz1ouGa<9(Yj)SNi@E1TNEVz6yOT?v9 z;NM%WfsB!>`Ga0%$@}H2 zw}BfyB^SfY$0Kh0D|T89Ve98GW-+j_^OQ@9$Lk-{3$#2b>fMT@mSsdD>>K~S@3P^` z+%Ok(YPA^KgYcgHjtckyny@Z|A(n`6$3^DKHZ|}~zPwh|MMagnM|NTT_u0@{8Z?G%>N}Ze7Mm$MYYm z$%>C0W=-!W=>2}I1FpurLJ{ZfKm1lEXidPSlb(TRVd@&yaU|c`1SAB85cxofS6Nz~ z<<|uS0?|@dwekB&C28xCu?Ay_dRZ3M#xV_%Sogp!XLm9u2eNiRuA(h3DoZIDhu~OT zm$UpP<2$j3*N|&c^xt8=MS5nsk*#s+k!SFg9`ZEU+5si-avKXmKgoC&$KsIA38LKR z453!}s1CG?XjMKh$F!~x)*%;?{!*8ZgT8Ng%JoV>&#&Xj2KcB9Fq>#rxtKUs?xryn zK4Biip?Yz?FC=vK$L34RkNIm1Yuey$CG@yh6DwPX+D0bU{?k=5*83`3G8QyfSjj)i zzWy{-=T;ZzN0#5p-d&j$kq}D7vqB!KS=CdDEG#@ThYu_Ou}nSXQH;aJuqDBjt(nyI z=f$nYnWI*qkG;>(r%ya~wiYq1+P?rm+Q;CIeqj|y@CU{geets4+}5L5rtdhIbU$v) z<+=U$yg}#sdF0zOcDgej9sS_l3;x&btfm)JPvlii;d2_$bL#Qgj!n%I!O3rcHSa6q zIxbETRacAFCjJ*Gu!P>DdgOgNn(uA&J5${*is#`7OEqyZOC2wZZ+EhZ2#uvvFb%v3 z_>}#6(xi;M6!mD+ILXMxGI6yHdrgs7S^JrJMnpp(GH;!^-g(CDoQ(Rp1sPtcyV-=ZrkWIY!#d$Qv+Q3cY zuhD)#9FVpZ_K3M=e~b5)90b{wc!8AbVQbsyr4p}F^VG4AV~378-A{uJ315Narby?Fiz!9EBfw|)razCO zHLvIl5_E)BRAxWO@ue?9UW2o2PNC&KxqU1vz#G{_69v8KElG&coe5|Mp0MRCW57`Co-e zKq#zCWf6s;N~Zv{sAiphS!8DTzO?XlD~z283>Nb0C?lf={%$3d!?EIsz#$6kA62FCZ&*TL^LYn*&}EWk*+G_NbI;e|673_( zI#pxam_z%^d(qi>WaDj{xX4yF4k(VrZjU&PtcckFjxC<>#|(LcdCa!k<=TDRA#7jvvKz?U!VjCvyIKI;-&e-$(7?6Y}-`gaj_L8+8N$c zR~H@~&#rN?)nUcnN~Xxt&W_b66)j#Ini%Ps*`~I~C;^|EJM$}O#D`wj>zTu7w5lPS zA7>PZqp8wpa6tZtG8)=&KXWwDu^YuO+rrs6^QKuNp ze%I{W0}l4I1hDHbEs~0lM>;xU9Mw_+J~CRC-sc;7)5k5X>4)|BcU={M!mL#zgTQMl zBT@_VK}0wf2G)QrYV*(o)Hk%>zrpsCIG(-mvyNZ0f6 zPOq-Q8Ghfo^mZ@_>9#mX9^liFDw^A6W_{n0dgKmiDPYutLyIR&`r+d?{W0h67{B{~ zGeKR*{yc}-(dSXHNqI)Ps8#Uh9~t}P{Q!(0-Q!}z6{op+By|k&u%eR2$WPrj8S3rb zoe`W5ob#U6Mry2@+nA-!hd+0GS~h0;rqUPE{*28a>3lTL0XAGRro9M0AAD;0V;b5! zBt4EAuQ61e%sDi)(qoy?c_%#t_4f7~Fa`|HYEXMywaHp|hUY%t`S5a0xV424g!R81 zH&SNno9VLdNjE#Zb9fbxwSkjA%-?BaRm_>Xs-sK7!9REifc-eH>pKy%dB_QNZ>>-U zV#d*M59WIy`EaNqp;*Q7*H$TX=XOp>dE;VB?3(xh5xSh$&NpX#y4;`QTkNuAnkTDT z+D68{*%_e@uSbjw^D9{WeOVC}%2TD%wq$EkXt$6P{>>j@Dfdw{K=byFXp>)P9O>BI z(@PhKo;;|ORor8hD$Dxg{qxS%(7~1RwjZJ^yPVS5~sFt1H*q72!9iXAo zDWo+KW1NIZm%#qExp;Yvl*lZEWSzm=AnR)xJKf4_|1!#6%9azqV4lh56S1)a%PUUW z&@;7upeALtnUd$*f8M6ZwCN*$;PxuH`5j_%X4-b_<@}7nc`fkE+AAv&Yv6{qFks9w z!X*C!q7+)CKCairqQkQ~<1elTZiIFEL>Pu|<4eL5)CUrm(HU8)gqP<#1LsX_L$}>N z6bwk8h(dr5#P?TygIx$v1f}t>?%K#1tOeJC?)y2M+z(-qJN5Z(#}Wj$2Q5Bu z3JxOqVYxvjaCm3=6*NC2;%Z8`M>Rfv<5(vx@LUXnicSQ(86n zWqr#K@NovRP-W$uD#f%*?Xc0DC#i*#ks?j7-QB;`rCNQ0|C9YHyTdU!Zp3=PV9o{l zcvKP_JI~DDDbv_3B{!mrjn4xUA}B z5M7M1S@lftW$1NuRAQDg!|yGSux`u3(j1mpOLnKhIk9p#T!3C%uK=}Kb5t%$D<$pj~41ujR^kkiGa5) z{(WrRlE$FzBFX=%cb;ky>cO{txFS(fx!PJ50aFtiWtJyaZ8hxq>kejU7*p71`Js&8< z9~%&m`gYsz#+j%0^}Xg(chY{%H+kd9P+M6sSRZ&+-%%bJZAPh*=40MO5k{~j(;6no50*&Zf{-CQW7^I zf|;00(#$eDG)6UBrjbtQC#2B4_waK2ta<2#`2(FE(*gisuhr|CJ;-26EK5F)L(s8~ z0`S0{RzOuXk@9(R^`HMk^RVZ-h5Y%Vx8zxjcy>G(gQ$4|DzM8w_XyXYf*p3fY36JO ziN~J(IVk8-+Lg%?4DkFK^4PasLgNULS9KbD_mfdn)}e{z zGw{MgQd@DY{E~N;P>@@~E)uhAJdn)tkY%fxLrvBBo~Lc32rAO8)kHhyJ?ZfMQABm@ zY6|f3*7k9Z5DkyMm{`#-a*~c~daJHFRe>QQN<`4~k?YgM3AS5Wr9PgM@ zsf36``fi64;zd?eb38QH`KT&duZL3_iE~;~VF7Kd@$Qyl=gRg|4p(KqneHq(xb!TY zuVk_1$>~mOIIGJ;96F>w@WYQ;Xf^?A`u4D&smNu6tQh#!{lGp^a97oR@q>(#p+GLJ zD#8FZ7b)AyIJ9u^&6`UzTbEfT=TCS`XjDB?amjxmy;V zrD^|uGHR6l?!PXp9v9!MMR?m*f?^annV$mPuMBKz&)A;vp7_}+`l@$2!EuiYWMFeo z+{Gzaxp1BY_~ahgrFhz!n?g71g}FLFwxDai9%pUD)Yjd7ys=ZnYaF;~IbN;62rD*l zaZD9;iB5sJyx4TL-@Yqiot78;wHqc1PLw~!L0u@u%8n4>;CaySEa zzNePLo2ugkPrTgVr{P1nrouSK7`rJ?wT(9x;I;_OeHoK^rn`P~JON0pV`7J)?G3yJro7Q?e!)@-zQdQrwW{njnXp9U(-foXKe#Rf-Bor1 z0H(}9T`OXVPMvb9M-|iQ@8s0z20o{>y59DYqH#AiLsSa}xZO?vsktpmILWVL*7xoF zD&bU%T$h7&7mPuepiBmVw@bbdAY?P!+*Eq(-Swe)LCG)azx&7Da7;YxnV*y)-K&t} zoxV9MGqubwzs$Z)`gV-`B}wPzrX}&!(=l%VS0U2dI98`PGS<-*7K&cCMu{!yLdqtB zdEa??3;KJ*W*dGU)Yxx8akCEh4B(^3UyfN!;tA&GH6#jF;s%NGPdKm%y$5=Hl5EM~ z)!gt77G`JuEht5;*h^sCZ%c3KPpj#7Oby>$v-WY!o(_)2_$`Wd$qqTMf>l4#b-cjD zJMiz1H-Qgi=8SA7eSF2ASTQ&qG~*&YeD$6;089A{%;`CLX(rrtF96H3$!i zcCt_84B-XB!HejEN(;@C9v+(=&lCgp&p)v>$|SIGtBP7Wz}kk}9sIp5=2XPmO1wB3-VkZ^Tw_;2ft&bio@|@451gJkiZ$@~} z?CbUfzaMA$^ta8;PnnA(H>lvasG0ht*U5(ejgek&c@5aA3}8d;M*NN-ShmVZ%cm7i zEzNVfAAyoZjt%a#XYh5;4T{6@jpMtq?qI9vbw8)A11xE_VQpxc9bW5?D6$`%UCLQWu zXF+|>E68Kv;i*~0A3)pN^$-!+0zN_@SWr}ik~bNpk0CUBxH8X;zjj_)+?r!Dssqh6 z?c)&Of!{+&nDP9RUY4VGY7iF@8%Nt%(qnGZC36<2y%lDRi7*-8y|JV{+rr4`d^X~u zVKIV*TTxI^0T=J~y;($Sg@QZ#dXd+6e76N{3_%zxIr~r5%>3@$(6hZg9zsB0Sb7R@ zdW|$o$tfk}|E6HLd(iZ`nC4xd0T)qjs)FClu6gi2$*G5*X<~LsO$zVE)&?|&#zY1O z;ZGy$;U746uqWJNh?!!{fR>*r%OF4s6<8$zyt8HH5Pq^-WTsDeAu3S8Y}MT$BA z0a1l!-UYjGa$%|lOuC$9*zWV;$$ddZJ?1miog{iKMmvmEGLNML-Hf4mdU=^53pvHO z$(Jj(oGnz(Hd;w9zx;@+XEc6p#bEd;MBMz#9ppiiGbsuM*1iE}nnX%t!aA#>nyTN1 z^K;IN^fL1UBSn2)OLHnD623J=x7uzvl3d+U2B@}ao4k!fcUTCdSH(KtkJD%u#V;56 zH7};@@)h?|bd1qV!bVTok}-MFSe^2SIN0!)fLz4iA(^vsWQDdq(PNaEr>|#|qUV}h z@eBKOv^oT!(07bnF5)G@BAY5Ax99`C<(5?qPKWAs>sd17(&Zl?9w4;!^~_zk#?BvH za_Mpp)Iy=VoL0mPSZ-UB{k>gM&l;S<%t=;Z&QE#PMeQOX?}?ZC73^kM+uBDY=)$`? zlj64hJ8@}l*8&bHn%07s%#ST+$?j!s=wh#s)(niTWD7QJxs;fN z9Q43znXvNVt>+uPB7&qyjUg4RUJB7q{ z5cN;HwUTI``)VNQYRJr%u4?E0a%UG)0s1|&3mH0a#vXxd8Mb@SVZcH-XY;?s?6u&x zqUhS%*)_Hlso0_S3~15V5(v>Y00#*kFMuqAHRIU zYZ$}3ucFR`+4MwE5?yqGF5F|3>-5(%kUR*@(4zG zS;-C8)--#vxBr82ziq!Q$J|!S$o?f<)!@dEh^$`a1R^@=&eu!tA@_9n$E>(qv-~lB-ueiCb(Oll2%pp{U+=mMqmyc8O-B6lAUE4 zI(n4tSf)NUu`PdOV&%mq%_Ah;rA|rAbwO%+_#YnFRJBdND~gkrqNeRjyZq9}JJ?e# zNW?^l2bjU>^9gxgDe2KE8(F3|bt2FtCb|^nb~eOKI=(5l(J`XIwP&54R+(lwP=D|1 zRy#mIOQ=Uple`Piu}kt`m{ZcLEb@#c^qV}irl9&a&I}1uiOKMd9sm1jGRbQh927Nk z@Zj32s(JiA-nDAnV#IO!(8~XdnQdCfHl^f|YW}xOkXN1EnHXl?-EO~XE`2G~B8SRZ z=;Nr9afTnkfsX`38oNXZ*s}x|DX%=cvU^_zTO>z#*E;MszXB{Zw6v zC9U%T8=ld0ax5x*_?mJ~a~}V2WYLwHH(MzO0SWB;uD(1uzJZCqe`JXfP;Ca4UQ)ra zyXKs|+oqt)C3SijoZ`9$6~3miH-}8W_67sA5eS@Q;l>{~9Wr(^YSC%XLOe^p705qQ zDdsrA%GojEO&wgB6B$ha>BOC=?;GmEaKY8bXPug&YvjYGXm08ErV{l@z_;qVL6sMl zzOHXY9@bkHzDX#`K6Mz#H88%yV1l!uzHW6r4G)6`QD^N5H4lGde8LpDp(;b`MAS)2qm2Q6TuW!eU z8y6iMI^1$zBTY(q!bSshia%WzAiFVrsUW&JFL6r6TeWnzh_Iv+m&9T?Fhj|KwvZgv zBchvDABb^NGaR_GE_4!TaNwbftsF|%ZM{lRW1>jY?a>qER+R;(*JQNgX6Be2P_0WU z`}Nm1Z)Z-yxUzBzwMp!6UeR%v+FAE?J{BKh7)djXpUy>iuC($5&fI zJ7|n0wxyIVOC(FAISqe!q`+e0o;>B%jp(XQEq!D0MUa{hbU71&lwVPD!xu(lUaQ7} z4_k@Zg^@}`27c{?Q<0SB*SPx3_&ctvH@URc z8-~A?5C&w&K{om71&EWXU>sy^m8NPQI5@d@KuLx_@v zx$UF}>d30`$kWsisEmVRM|Y(!Z~J${^9<|rFQ&cwt3ds@8+C9~*4K=gW*Km25v55X z$xxej%kaySQXaXkD!y?AX&tcE$(jJHx|WVS2b94SLVGxo^HV~UM^Llnp5~XXekO_h zeSWuP>Y}EH-L0Py<&&q&rAYD;ev@O{r>Q(RU8B)6YiVXr-e)?3BJ4zt`xO0S`!adK z?LHD{k2tryB2}^SrozHC>w=J$R!D-Valkh(7A(akt1!R&!^};&RaI@HUozmbprkA* z6NOU5H)Y8$PXuKAw79r7^dJhes4w-Y*4wvE7B9-2Pe72o!~kx9#hO8yFGEz>gOFid zT3i)3Lfk=;&Py#nQMY>8HtQoR8rl zkGNHX-fplUMI^=XGZf?}xI%G)9ZLq1qovAjpbxg4gZ+ z?-hr|k{~8Bb;}v*`zS_`kjQ8W+F-MmehZ<<2W*%g`24mUI%g=UX(J54lkxU0r+w_U zHl`m-uVJvhh-%0fg)VCVWq%ve5pF)RsCJm9=1HfvdNLN2$DD(fx$<< z^pLAoA$`UM->j;C=-)!cIEF<}AT#-~T77>yjyA8AD(4;_U0|-9M9bIfmL*wKRlaTQ z9gkl^#Vh-e0oIpj97wbdrN-v?5QE&WE$8FFPhNMl)qQ3y90b|aEhQ1zggRY_N7M^; z=Op2WNx1e7>}D624uLe7nIjH$F-+j-aMivuqc6|TtG7|!yurXwF#w2~f)iy?6sgL0 z?isWjxkL3d#9PO))Z zlZz5_4p5P2w4b$P%s+aOZ1$?Mw5=?ha-d*q^8T@%@)s??p$k#h3?aZou!bF2`v0Tt zwqfI?rllRaswb)mlPX&nLh0%*w2&U*!1Cdlb!Ut2DhVwug_z(opJQ80Lzp_RD&A)F zrTXy^|r%C|e@N~Np&JztO%BLQV^ zi@aj`;VyVYe*Lj}U_+#x(+(?B;hLc(U$VA6h8t9=_52uUb%wNerH;||4~ySEY7&O& z0(#lpTzd-&MgCC#oV*CVYf|!;GP5`cC&xlR99=*Q5}BzkF?^2yd8~W32Db9tT3Yrk zNWlfr4Fl-2k^m181A(o-GOq@%J`KqmOhzn?Qb0~g`hmp#A(pJiJJ8c)&Q6+i8JX6D61Y!hs%E=Xv=!U7Ht=^Jxe?Zy=ozL$DAlpBQh+Q zERkAm>m_Npsn*7{iQ1jSi6tt|$aU{tr#|!f{cc_=G&RHXDW+_JSj+=lat2OC^LW_( zhgYNr{F=6$=ri?Cc4@Zpn2nps_=7%(;6IEqFi@|>g|0}k-m#}66a|jS$wsA%s$$v| zsP{Go*TGaquAaA;Xvp=rt1-hFIeKJnB!S0F-EN%{noXD0F?TQHRH!!Ed~P{-+}om| zvr&LQZtcBLviZ5aN#Ja*7JsT4x(zmLcs2V@V1%axp9`r>nDBh(e>rRZTh|RSZQQRv z?6@UDg456|smbnClJFpj9!LLsAI5!pb3=%fK<4zl^$Td1)*n;W7`|}rornz|U4~Tm z`KTQ81FA40B9I8E2%3Dd1&WtRl;MQQ>D2r;c5OFQzUzU51fDY_klg0~(o6K~DS5$tNZ85*CWb@L ze>67_6C6Z&YR4m(igZ%&y6LjE_`W^5vX!l~KWgLVZ?oh{6VdeuGSq7%cTxR!@g(nW zqO1mtMVAlTz*aGYwd0Y4jcA{T4FDXe=OA4j2t!Q__bokt+!I9_|iEl zh_IQ_TUlR}$@Q(!i?%{WO*We{B$336KfuM4P2sxQs!ZLLv=*d)$)Di1mKI%jagQij zhI_Jv8`U2;b~Gkfl=*J_L}-SabiG z$DwC6Xis<9Y=i)6O&^uFU6Xgv+7jg|+oPhLba!@ZoTBFbW_>R{#k_Iw(}Lnc<7~xAwFKxw*@@uwQiI&Wodl9|9+1 z9lo>%7I}&=?-?woAjy`_v~k(q-zfiE=&Ach?+tx9M|WW8RI8T$ZP-@a!jq zHYNU!xxaC!k!QFkNe*WUi*`LXo~JL!Pk%!D@K>PaXW{Sh>!Pu1pGgRIH1g?@a}0nQ zM2x~F0ir;f>+b&pF+tA0VEUawG+=NR;{V}4ewlk&w0H=VR?*QAU}<=h<*_G>RyuK8 z8Yy(=HC=TzLnbPZjJvN|=w)1gT=H9O@Ur#RhH ziqG-7DTKoV(O|>nx8d@??UM@0c${!JMpl=QttAu%tXTFOaeomypb!p)iN?|(+ps(R zc-7iK4?BYb&}!HnGL{{f7*XuaI_@)6?0{ktQEj z<6*uMAX}XHEl%EiDReX~M|eBT&Q20lvSN1zDE8%xGY8t9)q~smx9_hY%6Vf;o14P7 zemX-q7$Fu34x^nP)At8_zX<}8 z$%Z>%!yS0rhZSPcDBD{*D9D&?e*A6=rd^^GjdnZ*c06yqHFR_>M>MiSI20qN8?f8` zR23NxWmAD5O2`%$1r`@?yW@4T?1UpkB8gqTbmR9JIZ$3ol##3+{C@{uB8bRV4~16G zTlZL1GK985MB{06$$``5qrhv}M?9yaYbr`MO)|d2=JFW#hNf8!<#3lYQCC|{k!wG{ z^X?%?2FwmW#g4ZHBO19(lJ(^+Qdt$z=*8=C;kF-8hC?!7c6fP%g8SR|SvF&HoA<@L zN-od4sf>(0%$PtS~2yRDF1QQm!51+@3 zad$vd&*eP>vYMXvq{+ouUzlPk6(bUjkBFM)T&ySZ$d;AWV3GS9niw}*g7Mi4UO*io!G`0H*O8_XlR_dl^~IL22D2N^b}Ct)J|7-7rkB0lm#3ZrNh1c z_<#?^fcFMn%aF-rPy`Epj}M>MjTISL31FRDLQ_;U?d`ww0lx&YWYQ@T$sD?5#bB{w zm8CaGEXWuPR@{!fQ@omrlgwnu>hK1Cq#w5ykCBK*^9ldN4vQl$j&i!j^%rCAHQ$J_0wUEO&$^2`Dmd%h;6ck-UiEc3QSXNC_TRWZYEi~5Twe0_Qf8ptxik8igRyA~8C$T-p(_0aqMV6Ug*=8r1 z**%9cHg|xsng&|iI_TsuDs_H6=9EZ3V@U9?O z@s`wc{K82#m3z!?O>_5ZmeBeF)g^xH770C@AhNZ>^!PZln>xO#Ryt0cpry=1HGJScRHTyl$r*-576x6uqXN}7*QUu?&|uf>`U zdYX7VMLL~BG#WA4Y*-~>Z{ZEWh{p`+#PgxyCeL%JAWL&ojLmG46KxdL_s~>q!)ZFKH>yrHw#MA_G|#7kNERn0b*)qu zIX=C>r9VNupG=_ zD{rE&|0MmLHF(X2Lo1c{cIc?t7~5;J+ne8DC{H4dp)EFY&IfW{9lM^7!^0?oIDtDCy?tu^w7${20XOKjzwMH@;k)nP750 zh$`DDZs?}5*mj7gYIQQvH6|x!7?}CZe%gd}s(p)&zO--R4(*Y+VKH%Nr*Z$P~Y9WXwtTsDVDMl=`!RD5L zQ%Vxu+ySc(r_+k*Ao_hD@UubJa%7b(nXCq)glsfnlHSyLAtFjftd_idjh0Q5&E?pi z$F(4z+oO)RlI`H-)__7d=Y zLg4|m1wUYKXxS`TC5NJ^B-Z8_O$KpTEtt(t3hi#tRkG<6$#|H#=UXfY=X0g?XRdA)1mVvNp@}2lu!$u|d+{qo=Er*2Z$22H{t{==-@KVsaEx)iKC#aw-=u z-Dh-RlxuTi+%_8WBl?<(lFOm$27Hx`wDlk3WN$42r+FUHUc0c%SKEl2|?FTld;|B=}ntaN$qSf`E-Pd#UQ%3iI&zDS}I+KHt};1=vt0= zXqD;5_qaDa%VyR>RaZN`z0LRx!l6v8Yf6Un&N|O;Ug6Q`GCR71`i>4dTC4F`3_r71 z%e#Y`OA=n0=Gnss+?m)yH5by{)k#Z384md{@~)1WO%Ph1;NkUa3@=8}9VN8&c2ZyF z$9jmn5#J4Ta_Jq`riXcS{|S?uS?om(96i-bnali&Pu5|8t}7_19Tr9&@!-)2(_tN7 zSp&UC+9~xp4p4~J$i%joA9>9EN2AQ|i1_Op=;?2z$Rr+0UfCCPg=~C_smFJCI6T8z z%0y*HD{ZZ{6xd9Ml6!P5M{IkE@h1;?FtS8gb<)()NmqLv9(k|MQXM6^&cwqj{O4aD z5>ixhs*0j0=#quvswTRQ9_LtJ8&w5%jKAW9l$uKsTApV3!2|A0ZlhU>XzuEusiqkF zp6BO%LPyQU*QD(UR&q^8h~^~HxvS4r)xG4uQ}cb?1>lM5L1(lJQ$i}HUdR; zP4x7(QtbZG153+f$SMjsRVBW)%0woC!)C^8wo+K)K+rX^nKa3GjOB^PtS&9Fwh<pgGt2wfXEyf<)tMb{I|jZNY$ETO!0fbNba$^v%GVwQMtm8oZsxP5Pg z#r0Y4T)T_TfgJz}lM)Mm1Q52C4(yqRmf}&~cZ?Horm(7yN=Fs&VStW;P zucrU(C!FrA#$z)givqf)P+nO{QNW2o`-;m$E3AxOl$hx&HC z%Ytmj=RZ%4_Z=;sb&Xs$gQ~rL2wxB-WZ8i9j>q$KT?b7-wpnqyG<1`LqN*l3x;tsD zE5qk7A}R?&>kB-4aF6>#GpsI8a`Tdo)$YLI?4ZJJew#8nnv!8>W0t4)Z}RQ6XRM`U z%6m_8;%Em=WzGZG9sd2$lpKnpykepR?CNSt$OglENi67^hN>tis){b;bs!}`k|hix zpy}wEh^FW$*(|AKl4L54qS`P>Z}ue7HHBnwfsv63CYF=98aruiZ=%E|zn^4-uA{0s z6h(dQw3P6J{_uWA>NPUSFsqY~xqj&yw}w~IJ+*WkJI#gOV%#sA+wQ$nfQq7Os2T{8 zh$P8KZ;@6PMKP~2s_W?4EICbk;{=$NOA=a{Wa#+<8&Rn4ZlS5E3jYBmK7KCb@4Gi} zyeJ{bc^%camYj5jM0k~{r+2yd*ZYjEByrUq;n?6Y`Ww9alHz-}$n#TlYmwQZ>-?`T zAF&t{C}=*)iGg0)DxI&I+y0V!qbhlR(q3-~E=qF#TDao0qR~{qZ6>M>*YngPiXx$6>~z_v{6%NJ9N)zeo`?` zaA}15S1<9G%j3jM1+;b^;beb31uoMI%_cfpHpc4A2>0(kV=*REdE`8Uea%z`Ect7H z82a7b8ea;CvH@AzC+{YASebmp^~=||KC}Y9dfJbi;BDV?aWB0i9 z-7TKX1ThrV(Rbo3M_Y?@C8yhw<0X2aQ}h&c?zFTXBV~`qQ$LAc&akUINAC6gUlgdR_by z5F|5>KsCqCeMCbthpnKNy1E*wO5B)@hTR0GMtNlowGDL?IsTn5uRmjAZIq|ObyU?< zQ|2(shO8&KB#dt3*;SCuami zNyh3arnsm8kM)4Mu75W)(&0r$um6ev_fJpR%7_#;baQ_27~M@}xNQd1RD{iiaUR^f z!M*2G+`72U;zpYP>t9aOROZ6?h8@<_H0!goOinEk!b4qU9nCeq_huNSDrt5$S6ST* zk;uMWiWQKJR@?=ploq%#zcJI3@8(|_z0JihFLCY3B8sb;YIjdowout;MlSBEtOW7&B`j(w0gZn`)>lbH1kzP@P;R#`fAW8=(Z*S2C6YCc77Z zVF|@v%UhBmDr!2+`0a~)`Q1Z?W)-MpU*BhH zElx@2N1VHGmVu6P9L9IK(AP*sx7k=*BbdmczLLcdv3ZLrDlEYN7Qta%&l205;_hF+ z;OlFntRy7@?Vs{5|8$DB3g0{B-TgraJxgfr3D+-v$6v0F5>$+|o<7IN7mm|b<-`0d zoM6(_9I@?H*4DR)W?r5b5|9jLTm@y61l-t6Z@MOVp4%9^$#>seFp6PS{!&w>nL%{?BQ|03yoxC zm8pB*@o)cmi>b9Jj@l!fIR7yhj@RL_9MIF_oj@Uz+T{7w|KLx5ea6&g23P$6pMLfc z$J@$r8sBul03wRM7t9NH_3NfEoRgyNzCy!JOI$#gA8bbXRL-+sZ@H^x{?83=TI#y|h@ zB&`+RLpa%#=iT7kBd%WjjxVl_6ILy>9XrSQb4O_^^ZX>ytLqA}two;QyUUY>7>0sw zKKrzvhH^J%N#t-;0`iiWI~&WaZ-t0uUKd|la21qN5^%qz;Fgz;TpPW?*MGUp^`RxQ zj&cSE&hguGofJDwhmdzQvWacxo?PR<{&JN^lbgszZ5%uETRuP6O2JFKD_DwX>^_F* zZ$z;BDX(duzM=q^-Hbt&5YbUf%c!oerK-ro7hhiH!Q2{iqYtju+xNP1o~<09^+(Tvctfwzbn# z;{J(WqG+<=^i|Mxw3F$%4d&NoSz26TaV1D^)nRNF`GD{7p&0O9pp#1nSzcIRBW!eY_PO8Oenm`p9^_d+ash^%hL6q@VcX9f6 z|H7#z7xs5r46xuVYGClAN)$~;GFq^hO_*L>fC&<^(TdAoLB~KJ3#&oawx(HMUS@G= zjZCW#>+7aMbR8`hWqJHDH^2LiYfl!4;-X<-kU#wHEUi_3>~Bnd{QS_>G#gWox%Bm4 zdAyn;_fq0hHruJ{`It{GoW)rtzSF{tn#c#&fBt%y<((W=$9~6eFC3${sSLNxgh3L~ zRUiI9Aw|Wd6nekpo7>Y&-~X1&)#cbMZPfbrP7vl|3rtVXGrtEzN8W*%SRn`=*)3uRyWyMWbGOvmXz@`p3+m<_KBeROm+M<%|`(<>LbbbE+ra}f+B zZJavyG3N$asq`PT3r_$fBuPLNLDzINMM2Z`d|bW9$5HeIez~4eBvy@`r7@}(Q`>6 z8#COy_!WP>H^FLDps4dKpM3feN82m$*$$a}fUcn_2{z`QbMw1P+;}w2QbecrO7RMfQ_2OT- z^=z4#;HK^5X@38kQ?yoivAkp6eJeDDOmdsKr+2yZ-Ax{juaUA8(tF}F{&1m}hB7Z! z!{O_`+z(VG&iwFAzW(kGQ`;}|9GIO2w4M4RzdhBpXE8umGh~xn3}3y-cQ+pKe0~S9 zppjE&KIZ(1c4`WpKS(|t4(RB*N;0&-!>iwM<;D|67b4iIdKox-jteK+_E`wf(UmmO z%{iW4|CTSW4YRPF!&TeQiSy?<)89a`$NG+?)l|~4O`cu+H!e=Z3B86dUBz`A`{Vz^ zZ`<<|d#^%AQ_=*N$GCs>3YYIZXJ#W!Vf#5Qd~%L~?rJ<1`H)G*>1eq)>oddLzw{j! z?@bZPS*Yqe!G#NF=x-^*wGaJp(O}0{T8lGKiKgde53`vBr_auD=da&#{oxFwx4*+; zHes`zroGJh3pXt6^6tVgSHHQ$z1hesaUqCQ9r-=K{p9rC#QPn=3q64%w84t|?@bTg*JU&817Xcr?CF##T(iLG1 ziAUGDHME9qFXzOC)3lX)a2&E@Q?gNJ9$(?x>ra>oz8YUz+(opX`U9Vx>cHxK-M;6$ z$Fqq|hAw~2rCUQhpWney(#pwmpYYM~7ODcaLskgT(KUrcaGnQOFLCAO6Gj(yaMm8- z%qJH(-QP%|-S7&pNX~Madjr(8YY38z$zsK9d@&)OFIwANg*5ebv$nd-;>Hkb(QQVC zCi%Fv2iGs&RHu*(ukiHif8(2p7}3`hc-&=84E*8$=95+%jy-ud$>!V$_pV*x%H1*M zwzHJ?eZskqPBPea7z+V9S~kks%rG}Ee#@1|bA)qNYL5(Z;lgQpn~HF}G*K)FyE!TW zK&GIigh0TH;Wg`7L6orj5>L-IyLRWc+J z3Ysn;8_gIEhJ8+T2p9}TOeP}&BC>42WHBP`;WQ(NCd_6#E~^31$tB`sbGbt}Cb~B? zO(mU7vlEFDNhq&O2I$rp$&C758bSowg3W2c_U2E4C}Z=NQCbq9$Z2FVmS$&bi+C=F z$}dl>x|SoANDz%g2`7KrN+yUBhCq@`?)4HKzbHfr*<{0Idh;0s5JV%+!ZJ#Ve7G#L ztVeg)iR_TnbgVy#MfCilA-cxQ$P;c|yUoLqWs;@>+WU?(IBZdBopg#u$0o)+d)%(IezDlGE9PGz-;qS zSXoC)R|})#tE^9NGV*+y-sWnW5|C(rMz+IN@;Wl|Nf`3yE|V z^>q)IzU!Z`HpBA=ce!@+F;nYlY^BZgpFGWAe;d_BPRws^gM7EpHPmd3=;l1PuUz5o zqjBbgDuL#H22P&hNLK@8zI`OobPXjPWn*!iM|bXU^Y&Bb!U84DeGHsD#j&n>O1-xC zGTEl<8tHf{|L#iUUizy5wm7Mr{(7l6T_u;=VPj#8+gERJ|LF{?aRYV7PH^(%0DWzh z6gm%=X>dMi9Asg9h&wm#aPP@9LB&B+{{Vw0j?vpvhR1H)AFl`!vOz*Nyg1F_#piQF zI>gpigy7RvrY0ttX=|ae*p4jz()YKHn$3`i#fgM>UR#9qCDLSH>-Y9O@2)ZS=2Y8j8J)?*0Kz4)oDl<;5f)GTv3v#I_e1d-8yrHyT>(|_ku7LE^NB4UjIL&w9O~lsr3;)qbCvFtMtIF;cC_zj z|IQ86CVjXT-EdwZEE7XXGdDrYh!JR96JajW6I{ zVjW%FIQB#;sHmzW5xB?Tgu?X5aH&u&uX$fXz%q0S*&Nf;v&2e^7A_x|4j~l1sdCoWjq9cIc=fUj~F_Z#op@3pqy!K!Z zo9~Qm3|I+-q6o^8h*6kjY9htBCxlzblTD?_X#$edfxPO%|9&J0PCRZ8exDOe9W|dJ ztLe|J0bp4gs+wVHR>ibH^7-+(T`boz)9vx%^?H#+tCVZmEaqNc6tS3td@l09e9`Z& zMg-jcIITMm@Jac4a@w=jcy}O1RdW>Qs?L!mAjm%aJ}&{Uj5%$f<#VXUa%)9=A4J@N zB%6+WNN`huy!I_~iXh^RRyIWd!?o-=beMg+HnX-aj`xM3W8a4|4Kw;P z8!(c?MWnKsnrJD1?GJ`YdUAr%!4w%o#OJG`zBWNP;97J7Cpo=@%Bm=f`f-RU#`*`D zn4U#3<9MI>3|V018Fm{M#K{; zXMOuoTy%v*S`sy4Vy=kPx8ulJMMEkByv{e64DK}mM%OsoX;riLr zoIZ1%y8~IG4I9|CZy)=2Z>F)#w~7|$-wjFjP}R1LcO7xIW}nqLhucqCLmg4yxBJGz z)bot@cX08WGn_helb#ug+6_C|yRV(S+tyMQ^{lE*<6>IL8AiMBaQ@^ePF%Rploh0I z<1X3{w6kMfJ;{)3={8#yhBC`g*Gi{f+Osbo!XTIU|nd{se$`fncz^;A!*}rQO zYm(kY`$?Y}qW{r7uHGLZ=ZY{f)X9Y}rnvc((V&=CC)NL$f!RE&sxWlxOa7FO5DkZ@ zY~99|^-YuoUhgxJoqp;z?&dvz4LcT@UphQN${T8k_?~@7O)W>Nx1_sgZ}NCnrhd~d z4jwwl&W(*!Mm?*{p|7aBBVD&Rcj7cBFFs&K2vfg#4+jn(U~6kN@qqIcd@BTyJa~OR z{9YMSDq1#!q8pgJZeu`kp1SVvhsf(y3eOnk1U#W6wKXo>&!j-K&@w3=-@C@iFHUpi z-Vk|rl8yWKap=HaHZ;TuxTRI5yE^LZ2={MXIN+83#y~*Dh0*BLO^u6ktO*J5?T?LKgODE zhgh?1rQ7m+EXxE-Kv*iDwPB*`CW0s-%Ed73*Z=vKa0imC-~S=&U;DMbJC!|TNlskO;uzNRSqiGkGyAvzmX4*4(9<(Q zYFfdYsHCE@il}Efh0|Ua0uHd{XWwq0dNqBh6n`QFq|hlJIQ2LrzQx`X7RAFv@DtQG?QrsL3R_Zt|8!jPNbQs zke?l-t7n3|CK9Z#r8*wQ|KjxTuNeVPFiGo!ae(L+0FsfyrVZ8ZWc3!^Z`gDYqF`m1xC??~aQXkqW6gB)nzN^50!#cF62kqB2b zv8|$sm-*aUhDv^VfIH_;^6BU2xieTGT)&=!@4Q3%j&;<;yietdT@{!rdS-}gXTIi( zudmTLVUcLv$&q7+*tMydny6=`Tlh*4WiOS@+o)`Qxe1h|=b0Y5&-oK4IC=gaeOWiH zyZ3YC=svcz){tBxclkwK_`Jvy!?Z;`Byo-uDxlU-C$^FiFpyOPu)f6sNEC zBgWRSb>DstAKb(G+UV+Y2C)p3^azh`T;TIhPjkI{8adI#q5TJW_sA~lV%`@N+B7NT zCK>7NWngTEybz;lZ5`Fg@Nb$uhr*PMey za`?W({1PlZ$K>EW&Y$?2lNTP)pYyVA?*R@UX=ht&4YAjr4(H`D)mer+Z*uDMulW3% z4syO~w(Qx@p+kGw(p*7cne#BKWVjQ=7sarcr8S_5AP5Mu14;ZL*3lyFV3L-7KcVF% zk2DJtbl<+n*I%CI%#9%&WlikZx1YlYcF|THUVU>Ts~BnY;M#dU|Lio^d(t?Q%^W>? zltcTrQ6KZXa2+i=JHr9Za}w86-6x;bQhft98TwoMk?DZ&FWL3 z9|Z!E>?dBehBn#5(8vU{Sq05<5J)CyD6gTiEP~Iunt}j-Oo(_wVG`wK1mzUDbc()# zNeaznco*@=&~h_Ojr7wyqhJ!CtRhJ`pi!`1}F9bH8gD6lR8bc^C=p9iX|b4zFwRlnIuWBRlq(f$==L;3iR3K{()h11H`Vx-!k+ z{cD{3;uM$fjUmJuIe6$D-aWL9+L&(dTyTMi_gz+y?X{<&3g77J<5UI z>#2?VSJ)8n9kC4ZGebPMdX7&&J4eTeM%mh(95`~21H0Nt_#CTmL&{Rg&kWIV=2O1- z`YJs$GBq2vbNJX{cC4!<9$3jpnN@(PFf-c8<&$4=>cV{{tS}qe_wvDe2WhK|KgT0* zC9%NFGuC^T3#U$T>T)+Tt_pS^InL1o+i0s#5?F5i4I@jcw}Z1^77YP;Zw1@-9OU@B z`)Dc);9hOfEz80LBTN6i%bfb+6z6UYVMQC+{mwBC?b$?ARb*90)@u1lx^G|M#206| z)-{8-x{dZDM>xEHE7c*_5_)N(%%*sF0-jF<^6y5Qv#6?@#lD6nOcr~p@5>9 z2yPi!mY12nbp^0=a?^v{zjB6u{HJr=PZ?CS?c%_Z1MJ_imiVgG-9hf0`jjtET%$Mb zpl;I+jvhP2wzgX0OL!$nz9coRTRC<-foVN2b)p5ROpOfE*FDUnE)uG4V{LVia5zkD zOC=Gn@cf!eD~VBHYWNYCPkzPeiw~J1!sh+$eDK~uT5Dp2UdjCORbqjWXRPNA7fzn$ z)Ri7Go+@@9InI&&+i0sx;D2EhwgniZx;y9{N->$2376H;(o#*(B|qydWSN+SX=bLU zn967%x$wmk_*d;Z+5|mA-`z```tmdv?u;Urwb1^~I~>@vku_zZ)%T8Kq2|Wvx^&VR2`!C(JW)V_qhMKncAfP>4JlnMs|Fd{+`DS&L|)U zsBNewRc$g30*+F&0Q`G2XovBy^TGe!P z!$J^c98M>)^s1joG57j-_f1ZHb&ea4CXvfqX+QQZNA|9#GVH;*+Kd;=qL?0_|G{;> zIenRq!5pFHog8`Z9ojcHkqo#NH4rX-Dih04DX0b}0+Qsw;gDa0PM9d^G5YRaXalC=r^eQn*n~Z1q`kT9qseYPv?B)IU53->?fzP?fCe8D( z3^Ywc(~FU*^88%(6~A4EN+#9K%?sx^ceR_e9AneIV|;jgFKfy|_+5)QXe^4s?8qZ- zT|CR_OPyq#qt{+QkWg3_x1(;_~-LlzyVg+^axZHgEl6&B;d0tq%DCK@ zVrrz5M-Ly-)>O{g3Lj6BU=|B14|R6ZJ2XyOm#8c&qpU27LljwM9cr@x+ZeEd2!ey&fRXnD>qOX_TZ2NOhY9<)yus*H@J3x z5Y=)~(X^fBnk3N$c>_%)%}i>T&cPW(hlfZ-1C{XrzPTI`f|qD{4Xx|eaJBC?lf(D9 zbg`cL@*vF>5xh4(9>G;|DoVLpBn zRZ)sYG>YMfnx;}v3KYyIlPp1$aLCepsv12z!O+ksLz6ii-Y{iVb(DoYB`+!`p`aJZ zQkY4lxO?k5<(1`xoGp}xy*Op5I4M)IWG4H$eD*509}JNdTvV6Wv7xOBpSzgrboIT- zCPrxk|4G|46jh(kXKI-Sx>n5FKfkaN1O!nk-aEzczryqgJp*IR=5@T0Dk`cfNd{y< zz~OWg@Vn6SIi|;_xPIk2$#{&wmRf?IqTvNoM^kc44L{)W`CB~fokVkmsasP=eN7x$ z5Q|XK92*3C>9NsYJusIK05C_pnoERE_tbItRoo<;(RtF2Gh_P9~vQ( zSFxlJp>U9J=!dR}@cps0G((T>aPjOl9!(h3ZEj_E`*zkOeaM!MrapIsfha$<7&8jf zj13LbpUNOOJS1vbsEoLAm#itGw~94Q4K&wx(tT%??wc36Sr;SVY9JBxAPGe;#+i|a z+_-j=JCDXOTuCaMH?XbiaDhauamkxXR`0 z4;fZ`>{!2rJ-atj;g>LVjpufSAUvs|BM4v`80k@Z`bL?~>bL@N%BpHf1|16)S{8<` zVHi(qp{8n>ro~*LHBD1d3WWt58UmtR%!MkL8u{sA?wq^8<-2`M3UT&q+{T`rZ6tjX zmad^bZ{Z^dNMbQ+XVqcpWG4E#bLBcWy2i*mt2w-PFI(5u5_W;EzDReAY2M~^*VGmC z=>Z<}PEs&s{IM#kD-wh}3pNxi6J6IapZYE-rH!o8uNXR-s-h@`Ct4^LHwI-%#4-v@ z^mlUg)CDg0O%try&emN!*w|W)Uoz1(^@VL-sHv7^K9djEvQ$*vERGG!#58nNRY57p zPjV)UBC_=4JgW&y&oI{0!Nt>8xSvueYu(27-CJp{4CAm2wC4^~K#+<$SGq5wkR~-e z$UrKMB|3>#w@@ATF3=|n(=;%2V?nW7gMv~_8DL=*qbdyzRaGb$!jnL?(p*gxEcC(* z{daG2`SKke&sbEi-@x$?_EDd3eKjU511&es{fpriB56wf^|W5!&8%VT)RSbd5oy5 zmAK!HEQ^Sig`q3t(xcqIdW#3WW27wy4Q1t2R>W3Uk=8j(jZCVKJD0C>qbr5tu3=ky zJ6qan2s@Y7U0ITl7U*taqK^jy)2NoCq`UE_Q)(@$yM?086&F;PrjDj6s7e8IQQgfk z-v5v*r_OU_V1{t*j-u{1SK?c)?#eDa0T&+si&jh)STe(*V$O0w5OMh;MB@n(G1sbf ze6aKkqdgs5Jad%?;~G`#T8g?`5kfYX&|Oi&AuZJ1S;mG28BC?IWH+(u7OG<&+zWNr zD5hLpsJn`yqM0S##hlk&WnmhgIo-v=$j{Jw`vzC8+@*I`pl0JH-hIEF`nU^+rK3K7 zB8DJICC54^k#GQ6(3u?{;bF&hE>>3(cD7L+_v3QN2o#GzrziTkdFeVg?({KhI*FIn zv2AlLevfnY^{S<#X2X9lTLMW z_3|CM2WBwb3F_)=si_Dei2{~w3|O_;#sC|eMG!<6@!Dp#?cdA8p)a}F+rg**-@j$J z^ALNswNM>$pwIMi=gI{x-RPiyTEG!#Q z$%3zn=KViq_nHXKsmzKzqaO;>P)SdWks6;QtImBGO>||J(ditDrei2+#s(kLbzjF{ z$~h`XPJH1qDiT4wrA_)m|0TZo+b{T=Q$0l1Y~#a!{y*@OT~$P784xL3w}VX`z4Z1^ z(b;pIfBG+zJnq`Tfn6J@N%|4gG^39naO1*dE_d`XnKud6tYbs_F?QGc@w-;t6b3M{ zOqHpjUQ)Apl=%;`!FcZ=;~51D3qzS=sJEL3Qf7Yqip~JRNSxY=AR+>0Aw z;WIk=XQ|)!bAJAdpL2Xe01$8nV$^KdN_*3NrZT+@-a5tKP7KiXa4)+zHIfWF5DGI4 zci-jQsSDidoginqNUYt(j%}N0EpsCZU@1Aqx~_2fb}!>ugV?$?#N8H|p>7@wz2H^_ z0m&64mPk?-@vOql83SF-GS=72WZqa%&{Ly#c#_$?j%A4y(qr^?JwQ!)=kwu;?kE)% z31T5PA_DsC2=~wYk^k$r=SZb>cKrN*=AVDGm(4X^0Nn99>ep{!U(0>|;m#+Bs+NbyL523)@qp-0eI`f9Ey+{GX>8?A=TI))pde zovDHQT)%LI3)ecC)I8L0X<`4N?IfS;y=tKY7MI{FoE{JeXM`d|7tmk5*Eh@ZoYuSh_;4=PZBy|9-}$&MA`X_Vd$U|4ZK6 z5GWbR05qmY2AG&mlbg558BFvJlFDe9mW7s^X1KSThjNxVNf(?xLXjlZWdQ_bmWlq` zoVxOe!HGPP_4OoT0o0K$9*w;CUPWhsSUgF2+`sBP)=eeDXy+BK-05Q?Ym(T!mblww zW}u7N7ab@F$nGGqL>bAj2T2q#b5msQ{+WOCZ_hJUaMF74m;CyZciCF!DQ)0b=vtPs zfdQs63fclK>>C_sreI)Mkex}<*YyZ-HZZ?nkv$O-$pp!W2O~4W;|I4md3^xg5=qoI z5R??A`W`X$!ZwRYo+wr2aiT#tMdR8msi7gJv+9EOsPv6Yl2HvTQzbn)LT~3ov|y>| zqfjgWn@kqZv$}c|w8>5$-oDPcyD6+-l4NxSZgrZ0uH1_c6hvfyIkgpGg5Kg>Rh#JI z+@F5WUw_eo<_>eE>-nHSqR1<8pol%O&h!RwY$ z$L?_T`dzMfPT@*6kgQB1rN`*)oOtoAOHSlK1x-}}T#nVXOg7aFvjev{edz(+LmB*y zEtFNp5hi-*e(`M~I(!5p398G2$dZU@D5M@<;BS8SDJO4@P__LyAOGT4{KbxB=?Dv5 z&oMJLLTW0rpva~{daRF$bOGJau?mw6KJFr@OfvV$6CGZ{(IjPw08Xnw=J6RWTcwx2==2eal~a@OA^W3Lwr=I%rbi4!O6iUrt?R7=JNL8a4HZGk^SB{`!l1Sb+owfAg>T^}#x-B2RQTJ3U5fY@FG7-8IS2 zj4?c!L)9%zA7fB8G77q`A>=0+ z?CHXn8(*NiKEkmiWpO`FE6;4tSuWgo%)pdJsHKKv$W3a;< zIDApcw;bZ=)(2#=54^oqP#j&?2AbgR5Zs;M?hxGFEx5Zo!QEX01a}64yTjmagIjQS zIP;!U|J`?e_FYeP_f*%~d--~v6CbZKjp_UU>jj7klvZL9aEtWMIhA=qDupF+**V43 zZxtS|J}L4WVESvnDk9c|yLt!lNS}jk;XdhNXQzn_5zHW|F<}@_IA!7w_Mybo+zdZb zKlF@t(ZWpJJv2l)-&473%qI#_SGNeMUWlTTqKa~~!I@-|KvW5#f%{r?3lgJklFxbM zZZ~N-DpXJ~Oy3O`J~zp>y1F38oeZ4FqkpAaen^K zExtu}1fZa_)w!RQM3JGrxasU8QVFy!YuaY2GcOs@5?lj|qRP_i+#Rw5q%_b{V)1&k zoBiRCg_|9&s;puz%z3)D0tyIvL|NE#jjURb8|qc2X}ey%MN*>PL;AM zgy{c6F?#EcV0Z8a=}n^>O&oTOJbepn$U0czg&I>}Sp_y2`OAZzd9_H8QnK-OmrjJQ zuaW_{$yV9m`7qU)#CLez94^4;F_}j-)9; zTf?B@%f>dcv0e8``S0vXd}{P42hKY#d`{JKNuPf5rQs2Hc=!~i_?c>A8$8dR zZbmLlZK4d)ipe>F!$$s{F@M*t8ZY&47U$aCNrdypZx`EMk;)=k19lTO_>aV~qEA{< zgTZ8RGo989uL;D)w)R)hr)J0o%q%%e(I;PW9rSN(CYxW#<%eHiWE7?nx!n*TiE`i6 zm@_uz%9xWv7MuPC_6PcRg7MXPp-qtM=Qf0%AHg;-5wuF9Th0L82ms)=kKJ7vbUzK4 zPPOJ+6%tlj-u4w-X_45AOj*j@BeUgC6=qZK=US77d=$8u6mwuzflDxC)O#P7$o zZ*P+Wj_Kd?=|`D1nth)Zr$NS_!wBN)a}^GXA0Ljb8|-6e!4Ft$;PGIAQkCDgFYv?d zOjEW1(zZy>i=ERQv1 zm)4tS$F|Qn)3F7(B5uX{bJLFuBgaDW_I4}{wVOXLFt|Bmi7iM7@1DG`BZdzC4Q~8I z4U$~vyx?8a6t>++PJ^7fs=}xE4q0H(I^ra0IYl%w!@&Q}S89fObhM$;KD2Hz9sJ-^)dBwlmIa=-ll7CO(jOUFt@Y#XEVOEq>bD}mO z;0Fxsk;6R;2dBbgoEp-muu<%f`e@=ASw+zS1#dATy$7Nlt5+Wk!x4IU8dH_gKX@l6 zmh>rQ%A@Rlw{ihn{uVNu*pxIMYv-Mhpbo-y!!CKT2uY6{R?CkIN1jjGAz+Iex1e5b z$b)Z|Zz5NweIZ z(h+*S!)oa+>3Ck%vAD$#pPPibq@bXmwp$tK9wKY9$sJ0L=G zx-)+CnKcEFJFVSUnrplj3~=@%xCeWYT6j4RM3N0=p=#X61ykT)6{#4Nc_)#ow;zm| z7933PRbgXoa@0pb$U76O_fsPtzB!R%kzd4yORSGg#mDh>QXF+z*l0MH83g=K|2Yb+ z#X9P^QiSxMv9u_@MKLo8nsJn|XE=&zX@I4&!n$WBVXY(Sg!4G9tBv zj-d{7DQM!yrMIvtmGR`Z&qR|^*l}?acgA-|+{3pPtCxxf1wWSc^GJ#$C8b-u`!48L zmZ*c@dy9a8)`ll5a-84app*ESjn1%v%L`Lm*R!ypD0@xVzpTB(hrDn_m`Z=r<9tCw zBvrdhHT-T5DC}H$rN4C|QMi+$eQcJR8XX2Cms&Vg(A|VmUR4uwTm8P8%<{Of$oJl! zU4nUK{hjf-&i7im74J9s-2~2zX*ne{RqDlQK+?$Wi?&ww>!UC3lN?%4&NBTmf)5~= z?}%c{Dv0#YootRsUlIj`^3T3zl|vtl^%VZL@}avILl^bfLkx`^F%2dE+F4sR&1=Mj_x9_=$t3}hEe21%B`*^=AF5h%prC0td0>QEVhI+D#HFt+m0W{IP&#N8gT#&&1SVcCiq<|iEw(7qaXhc>@n(jnQqm#PuN+BXXqxL#p zD3#%pYxFpYz7ov4w(e%!R44Df1&5UprFR+pOVFONCCR(ko_ra=%pH>wmZ<>D=0yE( zscGh~17ppkJLTc4NfJRXR9S*DPcQ`<)$uJ>@i)!OD zyQnev<&cZZL0?JEl+$?&5ywQcLg*Kb2nS4`Hg3;E8v-|fdVl|q{yjvrxJgIOLag+7 zIu9Pi^7dc6p9*Nvv-CSG*O?+5`y+d3hx3Ej%$9|=^wCAh)68d%U(1BW?GzCw%bJxv z7{Fz*eNbaB2H{gM;@#N7*ipuVKN~joB#Wl8=4kSTtm4}a3+sf2d|z4BcXz#DE7A&Z z@03ZJVhAl+yPr5YI?|%d=w*NfV7&3LTaNy@KR5=C4Wx|gcv4qds*?F>2R{mp-G!xT zPDaYBA4-mHR-p3YpY|3rr~HliD>RWQ)8d%E53NRV;^$v3{;RNo7#jeosHh5Stj2QT z7ckK_)3h32SrxPNj>?ZjdBW&x^>Ip3mu+~csNo_osCvM33-^+oE2jiSfmXgy!Gzq( zLEdLa`}UTETwk$GDv0U3nLaT|k~Y>R$Jg7eTgGt8a-|X>4h8s@WhqJ_&^WVw7P zbtmf=`s#NxV;u+_Hjqf7wmy^f)=kq0ZMo7(iAY1Y0x1?bu~rn+dn=I=vtqSsviKRA98)oUQ<@O5K;eQ+W`S-#{gJ_-}{5N|KFHwVTZUCNT zqxg$)RTa;p<+b1#Ck+Pvgr_L=rOCQtDH@BheT2;5&Ka!P~V}k@9%tHuXYRTXWXBR#};LzW~?xtNsV+ zEqs_;T$s*|8<<8kt(Gb%ELIqovK0KRDs8EhUvMO88=O{6@w*^6+3DlpDNxkmnOfmS zJcQ-!1EH?T2`F`kJYB9cH*jTzFwnKHc(BXwHMPNflgm#X}}_>qkyPKV<~-v zaBSghy#D|bHHblpq4EPXA0nCBKRu~yn7R{?l_Z}$>ZT7YA42?I?j|0rb2F{8fh@Rc{}uKgI5o@cb4 zsA{p<@8p~c>fw1xB$VSk{;dDjAjFfKt2a5u7UaYI3Nt-1RQh+^_HH902X_aHzWOnZ zAa+Vp66W&|#0SWm$q{ej6;{?_OcP|38j`AaL_v~B=*)NLW?lD-QFUI!RGM@@KZ4Nh zf6o6xz2=@GdC~KF=~?TB^(rYjc-CduuxPO;Emdn44C(X&-IY7d63d_M(KJB`FR#B@0N> zH@b`U&*JhWSJ%|q^QdM@F#QriBR>H`eKI$FIk=ERbAH-YU!*+j>ZSBVyUd1syJ22d zWub%^nZFUN{6xhZK2Y$dl z4PgFp@#hajx1rAC&R?U{MVKX`*3=Xf-ol`yDO^J)e3nVQf4%i8N>kThmPe)Cy`i#R zeMQOVTpzU=vfnm0n82pgQK`nJior-*-#SVe=Q!z~po&4;G)~q?<0+vb{#P`h)abz2 zXT{sBaGI4%@4!~s{wpk!mjB8NGPKwk;~MVkmK@ghdmp+JEG9S*3o4@%yO3zxFW^=0 z$CFl7!_3(tOy3YCw?)03*s}Z4U=}>aM^Az1t~LCv)_D1~K)Hka6T?;ct7U!gT6WRJ zOS0{X&pwU#vSmISE|WKoiX?*OoGM;G6!(Oj#2y#u-5ihKJ?p0iFIin@B?wrC4!7)J zb_vT`=?PX&2t|;VP5I-Ik7I9a`U8g{Bxnu}Bgul4r+bKV#1O$bnY4)i_&!y7C-<**K#oU8jQoyLA^-Rav&PQMl}BbW+x_;`N@6}H9HR`e zj#-)qpN1H5?{T!sYhJr|2U)GnnWP|8Zw$xK&~xvAv-MCFcY=xBoxuC3jFpS%`*xIu zirR^uQ)no^@^Jh62>jnO@a%6pK@oU{CTRWFcdrW2wNQb&`DiDQ4?nTfIXMk`h!5>n z7#q!uWNfYZso#8|+0M+*B|W#OFb8b6!bV8Q(`hM);kRAu4m}qv$by?+^hq?SDvNGN zKF)h+RPy&%q%LnrP#tObg<^#<%HEehld~uFdT!eoCkFlEphN2nx_&6wGd8;;*B!iZ zF-%x3iz$BYe3E*DbuC8JvZKYsY~U~2np!L$ zlMUX`Kp>EXk5AUrlw!{2ySB}(DsFh+)fJ0kS&El{LtqC8LS4h$%q$e#%*KMNe{#6e z2|-Omla-nIyRFT;B*)|yVa7eLuTS(XKzP>b?gUOLha1IU()Fp!Bo$*Yu#`RQMIRV z!9P#u5lnGm!i|4hXK#LUgm14k)xoK(T;qGh`I&wA#wV+x;Y)mt^ZS&qw5G!m+qK>H z@o4=Qxb|LCY`^IbVC8WC_*9q|r^8BgX~VXgts2;I+IHg6Y{%QeTgSb^IBu8pT&94? z=&~vit+B-ygM2sZxg@Q}aX9MMy?G{NXJ?nb8MSQ>o|I)1Wc_6>h$om`%F4$VO)AT< zQc1$?O7InY%l_?in!{8A{s2q;_n7NzXJ1o`FcppaD4|u%SL~8R<{)K#k@adq&9TBk z7No}2Gga!Vnn4m40{f9 z!E{0;Q>v+`$e6k!b|pg+C7MNP3rIG$zjPF=G}g<A4T$Z{sZ7fyV644b(moLTZP11!-m zW&{?RsdS}iP`{jbI_DIgRoK7bZQnj$`E)UC66R=$aOFrWyXzf+Fb>HD&2^};5Xj*? z3c62#5_D_ruMc1tO%{cD(5aVPW)4Byro&r6kG*!_0BaM3$;tYO8(-9riC6yt!$zf6 z$jF|~3AG>d*=B!+NHV3#H56yFyR^&fsV){(a3Nfj_^PK+oq3ja>2s>*W7VIYI@FdC zdq>&slKn2BQ0RQwWLk7MC_B?$1e0v)loascB!2DEGd62`B7S-g(64P7K->YNT)pz5 z!L8(&G04|q<=dXlj~AWt0RVu9mR-jF#_w|{O*O8L@TJztie=7i`cM#}zH0v%Mdmr! zvSPt|552v1dYaiDEP-7Ili>XO(5n9gk9t{%TlHd6~;GMmFyx1-8EQW;&gNL ztK~5%6GCk{lEP^RU+F?B9j#g4;*bMBkH!+9I(oE{%Q*TkBCv-pVit!s9_KD%(nc;K z(kzWhR{XCYj2}?ZQlb3G66pQwLzTm0Ek{Xf;j%Kxu=!XBx< z;eRdfi6pJ|uUuS?Q0ZaTS=u<->71XYqG+;#;!rys`D=r03i7rmTmCSjgD*@YHMltG z*2cP;C%g!eMUk`tBM~iEz*62VsR=O=H0VL9*V+Y(`9TOYS^JM#qHbN<`@WP{jHJO` zuaA5haFRSW18?R>14%wVN;QqC#m;L4DXFp#ti&(wzf!XAKhr_*g&f0%2WWurfV(&C zH@x(hkD-k3_rI)-ud8u{yvsnH`Cgz~bf`iOA)}#=>vLNj#5>vFUUUt23OYBGh*K(O z3E+O2r=v-eK3v~_-G}+pwykxJ)`iM*Mdn7Pzl0jBaxzxSs^Z#?8jt+R~?*Atvbz~BT&sH-;v&L=q*J;gA zMhME^v=~&Q&dv7dCTyE2*fSU#^$VVOC`f$w`?>RUYRC17ZQjIj< z80R2cz#VVYTJ5De51yDJsn<&v=4x*T4%X)N_41HZ{6osqkQW>NgS}ob6MEB2n|dpa zwfL8wTyWaBy1y0%CiL5{gGTnA%>|`qF^dDvxgPB7Nr|19*&3Qykn?`{vCl*?#m)r;hDH37<$Rf(A^b zjg}d+;dNWT@UyhIJOlD})LD3bcINR~f-lb3J^05PGhO4qzy*I1MT;5@tMvamzVnwd z<*(hm@4aBeW#r2{y};I1N&#Q9?5~XzRN>6g?Zzev!0xDmuIq`(|4A^3 z!rn;xVG=8>pjNRgyPsmLnX$BjT;LRs?D;d(6Vxsmvlw(2;vm`K6@HXUNQ@Rw=!~V5 zB*?5%Qw3KU=y1{#Rvn_IrWbe*_qkb6 z@aCVRSJkxAB^COkTq=~+EksN~MVE926MNp`OPDsM3tzey4%f<_ zSvp{)axHGKWHoH)r5n*>CS`1WVLwD*^Uf!6@5y(YzeU4rX->@(N{NLIsF*~t-;^Lk zSBi0E*7Ids-9w-JyPF5ujL^ymgIT{8eBw-~6|H>p4$}NpvFlql_b)<>ecmUJjXeAn zN@~?dsf)!2(0|NAS!TJ)YCvlwCL&9oDRLVI2K}6ovQ0q_xkKD8i+QED!1#|+D#?!b1Fmf9i?YcBu+XR$^CU-`Ef+FAA6e2?D!bxve~P z(TrMyJo-w8V5Y-Rd85ll_hZztkVWlsv8Sj}iTaozgt(b<@N|5}@|p8R54|#)58ORa zl;{vp+8tw^EQ?TE7N271YnC{$OZ2zDqmyApqs4KymK9Fmv*?^RdHF#Fi$Zi;5L!U) zqRP+BEbuL=ri+_JqzxgXsCi?F@r&)5ZV;XJ->61_!t5-RqDaD5P)U;H4`@>f1Zc*= zi1^@U=#)~9A;D=hgXZHl<#l{6YBZLmp(<3eCku?U{6j3i5d-B3(Qbd z6gZM$nbKRV2~KrU8z*g722ebcPe*56x@Usts{Xp!EjXhG*u5m!0c{4Xfr)T#Yb%Qu z5R9%Jz6VGizU6e<4y>M$U148l=NB7w+xcp^G#I3R!&!~|qhiKzPH}ntP@}1zetOw& zb9KR6@dSNIOe1r|U) z1M9eK|8bW?a17l#l`b~GoJfftQ{NIOy~{D--7v?KaYubNh12<=*xt@(W!qqyICyE# z&T-Y8kH2bY=}pnEBhkP8Zzu1O`q=8PAME8)g+|Q2VgfHxSQH_ZjQKR3M*ej)bi{;0 z6|;!aj1*uZcqh!GDZEmBv?M+%9AyP{h-VUqcJbdaC8R}13YSr0?N6F+u5T94FSi%A zohUG!!?vAJ_{}cqD;F4uh=|{7FVGZnlNmW;;lu^0V=!Az*`Lp@Wky_J^J?yZvHzV^d7)H*{Aor>0Imq=G#UMS@s06Oc_1FgR`zni3ohfaQy5 zKe^*Hegbiqs4$vG)c~(&BM1nOY__uKm?C}d?2A`AMPYn5GTY!_tPo1#7CY--oWm?VT}y7PJ)W$cPJLT-2RObv zNp_EnoCgtZFv>hTE316{Vz}sn|0!Qv3d=f!9FVcLfgs-5CA&(bkcP>wgK@7|NXlxsIutuUCuf<``^XJAT z#@pNJ%4wBvzeN9|Qn9ZDXV1jO4gkJ5gcd*Ht=_r}jLs3@PdNl8=1}a($8H@;S|Uh6%-snPMj3cab+3u9OqCu& z0aGWMyVxWRHKUzWO0UQ9fx4N3KP>K;-@1ZT$I;gGjROL*CO6TNR_Ip!qFid?>5mi5 z#VAdZDca0+AZcKnt zo$5H%N_K&HfO*V$h}bTT4%m7&wE8$ zbf{}!;h$JI!}pc4mTk=7Zld;yXt!zzsMCA*{=GLXFy>>d>6=?Shc%x=np|^Owm}?J22)2KBTIhw_~uYo zkpD|>qm6(3XUn&;Yl7rD`h{`p2Td^Gp026=>u=}yL$IC2)<8?T_o?RkR`a3w0^`UU zV42!iYuWiKc=1m2OSUGJ%(;H7|IH-CGa>npE0ye`WvA`%h28Kb@lUHeV$TuB8L;dr z-@kwubDjO_hc@o8*j-QUBoyhQ9VBB=d?JFqz$WC%A$mG`jBP+XzOd3Nn1v;Z6?&qaKxRg|zFspQo#^-<+w?A-c9KscF zD?e@ToXbSc5f?N+adl2=Vc6f%3_+7br1>pfM}K{Hn?;dc?YFv$G6xzJ9{3Q-RVBn< z2uTi8<902^t(Qu@$hQ9b(@y{lc%UmdGsDNb;q%gg`{Cj4dK+f}dcBX!p!xY$Ju}nv zPph-Tsjs8##5H<4cp;g%YBQ=#P-HsJnEE1?b>Vc#A+cNda%oD2_#D8;J#hyluUeP- zgN-@$Gpf&*+uE@aygLh3=yEaETDLdz(4?Z+*}id!g=odD5GsHvZC)H=S%jQ(2n_63 zJ``J)W)|3JUaP(Xr&xR1C;N<(?*LFbD#KRIJJ%j_zOI?Rs26MtdqWOSg?)+3PYu_6 zxL5df*ZNlF%>tGY69UgqMo(@QIbNbgtEa_v6Jd+L#cFV*X%cvav`KN|T+o<}pQd|` zN~h!B=TH#7h78C_eZrwO^?HUwH2H+-(@)K+1luVLTeOg#)&X#BX-kl3W{GetEi!Wr zjTyi*JT<>>D#O#Qe$%PbbEalT{{%PH{3~u5xc@Ut-3g-B%KtSWW{17A;%1Po$SF&H^~bx%gTJadw$31D<0N>k~~R0$=>s}&@8cp_a?g91N6xI~kOF_zk8 zxiJ9Ncf7!Nr|2+ceE*n&+CJh9MMUZ@lxAIO&-86teAAt46ul0qKZt?5EsmSi#|_=; zD1ky&>MqU?8TnV!pL=RJ52~q9nBXG`!9)OqmwLmSWtO}*pg>)$f1wR4PFq;xTE@fORDey5;FW_~E z4_~+I$DvisiIUKET|piCI4y^#+r04F+$hF^HSGa;);@aS6^_xxc_V>PN%>oT%W#KP z170mvh_y|gpGmBI`N#o+-C@cGLZ^v@}b1h0HJcv%}@-n^=kFlyj5N(ALK@g^&?airPJgcc+^> zPeZmDRI_ABA_Z|=V~Zc~BOtR_J?n)8Wb&s2KE_Y5q{xub*`>aJFG1)qWaN}Gdi$#quT5Rk@s#GP*h^_DF2Hs_)0INw- zgqT%&-s0&jOwOi+4tqY9QCH=$RN_1~YKV~T*IE9#mp8K=ov7_fq2t7(tZoYLH~qdj z@}z4qq^m%yBX4&oD^oX38O4bV}6?Wd`dm3fimxt2P}_F z3c*V1{5GUZl*va+uxBR{q{NU@nbCQ^4I$+!b~B$U&$#_#((!$2iiI7}??Wq5p(@#> zeiIsAnK~xklJ)Tf`SCDB|5}0I6OkjL1nUvA6MTe_n>QF0!3}qL3Fz{akNOO28HVsW zGt#n8okQoc6g~?4IAEP9{GL6gSk;nJOAQMnQ{s{j2Gn!vY>}tLI%LTgP5SNeO%oWyTT91*a}L^iH~0 zLnf=G%IL9NEh+bC&X^@uS3wl{HOju93dBf0iO^rtWUpga)+htt%TO~ncuIq!N|!W! z`13O3FoJdMuP%1bJ7Px8F2i_bwUh%tsary79X0X|X%?y^Fka>SK6Xa@uFOKrWFo4X z<9bE7QL4VCB7h}_F)~t3e9_PmC|~-A^!*UU-*7$6{ksNTik#$%p@GTEgp36@rrA`C z*0w>|kC({2tm$XR&vS~uin8UBu=#(#5WRE7`h0EHB`Z+GNC?Xk<}(u}q|lhVz622s zZJE7H*$nwmN!fX3jg`6D5tmjhEPjJMsw1mBl6lDJ-Y)ojRy+KgoGQW22to;eA;L9R zmi1;ULw>)p=8!!;POStDJC5+zR&0 zaMS`{gL?eiB#*0u`&MP8l)gj^1^rR0NWg2`$y;|9`y@|hQ z6KA6!QPwiEaacTmI{1XKno@1==GKuEmH~?#plDV3gSBm7!;<8Rx!`-fzrM&{?s?+l z;%Ns-=7kC@z+kad=EzcWVE-xd&*k@A`3Pr3hq%l_doQLt*?`roUpxpC=B~# zGkZPm>e|HFnPo8xzXYKc*r72TTiyI+pE>9?!J4&^U>oC!cx50Y8R8jRntgw^mu$~r z4V(@-uzllboiZF;_KGV&&MtMzM*;}F^Ric=vsI>mqI@@c*nuLJ3@9m)x?{<3j*T4L z0~@-TGyM^MGsL|wIeJJ>XIrGR8KS+r=ax^Cns27fmn-UdyE>62%)(Tz9*RS2V=Kxu zlkt43T29l#Fiqolh4*;Gfj3n1Rp^x#s0Q5ca3^R4g_zxY@ys0v*_y?wHHF~fN^@HN z_10BS*H*$^GI3gP`G}qCZlm8oMOnqd6y_Pz^wr6Tk`8=cVdln0w{WCKYwy47s?}>H z6onE)0TcTdMB+f!5gVS64XkYoek>E;YRPG%*&p3aR1#!)_eO0Se@qJ3oe24vmaH@tC&29$$Af=$VzL;VVwpaOV374P1<| zGR)6|$=CS&F`IB((^p%vbqoFePA|}q+ztWxB6N_ortO2rS+7UQ3i}y!rFm)aR`+9i z6dL_9M~=Jt-lZI`t}YlMh+(P!vvQ+lCU%Spx2t9IcEc3%{twWbf&phsUnV6*=n`Y? zSlHVJ51qf7u9G@;eG*)3T?{On4A{*SYRZ`<8!sJ|KE3V9XkzdK1@nfNXJrBN!MA*+ zFXhnjkD5<6DKx-~d@^4D*!WmyN59A^aLg=7JA@Q9$`r%y3IwyShHE}wF%!8p_auzb zn6|sUXvV2qr9GFW$k*ik)?LTVZynfdAoJnh(7wYzuuC53a<`y4(gyKb_jF=F4?j9<5IcS_E4^=XhG?G{x8w+k&!Iii-C1JF`P=Qd3Y4hW$zcW__!;& zbvXc!e$AbGSKRuS8*H<#bYT-yhiE0?fbkb&l!~$GL@g=7zhiGI_xyo%bmliSzVZPt z;O!NGb>{%%06Og3G;Ze?;9>M}vk5cdlJK&PswhLOmQvIy$Qj;TlkD&%ES|U%1bhaF zgJWtS8NC*t&g0eEBip)tRAA|!`BXet=Gz-$zI+YFm|PQb z?5qYaIk6C>>c>aIgJp;=DW2ic$w)%h8lPx$6RQB*aNadpyT8MCm|s406EbcI2dlgm z84ogH+)w+EsABImcP+ZCMmu5}Ro3wy-@M;iM&y|yXvdlSLR#t%2darEM+29kInr!| zrVigYjO1(486%tS6I?Gpc*ME_vWcjX_`tEMlt9za+y(?YqHk{KlGlqw5K0{+SZT^& z&HUpfuL20X`(>9X6BqN3UJVirhrb@%I1bZRq&Aij64|i`H}~#Zq!yoJcl*sv)sP7b zQ7qSG%c_;9soE(C@7&T%oaL%JKf&U51tv5Q7^ugHZm@b+*=}&MQNU{yBfmFj z_MDN_SmJQW;Wl=UlzbFau9VPP!@^8{s-}j){ds7vVw&nn`T4b_@MS^Ch&_CZ3L6as zOZ4=z(kB<=g89m*+V$d%4({=vTKtSC6bsRRFwy^N;XLnNLnPe^#mobq-VE1tUz|s^ ztg4GNM~7OnUfx)hN|$(~ZChU@;pk}yNeK02VKpZ3O!z1KURq?*6I`^{9a(%VQ)df> z_}28b?;!4NlH3IPr`9l(@@vuf;aOh~u>2v3cgV^4$YO@;$=<~HCks5u|+}S7oxfzY7kW=V=RLMvS z5t5i;xa!J*YI1f;py2bIRjmr0KHMUh+y8j})h;x}&k{gfqe$fmeA&PE z3bM%Ap?YZjT0HdY`gJPpsiBZ=LAK0JAz;c(Tw(MFXZ=R_z}G4Odpp()_Dyur4L}hGt+8>y9@@T#Yua-``fd zRGw?kerp!pHi=7R${;pSyg}3@suTfRR+F@mBpByh-`0P(4?&Q`W6M78wchpQUkh_- zcvhCqZ*o|i;3WVM(_IEm!WM7zxW+gbA))|6b;n%sH_b05WHeFc22meYP?2X2Tmvru zl`KD5U;TgaAfZ*WYw|2Od)vZ8cU=D}^)yKmFx}OynM;kQ0-L=QU)L2!9V31&Fd

@_n1ytR8lyudtI z&np?3B_Y}Rhsxlux=L>7AY3D(s3Har5 z6S=a=HPT@3fik~w_AqOQrow$Whv&w~Y;Wbx1lxy@%R-66bcIA|-J~h=rS3NVIPMaG{8>U5Ndp)8wE?U3{CT*Q zI#VelXNpujQN(C6x$MWb-FNwcvZ?Iof4MwX<4V!bzJ_1+OkM^EiYAOKwK9u}-9N*5 z{591?z`6xg4<_(ztW%~2gaRafq}SCOz68Y`aB>w%*!?1-zSt@p$ThyKBf~M>@~5v@ zByaPIJRhK3ZA966G9d1HMCl>69;wbC7(fQ6#m@g!ttY7P(&QNYe5V{&p#;h};1=Az zKtqD_6Lx+X_i<>~cGz;SJPDw8#!LCTS(7w$2_h?cq5zU}VwxBE;7>4uvbD%;5l^)2E$;WuQca4E0b8rHi8JRv1wLwa0ghEiVM=z9NLsl}}0Jg*$j zt(4yRub9LI!+}YCUz%}`j(_GnFXBo}%1_62bl!sWVjsO5@TuH_gG%Y$px#=~eJb0K z3LO9NtQwf`U+Z-$B3j&H=c*22_UB9pWbyt6&GpqJ!H2(Q(=mUf&CH&7!a#B~E7IkW zV(?O?*BVY;b4aNEP9FlyzeJR)s+9^_~&_qQ$wj0o9R+Cn0#1*E-M?n|t zQ0O(643xQ#;T*uAAWT%_4N5eqiG&cV8(2Ar=m##qJ2*&+h@ zeYSM+E{Vk)*n;j~{hNFVN3(c7-T8h{|5c*Jpx~X0*>nyw?rFxbl*$1zpP@15z=4Pl zYFeabC8(d@D1GRNnmhtz$?+{-c~Fzny7?WiFMKhPUJSN&4FaWL^L}Zj-ocYF5vD|) z14t&EiYH=jsm=u$+HiAjZ-F)9$TR#_@}CLJI|WHmr(nfiXkPrn1_{J>CgM zJ&!o1T{YTFy2DnL2_iE}F$$%*6E|iI3MQ6ed4uau2I*DMkh1V7TS5KRtxGLf#lb=VxcVWSS~$mVQln zJNr%<$0v~O>-uqmRT`BVVY&)p9NJDkZ%};v*DG<%tD>esSDeM`b-x!UQs>EVa6EV- z&C&7%kp!QR17G$8*X&{LT*NL_PV?N{yjZL?8ZGgbQdGzb(Pja9P`MeXFjn{UB>+f^ ze5S^{a%0qu-6?{{W9Rg&kHCkhgC2fs360AAVuCX%C0;G0r*Imtqj%3X?(JcV1tTET zoR#C_ENCsXB>m{l?$@YH=)eGN!x>Kv%vTkf->I&-VK`4N4jEROQb%1KosX|Zt}R<3 zDi}SDW9$AzO)HbF-0{+>z@|1NIQ+L@M21g=ZFiP!%aHKWMU_eo*%FL28zK$N#5;^I$YkWJ0&Wi=Gdr)Cib>O(Yiy5x zN2jV5NUe#3PR!unVrWJnHmRBny4>&;{cOwI^58N5n8%N&M5dOw83q!k|IiN7Bui$>M(1@`fIpHaE~2Eu4{-3$%`m=tR7f>_brD$@lpCFq!+F1Mn>RK~} zDM;ExlTUsQ)#3gN^7(Fm#oLM?$aS0L=`yH{R1#w?)`AV1R%*7Gp0V8`8{x~U!axqp zKF&R?v@AwN`u6%q?V@yMJj_@X_;ydazPQ9BmZURlw0ZsyN=2cRzHn~$bIZ-ZJH_N5 zWRl-?O4U{R+<50p(&OrTNX$Q5L)!#Ld!Gbh_}86udswT)u^M>RPe|H_YPyI#FgpGe z=>hGI;Ny8_PBs3OxVjucBXD9zRKXireq*|A0n~sY{O0tm?QI9PE`BT&sgEC--D;%1 z+%Jr#>1W?oMw_|Lv3upLw?v#cxCYo72Ghz)Cl~0634X7+Z1iy(^nM84`_rE&x1U_% zg^0UGe%~%>kYfGdK4S^T_U05jTlhtBqGj3-9bRWk z)W|VtX~>?-qyjNORk``w{rNjy;R3CtYHDIbOVjN0HaZ2j&viR+Yeq^U@vN!I{bqR6 zK}egIJYy_bu^?%xqCB3Vy386bQhP&mSSsA>be6}!Uh>CKnp}%_6$3tB2(+Uo>aZq3 z0x`-w=G9Mj{}fko@v-=c&9S%u5;Z*;#rdQC8*}g{Hz%vYQRK-R!99S8J`k71qw1e%=b~%2 zupop(hE^*MY*Dt|f1N{DzCC+!J1A#1(FY1As%bv>`1kEWW3%G*TOx9oaF5h4)(tw{ zjEv;cjX5HgK_3@5Li)nRno}v$S`~{NEWyeA6h@lLj2;jlqLS1XGnbBi4j;M+XcFjS zJ0&f35#6=sOD4wA&zSuU_^2Cmi(UsbL8Y_{jn<8v$YcM0TY9BlcVOQ6oNb{nMPnpy z^!18-Bgo15P9!mQG?xno8Pwv1;SkZ7&C0!tO>nuaft5#UQdO{PDDBZ#V^LV7#pcZJ zB)Zd!y%WYY^_o#iIbRQvl2GZN-8ZlAft-G$?ifQV>E~^8#h!$;F%XkT=qOGJh{>Og zFx|kv+G7dS>p@FO{Dbo13)#eUUhkb-s%&*t>w)a8RijC3a8*07DY-nrjfZ#EclyS4 zDVrRU{+AT>63n4!liTkd4{(c@HeEn8vSzzodrhn54aC*l8b#pWC z&b{U8+9F%_Id|ik`+kCcQMXtj(JYY_Uw*VPmh#=jAU<2Q`e7~k|9Sz6!CcQOB8|Mq zM8xK9Cb14J=X#wCV4*Se_KGByq#<+dI^V2vlx3}9y9*&JK<2f9%Vwx;uT}8FuL4*o z89Lp6CTnf*4=^~IVR7qoaJ^WDYrc{wo^IXN0#+v``%tni|3?0qro);V!(Kon>HfhQ zI6SpM{~Gn3BaWRhAS#YQMR}5)o(&NR1I#D;xGLECQ?eR0Un_-WQ`cFNq)0KE z%exka{^kdHR+WDjJcA2Uoq<+h-3o3S0JOA9YOBC z*UbZS6K&0AB(YBE3eQGwZKiAD5By&vzeCluulVWt5RgO>Q4~Rtt~Wo)Cft1w`SbtU zL;76B5geeS`FYuF0-~hH-t536OX#!;ic+UmQ!gA%m%KaCKvTyEzx$7G(A4C_WjCM` zs#i*cF*XOe^S+Of->8i<$7nzjpQm{Vji9A?G0ad9k!2miH~2{qO|CE{1J7}^#Z{CT3-eAOPvtSfy48N?Xs8{kFgP?Dr zcl=%c_mO6Ld^Ys5K1U`D^)z=+@W+l3eycWyxJ&Yj`ezG>q7F$G5rhVR%CZjK z#Rnw0`ndnT0sn9o%uNLP+*k~MuSW=i4wJ=<)oMo8fudF^mDQ^`&3_^YvI(!T`$`wCU$w+hOD8FxgNOO}Dr>()eS5Xhlo?h<#KFHYnDw-xB8}u*aT|v+xN;(8V zXvnBuKzNaHTrX2STjldlW?4JP(|q$y?mxPZ?P!wSYpP2=4?2608xMZRe`&viB3beG z`EZ$^??ccVj94sY3_3X1YLqMWEAy_-;HGclecaE>z}vZ#-4Se4oT8A^h=#|VS_#U@2}egNs@%#pud(aTdx8^He>M)^M`+QGM*}8 z@&xG&I-bkB0y<0<%Y~k*p(qNqTK!7d@q$i|$<@tU|JaAa)r8w=Ko&Jhf^g}?I>}(g zcke&)e~vYHSCnL=m+`Ln?Cca9@9lzjQ7aVl2{yM9oR{i&d;94O__52N*6SBRj<4@t z&`IbG^0l=$UgPiaIvDV?K%-vE6F=Bub@Pa-CBV%I3sNn|>G3{miz3=^KV5B34A(EA z^4|dJ6wY&`QW@%k9+R~hcasVEMNQ8oGiGZGKBs}re34u#MZQp=t~p*wb%&~yIN4ic zd0~-I!9v^c5O3V+#G)6jVZQCRA()%+=s^=C^pXfy7*BO+XcujQstWbGhAfH5l0cIkA9y+My&-}sZI=kyL01Y}DyZAL&RqnC6DKgOPaY6t?N-G|>QH8K}; zI^ajBx7AeYN|o}3vsBhg=%`aFoKve-sZ=V|>LAJn3}*Re0`1q9K6!4)Lnl+jDlkJc(gXK~?b_0r`r zb9P$eXn%*;O%GmYD`xpwriO;9RLG`J2uBi}S2PTcPP#fAxU6EMeUr(FtF43frd3kO zBH^udj_$ZI$aajfgic2zxUG~(ou06bO{qxTg0d#sBHb)c9 zb_4s#3W-RRLbaQ^&VcOj;PbZPwuecaCJ1eAaB_PBhwHRnbxdelol2odxm=+x=rNe=G&x1YD;|WBtqrfG z5hRht@4Yi-Qm zF<3Afo-Y&idW}LhPg$vhWX58#V6|K=;3SB8%&vC)P7%F)xeUg?-?NCM7hi15Xd0?o zN2wLbpN3iAjFK&Cn4CTW?M=8WUw=G;WWd(kjtLRHbg`dn=n%dNM5BXdp8-ot01X{_ zlL^Cfby=o+DWseCcn#&{qTX@_wO*$JK{7dL@fonTbfVGFFZD0rU8Po~R4P-`L?qcx zi_?JqiWNyZqm!04J5E7HuNS|E-P+(?{fmX`f_D{^a+dwQ5L>&a==2s`tpR*)^H=(% zR1w_-gfr zefk34)ljLF%9P7hR6&o)Y{q7JzE1l>=w$TvR)S_7lKf0hy~KQ$Z}0k2ysOm8WK(fg z*CV9TB_z9twl**AO&6{7s%47l6QXAYDw+v*iyZ@Lw&&(qTixW~=#)&M29g1*(@j_Z z5I1l15cIjfYKiq4*Bh^c0Y3*cjasQOy*sN|2n71+^I4Iq8Qi8KlWS2D$yPi~b_|zn zL+~1}5;cm&0@+*%Ri{U9w&O6#FLc@oIs$*Y^4L^QBOVdzmRjM@wMbpr!Wpc?qray|a6N!_`6ev~e zpp!7!owT-h(l>B}zV3FM7X8;ww8oARUV3=`QXwG7W=ucwDwS&q(wLHiB zOMJR@%)wETOukIDuA!3**jz1iboJBU-$T&v#%h#a{!MEN)k>90rAobCqja7j84I(! zvC7k>7zNGBz~}_SL%n!R!dKaW*A9XXo&KBe;>Yne36cYkzmGS5HAwWMP0n^_c=8zP zrQ7uQo3R>1)LMaT@`$aa8KyUq)b&ja+wK@TpYj)pwgaQg=s9^U47a+lQhm;B`e zf%~I3==3&WH;Jg#0;%Hz))r>@a`hCw%}xL4ID^4f?1pQ4hUsJsCKRM zM(J*|V|?Kh@1GYs(SXrnczIR4R;OOg5e~;loSY+?U9_|X33{X#7}+mbPc~xsK|6l_ z{%X|dJ~fVN~=?c?keIg=n(bBS9~sMXmy23rP9y|YGsP~42kGI+p9}V?WC!j zTDUoJhoP=E9N%=h3EvS|_$5Lop*LF5zg)P`>LoI%1c%WS6;;OE(o3(;jQxr>h#=~b zMPA^@|DMnq6^F%Q8KqvQS}t&&IpuI~gT?tJ))ETMzAnbzxJy@?^Q$50f~d!6(qnw- z2d1Lb@*E!@6Fo{(m&~+yf(-g(4A-nh5b#xNKa*tmPPwVqvc#gt#Ns&wqZ4`IC?UAgS=pG(rbZiK(`6VqnRfTG`p%*Ik zD&@j6-koQ5;efNcnZA)RMsE+$YSmv;-ql@_cdHcgDc07boEH`J_BPtv+_c!mt2r8f zbl$C@)G8G7Y2t_bY^^LYy_*4RE4S|4BViSk+_yG?j^W1?-n^bjT4QXQPpHD?p}I)X3SUAn}00cRn;1$LK&s5P^}cnr%yQC z+hlHPiH&3(PiG&a_r?gizcKK*+V}=)nuefN$)D^o`}qPV@i_5Ro=UBbPLeU%T)4fR z^bPdW8*Hc9ZhApN&NaXV@0z9W)*S2A3`a-DB$DR{<|f>2?f6;@SF=e49XiQ~=||w* zYUP4=>k8#!j??1^JL@aVEriHw7Wzge7#Z%T?Sgmf)e5C_hSO5DVTaTcY|S4L-`FA) zKO-gQb#kr%6{IjaXD0}R?8Gi4F|GpG+}yP7Wr2Ykz^BAi_{o&ST0ho zR;axSAD>p`lPaW!#w!aL&k0dXnsl7np#e<@`2Fk3ZsgXN4A*6_Z{>Q_AGiDNfIF zoJ(y?{Q4n}9*xn{=HQBnrPm5ty++|Q!q(al~no6~h zBDTBAXNyt(Kla}1NscpJ^ZR9HdGETb+B>v2Fl}H70w4*JXXcpQjok=^6w-|@SO1J| z6`|0LLfTd69L<^K&wGsleoBGZk>WeJce%0*KFNBgJ9bVwue;r~so+2%0Nhf23 z4nrhzI^6Z0bX@4-QcokLF3THD+o^e(*v>Lj6VuFXB`~^bIMd$28K=Z4^u7O?(9qO8 zk@YFYrxsb-%it<$rLLi#QkUrz7?*2k*+W()#u*q|&ZmrWCoh6#n^$dZG`OP9EK z`7-C4%dnhCDjNCpK1&nh^bamRiwhI62nYKiG)pm!J#BPf?BQHP0Nc;>I5?HiROCdE zt;GrMJ>4Q9OH`d{q`sycujv%X&S?s%@CsuC<4i8@kj&-Cq!UDsc-QEwrL+A!Jw2UN z`)n9rT2n=ivA;e;|D!SH_VQF*>ZZG^jat7ANeI8EFZFiuV|+P3G0yB-1kviD;X*fc zJ~QUi5UeRlQit<=`_(YJ@iZAZODYj1bQmJ381OW9a-sVY-52U9w*Q4!6gi8W&y!PB zQo&6opWIi6*npwDTps5v$Y7)NCW27cXn9_oQfuh zNV>vk@yR?cAc{InMjav=T3#lXSAG?788x}V+~f@NYhiT0HX7R6srK7XZ}t2=K-1Jh zF(98u0aD=*yNXJns*ZD4{dgQ^^g^CYBFyH}0?QkFOb#5fe-J}K;?|XBN}b2)B7eY} zLQ@r#Y?h3wqG~G9-EFjdfQp)Cu6FrwSoDZWmUw87)rCb?w-y;X2oj9t5u{u6w3g#M zVU$FZL#)k?aOdkm_VR_hOVS&$c>>fn)zH@2MO%FtMW-TraXKIw?YPSt={&c~=JpPI zQ=81LuP~(v&t!r$O~7DwQrYaKyygt`l|HN{>6POYSDc}>WuNu+O}3{tnci7JeWqTi zp&??jdnl=^qo%Qy+A{A;W^%tRXljmRaGlA4ULHJ}VmE81w7HWnZnogJn|@|uT?0)< zmJ7PRf=*Y^ITl}MMlK>rx`Nk+rlDj~$XY@3QxHV-_5fA&jkN4;vbnX(_R<`?>$7M- zu7#$d2|DcF66)(KsB3JXve;fI{`^Lv=F$W=X6V1$%af^1QsxpmyLz~Mp&IKcA#PQU zva>wS{cro&N@vMyfFNOU6;oGHK~u+B+8e9zJATXjq>)R9*_a*S;e$cOH=~%#I_bW6 zp0+warc+RqK~u@bcbI!Rz<2kii7EvXJV|fFUR*&()fw74Ito)urr$0<{d!PIhqss+ zdc=d?F*cKW0L{6Hv^oh?)l<{h%K5Hy z)D&6Ya7suew!6sa<34(a76{^|spSG!yX$fMW@Bs(Rmqarndb4``wUEOkTm%@*V)6l zmP*{mdY`@PQ`FFMQMMK*xc^-*tBEWCqNK;_E~dJnoR+f}Xltm%?=ZafP)at;=E4|v zzwYB8uRP;jtJ}|+stTIg&(hXdMX~)i&bz4)>odbVyf?_ib{tDZH=W(*Xsq&KJPr4# znkO6IVRp2i?;gw%Q;&GpV8T&cK}S_RZ5{12Rr#>KTxHW_qI)Y$3=A>46v9|>o~s}A z&{|zoXu9}~OSK&fO(7XvV{)L6yS)?a$!1DhFL3i(^AYd9?-MNWZYH|IlOOIddzc{o zBk$T=l-4#;+t|jr^KDcYy(qD%W;4jSJULY%9SyOk2?Q#uXm9SM$ZbVWj$|~*_UZ~t zt2;~$g$PA6r1Coc!dlouPSJ2jLkKTn)WWPT)9Gb zYYoLN3kESyI=avLd^LB!{ei*RJ?4fVGgw|i!0)1==xyr~e869W55<7@0YN}#_D~$~ za}eEPV|JLtjupL_BbNygOy#f(!Uyw>_Xf3~ji+iL2nga&uZ19hC>EwTRJHK=zb<~! z0F{IJA!ZlX*~?g|XltOosbF&Xe$qNB$#9TFI)i*nr9%)TtWGaBi{Tv?D?}uNoj`RB ztr;`2{wQ(T)$0H3_S7SFD=H?T8ia2lPuFv@-m5V zkff~eYRynUXEbBAyRezwv39V$3H95(bMMyUmJ8|7N#j761PXe%L5?80IY(Bus9$N}4%J48YoOpo-V*GXLOZouy}9mzInPW~&p2&4li!_(_uqZ_Y9Hq>pR9vxexVO#L zPK3kNNuKl?k+e&kZ!E=ijA`+&4-F-kB^is7NXs0v6zB{VEH(#r%TMW7tEjmYn{&fF z>3hV3$8&_mV%jf#%*`ujsq?))QS>e$=y>JTSJNSlqA~(5u>$;nwAc(;UXc+q*F;^(J0YmlAYygh9yw)U0i6c#A7=R z9eY0?nx>FRM2W{!WRJPI1WAY4>cnm}|8!zp%MsmPU}ESockc}{v!~*3?Bx2#mpNbM z#P~)$_x2!21`M`x&R)5QFOnoBXUQbvL?Q{Y$pe-qhY+CW>*fBV2{uv|>N~G-{i80L%WUuHn?b?1Cr2uLKwMVI9}~|>dLtHx2fIo939k_q zIThhxb(+Wb@A6<^o)BJIFMhvA{Z+>L zdqK%@zP*7uzxBj;PBb_O)HHJGV~wbsBa=yyh{p&=(nR-`86VK0DLFbj8YuUekF>Yn zHZq|rX-gSb zZ{OlVLn&^{=_%G~YMyjFN<4XTd}*>ea9CgCFZk?WIl`NBjQ00(zjuVWLxHmPF0S9a zOh<+N^zg1|#AvVJ?3GItMGL%}O2mjplE|?=7AJ<#3y|$TOGCLE%hBYGAlWIdsHXM2 zo~+)6zv2wd&5hJmmEd(*(Fr+H(IDF^^Nc;|=kdrKJ8RQC=`~Z`)WF3mGq$%rmQ{#T zQ;{HXSv__iE$NL|oE{uT@h2pHROD2corQ7wA3osjlVuWyV$Sw_%#ADURC&!mz2|sG z5OfYoYMZ(Ek&e2IjGRpqk4A{6azuBR8ST@dWYctYG#u@tK~pvIxxzjKO-Apop{?@@ z*Dto=x9X368zcIn3Yr{FwA3MySU-dF+bk|Dv(nm3t=IUT@>U=4b8tGIB7bubkPHs| z6}9A4SltQ|3#Cw01wjsz%87W4M)bd#um>-*FZ6}OsZ=|ZOf$C!OdkPdZAjkIHAQMZw1XHh0tw?$^^*x`_TII!aj5*ZX zf*|TKI?HM6{)poGG@{vs&tFP;u^pXQNWcn!&F;ce?89Z1$izbI_phVi_I;xl-iC>lnF*3we6R1mA8`3 z=g1_Y9PVzgytu&B_yXgPw%7}&kW~@u#YQ~upb(;|IU?IjOpQ&j8p*v9P)d3e-s*PF zwzW{<5#FiKhn7zg+MK2DyFc^olXWED8O~n3$d&F6&XoJGnI+V0lIZ>hGh>51e)N>N z=^^&QIqYs1ms-m4T13dF2yRaE`2Is4jBO!XE9ky{jZ5cSs44YeH%lnlB*E(D-#5Y1p-M?}7av`}%9XQ~SoLor-6sG?MIeDfQeXY)Lb0kA46+Lz0ullO z0t)%`AuHogxcfsdPd8<3WsTgp^)ct0s>$-!w*UYj07*naR46U7W728lQc-qS=NRdK z#FOE9MjqZJqv){OKc=JF_YTI-HL{5yE0e=atscC>Pat3`uBN{20v%PZlM|L&9yuLh zYkq>hdw1y{-yo>DXzIDnCpUU%uk~SiCyAY(2g&HBqM?h=eT`&t*@AX;aF6Br8D?gd znIGfjU}(?+)`!Yp)D51 z26%Y?F{4XiM0YipuYShuYb}(yEyo(Oz844*Mn@T~Jyyz_QpmXs$#{hQtu>bB=a`yZ zW%S`5JE1g!@iTfFOL6{&CIr-cnuC>T#-;m|VMX(Lq~7rA-k3SG@**bMJ- zYpjvWL|7TQ%j9mB#4CIW7FP*%UAH(_ZaTqh2GA6;i6CopV+=p)<-5K)QU)(g-PgEz z;}U1nD+|@vd^KBRZ3cMTJ zTVZ-)lEwYhF^NVIU+sC$wl`B-{2EbtHA_6W$^6p+9zN*j=~4vATg#PexB2u+Gi4qN zy3@kDqJ+s=LEA+el`UzqxeTdTguSg*7U$=fnO$Lc|A3uv27~o;&earQH;O3P7<8&&g9%Gd&lsu!Q!I4sgrY!m3VC@$CsLt zVt;*sr;qM)@6jYnhbsQ2POe?Q#^v@Z?8Z~XyE-#wPXizS&PygMlgXxthY#3XU1DZ( zmc@mqe80IzB&(tSq>K816Qd*`Sxaf{x`wwlg=NY*q&zpBJB9 zL{3GyGqlOU<~;pRw`eV{!ur@7XA7@T_5nP;X^UtJwXulm|dmRy8_fS7tB1;@gR}q0pd9wE|(SaZ&_FNHw;10 zqmv96bRwXlC^_=4P2gxKih?ZX(KG>3(xcOff1NI8K8+llW@KiI-Kc`Mt(r4uYVa7O z_oVl!0Wzyk`}pqeEK8xxEAP;ooqXo*q`cVmPKyDEI`lR_wJm;XU-LFW5RgO%W%W(8 zcPuh7w#j-d!uG~CF}WEJhTll#S|J-hVDjM|zL`4YFqMDdRY8;pG+jpUcTiJoez(N{ zoe8VAinHFT*SrZtL5I=mrT*Mmn&#G6SUDuPyTkU*9%-$TW6Ls<1*gw~)A!up)GW!+ zIzwOmKm6D4##tNd=aJ1xpuB>fYU^7soN1~|Xk(uKKYvT#YV4JcA-&l_!!-lGvIffB zx)XHb-wx#H7R!^veD`pPm|&;p(rv!@>;lc@j=!9T$%4&UL{Uj8E@Ph9AD%EX`MQ6l=yd2L0ZmoO=W^uL*KKh%R7D}5SJ4Ck z(P&05ijbE{?9DUqWR%gFJ@mERbbt2m`A@g&&!7@*3e;|HwG4Dshb ze9fcz2!gYWwvRsL?{8nGvCM(-6cqvh1j&TW6Ts#PJoi_X>o+db|J6V9hp+n?n;N9g z;=~{D?_p(kux9ZvHELIE(R!RA_wbCK6${mUq57O zFOR#bg-f@-;GaJ2z-!TSx}2>9B!eAqz>fEYrO1#9F7xew`M>z4Z-J$uhukYJBj9t> zR%Sa@-{5sn^BK10$GG#Sdra=8UU}W(E}`p7Kb4i`6dl*#t|{cw5e~N&c=**H`F>!T zgPe(~w#(f5{5BtTl>en`_q0IJA(`Bi*SKH!vvwuQ+S7-8^)FxX?cfF@4}QQK2;lcP zC_PS&OU;u_2HBW@%7d@|#J3|`Xx1W{dTw$1_Q!NK6bg**_PeWOQ(@-&?()?{kiA6i zrPl>Kl}&u&ze}O8Dw#+pF7{(r*~ot#q8tkN5A8DpI)TB#)JOUWEi0k z1e&nB1K8cq-K1J4>F@^Q_rB);{nKNnrw4gtFcYY(<&!4Iu^tYB&Vs{h!Qm}=?yoA> zKfc7{ul|`oeDj2fi6``0UHAjV6xoa4fk#-L@YVtYKm3`yvj@j?l8ZFlFySq$J-Ha5 zqzUh@GV%BU-+tT2%z=WZs+G&1e!)L|(t+C~oig4nOlbQ`?D$?-iXIXNi+uB6{%^j0 zw9NdI``j(7#p|@w>=%jcE%LO#m(ispw(9eIeDe}@MK;W*?D?M0rP!Dr;fHS?Grjj} zd};NT(X9lit}H*k7@#T0=`g{~1@8ax5BxB^Mo_U*-Eoaizr4+r7C+9@AmQ~q1UEm6=gwt1o^ZA=p%h7$X!r0wE@n63hU~%#Zy-qi- zk_v7$*bxK~og@_$G6WsoA|EcNDoqHREt6K{PsXyNmFGX7%90x%}XZ7OsI&oO^gih-mlWp(z=X+Sz-SQB5;^2lij1nA@H{C@U=6_9QD?yFbW`N_zrs%-P~>%DGaoMzq^UVlp-pCodimoYe&Fd=27758JvVRj#q|qR z`)!5d$ZrB7g0Yy^i(Ra&Y_h&R#qQQ7tE)S7*L&YVF+f0XwBYo32?QYfO81*sFabYq z3RTn4RGHZBJiT9k%@4hkEJp>(n!5S;_HAxlsKskOZH0i>Kr~_YRMGWOH!EvFg0lxK zOfRw3*-TTJl~b06IT?b8$$G?dyquH*v(tymZaQ8LMpKbfA=YPyx%1z?Kgsz)k@cFIFv{t&%zw<&s0R^pmFGa-?g6&nlbomMrLC4XarshaTwpkqQ zV%w?kefU`rbeNn0+OBr9xVXXg{wxRE>&(uqakakn zXnlUpcM%cIep)Yfvb?;>#`X-`o13hz?a@{5#UQ=y)Q5oHXvOLE;SY$f#DyT@by+bT z*Zq9NyV0Fl9{%YY?(|Ku5*I0N?&0R`+gv|igWLGNq+)*oL^D=z4PDo|SY8bhTnI8V zzQA^S4R!WB%hTiB>s=&cs-Urxv0uWRd9@he@wu^?#N*>sB}X#6$;`k5zWSz*ne8-2e?1q! z_;>vNY9nQyx4-B4)gb7xdP+Ha{Sq@XYaE1D*j`^}es+T^bf&E?4FWpbMK+eokcjp9Qw;5|Xp@?;ZH!l59MXpC_1fc=9g3F{eJ zTdMK9t*633=5G^vEEWq+hZ#|o$tL4OGC33tj;+tAS+bcJ2aznQCSb5Tv70Rze(CyY zc{0f$GgE6s5@~eKc1p`i2-x1S{`(6M05j*l{2!>jo;_AG5kbP{F2-Sff3)(WoYU(( z9t1%`6s5luEi{e4*5TpZLWj*;#jXGGKhvF2j@RTiTCh9cZ$VKz5=npk8AwRt(RHn< zg#xLjp(-+|c$`d5MH3BJZ5GT%-7y>2-FTdObkQv7Sd4f&gRJqEpJxIFi{+&-G%Grt}QiBI=aL3P%n4y_A|N^Mdz#M%Ju79zjB`XQV(YRPiat} z1Q7%yPL~~<)rc0#kcvl$WeY}!$KIYwnp7%IG%lk_2CV*490nbdnjsd6lSpLIbS`Xm z2Oj&$vnHZs#$Zw_O~g@D%k_W%KXLAh6FdWq7OZyHOV^`@ zmd_I3UuNLJUGDXcF@Gpf+|bFb&p)HPt(Nkl(@+S|Q1ddGREktKhk_oP-GzQE?yp{$C3MpeN9Hk$(&{@#(SJ)nKqVaX4OLN=+r7jS*a* z6DG1!YK_BwHxBtoeau~3+lqF~D9$)!`IvpEzD z*zDHV^RC@Tk;jF@ED}w`iAAHN74_#goBSdOfPs>h%lx~tR&JljyDpqg>x+NXRPvb^ zhwBsE`TBc$M^}hwF50eKThngo7-)C;5mpga*8JQ2FD>}pF zk8g4P(pl=uJQ#jaqsgxeP0J&v(*@quBn&1CcB|sRgx{%WH=ZFG4wJ|h z8X}+nh^A>j;khUxisG|9g{Brfw%$G@Y(=$P`|tl3+OsO^vEEh%-nG8MyICUJbBsKG z$hY4Qvz^jW(%j9}TQ|9Kw(c44zF!>iZY)M7r=kjaEVh&RQjiQ79ex5{2X>Q4G?5?{ z4wF(Kr8HD$C630SQ^JG&A zlBqPAoPg16#p$x2xVhKzY0~K=@l+lp3BB2bQT#1Esstpx8JE8T*ZV$|7f?u&rIQJg z=`3dZ-qY0zQgi%nDQ-@4Gyvyu%lB}tWuB%-%R~KP9 z?xqq7#h+*KrmCT->N_d#6im}x6xmMKNBoA?iDUN;x%0zg zCRU^9iW<1~=_gz~-$b?F`O^l{?+9u>!Or3sqodPoB+OJac5vl#D}L(|Mh_hgrC3kmUExLE)ijk?-Ok7asBqE^qg&=I^e=`N~+LGF2UCP7^6?8*-BceZ0g|Z zl~#((CuzDAB1$5aA)7BuPCK2}6Q-^-G$l=<>@JD7YC z&>76Xh(Iq-t>+riw@6;RaWGLh^A!hsj%;aXAl%a&P zJzaD(l^xH!@M3~VRi3S>XfR=MdnvY>SSLy3;E-@6Mov3!`awgH6C{#pGO~isWyWMS z^VV(SKH#syhho5cf*|U!xcpR}u~3v3k#q*kW;0f+8J+lHn&$mNz~uB$R9cGHxJo2` zz{<)l$+j|VhL^ipRIUpVG2o+%EGA?|UH$^Ap|Ds+=Mf++j78B$L-u zS?t5>b^guYtjGU`D!ELQweiP19-Lw=W~KIQ7oXnlrsP;tK#g1?#KHb9J5d?IVaD!u z<1k1+bNu)N;H8A{v$fDjMR%F$f5^k9D}>b&u6%Z#ix7cGD}Vc$zsD~Fklcx^acYKvjIU( zkxR!2$7POc1Fs%N$&$;23B_{cH3759gvp>kz61UgK#`+tFO75myI#gt66pPn-2TVk zbM0ImMUFQcJwKV_1?+(m{604hagRu7mz9-$+DoiBjHVZ^QB74y9`3WVxy?aJ#pw3X z+**Ofq(@REOeO;cg9P~$sbrjRA`j-{lVn;xO*$1Ln#`ez5_+?xu*o`&YoV!RlY7jL zJmK!$K^8(fN}Id+{Xc!dg~k#bM%^2D<(za+{Cdb|lI*X}Fz{%a-Lw~DSrsJ}0ql~J{=<(OOnc} zNUl@PyNXP7cbTF4z1({;M@R~A@kW7nTPh2ZazFnO_+kUb+u+?ybf4Afr#zfIAgkY{ z=6pkecaISU*VH_jBi_v^ptD#p84OrFwX|L_@jusm^!n*+Ey3#KDE$wfvX;?P*7ZBS z=q#bwZNu%apu};!l*{{ul8dpkG{ODv?lZa&#Zc1B%`ZRaW=}K4cH=4IU4{7m8dJjq zjPDv~%o?d|smEtNZX&yo@J+@egcEr*u`t19(uoLy%=*)N^p7sG5;aiK(#_3V7btTW z(Z9S%s!Bc{C^7#$U zHG-caZ$ z^-yf{6uK2um3LC!{(zqa$yP+5qMpXmF`n!kusSi!`1v}nn2WGKw{ujp5w=(77@b%p zmJ=|QwNYOkpy)aCGA%D7XHvw{IRsI{V76m1={ZR*IG@cB**_qhl2LHt^|)|341WWO z%@d#%ZTlEI9{Vma!p6A+XfndlDVPoJ`znj>d- z;VCMjv(Ckf0t70#)IKvK6U?sckx=y1mX}gdQH(*+>L%WMUsWHo`(igG+ICk9c%;dD|`?!`18Cmz{m zVtj+nau;U%%gGsyY&6W?%p}Xv460!% zKJIFu$YyvWqjoKyC7n)@%;XEtcB=!6QF_+Jr*~CRTT@0&@hT(xo6L<4vsB~3Z8QGm zde&5O>3x>xrWv2vA}LrXEosjY@Pc@f>I* z_qW(uUS=zqN9VOrR1&~pHlE6HT_vAnb83XgeZx#{Whp(^&CM@v($i9g?M;%;nu?Z7 z6HjKy=2b+!5sSr!QU7Zu3q*`2D?XnSi9G4pCSyb6l$8VsbX8z}p$MsgmSJmlhQ-w# z!dVTw%Z;zdcj^oh3sA`>4w)Yrpl^7N?X;D1pWft?TbF68@?d_Gn?hC4a!DeIEQ%(g zGn%nj%)hd>vxL=V$L+R|&m>8v7Z@CvrmEP5qte5RHE4x=Cc^UgBrAJi(unv=O7OTG zr?y!6>mWyDdx_!u_voA6L-W?tbK?d#dRi!Po8M@HRa0cr=_IL49t{zr)q&Nh`&GM@ zMbU`M<-l&$7p55&XBZx7rZI39yH0zN=QNq{)+%%3bF3$GNKP}pfFFm&bo7jq*_$6_ zp!YFDOHu4K=eYXmO)j0S!)wu>Zcn8Xp`yqMHbx)O+c(1WZl0pXZa)9VFX?J2#ces> zi{)5o8cHtxY&uiYn=xA~nE&c&xaT1u=`2)K`_PSS6Ax}OIW|dcZ56K801o5xahgg# z8)s{Jn)$UIBC?9D)F$Y?k^lf807*naR7FWyDP~CmlLfEOj;Q2FMb>#bG)_%r2}SLt zn8g>Lf0~+RYi@?6wH?B;hQsYW#k{K=Ny!Y*H!{yo)=uZ`Px$2KC0Z)qoOhLMf@n%c z)kO403l__p7W`fZ0np)aI`DYRAqoYVnbUVG=ZI`AGIakw zk7f=Kd<|T@d4n50%>LK_e@7l~dvWb0G=4Tih zY39u5?Z@zLj>FYO<|pRaO#K*N`f-@eh)9U?A?u4X3@)WuizqltN^qVl$Mu3ivWg-{ zSe>3?Vtk3il!B$mOY6Bh>_>6x>B=1!cz1oIm)=KDncY|Lw{&y+_n&d0A@GL0tD?wh zlBq(RDjCdJ%$DOlM1C*^lid-j!2PHYO%n*g7DZ zQ*nB|_)AMLiz1?E#OCzVaki3&^Sf*Xmzf-&q^`D{E6qOsQZ7;N@!%||KEKd&d&A%xQT(#DAOIS2 zHbXQVC6mjcNiOVm3s%c%3}Al>Dsn1GDxH2#!&@O13=>busH%pl$|PeE4)*que~gX< z5uL$;({4r*1vE8B=5UeW!C^)hgBXkIXzaSd&1NTsQ9lbs)wR@?O|rPP#P0GK_x@x; ziCv(fvILLAgdUk>^pLfMaYp)w8CwY=*nCtqw9!&i^lVIA)AD3fNz&;;hjamXV!<$p zw1T3l1v!gIh{Jswsb`5F3BAdJ-D*4qT7fS^D^%;_QPM|RV|$!Q%ct7&xMnc zR*-^>J@nrzjZ&q2o*EU&XE&q(<+z=asO?zw+c=0xg+eDervKPt=p92-Q>9MEiQoc% zPFa=~{A2o;BzPw2p`CSfAm|dSY(W^4LfvKu1H~=Q)HXi6%cVpT+t5WS-iW29uO}^@ z0v5LZ)QiGUkw}Rhlc>T+P{|yvAGRyo&>kqJ%R)%&>-ncA)7u=P>8qe!Z9Xyl{aba> zcUuMI>$g8&uA}ALmT-XrKA{Lo`D*KDjKu{#xilYNFkjG1UM_ceM(FgJ)uDy7qXn9L zBPA@;ibu&w?g8~Ai3zp`**3NLUCW`0XzUPPFi(rJa1Urn4U;-a}gWV2H(* z2A(;MrlYrSeg51eD7<4#DBQP4YvJIqgV7%TodA7`5-LzkZ^7crnMgVNcYCF0W;p zT}>@v5sH>H*CZRaA{Q!(kJ9k1>zY^f#)Snj4zj7@lohn+W0n5(M9}&&*GD}pO`8E+ zm3B*3)6oaCuYF_i^^BH0aY3WHGbcoeB9Xi`2Gx& z1n-8f9+68E+HnmaGh%8?&XZP(=gakH!8<*BRNl;u*n*)O&#hEE^}x&W327&WUP{_R zM^M3pSy)M2pWi-5fywjRD|a3?6{UF;bfs(<8C=;4-*L0_>v)c&vDepM!z3(jEvg6H zL~h*HmU6KW98ut*%iJN=kV{rmWmb8_Y*zvWm461DM}01-zZ0ONAi$K1Q9(#xiLY1a zKtJ-jP27``2sO>Ergu1CzKH#JY#8;o9iBuu+nh34(t@?Hxj3|e0(LIJHa?Nn^RMac zbWU6sskHZ%wfog(`W&==C7}7RQZk=iIROjf$f69vkwdJQ|>j;NR?BTBSFgF z-JzUnfV@C9qpPC8ieEJXE)4c%Uot=b8#gByRU1^=&X|zP3uS|kZW;K zO~+IcAjv;6{Nr{A8mb$)bs+qr+b6jT4sue$1{(kVpjR7*wTxw`I3X;*K91ib4;)*GIvAA+9smN^!rMOEBwscYRF8Os|;T2d9Xfe-o1QW)n*98q%U}S54 z#o##Bj-M>1hapAg=*FjZxKYv2lh+?Qjz;9>7qj$>oSlUT@ZsAY(xn@(G=b%L z@hveA8%Z(;KI(7uO4)!WP!V84$!wB!R~wQ++%@1~9Jt+XZavnutRMhUG1!NA)r!;e zv-xuL{*2%l|I!aY#DHhK{z;a;piv9g=YoI%kyXcdV>*Q26&P^%~f>6WpZdGvb% zwsB?z=U+E<*zEXNjAVlWVK_J##wqaL_z?|ekocXF-LFx}f#NNv^4X{t{>_wmS=CXn zmliob0y$udfrO5?u@pLG2r1(j7`PXD{}EzDq3PhH!Rm!^h*+OtMghdfxJ?3kB2 z;1@7c<|y8;@tNrI1d@va*XP#}j-M=i+RCDGzD8U~^Qj}`R^8Fp zEP=S7WoEM>j*Si_0D!EHtrriqgZEU6%Et`J3w!*D$_Eqpd*Gz9p#6oC=RsA-x8u)x z(q;HL3%mXW$O>JV1KoW|OJ_}ls+zH+=awK(-=?JB#xH-KDNo4M!6{nMBW#wRQO0L_ zR$1?R{af2dRpPi=_>kH@Hg=yO$e8E$qwyhE*qzEIcZ+pnRH&!xp-0;kyW1k^tjGRv zYT_atyGgJzXUI4tq$lw1GZfs6&*#;@p9n^fs4U$tC)U?oIWpCpg#tPBnL`K~-Y56$MbM8U^6XpW8q@8RyRRK>!^-Ww4W)Wbejc#6^}yhFTafRd)N;Tp_XTA>^~A>nFclr8OX zF~i#}sX-Ao*TI95W@k_42*%;i-K z7q!Od>FT{Q9j=y~owH-j3Pg33ZCygcgiYO|+pI0lCiD1p*-uuD0{s1V9kC`WRR9mC zb5h>$M?WDSBqlR_-l#`vne8`+3MyM*EEzF1N8`#^Kn{h4e0)XCmWf$gtbQm;JIyq2Dvks=&miYc*r0>H+{Hnq?o z=I(__JC$49-12kgGe7RD8E}yX29GGm+@CTgImy(hDr)VzzEz4S>K9NhYwAkJ23|*u zln>`{m5Lbk;@Z(PCs3ScaQ!#4#I_XX@Z8XQr1e|-A z3arC2@SM$i_EcrEv z>;;EsJA~Bv_xKiZVcK0zN#w0aW8B&Q#Q@azMb@ZIlVVwC++I+ETnMQqEI5B;{mWo4 z;c=}4q|*4bT_4a08`)V%CyCbPwwP2m{lz7NbuPCQ7z1l*=>Rq@tnIR4mw40h&kGBv z9M*I)%w5cWWn5dCFV54=VxZ&*O}CqH}iM8RM zKoQ-^3eaAUaK@4daa8$At4NezPZ1XMcL0cixEGC#!q$W~pek<5tTf}~6P3`4pHdL4 z>7L1|xTKQ_-f*e<@RC;B?gbiV6~T)mN^nv@#r$n?|Z^DZo_Wh6vxIpH|3CKfnQVk zn~b)t&_$keUSX1{p2#BtXUX|wmpXO<2Yu1>kC}^k{I7hc;WSJ>@|5NkF%n=_=`AzZ zHL8bAcgX7fDa5+ryTj9cfGLx3-^t*oje$lc`(rw}z~WI7`*-)VYQ#e4w(zk~O%~GH z{>vmM;;6?Pu8lYn$8MWnbC@DG)~i1pVfccsUO*9oMtzchPge`yxO_M`K?{yU1g-B z%@MV%?4q3G3+n{3U(|{DhuUvTAwC)}fwqA5gv|`>=@^t6`|V?#u?f4?z{RcLW`+*& z>jIO+$ZB>@k*Nt)BK=6^HSf$@i#QcEEP+oJ7XfJ#*_Q5YS^39i#`Hn)^;3>7%!^@L zujlXu(WzSFvk-q-+$WF1-vCV9JAn@|HIYOC_Vh6^$jJvnYok^Po8BdzS**wFt9Nvq zdIB|O^<0~yF=yUHDla3zqx)(?uLCR@!4fo=H$pG}CZBS3>oW zQ||hz=}`)3Nklqc+M+n_CuXIUQg^aqp`|Hw2xji5B z>TZ>~)8Ty67-Z>ucvM}Sfj?ZDsx6PWugT?f@(QhMg8=8Sme!YuqnK-8>cTi#T|+OG zyKZda6!;!#jNqKh|1~uuC)?cG9(f=Q@HRUSYbg&HVW*qMWR>C)*D(V*skW3%@Exsyid8tDu-2PpOZ z42?N#;Sj;Zgr}u+-K;;~IgSnvR0Iw7!4gI<@cr4cWVwXtIDhl-V_D-a2 z>g0^>z$|26ic4Z?Y@)E#B0YDDj5)N-PI#bwUfPOo&OLTEX@P7ul1JoYg^T`$Brf#u zsN;p(2GL|8`2a%`n3y%LfE2^loc(>YdVg?8KHIvwn2au7l%9c)IED?K-lP5b$1jw_kqkNj7m;sKRZ8>dx8#<_DceZL0M)?A_ta>R&_vyki^3_;+P^DtUB8M>x+_Q5ZO-5Etja3dn5 zx@0o;UdYAV(vN4i<3tYSWUilZS3f!0%|%dqJ8W*BMldhVFEX-lET@z155I29_rh4K z?WbtYspoVG3ZtnPNH%9b50M&25Il5%(si_pZtwX}T`||3z9q+Flm1c;&u;MkpFlGQ z#?pKj%=2^5AD9OBpL8oW3u$gZ1o$8 zD;rz=pI1X#${c|fN-_qKFZpczDKT86qM(qdQY$8e9>)N5SroNR=g9HcpG6|SO)N8u zGk(}3H=CsMppb=QL{^|jnyR?9C8lD6+kNv>8qPeFtUrvLmVvtFl&OP`w(BWY9hxO8 zl4`$A)8@@JoV&>Lj!rS6dx8<|6Gx|D*W3PrW;))-DlsZKAv1WJh%?sSoQ*xk@6&_? zNL3Ms=F0Al3<<>X8r$Bd7$4sg$|YJRarqW++Vm~nQj9-_n>o9~GosOs+tdcusWv*w z>Zpo^2~(aBuOyazc5)-)qV>I)Y&4ibiOgJMRy8N+axy=6ZMg`O@ouAYRBOYfs^mv; zNSy%ZU`|GUnt#+nuJmN>wxi$Y#NTMl6$i^2(DOL$OPo`KX9!V+-3oUE+AUd5)(i~q z%JBu6*4CM^&O0|=C>r~{@qcD1n%loE((OBz|GDVf!Atbn>}dw1S# zU%8iT**0H-uW?Vvo*PGOkeyCEx!ci^bx>5+9h0L_M&8-Z{V*q3YuRT+>Ru;6hW@o%Z^Yn$K%5U@^>zE&LH+!SgCoA1wQ;3NE zkkdRO<8Rbw61Q-%O8MuBFz?2eT6(OXYmN(u)SVfjXH1)~#;%p;z9lA#ULa7@CkDQB z1eK>>TQe%>?acnmNb^^9K7CSP+E*4wPxy%{7CGa2!l{7ObfxwT0_*7I7Wp}&4Kz3b zAzq#-DpOP!xH@Le0&Jf+F65SQhhf1FXi7hf5*=`)qKNas&(=0|Gl~w|dxJy@u{t{X zwGKToH9JHL7Qf+RN)3s>L7uKfQ5kae0=*4|oi=+p>m&g$1_%vuP4`5Q)>m|J}H}+3+y%v8Ic8;rkWl}=!Qcjm~S0f1cK_6y)n*c?sGvt>22<&U3zIae% zV{h&6mtox#o_5o^FNcJuNE@3n2mYy$ac~*yRDW+J`>x3lbx+6G*o~BwM^cu;osek( z_&k9A`O7}h^x}(#uUoUtbR5=o1 zIU<)nSAq$2hT8uYOzW4#R8=+e;Tc-GHM^lq6&L!~7YX=njrt16nmAqhxTb--P>0%C&=$3MR7A&G|>gr+Q6!OoM zVBU#6wdCkW=I;3-dRfS1w%aY=l4kulaX!Aq9|;RV1A|Lr7W*Duj~IFqU%`KKN&0sL2 z{|R3ucFuDLaV|EH$n*Q<;}^uQN_dw|b^2)7&;e`;Kin_@b{6g4|M&n030hS6_k5PV zzBbV>ksc)u z+zL%~frp1&s%1aty2##_h*eJm&k*DFfwCq^5(3(iM($TH5gsT)87|}E?UL$$d5!nG zuIs|m(7v`OCm;O2(8i%qC5!5Bu+BtsCErzYxr2C4HlbIi<3PS0T7 zj%N+3!Q9_JwLlMHFK{!7<4P&jS0ZIlruqur>I(# zzVUs73onqf*Wvyb@o6Wx{j^uznSq`)Jbo1JlMIJ0SKi4pOt4H~!OfS39+%)0vT`~d zH{WYqNiI^tqSn&5{A-<5O%p0)LaGo$s;tCF-ORYAS#>>yACK55SSmCS(CF9zYue~Cm^rL`{6Ow^*P?5Si3cmj7Ru_p7| zx%VNJbkgcIW#AeP~(oTA{S~dm)R!GN}>9@?GVqD59xC zKD~j5$P^E5-S6Weq6K9g5f`PxcgO(t&V~qkc*`9+Xlf0v))uF>`pEvW`!_l%F^Q`K zWuI4u5bS^1cqd@1OSncvn~b6|9vP7sOGS|bZU9#+mrGeq`cL2ZBrC*6m&mfJN)X)e z!vc&0G-((d_((tD1EDpYIZjf&190%JVb*38^p)kp*S2+IbQ> z)Rkq49a14z=H5#IwBa1@1g#S-oJOO{ry!%#dR= zg8_aIx_C^?w4x_l^{r5&N@c%)O@C-$Pl`h(1%-o4WPJAoM|NWv+w98@(@hkkrO0|m zp$luRbOfDl`fi18W^lH?O(WUUNDTwIV39B>Eh<`%BTEQ&bJJj<&jNpj^1=PA|5|tt zSvz$K7q_6cb^09e!^2gPCS6}fQvYjxmGH8!b-JY_%ew`L37#Slqxfb7`eyvpitwzs z(jjCwcJ+los6ist|_r3RWp-tjD7^6 zOI$fnfh|)>QeW6yE}uj6r}uBW%;*aojfI)S^}-7Vg4sx5AnVyW#$Plq$gGe$JAGYA zKJ*3kU{QTv2~l60L~y`;X70%4$j_Tb5#%xr^h%eOKHm!TUeGg-6ZmFqCb>f zxe2oy#@2)cSGY$$bNU8~*k(^VVD~aQ$kfo+))a=UM_<4g0AsP^Q$F!iA1v_Vo0eAT z2Z+mQQWrlNC0htaqR$kV5p_aF)z9w^S&5^ysn7g7NNSKY8Zy>$8gJyW&D_e_nBL7f z4B_Fr@Y1#K@I%}&cW&NsKUW?w?53sS-)ind+ zUjjf()$RY$1-NNLX)!A(oiB1Db`gw(7W=M={O&wf=s2~WD3H!JNV2aB`6YPXXq;}^XXJRDmTNU>zU2NM<*OK0f*Ew)38?ld-fYK5%8DVy z*wi%m`PrKbu=X|(fCeOzr|qd%oO3nctNnKl=ls)=PsY)QHp(XJsGLvlnk)6IHCvS9 z)!(R@HlEO)4V;n)Gr_fiNq0Ru5p@l5HEgP5x5KQgQ42%JBZw8!z}Px0hecc@N91&v zlE$@7PtNFZR8?(lV@HP^1fAdQ$sIZ~F2)?(b4na0Y1Fj?H-(432}ViAW>93vpve=! zB?gLSODd-r_+dq#8fIj8l$}b^M6ORBB~?8tbBktHkoC3@bNusQ!W36Zk|WgCq_Jk4 z$Dv51%75fi2T0y_3)HXl_kRf_Q`XjQYXt{fw&6ug<`nh%h{a?1zO&8#W=*Oba&wG^ zBCMzC*dcr3`jSugSz{zyDSI^byRl2qzPy)_yP77Alb@#cM$gjiGwVd{Rh)tQRg+IF zCG!xlU0sRqOd5@vN@o~6Kf{Hcck?!)KHiX?l|@MqgApV3aQAvixYQyu#2a2ZsbC7O zK}W+*F=Ue%sWo-}!iUpBV&cXb6BAw#0tfvj_~ga0RVU`_l9X&zU%I1tjfnsa|LnKr zm4|Z3nX^X1m>a{NaV_fNUi&=ueqfj-a9z!;8rtn+hr@wbvZEaTGqt{*hnH6e2rO!8 z!I53vf;M9$o?ce;acud74|oU}MR=KQiBoi8&VlIP2$^joV7xo>ke^HDxUeNU?bbsb zcXO4Ikv|3QOMIncT`^;cwL6d24>dFCWjmBf4BYkMaUb0}PRqEhHi=MhUKbYbpd+u? znP7pI9c-~X1cR@ieD@Cy&QF&QR&k^R6qyqG>+X3hu!VDM zagvB^=a)&O0Zik=PI+t3(-*e_8{9}iAtBI^6%#H&QOmF`Jy4G{7s0$+ZqaGs5kW>a zHr?dt6V_;ARNSH+b<8*I%DW#x0{k}tv$0NPwhW1UvhZlW^;KY{pXH^prEbx}rx4K< zc2!x(ScEbbKsAKJBwwy*+1S`r)zqjO81#ZMHhC{=Iw=xaCEN$&l)OqhkBK)VlV`tg z{naO=%pk*&KeMZ0mXWcJ&mK8-Vnm(Z&r4!*cF{rp9d?_=@Saac}bjdq+ ztFgGRfh>tihKAR-PVLm8voofA2mp|seGU|V39`|{E63A|;5y8;Ez~-$2`Z+I7{V+< zB7EZR$cnT}kRkM0)DIv_T9bRuy&w?0y^g+s+=Vi{T!$4kez3>+>atFF9YW1Wd*8*O)Op4r`<<=}aUPaNSgqvQ%ZXXRj1;5@8hUwKk@cn@^rV-07 z!0My*cI1MRDrZ`t9klWUwdH@Eg-(qX5ZtxlI}sRO0HeI{DW6mok{d`*ASU^; z^KZ)oNJe@RoC@IndX^XZOOGK=`{f=#6uJs>Qen>puZR;=f*!$jz^*O-(48hcqX9-^v3!maZkZWIEmFve83e!Ecgd<)M0^J1-H z^fH1AeNK!dK#fKX?)II4g%wLw3DPO+dth^h&v0UUX_gB9N%sUN;j$G+^Jo0FoYb`t z_pCq8w}EP`=b@t0nJp}EDYkTt$Fk;L%=KY_Z09y?^g2KY`OV)=i!!;mTg-#n_ZM6{ ztb|7%CB+!SuPfB^)0a51(XxEon}8Y9`<2N-;*ClFf6(EHafX_kFIl(t(}iCn?@3m7 z{U(frP%vOUl%{?SO7a}Uc{YLcp!QZ(g{=v|NcSszLhFI!q-i8DP)C1UQXTFBcc5^|ALo?}drQ?!skK=>M>uI55&O; z|2%Dlc{UDH=O^t1_#v3?#S9nfsZ0K%XF8xiGhMe?8 z7RV(+jp7wbme;SQYTvLTKznUMO6rztI9XX);fYJ#4~QVAdZs9KhM~j5VSg2WnsZ zBMPPE5)RV7%Gs{YHg5$bx>}pwb zt{jWiU!>(cUWNu;vexGkx8~G%ji;lA(i3N*$2gOw<`j~T#Rgy%@DQDyw;}?OXDE2T z8RxMBFvZYhs1jfFQpr4BewZaQq9gM z3WYb`+Ul$CrgT%xbOv{wkap(bR8y%&U0`0-FN@qQdt4%zBM@k!(0Ubd_**i znax{&pJbEdN|#qxDFkT=Cri&g-2CTk?d^* z-b9cm)okbX334hF!xDm>2E|%sEVlrtFvy7zE)~()1a| zS5+}VK^6fh+N=a`V^gEFfBcGnSP;H;rq(2)Hf$ulHB1&{+yB$|q0cYE@Nlru{ z!OGSDZ8ES20=Yocy#8appGNvI|-K{BMU~sc2~jSp(eD zho6n9R7~xSf<7KZMa`Y)TedWA{~O63;dl7I{x<}RuoY9Uysn4}ii!E-{hYnVwqM6L zVNBfwXL|jo51yW{>i_pZ;EAD?RkQ5(K55~`Q+-}@KO)rLpXz3J-B`ao`9GUM#Xod@ zAt8Y!UUG9}N^%tlvDem4jX@-XlW7Rtomb|@2E6Y;Y7N)3Arp%)u`3|1IXUU0L3ZZE zcx-HqTS#Ji0om*JjXxKV5OQ8Q6$mvlwiCsLG>+a?Q_&#pd3XfY*q9VyP^noVjYH2$ z(-95U(ua3dBjJL0*xiWrdD)l<*PK3o78_Yu0gpF@P>eftua$<|WZ{J>3RIh1bdjP- zz^f#xXoyxY6pqZH`iRy6NvN9Fe8FKqoGN%&*M~tmORH7wYHv>hDF)nL#{2Z z1A|THIS-WK6b%KxD+nOBj7T3pQI^>9B)LHuJe1hR7t_)}GK#0y;P0QgBv;oc{i@n{ zTCC#bO4$L3^X~4hipd-TrB)0glFz>cz`M&hsrgBAr`l_8tZM4!Ri2BqSdyzDn|^`I zI3*cgq9y-)nV>&gbt;urTtZTux0hi`Y9M!+wKoT!Dl}@}6Zfofj)HW0SuE()SoJHd zj}wZIwXOB_#WMbHpC0ErT^;iRVq?RD_|q?22FF510)ir)(I zUo+2i6^JoPXZ+uK2ufnaDxdno&(mxy9-_8#B||%3`TPmW}T4VbTw7ns$`bT&e__ z#FpIVoh)=HcpXFx6zj)L!>G>Kkn&PU*vCtaBCCW7{QSj#3sj!8<`U|vyVauBx|J4R zACr5U{TS3c9Sz8)sU}>@M98QIeAo1SeDlZB`Ho?ruPD%?NMUBU+IgxMShR}@1qW@g z!Bb;rd?e73>*Wp(VZV~p_adEsFWl*9i-puH_Mc{5cG+zaE`8+U0(iM?t*Ggsq_)4k zyCTl}i?m`FPrQsr>({ny5pe`6AWsQ)Sgen)s4w=Y7=N`mEmbF90beGr-=8$$m z>c5L?U>C(%ze5H^;JE3R5ng)i3&Mtmil3BraK7XVBlbKPir98?@_$^hiOaJygW zjo=|dbcT^0T(6oMaEDn6x<@Y_GDJFmr<)VQ)y4&Jgx9jN z@n0oNpKsj7P1MzONPhQFZu+zWUA(|UoPTafC`~Xn67zh0zFOw#meEpZZI;92d zoE6)$MG~AF?tMZHm^#30me{J}IqtwQ7nmBGpxYo;IyxaXcZC$q@g$IrpZS9Bj38Go zyfAic5@uD!LL;~j7JdvAK>#id^SCa8LyynTwwVoofs?s=K75zkUWxpkn z$Lk#d94Y6hgL0BpQn#BXhvefY4IWIInlnnG$>O4l+|fO|AZycz1ae0@atlWDByn{qUuMJ0V;6KEc}k@~XnWr(!kcTwc? zKy|i&Q*z14_x{YARp=^S+ylcCr&QYK<74l!!dNjHu;#J?9$$kT1d?Evhb$ z>}L|aK|JtvY7Pl02KavfQ0qN210FZjoLvUEcvHK)jUQ%rjHz0+vx$DcSiutOiz`gk zHlQ!nLuDv)W$i`^ptKT$CG;>gsQE1;?@*p|obU+CnMv`7>@2^Y%Gyah+gX8`dSL1Otq^2!Msq%N6pmBI#Xz8ba2CwkFJ*(d( zb}8pZqH{Xi`KBxbaQ|mAgxdeyNM$#{H;797Fv3R;i*tVUWMp=umU!(+yR&$ZG#k!N zIVSHA%$?cfA6dS`$ddi4cZWVTRoZorW-*lqmN9`ITKRQ32>{Yg&Ii0Iy#{Q#a_s!Owan;Vt2yJ`q-c$AaW}Sc>kJm zL2Dn=8{EDU7k0XgSI)d>9_IDD53ke_nx3s^MwvT|?gvH5kEOLR=eQ4rtH`aENlFg! z#@QAgS$h^v!BzQ}y;4`yXvhnbB(N3jFPYa6HWxAfaJd?YAE+mx{AT|tXkgWp)+6Ay z^|ka=EyJg$SV1-_UdG1*8I8F!wJ5-R-M(K+h zYBKg{V@30pdgsN>HjRAUVs|d2g-(tv9BosF{z7#yZlhYLsp?3dMsQ{exrax-vVG3G zYq%hQFCqEB{5atK80?-!o;%djRsY1VK9Y|Z&~Naz!f%a0d1gLR_Yc{-_f63M_CQ|% z!l$F$V-?W*;U$2<8B+`s93zg}-}Yrj z|Ep&&GU8diw{uMZ1W~o~NInD+u6I2o=V!RN!a}Kt-6FQ752i{VwQ++6N8sMT0mHSd zBn4!<1Ff_>9_&e{6DZ9tFT-{MpMaG(Sd#OUA{^(!&=QUEtTX(^M+pHoc zTorYAizoD!n9j*!b`n+q`|`Zx?RBHC|34Js1wC*q|2VIq^9ho}2P%x9X^ zh+<|mNh}R>EvqkS4j%Qqix0H7f%@8eK!3-V1 z?===Uj0%H(H~qV1j=~K_g}8f8KF8SUn(RFZ7k-tG3y($!E?ocv2lX{Q@ZVvSJ|T!F z+>VC*+Q?p7Cg5aQDmrA=o@Bja=$y8&YS7hIO9HLcZK`=iH~Y7bS!{j&=jYfw@J%r$ zQN_eS?b#1b;8K4yE60p~TvqGqF^K_%8N5tGuqYNaT^nDlxV2wsP3JArgZr%89g`MI zUVga{guDOp^U`R`$&Se{C*fXiy?w1OsZWOogC?A!pkOzRGfH(_?X8Mgk$stWOMd7RNl}@jFKXmy9TU7`D?MiQGYVg?=wp`KoHi6+@C84OHK(AS zDw0At4*R9hpqZVsQ^Mf`qw$vTb;Dsb;y;rz)z-`8S~+w3N@1fB&589s62yR884iZ z+yWwC)t!Kgc+Psae^lp2k}Va0NlQZg4a&)>3d)5thiOuQje~2fxH66JujW!aGIX#^85Vg zaz{Y>SpZZ2q225Dvl0wgJC2YnlC1oZ+L1Wt?}`x#%OuCb*7UVYTD$KB8}?JaFuxZN z^e3Ek_TvhN_tJevxFs1r6oVRz+XRv`D39b;#la~uJac>t>~@Y7KUkqFsOw%n`hrt# znkYd57;A!udbM8r^6iPn{kB{l7m)xoy4pduU-y!O6#UZbKn@JvSDOXmPEaA5 z2v_lE+43~jsuf8D*Qq~Vk zdEm_o~Q(D%_x4A_X>$5eiW2bb%CB7q&zHO1loM|cpkhSfp;kWA&s|58w5W_VC5SFoiP<>0-e$!tD{7B&bJ9u~?tgM!ShL&vS=yU>r#LmVy zc4i5Csz=|ivjP+WDmbNfyvS(tPClQJ#nl81P135_!mp_F5Q9B!D2v;T)K`Wey4G2w zg|(eYo3kn%JbP3dbUUJ=^2<;0th@T73V(P@yuBRv1PnHaP02q$VK)<5RTMT*rPVRS zuj-n6yQaVYf;R_w%j!@R;E=O+#_Wc7gq^#w@WBw?4%~@&P2|ApM^D%rk`-DZ(2tw) z66z3h4x3J!*c)K8XkMp0|6JI9QyzS1m5euFNfc%=F4E|h%0}rvM@w!=Nb#ExWFDIXc)d(S6_cFn`Z{lwB?dYV648xG( zlHz_rNQz4HInIA@$!KZi9ay18+yhhVuw>?SZlyv4)wK1UI^H%kaVoSM zTN=kK=+r|gYeob(n=hKqK_R2;FwfE%+4wuMV^V1ibgxmISkmhI z8>?J3eXFLVsI>-rc^63a72{ayi?fSBB|9$?|5=J2fpN!=Pk!Q!cdc8J%IaTs*enQd zJlumjYC??Ck4l1$rVEN%QVg0E^be42&DVGLf+gy@n|UOH_)hn zEJAH12i0#xVL>>8dd{QWKf3I@@z8!hNlb#uoS@l2S8G$$T%7tE9%(wHlauqi)#v9d zWJ}v>iEl#tHKS9};I|eFiwpd!-&#kE&fS^4xK~Y7Gb-*kaKT5fETf~r-h+E$LbaHF z-ae4_;Tjd2V1{IXW5zv6WL;50M(~XsVC)x>e_bU^Wu&ek9vm`( zrR*8g27m2och9@er-nOF^C*i5%~VBb_+m(-ot0Y8C%$es ze#0PKQwgIR&kqn=qA7Igi^| zS(gs|;J+Rh6sM;4^ThGQX6|hCeIUm$Siwq24X%BFXE)YJsIPpY9tqB;{dI;6w#)_;w zv9hlz?cjn1aIF9{jZF>Hdv^G}NjCdZu$pGT+2!LtJ(zvXGsu_&u4r#7$qTJFw~fsX z3;JU4iF&H?iZXst#HYLI^mmg^7rs7u7YWe2B`@fcY5KODeRF^OY64t>^oZ4L+x;Ue z2`%lb^0`C^KsQ}HiOjU0Uwu6x`uQlmw&$bBm^*S9a+mSn2fSKRU(dfMe*t~gRt z#ofd?nJ545OZ&EY5BHp%lNj2%r-NE;O_>$gJR`?!w_5g$^gNI;*RWMwAhfPmIOf0Y z4(lmQ(2-^3lhP~ge}R$5AZfNU{Il z9S(tL$&}Vn zirSYzxW1et+%8JX$U6f&f#Jrz(<3Rtk58;D&QZQhR`oj;k*7388 zKW3S|l}L9Tw?BC==)*1njfy&xq~pReHl67!1pB5xt{6ZB;}ELXb`o@zYj*P@jGO}y zy!sEN!~%4Dd9rg90dq5Of*3TrHr80bH!sxfle87^5lOZFx;;dghB&06s{`U`IR(3 zfB7dyXCti7Ofu2bN_S@sjc)O9EwF|{HonZ*qcJ8HBBaG2BkzC6rSpSy)CO?c%m{`; zKDEo{;slO={EP>S5tb*%m}+jKr@NL~8}E>zc|_Z@ZRZe z8Y{fmEi#5uAe#)+(^kcw{_E$A??hOfm|&*An}%vHe#;?}C4z|A6{4}nO?Af`swedl zdmB?c4Np--##`OaKyNG60sGI_5HxfQCC1X!7^4qoSxxBp>QC^=Kl~j7?X^_-omgZ6 zwU{G0*um4g-|+dL@39hIWoCSm-hpyMMSy zL(q-OW=0Y~R|}-O+o*7vkpA)ww^vq}nHZ<*L_5_!C$8hHW%4h9UZR-UuY?%cS^S9hn`nww^_sfC{2hC?R<3_VXay3E5n zPZ^urCM#DnbozZh{rDVh)jph78MGq#^74tadcM$Cof&%^7%oU zE4}-BsY*VzOJ_?JH~xH+M+;HrAB{3S)ImdCkZRi@)5c1Q@Y*zYz8Pa-Cyl#qfO8*S z<-(~R>O*d;_;b3*v8<(e9rO~#>=tA99`R^wncbp| z*8a16{P&mXZ3y9WSuu+SN+CB@ z&_EDyRkt&E<~)Nff!B0<2ndp?Jim%^uu{v#*qVRFqp@Wo1rt@h=lRX2=jf=f!0#&i ziMm=Kn+UToHp=zSzU1C=l=){*nD1$!wJ}7b%);at_eba1&WhA^ zo#Mk!-)E@1v78_iH45oHdfT57`0^$Z>;cW^f6U+^@N6NaZCGa zs+W0JGej)jTDk^CxHMdY)$}^vl`)&mJTKidbabu!t?QbB#aB<)zzA1P)xF-w7G*4E z^AToA{DPkfza#^G!7n%fMj=jkW1g|uZE}K_s;;wKK7W$#8W)!5U62kOE+=L^Pb#v` z{LU=l+560|b<$EF!sa*}0qVIpiQR2B6Gdci1N9vz=xDCP@3cH8Ye}}^^wrSX-pShR z7>^dBBvZ?*?__DNK8Eg$uA#(MSy)vvFdZ zYlNT0N$zg47AY`P2c|s3jnKd_r_NvCbZ;Zh?*tf~E*HUyAeWaX*p6p-wi#t7yhS*nQtLEv7*!NQ zDU#ZpXJIWuN)f5(KE=q$2q$}MaDL|poGvFWhXrkOhNWnVmAxHy!rMd=8r2pV>A1^J z{*}=32_oxD%x}agiDnvxKji$#Y5H3HSf9V^4qP5LE}KklWtx>6OJow;Y;5n5%o+I1 z9BNpXAjz0*GH;3pDX9(On~U6iyiP&(a`NP9`a0_H*?y*rKzU|^n%H1@X_b|oG!}0y zog*Lf-suxmc`PpyUk)c8uM4@9C9<%<#?xI=u`SjkS(Fw7%OL{vhOVKcql6<-q8SB8 zYYpxFr|D@7@?EoDG}-Wk8tLh7XKP`Gy9*0s_I3!zaugLEm-*+p9=ci}7g=I_ev937 z32%D`L+37YeyAOnNqkYY=5*t9m{Iq3SXtg+XE922XPfOcK+el!|&WcVXcrPzOlgFnFx8^LUZRJBO@aWc2;7OzrR=5&5+() zVRa|L;_e#j+i`Z&8r6rarclx`wpW&!+DM=aW?BZ%bN0+IJx#tBa*cKeE|(LJLngek z&5iL0YtvIKY@DE}+C#ufS>jADQY>m9$XFd7+-?_cm*d?CR=fgga+|H?MW#1Wi1sSl zht6~M)F7R;o)?lI4hL?J2diEny1K$zY=vZWp2f`^?I91|Lvlu8ca7zxRhFZ9?7>F* zE?nizPzMb``}5$l&F;kMFe7UPcDHtTun}Qle3I46eYmYAED{)of>J7>lyoGs8Jp9K z$L->;5ggD9dql%wB6$a$=gx8N%m59Z5{tVJF^K}jBmd%03qviE-(6*LeuM43BHoq( z`p;eF{gYj|O~Q*ntkaFh>!h^1L3m@Ejj27Nk!`kO1$wGnFKJ631ih4JZ*z(1l`yfa zPQ}0pPF=Xb>D~sM-{Coj(?!5 zgtv$!6`K9WuNqk|WZ2tWU}1fijAo*y{{rXFjWF0%@q_)ujol)^)+{rT3F4_RTj5<| zDUB+Ncqn^L%_WH}PBOQdK$V?z_MhRx$S_^C?(gxX!(m6(3uMA!Hg3bV;z~y#h z6BV*+vpiW%P)LT^jU~zC4MNtVJnbI`YI2Lsm1SnOQpnDlecm0QquTvF-t~Arn6(_+ ztE;TV*U0QHvbdF}yV8s6kiKL-vcl5RDl4%fj*4dbFI?gDP&@U0`*R!PTi&IRCKitJ za68QW_#~@W`f-?KERum?DCGgiB?HlF!S4F&dH1E~k&ClE_k=%w@q~@6osN-i-02AO z$t0zJ@vr~wp(_RQyDLo0ZxK!u@wE*xaPATp20L*6fOp*MJ$aJk&rUL)sqz}=&33i+anZh+bD!09f3>&LYS;ujnZza#^G z0;u^ITkBiwDK>)DbyRuE>0iUpF?5Ca)+*b(dn9ujlGRP9x`wKd7pM8%atPmLlu}W4 z)>l~DQ!xcAXzS^uK49aAK9L|=@K)8+*4awcy#+S18!WBv5bbTD+HtswSVPy*bPZiM zkYp1!hXb>G(Do~0GF!0OtotpNDypVq7{{+Ozz_tGT-3GqGNJ{L{S6Ebw-a=lUuu06 zBpd!Mf+&==7B$V_7%s(IgMp0IRY}L-Fj6o{)!=D*nyYZUWUxvg zxoB*zCg7Pv+=!CT=g4F=^uy+@1PP0)imstkxSBOW-KXfN58`-9zgWg(b<^BZjmJ5I z5X(}?=gHRjJL1G`}}YW2Fnr4;_5LgvIWqrKJ+bomJAs0_kj# zLQx0fElx|+vV>Qrd3b+}`8}1Y{`WXN)Ja{yaqJxLw+j(NbW+pW#Tmtm;i{$gY!^X? z`Q;86(Td0Gr?$?Id3+b8R3LpMo-;t#(DX9ro2*vsE++@q_lVeRHk{6~WQJkr`~39t zT?+vT*&3jI=pS^WK^eQW3VYWBc*p3fS@3A6%=X*7qWX_#!BfOL3 zFW1K@7FDi)IYlVw;{EfT|MCa)qr!s2SHtk-_sHlLnuZ2wt@UAjsT^6tV)Ia46U6N> zBkZKeWQyeThutU)^64b8NR*^vfE1#mw}tAE`=z-}f^5SXYN78$6JyJJEbeWvv>qka z-9*4DQJxu4+?TyDW3gJ0-mxUife;-8>e@JSNkX@WIB~Lz8oz_@Z>0i=W}IF>Rn>m1 z=2eo}40}nX+$q6f0tY(DNQ7uKK~6VQ>8quuuMxk?@=_JLWc5yHhy860kuJxept+Mp4QlTIrTYa<+ z450^_@wN;z)Z2*X0G<;h2cfDE6(JWAQA));nXHC!$R$;a1@^)b;;AepT+}r;)7n~v z%E*oydiy(=THIo8beG8HGMmv;)Ol=}O#4Bpl8UZ_*fw{L z*7^?EPh_k%FD-4=IIXk9lLd0wJh{AH_C4PCI1P%~ERoesQbhx^CrE2&GgX0?ht`TF zJAvv(`UaZ$;^8u}*fMKd5hAHJ0zng?qN)n{q6P?9EEeRWR^JF9JA*V2UgqCbo5hgd8@&M;FGsHOWvBR;3)2UX|-vdu?*Ya3mi<4kR> zkPa_1vyr3OZN*~SpU0t;WrAdxSlQk5ka{D~| z4v?`RAz6L24Gkk!B=NPMVz9db*MYq2Bvct96mTHV?@=t2{oljBs%kM$JRBjO$)n(= zxwGY9`%;uKIcn+c>tK3uoB2n(gf~{%jGd&`V?~w?45Lu)$kGMO7BgnEd<6OBZ=s>- zCGvR{<2ipHN4d3M@YmvJ94$F!Fv=~+*+h)+#v-$`E9{x->9vIjxlQ}+{Y7%|6=tXB z2q%jux`AOxL=$;bqn+j&FP5KyZ*u%$kWcOr+uk9q$^=~@>gxPh4;;QIAlu#eDr;$Q zo7swF+1=SCnarWr+7IPIiB<=8rw5N!B&L)|CsO1~D#lA;9v!7vAe+mV2eO&`1iV(v z=Hpk}BnT3+r-2h^UDS5w!DPo@Wyg9zLQ4Q7NkWz+1VKO$#r=xzBWyK-glMaxd$^h& zlLNoY1nA_C=xmrA9$ZcvHd&yM&63GvC~1M0hI|@^Mkbvhn=fJrCag9Oey<7n=UH?M zfFN7&*7b1SS;vWV5nG^&fY}HW-K1(v5prrdSiTuF8*U0Dcq|*g-LB?Wr;&oXL-D&kM zLXd4ZDmuAvwUWL}3A4+OFZ7Ce6@q{$$%s< zBSFSnRYlO}!eVTbNW_W8@@S1-e%Lc^Hp~3m-=1V=H_83cB@)RT|LwDS8=w0%JXcdgFyO()I>|(wo!u--qX$d|hE||h($I9Un9Z2Y zrt*7c=xAEGa#fVe-`1{U&0pF`;5(!AMw14m7kvaaygkW(J zXd2|ArgO>$CK$OHI@ui{^NhY$Wx`@T%A?SBvvmC@{0v5ZI zP+bi{vx!7LMPw&Ve6N5JG$EjsWrB(tAeNJ-`wq}^zBKmN;FS+vz~ZW)xxa$u{x@B^ zO0k${FP=d+K(e@TIc->vsf{VSs%SZJ0e9^HnrOij3gWaJye|o&geZyS^+ZON4$Hd+ zV318^$!1F!f*GqVKqzR%d_W7fAj&v=ek!UeaLUU>^Kn+z5)|6qU=zQ?y9SaZW3l{z zceV0B>%;Kw3#erGHkf(#m`BswD85$CT|7r`OOd&SWBNfJ08zGL4|Q<VsrMMcxW zZn2bu_yR9@R|ipgJ?~-|7@E32^93ws3#MuxCl0%p{K!(M~%Ma`+o}% zL_~{=K&6X7w?&=CPYC;EoMo@wip{F?g~#J3;5kCFM3At$Le#oKZ#Ym#Rf|NoV`TCr1hX5D*N5LN9b3om zZ9tICIDC~jd~f);&{0Y`cDAAv6a(4np(5bIb=ZL>Z-kDarrDaC;OUcD!kUx16BoI9 zx}KoR{8v<EEBDuGaroRMYi- zpeT9vVo7pE6~XMMBH+gBIy^t=hOysWV}K+hiLaJF6GXAR7G@dIP>DzP$YyisxDa&( zy;Pv2>Ii~>N!Cg2ZjcLSNu<(bb0st+tTsCimm8lyNGRyRYI++Y3V%C@CI_yd16S}( zM{4AAY4&0%O1g+-t)Q;Liqm>{L(DJ?baW8Q+TfD-3SUJK5X}~>4hJ?#Kr568Z$~MW z8ZZnIT~jD3B}$r6PM8{bcGnk)?WIVkv*l`JNych-;BtHM2ZQ*%&X+sm0Kw|Pa|~rf z{%VLaCcBqPyO%d^IVhy|5+ss2bjgO(?Iq+jAKErD3Cf4uXIz z>7--ZET;1$Q)#mK5}F}mwmEP*UHAe){605!i|Gx6W`A(Knp*A_-wU%a02*YD001BW zNklGjW@A`1sf1u!CXsBv|yi%44GMNO5nHa0{+a!`{GPwdJO~7Qa z;BdI`_<{udUR)0I&%87I=YwC80Y4ISrAQ&QN2KVarn?63`XX`dJ0FQ&B$wW0aXEpl zahTTDM(P4)jF3n!^@P>ED4V+l>YR?B?k4`#phTgNBaF6HGJ98{P{+i$C5}X<8rY_{dBq(I#+pNxxGx}tKi0Y<&@FeeDI!(P(KHPBJpE(Sz zNGZF))3If?qj_wBHX56osP)OnZ~6J?YMxAdozW*N#FGUap>7%)8maLdrE=xx3th>u zx3k2Yfpw3~!eC($5{gg0J zb5S-|mzY|JVwhZnYFlWnavkA0Nyz2^?SsRdiNs0Vo+dK$75~rwn`dOOgT`tfc9Tvi z9cOKRj7N`VSV~!F?d|96xnY`vu9u`!{&m72pW0$^agB|g3>IG_b@h$Z2P|*?ulo=s z35&&yBnlW>j!d>duAuXhj^I8tRYBD>G{c}&ERf6P&|cFsZnsP>Ur>x{jvh$?eW_=ZjHR7M57rjFHMK zWk=ZNBv92rXWuX*=T6eqRE5uBe(QVNj|xLaD%e`;LC$5V zkaER0S_Y+%CY{yL9K4+KG7Jn|Lse8%qg;WWP9{+_4Fdy1QBV{G#Q?3CBC_;|zbvlv zXmXiwEK5$&Fc7dfy;L{0(?4{IGpG7#srBQq$j5I$>`wxNQf8Zlg%wsdl9=6<)HXCx zAF>^4UI6U#oXw0Zix^s#T&_T_pusD2{tZnn^Be}HQju&ni>m3M3+VYgimsz-DoT2r z*+(~+jw~{_w8>5)hh~5%n{oLoX>9N1)R|KZooJ&b;KFj)g!zjLp_p7{c5aPutbje( zMq^_WRYypK97pJCj=kM=?mk>0l~ZxmH_=pILxoE^q&-)zShhPXh(a1w$&t;KP*npC z3O?%wx~ft#%F=}SY?ge!fNp@Gsc5Bg!VW_x8=2?+jc4qwFS4)^C7oB$5RlC_yp?tI z4xZ-J$$om<>j^k5`%FGrllQLB;CwTvZ3v@SE zVt_f_upwOYUB-TXf9s%Uoe0ksAOhNht@ zDjGVfs=VM`Lw?S?s$rlNlY|!^@~7Dq9#5?hj%Ug5^RCtDqqe1+zQG~Rp6;Wm+K0m| zzm(+Bl^oHPDIVQ>#9SOII)?e}Cnud-sZlD+PD7uEKDU?!MOh3HN)2(?HR=0^H z^XLYMCJUZmHI41PoH=`%f$p+&*tf}bL)Xwt3Pr7)R4Ao3nYf=|Y-gV7r7(NhB8p}p z$R=FAD%wvBaq`pm)KSJ`Y1J zQp~1^3QgBU1mMdTm2LY?6md?{3@Tn$o^UhP|7Vh%L#Zk<1 zc?hbZYbYfJLvm8lGQi1^_xW(R5|2$L{#I`Kr+|Tyi?cd0%Kg!C=3)k+&UOZed#QF= z-^$RUqe76(cxrn&cS%POM80{n$n5T z(jKR4MbgnV79L#V)?}DH-9>xf00Spl@R`N8>ZI#xk;L{g6ZdX&Ybs1e^fNF#L|=Ck zZb>*o_0i7}23jdgY;BrHH*a!pDUIl9q<5&Fw%Q=Jw_=7z|Q7y;0t)MNsuXRv%DB4-c(JX(*A>QOG7PY*jd?NH=U!X>&T@Nic+@K z1WiLN7AWZkxm28`M>mN&>{!e)u3#k|q3m=Q@;Nf$MegrzF*7yC$G`bC=LTD-_5bjE z?+Of*Vv3!GF&^F>WhPv}S<%kO)e-95HmrwU3jtTahu7=EEX2vAwpf_orNvo|-DUaS zery;D*?5%g)h!Z*5{hO;V{3t zu<3gckWFU10Us`#1=&au-rQniGext@&-a^P4bV$OSJnvc#K~yoAhJ>_p&AATpce8J zRSiWcvNJzMHtfW1F=KN0sB`rKDx=;@)GOYA9Crvlk_(FIBe6ct`#Y! zBTRh#Iiph>?BS+sc#!@RE%>ajDe5}r(A7M9n+uHHzsuLNQ50(hgF}OKwbtMg4{L7; zSZsDe)gkPrUDCNIYb#;)x*Ko@tlzKVH8cw81UoD1>=YDAhJjitp{NQPASo(JNui)? z7`n>xliTb%Y}m{uT!BhFBIQc+T#jsHnFn7+SYKHqeB~;a&va7Zwj5kFtQXN!(|qw? zKI8tx1}RNLS2a`}%nl#T11A}I|9wt&))8`B-eH@@K*=ZAo`1@NJEP1;RovC>j9fZR zo!fQC?FE~#4B^mG|K@eqRs}rvk z)MEDKthlD3DG-Ec&2;?agOB{BT*Sm^%Hp{i~N%ExcMb(Ub4coFF`Rj}hQ52D75kWBat7FPTXb*o*qujb_@IrRL5Xvo_yl8tj z3>{4=Q7Gog7gaQy{3Fi8GSHNAh2uf@CLkcmW+X{`qa$YMDoP>6#?(D--@4C}`8cME z7Wz(}W~i(B721kF0*vxzr|Sj=<>&vc*18}HV7%z4)pZS}RHRTSP$;Q5&C;u@U5+UX zT|-qBG~GDxJrYG3Nj_Xfzpj=O0W(kT^5-v}u%0pqbq;Xm^Z;FT9!zhoB+Ecoi==i} znS6AYFYipUU683cF~Z2{UOH-B?_^L$|4#MrL69U9l607NOh+r_iLOoa_}*>4xVu1F za?w37!s&r_s(seC;t(6UN#|;Qsb20@vaO5O)0&W!)4iW2%g)o zel4WgntRCCU)|-wR0Jv1#EH`*40Y9&ou{K-o&K$K!?#+bWsPq^C=XKKw;akX+NC0e ze1Vdpq8Y|dl3@Lpz%a^A$hQHdA3_jBB-vcn*nRykp=%0-RD`w3+uZo-33J;8d@Tc< zIeU_xMnBdgI4iQnfv={H`k;rk$R_Kv6HGQ#(HtD0!ezlMi{;kpQh{uIm1j?8S=rh{ z6%0h9T$O$p`=Gm{nqPe~z<>Scha^*Zu75d2(C^^##hyc7>)V2^my;N}@$w8#VPE%H zmgPh6lYyq>NkvwfxOaoE?#&WaY}EIj;{DSd)cI{kXe}48xP63bYpC-~6V0Vrc=m+Z zMn7I_<9@|{xnjALPZHal<4N8tGdWX(%ai|WLRXT#yn}DODhMJlRLbf#`dtoLx-!R!Sij8%5%kZl(os*T)RHX z^kxoceGjM3o}srnh~0E}+gi5R$~+hHvape4Yhi|ov1S?r1JrnI`|=<jzqTNnYy^X6sd2nqdHmA7t3}e$byg$>fsBM^$GXr$jyMNSxl&-00 zYI)y1*tRZzqle?m0*UYx5viPJdYkPkW|WCW9V9WO)1+Uf*@gWIq`@lEKWD|?LG8# zx6@J=#Ay}La!JB#3rszG#+|E3un?>WaJsV^?|~9z28N-bDGJ46k)o=jl?O^- z7A0g+d|?9}Zff$|fnhxF@H?1yMMOzHJn!aHY%M(F?$@`uGro=PZs5f5SuXTfBF0sSL)Lp*#@(FX{0^X*6PM0S}9tDb{Do_GMGBpGub%lPrR+p(;6Yi47i)PP4QgM->bNUB}RL zzEw`tRRh^p=3UifCsf-?&xsz|8*2!8ETHCzZLKgnInLAZB{nx^xqH)u-Q~vX9i-YJ z?~kSsFxhRmJWdRYlZu8mdU|{4XsX8RkU`0j*jZ=h*%O{jt+Km5&+RW|oK6?6^F7qK z58rwF3x0h3k_ny1vg??~aXoWMm6P?k_Bo%IC?IN(?nO{^-d7 z_;xH0fKZOaA4cv+5D*N?I>JZT>kLC9ySv1*Z$9JCw`Ymu%mh2$hhvg_)hrb#Ips}~LL^z%%ufBYQAeso&mD|GX2MmpS z{!6+_F|*6s_-+2%XSaB^u#4(xX87XAT)l9DhJfQIYq{680+EHse0BY6zJ9!l=BS|i zLO-VmJE;pgkxrFwF#2eg&9OUt9*dF6|C--i?!aq#lf!bHpi|5y*xlM7oGKl7 zgw?XS5%Lq}7x z?5<33>-r78zCX)m)=b06kNEVXbDU@n9myzt9dxZgczJ=Dxiw;jhvB9+dfGzoxD<_n zp(`Y|m)MDC$SMaMB1rga+o=gSu)U7w42@DQ&c^s{{_@3b?v8Juy6PEz{}VpBG)Qx$ z>(yGTuedf{%d@xkly9zm#m$GyBs43nXD@MPpq0i-FE*1wDHCU7eu9UOr&w5c%C%IA zO!iYgdcT)C-@8=3Y@n8ML{}Hs$tWn=%SV`OZi02KRJx?sJj?Q$X5$;oKKPP9{P`Yp z+c_K!{apU|11_Czqrzo5QUXgfJMdJsbE?0Q<()W-TT?vvQbjMMIWycrt>1=FN)g*! zsNsdS!y{QYC9s(f^H{FnoUbqc8% zJDVHC^ZSnGcOVE7Hg5%0)z$dyuM374=vsl;+5}H;-{kk#pAsopsUJAYhaX;`za@m@ zh=l->%}-5JJEu=fF}0HCHj)ht`nce(ZDZElP%kdZ6s zJ9&|hE)UZZvLD$FGkKb5@9dzjb&2a!F%}+P=QBOU-q}HVTdQ$M3hC(nFv%ygEJYMV zSwzyr@|*$60T`3bPh5fHJ3Y}G_^=)R|hS1x3K@|1~+FT zEKH2@tfQ6s3LiGlyV5WYZwGuyuu9A&!viRg1e*f7w zOs^%d)(>$0>IYms*GZ+@e58UELAK$pY-6ymg}IFg^O1QT+<;Oh!Fy+WsqtBn)C{{D z3yhCGWORCqy}W_VB2)Noa$1m(9Ch@a8NuILz~rr>xuuQfx)5Hs9ji$KL!;E*MrV5q zb-vH}?B+8TH)j}s8l<(Shl(B#X6aS$vw@+PNN&$FcJFKcbp0W-+gU2QFL3#TOPuR# zz-#?6Q{g)K)Gm?jFtMD<%k>=sc7F}kl_C7j*W1>bnj^6_&x5b7bN%)t>q&u%6Cd!~ z-&|s#wG!7+`O@Mc*x1it*92P+R@j*z9f)Q`dn2c=d`flC9=TGUbRx>;+8S#cQRbiAW@BlA@TdR4T8QCBl-6MM-?^^MM>ZlHRUhDs2=xAz&&8a(F`{EY2pRSNKS8?j>MLxbf zOrzg+bl&wg)7jO|iRop&oQW~_@EU(2&EA=TvXqjjkO(g`J2A%S<5||C3MP|?s0%N6 z7ZH;^Ky%L!7p?UeRxcF|?euok;&(f+?024ON|CPaP8uq%apT$@ZY^vvH~xsH9qrWk zT~xWvpce_xJ?7#4$4u>tw451Y0sArXkIVD_qH7C;Gv&^cAHrmJ6R2sS+Wk7- zePLftKe)*s|9qF}%{1<&AufJ!l}o2v3A&D^oiCakc&geMJkiMf<}Sd#(FAVF%bP191r}G3^*= z9qn6h%TQ5O4FmDT6!2g0H-#XG`w~UMzJ8&$KcMc_&~>A{P67y`v|p`xIOw@eR%ae? z{j0|;r|mQhyvN^tFhYNOEncT(e<);;d`k-rH6dI#uJP5gc^-fDdukdg8Sot7J-l@o zK#`?~*SP+0iH+3D*#Oz%(M-Gdj`S25BcqHKHy|`9U+(b?HK`Dj>ys&cdy^z%LlVW3RbH7F7caRf52czH9p6? zXmA*S%Ff&p(}0}RwcoYl#Pe0BXM_r}&p;-%~TkN7vA zo};J1kMk``#i+S0mKRr9*+^ll7^Jbajhc75Z5ztfg;|zIzu?QqE3715<~h-1XZTnD znU7C5Qu`{NGgNZ%b*3JC!xuO1GPbabRN2kQ#jAXJWthg0^XNLrxCRAO4x4$0G;dMWLVrUf7 z5hlL;C%&9ZkSzSrTNCiqc5va>wY=Y9!z8`pyU9HKWV?vOzd8+BVc!k|WhTJzZY_CmoE49P)Lk|wCjG!qLav7rW5_NsOv;}uq zpIIO*l`H5EyZlb4l@G7<5{qTHH@ZkHp5g!aKX35A{x83#vchw;>;9{u5?i0;n?L@M z$6JN6PV{#m$rfr)yvNm#K4Gv?dQT3Mj&Cu$c!zj$m*wS6 z_6A$1@*Gx{;ira9F%xC#`tP{0m_DEwK)_Yi!kJ(F4}8?)!1YR=Q%Hs9dHD5L-1z1R zlgoSfJI`|E;}5uax`P_8g(C}D3KCXN6+P$Q=W;AT@%9ue>$BWVMOb?FHFm3npsN(J z8RCf&wF3jR=XcngnqfnfkmUU?LDBU8v-e(KZlr0N-!BXT-X@UV8>Tn(-kY*r-7`J2 zE6u29&T1uH$gGa`O8<#;j&yYP%)VBJe%m`@QCQP<-|5Jz7p@)<9IO*zI<#%F{BiA{K|2qAHoa zN5jm`tq=^)5L{khY8Gs9fFc!_IwN0?kmQnK?b@1H%)fzDd| zf7C=&KAsED4RQTqH}_{Z$v&qUD^j`pea@Xa^3q~}k&CfB*3Y%`7rE9q#d_9G)t;k# z{NV|@>WXl@Nr6LDaQLg)bL=RgXol+#=b0V4Lt<@$yKXyXlZc*86W>grTileicVeCB zr8l{W_zk}FQc~B+sp2LyBcC{R+AR60xF`3LuzL!rw3^s|c#65@7!T$*85^ErxvQ3j z5*wyxlNy4IXbw=<=AyDuL(_9))fDlKRi=j@aP8uC?o17HO0EV7?aUX#@K{`diL4+i|?8 z7@(_cER1mPYB!f|^fNpgp|Jfpr%oT^*xnr!zfpWCVRe_#a_|Tz!keUSjIcB}!j0%E zWA{AR%o1o>Qpq?Q8!Ba8ozy2+Sr{H=d5d=?K|l~qjN9SG001BWNklop{X} zvB)Orj0?jiW2jML@f3#W!0mGU$P+C;4j3qyWHV+(1YIYmX2|IIZn*9D>HLUTB9%io z1Z0yLv+3I&_6=golS~XfVt6@?y`qKAeS2wds>J_PVpB3%aCl3oZQIG_`XW=)D-5iS z((_=Pk`C`%``cd*o#@&!vs1H7hM!mbGg;kKZ>GuQwlAC*T8j0BVeWQ!bM@8$!;1+@ z+KzDS*bxrzZlug_f2ADL_Y0li+KojS^{#u8js`SlN=FS=K1jmd!?u3Wgv?T0hOWIt^Ok8$ki ze)cq%VKYl_?OuO;=%k`yR_5jyn~HAp{}PtQ2ubzDV?deB1qSY3r~ArndPi3g{k7~r zc#Jd0_R?69*YSUQ-;Y6bew3-1C03Irs>&;0%O4+6AWD=zP8NV^c-Vr&lhH7 zvz^k7)C+kIU1f7+lsnzsT)o-P;9QJ?hP|9PeVT*28mKCCz7fx9*$nHm;|vZ>Ft=_{ zzNd*pCl1n5Q-JtXibOKmaQUq?@7_%!8f0MbD(ef=3=GfGRU5!%`To0?-wyI}G8;=v zOi!#5N3M5W$9{L`QFgCTy(o_gdkg>bH6qZ$S?8q)!8muhdy2iqwfyr#fY%#x9 z_g{g}!LNU{hqd)6W8I=qXPnnGOGH!V~OC^jFZP5b%P z-E*%T6tjyVCRdgb6fUGPN1Sx_ zMR8b$=;|c>x2|!iyNBWVIJVM8PMkc$@%?Sol(?|SZ<<^auz1U9-hT$Oqk!_e4;Y?Y zWHGqN^1Oy(wc{%+p?=psIy!4{r02LYF@z+7-Q~HU4a(QNWj0sEzArFWCN#Y>d$SFx}@b za`XN;GaEXU2j1h<@x$zEucpXjeM5;j0m)>;UE0Lq4@6wW72N9^U~GDog~<@QXu{@l zQ&e8VfdlRA?kZsM&JC6y8kp<~7F%9QNDxF&TzCsy-{O8&JY{uMR}|tKUSKvBBODA8 z*Bh}J&-+g0k|E|t`nYoO3U>zP+0dLcojAk$XOGcdTS$RZc@4>xw*{SaJi_Y2JmX^_ z)aM?Y2&G|S=@&P0X~|Va?%&|*mD}8YG>>X4rt|o5P8`|G&cE?lPfup&A1B!RMmCS*3m#!KAA)XRwpuZp^Zp-#q+oF6m50YejuEUqlDJf~r@+6k0YQn$OAuC5y7 z@HpLL5|Su=&AUQArg3_#IA3``2{fH!bY#uf_9vKRVr!y_ZF@4YZQGgHw$VvCwkGDp zb_WyNw(Ym?_gVk?)VF==Q27rh}d_!p&X7j$D%^d60947vljI4avlB_^G_SZKpd{;-i%m&8~FTL1$-usA) zXpNR-zJJEQN*=BxI^17y_2kSjJvaEfk}>hSM%Ckdi})j%B&amfb2UY9#|f3KP%Fu=w=d@=-szs)SQ-g9IB{>5)d<>@+i&7Txi6oFF$BBhvf z=$A7+gY-yw=-CiG9X=0cYP@mxJt5g_E+w>ZuW{W@Z6@j+{jw^+)Xm#h{Y$?h$Q(no z0MA9_XFX3{`h-tAiCOH#Up4jAMadI$_;m`^WY4h>fYphUFzhg1l=7BFX*%l~t$r41p&_#C7lj0T zt{DPVYRS*^LO**x=$$H=7|`O#N2KH-2M3ced7Cb|u|&ta(BTo@pUzpMLEIJ2(F1H8 zmSN8lGl`Tth^kYbd(gjJZDss#t-g8CWh^Vz%L!~UD`Hg0BCQp^-f)0xZGM>1mH0kF z#1RPeY#gvwmNc^itIU*=NQQ{k4pve!*YI>n?dZ%Ndrb&<8pHp+7!w>2zp7J$69Kzh zJQ#zglT=VY^ID35#)}R97W%hr7+_G|0+`%=ygfZmDJ@0z8ke&*)y1e?!C%8s@M4Yo zGinfor@laHTIDA#Jw|i8n&8L(ot-I!TBq!Yf80s~itzdn<<2C}OipsgKFhHW`3|>)D zRX$P0oFV&1BRYA;zdV!I#3y8_wDYg*M1sA;9A$R!Mv$BacyfcIK>2eOX2iLH@6kz6 zYb`!0tM3gVNL+;BkB)Z(j&7IKLpG`1yE$Z}BX00EeB4J@%IXclU=S|pHG76(-^tYu z6HRG;K5{tkKvXqA6{(UFA32;X_lGwUCRW??n9wSi=YH9yg(RMyqqj@^k(>E;P=mZ% z>%S?Wft~}x!@04SCLhFr;o0{A5hkUPQnTwR?rgT;NTGZbGyDaW)Aue zNfeJzagSt-q9okZa@CG0YaFDjzRs$@=goDGZbny(l%4f9CGC9X>BqX9mCOO$_5ByR z{ByDdjwyD={ghIp?UJn?SZq1W_&_AsH~mhi3cC>`T4>mZ_ov7#7xuRiUaa$2W%aP+ zpYN0nP|e*T04_U!&(E7ma=`O@WGM|FoXFc5cdj zqvk|G3Rk#N%9iGDK$`TF{=>i~B*bBZYpP-dEQM)t-T%&Y5s$&S#(uF10eDv3thgtba8y-EODgRg}YNT{D-9mEpufiRIa?&x?+m zp@eH7NA2Sto=;Vo#S<&>e~Wl_Xq6# zgUum@`%K-y(+i7~C);sj28G4mJ8KNpr22@${BNBfinY&CWmfhDL*C(2+8JA;wE3~P zTK&N{0%MdTl=xT-?c5YzR;!eZ?91!PTq)aicEjy73pnD(ovy)j>yLPPi!{r1(IUeN z4wedRY7ndLzvs{}bwkw}dHJ7+Ztc0nmA@tphSk)@M3qa^zVi&(BLhY)BLFFo-6&#y zzHz9g`0ANZ@#`U|vmi6pA~q>j8-%+D1=h}bI6p2r6_nPDEFbwHmQ;NcW7EKiN^yH% zphWXzA;W8}cJ`bbQC`=;#AC%1t+6B4jK>psce$FBS#vzosm#RWSP~x0@*Xb&21@I- z8dvj+dBit+ZIrX!B@o8hhEmAz!}_iaXfLm}DLWV$Wq%&2kr6s_K*cgBX#Kd~Kv!JO z4oT24D=(2Gak@^kk~=$Y@la1mRF$A5OT98GB5?vRQ8d!gbGtW)nt%z5+>RAZnqNU% zoYCVT!di+svUOR-#V0<{uR^aMGaFE$9vl9#(L?Q^b)o)2II}l}aQa!`swn z`pNKdb&TazN|qM=o!jXSx-|YgpVH9Z`|+js#}`WJ3>4*=H?QciDb^ycR1c4H{@mMDNi*NJrgHko{!W zPj7TNdtds#xp%kqSfs)(q57)2pKp(QmoCpM1}#45X|DWSbSB53QBJ3qv>(StaJ!Z1 za+nU0VliouOc*bq#3*w9-e%;3(j9pTMXIjBl709Q^>495c`_uO_~{kqmDzD>%gft+rPr=#j>GkQ((#@4gNC9M@hY1-U9|2*)EHAI%MMp z$jgsqS_yLAe3%@O$WZdB5lZ|y;l9yc#M2J5bO7XBjOn&LM3hBHx(=hs=kWFBEPR*F zVwz?2KUatZ9TeA_38k!h>f!UI$4dPdd6~L^rQ|nG#OC|y#|c%UAy>*>Gq+)d+8c^; z2}KN>e~A&u>EnK_Y`!9$*LW6Ji)-Q@=f4_rrC!PcoYkiMwwS3D2=glzKHbcCpz*@H z0oeW&3`|?COMBn9uPCRpL<48#0yiU%(+BQ%OOiAMW~pH6e(Cq^W!jAWR0vNy>jphD zwY9Qgio(x1UG34t5pKvir@zA95{|Kj$8@&^@6Hp}45zk9Q?`vuPR@7auIQp`h>^i6 z_osp*Lxw)3V0S>>G$0p*`% zT;`FG^j3G&udlyP0AfP4a&j%m7z$b-RW)#S>us4BXeHsJ)`K^Te}t>ngUHKd!zz0p z1;3JK>djs7N}X3H)wpISjwwK|op%is+XTx>P*}GkJD;36KKxb3@F=qwIQ{htym(p* z{G8|1$;&@fT$G5Y3|&%mC9ep+fd@a}Oa_Wgx7hFCa|}F%ho8b@00f3Q0x8sqKS$9R zYnoYGLluG#Cy4GE7A?^sgL)$pO@x>)S(>&rkBi+zN(@zEe;e(aB?Bj}e}H?yQI2%WNkwt%mtRT1byZGT zexc3e)dd@!(&Bvw&bZ9R@K1?FB*gU*96Zrui^yAd0wEkIzyAb#;5C=E{cHUDsXQ&{ ztVeHISmIyb+6^y$Bmt$u*OZib)f6mae;lV0e{|G3?+)lF1V>2{U{@anYf(x>hWf*8U3qFe|ZHL z^${a^WlZ%k3urK2Kc^U>H=%1k67HX+_cv<5>Rb0bi~I!Kgd>ZnD9y85%lkX3>1rsc zrNor)%hkwIl3x$IeDj6E{cdfXU7X05^?3#_uxmtLEJwiYn9(rou6$D0AutImLPcm` zaxzUQ_$k8WJIi8g27U#d<7OpzX*mGe7SX7Sm*CF}cnUp3+qa zHnbE1*YC8=12?~G1J{PwZ!0owOL`U+MU4`PqwjXHtX}?2&Dzq(PCM_TcfZ!>BB=xb zJ0*CW55DQS4%XO3wGl!?gEhD4gA9JkQe`kq1j1}!wI!ai6_N-lD#f#eGV~MUl(0-4 z_e%dfg2vH>-p|Jcr>g-gd7@Q05s(foG%idVkRn?eAZ^xj)??ma-Nvski1l8-qTtV7Ke!|Ao&uF#{@9Y}J zO*2E1*cy8rs>$q~qa1N*fdh^1;pVpZoX>13m7*CdObH0Liu&06Msdal(AyJ1z9vki zSaK@nmg62i-Ao;G@1SQ8m;ic`U)h!g8Sc5tVX`-4YD@zBg{O*S>jukNVdf2rc83U) z=4TiAya&%oFA>Etv2E+G&rdiON0kf%?@ixX?+C0Z!8$S0is&>#PmEm)|I@H)bR7c| zd#6N8^?@^nlIodAvBaBC9Bnf*vlIvA0VPFAGc~wsJ3hxAMT~($BXuq|TmWHof217C z`#>ft(iEUlo_}jJl+I-{lVZ2hbn|*Pi?=JhbO&2Jb*^V<_LGrRJ%8s*FH z>(@=a{b?t713erG`P{v^d`@`6QT$_&kUudYLn%O-9JJ>`9t{<4$G6NIYsx;}_r#y? zg1xRSZB-W!84oulWf%61kqKjMJny^wiFWxlU)AbZ(J>Eeq${T}jVjW(JqmIrRw(_c z%_ipv8SRbIpMZqoRJ?`Ho+-A0g_7fTw{)3B z7%k9>)lvf(Tg4-z^Y`<0TTf(Q=gLrpJjcdzQH`{sVtkSwW7gF6!uW(PI}Hm?L?tpz zT~iCLJ`vsVCHhY#ZSQlCIh_Co84*GQ_C$c~;Es!N^AfXEG5cTFyr)8@bLz!= zO*s1k9RW-rrplh9Ay}1ov)WW5@QE7*TNBKGSsnA}xc`f5(d%&9_wRpiY?6fgwBm`U zOlScAWr<2z>5j}Pf~UKc6R>#xn^h9NL0;NUz}KWZOmNy%3ST{Hbc~wjF3)zXou^SX zZAv`ILtDgcrM6X9lVYT}Fhm`wi7X~{V4J+Cu1IiITSZ!Llpq(jycCl-VwuM8X6wcW z%zazl9gcNB+Pf-+k^)!!F9}EHa7_T9r;wn8Q4>w^#W)zAMsIn|f~ZL{Wz%GZG!{P6 zm|Nd4)m2rF@l1HTz#w4mXhN(dtYNMaC`1N1Q?o$Ow3T`iFQ5=`GD-@+2CM-sOpWY2 znL6`+g9KFmkcn>}F(t5f_k-`%q(aj(^P~_j9|)g#==c%>j6>5xssBD<_>C3W|4aLP z-|cAKB_um~KFy2$##RM>zbH8|;cJ}J%N#@o9YSqa?dgXnZksq`Dn;r3VhDL=6VI7H z&R%b)p#Os{<^2U8d~w#gRKhm?s_c z)Esy3F$AN(V@el@*=ZUXj4U2LCL>JtWJuE|BeAvAs&D0=j0D8ck8MhRw_N6y0Y}+x z`^fJq_?ly@JYFxDrO3@HC+Z3QC!wjSeLv+w(ug{SpP4S1i56%smnJ|BrQB0m;h(PX z5MgmSV}N-V7ie-&h!nQL(sRBIk1;|+rI<>Q(x1CmYHEkBRWZ;d7BA>ti)g)baNi~v z8i~rzJKp(a4`Rh8s+Mk3pOJ3TnTK5tR%vagm4VPss(0UU#~}?(10zI4_yF7FY-xLg z(#R?yHXIICLo?P4tqMC!kO{frm`WEFJP}wKM?>j$dZh3{MepgRoC!DrlO*`c7`$SC z1sE9~wNky2OR|=fK7&TULT2U{!+^-=AJ7?A_I4$$efM)NF%aUwr%_a>;92_6nWgCO zWtG+WQ)O2rV`7+Mg4~NBbNa#JF%js+0w2c@lCOfWu}BopLqWs@Fs&{j6RqC5{QgPX zgX9+{$nu^3VIq3>n631lCey#~)p^^1@ws3@buyN0{nP!uSH{RFdp}Bex^|@Elt)N4 zkXG7vp%fqrqivovwe|%i3_H>snt$GP4k!eCosp`XnDRev*7d*?MrL<UTBsf_GAM>Z_)dPT2*2k2i5vUPTjX zso2MZMRb)WXX-2qG=wJ|(ATFke^4u($jHGEP-|XXd5@ZX|JB1*L4o7+KO}feJTo&9 zDP22F)v|E*W|S6;K&p}52?S2}Ths;!L<3+p zf0viz4FxYp{C;7N^5?}fHXr6et5YB|<4U=B79L`90H*`yGc^s<5G7p1UaW3^!@KU& z+xO00l4JlSat`lAYoQ)yJ44zAP14M7gkW9D(LPNfjqbLwEoDfH33+fo0!7;06!#Rn zd;?9QndY;?guCE+$j1zv^Q!@CX~mx#sAJOv4>#&=e;1XGlyi3W`2CqCo|2f?iV@9rAyt7wPuad^{L9v=n9pyyJa^5)qLD2j9dNg1BNFvdOAI zr7g#T2ufK}+;m(zgv<~%y5L>HIp{18`WrUykhqK`a(1o>S#G%n)azCOZaa0^E99GM zack%F#8;m`M;kB-ROo*S`s{2YB-TbTH5**6PNE(=&& zei`mav2zFT7=?w13ZX3H`cc+yiUx*5q`@U6-{c=0KgQ_zHNlk{!9G_YEw|rPY~>ZA zK=U-BOk0&;OjpbneA$`YDjY@i&?Kwj)zUJiYZ6ue-Zl zl3AmtTIG=2+Xp8l$0EuK|vm!T5toSjsK#B2j>43g=cnBjAU~pd)QIe2PBT68swT> z84-7q$^6lzS+C0^R11BwHPAq8oTJ>{f;4f?jEIU2y5Sv#WF#<0L%qgKQC3%z@9qC_ zeMKPhE;5IynLzgjrW2SdjkpJu?0`o#DL@0=J!9T zIXNUHocS$f!JXc#Wysu#cl5`14J$`FODD$QEe0fbF+npnGD_UPCkL!cUa39bQ>zp2PLzhbWxPl3qjw>nD&&-p1R%XPk^^t}8Y_m+YlKHDRB(?-YWq5kaBm z0*YMR?c4Qx*m|IX1V2piG`y3-Qi}jkL||!2Y;d@{vdWG)r+%+WF7<2_A~;_tdRJ*x#(op=>^$mYPuGX1qqkfB=9B&lqJWIGNqTyy+JXsfQxGdS7fyZ8k37ykrAy zxvhSV{Cb2|WU;Hj-6aueUEEHEZ9-11g`wo~jsR2apx-&W2tcdxI|i&v`zQ2%A^3T} zNl@G}a!a`JeBLuPBO1)M_SP>(BpW)yYqQ+x%|#fy-!h({VlcG%{Ql$!p+8v?QO&^m z7nd|~+A)<=S?O%hW-^hU*WrJ)0K^7}^#coscx}GHV}-(y;P6NSRfqO!1yhv0{utNh zw(w4`b+pGAaY9?x#G7q?uA!NJJcP zB4J6>_-Vt}elyo}HUSQr*6I&k|E@8I}FEQ2EF#ce|f^g3ZnjRztO%h zd^P^Pd?&xH99Yu!3sY)fN^K|K^QC69$igEqLUE+)pWfNIbzTpo7iT|$|34j;qlS91 zOKA3#r4_{Zi~AX&I_VYdf7|b`V3k2n;ZM$_gF%1b9eGpO+nh2j``E}D44&Q)-k-dJ zM%2fo1J+mepCXUU>)ew5}XMq6rD+N{AJ=W);1I z%^exE=!u|tdT_o+Q%W4nqsLB#)3$+k)W#xL`njmedhM!i9@gUNoe&z!Uf&+l1WuN{ z$%~q1Z9vl6j5)@KX(3HGeI5{wc2K${<7_o)F@qp2d1gT1DovQ<*87NM517i(WDOwt zRcpfLUk>RUcMVF|R_AxYLL1tTFnPE0i@dI-(4y`T_pcDb$%>}WQbql@N|v$62GQ)qsFhrY~EvDmRs#4QV^}T4zF)m83%;|3TWNt zQg_^zP#H-58iEh$kGh`E6INn&9W@ih0<(o}c2Xp#q^jJQYAZ{~ zg{FJDssY^Ws-ETrPKugXo1pl@fTmk)_+XH+=qn2HLEVq$fC zMQ&7$*^*9sb@%nqa|;1F!RxAHYC#IfP~w@nx`lXayy6_W3?#l-vdA2XTwLTS=~B6Yo7Kb$&j4|>kMfs3)|{~A2wJn#+lfh z9%Y~zq;{@|GAbas#}njiYk6-Y+PSKoPkYG|EAb?j86Vt%7^s|DFM(a9IK5NOroVRi zPl$~jXrccpN6}W)+Bhx%&9(fs&M0X#_55g~1=7gTM8*L6c-sp&htCBT5Z-1~u!0{G zDuZ93L^PyAf-CJrrOb#WNOB1z-fd#B8l$h6iY1ltDA%^! zU>V(0O-Kwive!okk?#@+P05?(VW?0~rRSVD${%{5WinsWheD ze23_MJ7OnlkD-RcZDl`gc)vrEZKyBXsjMj&F%yrkW`2$GmcoYZ3i<-kjJ2J81n_;G z0vH`o!5rgfP-SpXSO4z&9cpTsn0}wCOD#R3jzSSCsLT0P7LqIKNf+e zFOT8*byAB!kXFX$d8a-<30~gma>wHBVu3(fi7Z_3h0Yp*@W+32i4?A>71hasIojX~ zj63}gDp3YdU8md}@THaxe8`vGnkZPU-`bn~!K2!c*;X#Tk}2)Dx=|u{-v0H!5Q2R? zHb==k*pXh%6%*@KX~u?rGF1QN6;qaTO<%|?l=0^82g)`dby+0rXX>E`Fr zsd0eiknOFC-o>xuNmd@W_*3gFS=ynGIBOsEY!8R9I#>bS4naxg>fQ2JM+ zs1ONovC-=xuOukPoDs+!(IVvhI3-;y1r$*7tb=h6^p_psDEZY7c zcr0DS?YhPTjnKY6x=iV+M9h-riEE@2oRvO){D7JjRu#@KF%!z3_?zstG4Z!p+&ule z=SX&-nQ8-yffS9rl$ozpT&fT}1V~9#D<6LmNMp{(IviXhxGUry4`B0N`aJdT&m}JJ zDc@TR{ozeRPoK9$=jiSg7?^30XGTh}viL6!p6M6w_?jY9v;F-vSCi~NeQ9qMoY&RS zIy*TQS>y9gmQ6hq*L!HbMUuw58$CaMP*jX8Z3py?a|}woXvHo4LQVxt=zkYEa;2yox%ScR{zAos{rc4pQvdalEcb~J z{9K_+iEj)I!~TjQD>xI1$z!Bnkv1^t6a@vCI_^HcUbl}wdoW^|`EEh_f94XQsWZ$G zzk~>VUVUS%pxAWzpdkAMn z{uVpT-BubX-R)YjMYBU)nO9Pl4uqYpjQfh$dQWjYfrahnKBKJ>Gz*z-nXsHFaku8x zGu6kdH7FrAtN+lfuDruS@{JT2#A?m!HqFXCIW$6>)S3G9csh2rx+*2(i|1Dg$AD$z zXdDraLNv|CuRuzrsJSL;qk>fIcgnYXS7<-Z%<~q}9y|svDDfE_`ezQ$@@ql<`X!~_tO-yf0{-HU=Xx%yk-Sq2kF$Ot4YrITE);ji~38tM& zhRfZN9P?2~{{(>$jH5=lc)t^iN}4g_wd{CXE05 z-N*4IyQ8NX;C9CP*G}+^oM@t2%ftG1zDS>}4yH0HKompZ0MdSwBPj@N-THTpXHTOR z>y>(b;^g}1A);c9s|)Q@Fv=PO=dZnWCk7-bObE`(du!%Ny<*sn6 zbGE?Ac8#a%hbC``y{QgnU(YpR;U4Vkk^4Y3plWFek2|oA>M)N{O)f4YdAShC`)vt! z>kI3y%YLYK)0SqCEQr{0V@=oStQU`quVX0wY znH(ZYmvVv_Ga?d45@|M;BW82mXQ4mHJ9`j1Ym;4w^^V?}w%43I$d+5Gq+#=qM>Hjq z8UyUpmWGs5cl*!FHF{qSAYSJ?-*^<9(ufQ;|AoG?Bif(!F{aNGrX{^|ss@7hLVtmp zplUNXc{vuo?on~daG>7a$8)#I(`W@>6}bh=e7n$||MO}869K%T;hw5;ByMJ+oYMxh z)crAfgFGjO`QDI)kJqyxM*dw=myh09qI|KWMg379G|tB^sRq`w6m0GpZSj2%&&R62AGPwd$jqqYHd~mbO`l_hGI)oY<=WRc zSsMLEI?DI&O6XH#nC3?Fc7{DenitK2tv=E?I>{^J5E^e#UG^}N&D4p<>ChWjGi&GN z@`Lbkk}j>8d^CpPeMyuxn3CtuG50tuadzI{wf5rvm)Vevs0Mbye`hO{ky+wS_7OE7 zj)2wNE?yRU_%p*#u)6lrua%8S#|YPQnf+Qbc|;uAom7nS^{xPwh3}o6P+;u%@3*=d znDkt{t({TmMIkm4gy&AGq|pRf3z|Qx!^bH9oQ!`H+Kc(n5$*;3P*mGK?0@9_RyC}N zB<^|TkkkFz{rjrM&-sjDZClPLA)=Cvi?>%-mx9VP-P&4+2aR(yZP|4KwGSM6lx6b$OBppRSIRuL0tM|9Fk zk>wQ`VpeK6{YLEPl2!de3YNJQTRte(n-E`q8YiulE*{|-7}a0GBZxFJ)9JL$WrUTN zKU)zuM4t#;UZ?uI#l&U&N_MC3O$+ZG>O-8}WrLp8a^V=*`n$>M`lvH963KcIXK=gu z;U(05^8W1`u2-B3>!gBK^iS5L*AhUmVM&V>SGasATy^f@!WrxPqM%9RA*8w1sC$M5 zxb{a2S_dr~cJgK;T|gCQr5kvUMowSt1Nor_eT=Y58kV1wqdQ*C69bn^UzpV>Prr7~;n zPxp;+miODXZ)uffzTU+DkL)X3Tu!v=?pZ&c_S=#zk%kL4_%Oq{VNq4%6H=C)| ziSngV#SPqaZq9FOJpTw*0yUns^<_{esBrX~k92J-@x*M^o+ z1a~Io*^T^5AziaoZIhl8S%93z5W)TDP!LOL;mTL6mT&~w@qkbt-s>UAH%(NgtZ_qY3x9 zyWi|k@cxT(s*)?A>Z96xzMJ~VDslGtVgVD3A9Jr~V*kYGuej$!UvT`#I?P2|toF%r z%{9y5Z3mYjg@|5fjV=RR{C9S6HVntUO;?RVUkg6oK5TgRDcHdAV#T6v);g^vfiMKEV9%mzk7n`h(I(`(F@KH#=UzwhXKL)|ZSOT6K z^EVy%k+#N`@R73m`Uj`cAFph9&ny7E~z>)MVx>QuSYzB z+zsK<-RGy=Y6*4Vq_Xo3`*CHITV4G176D3iC9~IIG*w51&39{FIqmtn7qG_YK;!L1 z7YFO>gS*qOT{~ep3eB7}Q*(}A{Hejq5N(S?t*^_?TkAc@ZiJrkp9iV!4r%)xhpL<+ z#&lgSw*Bqc8Uci`@y=cpvO6bV8rYz8wX?SlEZ}F7_(j81DWlu1nT98`_vZq`4m}o? zr~1m`{{g1|Iqz?fk72xLH%hCgQrq&5hUaz+mkG>s6Dcf?aYCxu zfx(vMlIEZ3I{jnxF%NZ|d;=T}G(sF@r+f8aAr5<+WpSk|@umL_(XgBP7Q4T9*<9{* z|CZhgn*Y$GM>E(fMR&iEkUM-?uP+!j9yeFd*p5wHdLB)dvx7oSb&h>{Wm(KZf)Jv# z&-qze>6h}jrX8oO`q;wJHJ5$>m}6FQ3*B7{{RjWMxr-Cn4&IeBsjfr5%XY{bK~YUl zcp}bRTSv#z?ryh!q@xn;DLkY)m^!m|rScigjzNO={+D9_Rl+{I6-T%cm>~NsCkjx) zL{QJf$`te5C>my-s^?*)Nin5;pFk6v4jIh2Tw!zKnQ5&N3bq|hP;x%f!TDAIr(uND zuHYL{QIrwbt3+u5)Y4xiM~f~bBh6&se#4q`S8FJ24Fv+l-I81DMj$T>jIVTpA#h14 z!8R>&{a+ewfu;|GtWaNqs0)hc7?5U%QN+P#Z}jR2oS6ZG9cEo`bBm?;kdzHyD>(es z7%KqY&sC_Ra4gv%8=H@i{8Pgp`I_{ae>)CbISacSlHXWF<$lQ@c5>zL!wHMB(`Z(z z+iEfk4J#=0e_>}g#caT8Uyqx&75||5yfA==(wlT|(6&_{$bxuj-s7Q>qrGLHg!6=> zYQU?Qh*~xl_vG|s8r2lQav|^~uILV0*k%!@Jbli_ehl52Et zno(4Xn6-U@6QUsd6gYvbm+G}{*#G26rFf>D`I6ii^@3;-0f1{51aQG{3SBCZNy4ie zaJ+83QkeUHMF}5DPeVeFD;}{ltY4z8EH5a}kA3*(#;a|8#h2X7NHIID4p!=~JfB~B zM-D0LzF9}yuo6?nH^2RaIfV(c&m%K#TFx0UI#5l?dO4{Gjmc2Z$J<+l`HBWI?X&)C z*o>#ygf6EbqD=5Ky83kW+h4@!w-8i6+c-n`vTTu3VjXWs@|>FD>fBIu_Bs0kaL3PH zAYw$F*p)B-I#S^0dJpQSkoO~)3GaL8|K|Gd-2GxayLHwg&FDLG|CG1VPgPV14qzHC zM(hV5%{I!ue%W-k0VLkAoGho)uuNW!pR`o_B?w)yjx>T)%!>(Zdfe>i?~kYqQ;V!? z?jb}R?>XRbDRAigul3No>+$s&D5vx2aOFTYacMU0lDqmzqXJ0B>h;!@*7srMy9H+#=Q>V@uI1<)4jO30Ucj&yDd{u1ZHob zQjnE8rtnE_pSarcDEnKVoLmBuUlvbyty)}}#vBAvctiVA`V6qC23+}u~xMBujkM|qxzai9k@wOx|D?u0%0V`E*~&=4KcA1Q=N+T9TVh>{Ld z*H95?Njpn6`5S#6htFYOu_9K>Sxx$pxL4=Qyvc=NLV z$;U%?LCV#olqsoxdbV{GqsU>xtLcotC;tU|g|C0hB`HH~WNXK%JS^UH?n+wvW=3A? z0;XOX&wpAs$g>zcBGRk)P!x4GrM;i3oWQ=%pr29Fuxv%v)cs*dMuzI6AlG?!LoGLV zyo1}o#n@ZP-w)0z?h+hHUs6lk{j3nvEMwx1_)^<*$o4O$3x?}!3I37Yk6k!5AMR`c z`{kt7@h}c_1F0;&oO0Tm4d?XFak-<$>2Uk{Io(K8(^i=`zp8E@O11Y z#~;j8C{zDg8Y!7rUGD6T3p;S*c-nielCYy+;~q0UYv)J!GY1p#bzvqiV*uL^N57J$@#(2l8@QCA0w?2pf8EdM(rJ@ zn5xXQX>xv!6osc?E8bJm?_8S5C?9h!^-i}VlM|F=TY~$A<5&bgms_;fk_BPHseam9 zL8Q|N5cMIW(BwlP;w1^&PyZ-KSybMfla|m3Y2jh@FJlUAypwfuat47AcZ7z+n20Bx zTHsP*%@44a5$)nSO5t11UQ>;HO{B5XRFEd5Lm9-XU6x&xLsJ1JrE6$c=7bid{9SdH} zmG+{}?C2o)CHx5jMf!~#%M`ktAy$tP$~zD9X#~X8(-VBi!X#sEJ$7*X4GwMuT#r91 zl3=W2Ks$|5k6ja3?bSJWsg$L0N83bcTl(T)9htn=JAQSdW}N7q{k@1-dld?g%j1h| zm15^2w&}am@6_T5i%>=_E6^5@+@CAF9g*(C?TTr{Z;FYNl<3r!t)fz7dm$qxIW8aWVFn=QHd@t*Pb;e zT*a--N<)ow&s~Sj?PI!^%Ep>D(Q`v9zA!hvwjyjnF3t~uT#67c^wUe6lc$wu&(!rX z`FwM6xNl#f)M4POZZ>Zk@KM?P3$lO2TLI~YHD9xy;0$b>;Q|(3jO__&f`+(MVDoUP zExiT&GR3^C>_kbU6K41cn0teW!GVpOnwtDG;p~m{#yP0yMc1NeyRXTv#6VHX*B5^* zXX7U~fl2SK%{Q|mX6u2U1Qr4$hPxBgc}^#`_6%81IU19WB{*z<*j*ay`nMAfsHZGj4?gnPiar)jK4j>n+XP4Ji zfn&@K?Hf{_lMC;&7?x^0kF1I_{`vOBbQW?rf`Rn+-f?=T+ncu1PQFtABW>vD@^o&# z&`PCJ9p+tjTYUEg!>9%*iOCeYsstkyi)}paxR8FCkFCnxl0DB;XM1HfSVbO2NpoSI zLTh|WYr9f9^x-AOjt^DVdMD827zJPd<~rO~Q7r?#2D}y&4BE&@eoJK(%inwUW>=!J z@MZ2SB4y>^ka}m(*aW3ZR2V8fu~>g8GoRvkTHNDRmdlGn=;#QdN9|;pD+)ta7yC`P z{EqbI&kVku%i|BHC)N=f`oYVKE^}bNSnZ#T=mQvB*0SK_Gh=CZ@3@fKx-7r?s0!T7 zjER6KBZBJR1;w4w9({dogwKS@Dm?*jvXEV~HN<;2;nd{>a@5Uf!t)$+TuorNNilA0 z*s50_V43QUGaEwWCqs?3!o;CW1)mzQin z*4=`+hAHJP2HbVG-@f{mGI}#mb=~>UhLtAiC`#`~^s}=!&n!5SPaE-EKfM)|m?flS zN(kG3i=XASz<@ABqbK@TG^Px~bAGvRmw%QDM{rmF`i%EccnC@t3_!yfA2MKt*nLP6 zqK;-ah(F+4m9thy6QP0z(N-F|*pbOqore^z?^iQX#44&IKRqvY;`m!9RA%uz)w3z+U34MH|Hc*>QW(xwk)r3w4J^i^ z;)uxQqu1^F@jS26GO8hNv*=Cl{!ZeAAQLB#V#Tv&iiu)!@TM9je@;$O8ZravAFr^? ztxL0)jA){4ja;l&$gR65Y9o=R+1I!I004X^XDdyB@XT+fac5YgNypTPBT42fXJ8U~!i(`Ngpq?Ud|ew?#~G z=f#h}82S>QyH6!{r@PmUCKfpKNN9`lvAzl$brn@z+3TJew)*#t#?tDXT%o#T;6M4H zWS~R;9H{8k8yn!%k#Vl$;no`uO5g5(STaqCF`XONsUL47erzT7rj3v(Q+luPAXf4>Uw6eD^DJcoN zxw$E-+5ADQ%TIK;)f?QhZV$fq-Ps8&Y2vqVWI|E_f$YY{M$>Sz&b<8mz?T;<7^LsX zXNpBQ1I8>5mzxSdP=8>;ml4el50Yl{KQ{Z5%wSQfasx(>H-B(ATh{lZAKjykk^a}5 zfJLzHy3YF^Vd~h1F-DVJUf2wt+3&F5lL#{+{%ct#$%v?E;C9@9b34;|Y@$L#Kk@@x zrq*v)5Xk5q95&Qs8czBD?{$bu0VVohduf3PP50Re19$r~*qn&}b4ESK-;r*6#9Q-F z?EkLd_}`_0qrG2s{qLc5GplBlubucB)p%;-U8g4YXNlL+y`rATrZ*Blvgbnv&w z#Mf#ea34y1YAlkr?p$+IIu`lV&*PA!gFge!j&mgIHR%`hBu@8lK)Y@Zy?gN1))`vu z_9#_VdT%$)V^2F4Oe9o%Rf`W~RMEq`5~oIyA+*N6di+FGiIN0WlgG>RkJ)8T8i2zm zCykdbP5LmF;ZeP@dH^B7=S$u0#h56mFgXDU0WuX!!N#rww*&91eUjH^EI*ua9ksXH zrRh6*2aYUHtn^KANcslIPjRaNC_lv?a7*@obx*TA*|`G2FH zn?O)qu*^7Dm5`876F5(G^7UPdH1P)kGV!tPOuJAF0jDehS3uhfw%eth>E?&{$J^pz zy0;bw-f@@ydMW`1a(LvR@!aBKMb;^742z4aD_W$eBsqFp$$O8^zP*eLf}Wlp2wB2Q zSVIG6+EUdu!;dska%vunl1PCXZwh6=#0Wj|qN&`0TUKs@Wfr!?oyCIo z5fY?d8W$JpU-xmYR=vJ-WXF}jphucSLy51Plx@DF1B*9gKsW0B@~N{@-o*c~A7LX! zgZ}+vl#SL9cmY(lK`G{Z1&gZc_T{Omn9ywt4m>l)nmfR_Ep{hVmmtOk9 z`aKahfqcEQGc`la7EfssGirR8)lwar_aiJ%%7H8r{Ffit@zb`eOAoCE+g6V-5h=*9 z@!<<1u*;5?d>0<%%SPF=vZQgpx9W(g5*K(+n!A$+BA~fff@NbNK;{v{7%sfFcVvRC zZ4$kBD=EoRZ6U`*ffjUDSuPeYT8ZX{qJc?=O~~ZmgSj~8jhnd?Q#K=3dcAU4!ocG< zJcs99oHX%^%)Z&DktBJ{$K_f@v5K1rlR>Tn|hG7Fl*G_j7#jV-Rg%v+9EoF}XlI?4Lls^0U zrvsCxnZh_DLv2s@;KqE*;Xa-w=mm-bYNOO@^MgzMeP{F7`p@SUK3j=5#1b1jZ(dz1 zT=!)7=AjT9-;vk^G7fTTCifPC8DJMba`Dg0yS#04AP~Bmp9?t`qh_(y=h&*-qG#bYS~C9YsFu`rX}?6^%&b4(7#>D+WJ2-tegiX794@>cT3LCnu#T8{ zXli->|55i9UQvDD+aL-eB`qz|-JQ~%(k0#9Ez&LBj0n;p-3;9!-5?Ah9YZq=@8Czj zzrW#KYZh~7ICIWDJDz9nb5DfYFMA0(2({h?!K81g^`>z-a-^i>{4UsuQj8Ldit9__ z6Irxr@VM~jz{n+~n&1ue68jM6#o65>g#)p`dmXsJjLLXv?`P8CeJ7C0- z2>h_mN=!`r!=MuH?3Np14-f5XYHKHMpom5*gN^}UB5wO73IDRBF-1_ud7g4&N{V~` zwSPx(MTPnG@oEgIknXm=$m{67g${oK!>TlR1jOH&R|qhaIb5g?&dw%I@qg&;3P$4d zI(=)}A0z8QJB6}VO7y*`Ch%%%xwtq4BmPtK?QhJqyXf_JQBRz7;kviC=eI>c zmRDYmI#Q$E>cJF^$Mh{fpJFjD@~Oa}&Ns79PZu&GmO6M;R8*q?5kOm;AY3YwUjJra zbfm;P**K*?EI5w%mj%ZW(8Gf_dcrwu=NLbCy*=~F4n@JQG3k2++nB4S2m6VB6F3xx z;Qm~IL*@_6hm+|Pa`t@f2;~^2wNDJ?cC{BlJeBtTAGLQm)^e=){}-w`f7yzvfBHDl09HSDK$cgXibx*KTqmx1Fz4^w9oums2DE+K%@Y zBrR0RfpuN|)Ju?)oBRByI7YSo^8W&mcA241lrp_7R`%ujl^u}{m2Z%zL1_K2qur*a zw59FEQI0lvh1UP8RSzcTT8lB0o70VjhB4^F{p~aWDxs*TSR?+QybZsZb?TVJbWvjU z=40yGHk?8d!@W+=EWQ1;7$&_o7km{yYZnBEJ!E+q5B017y>PRx8n8s@O#eu9N`P_X zornm4p|a`o=B5dp$MMQg`}LZIW5$ zoCMQ$sNy@R@&{HTEhf`R(`fAu8-!Nd<=+uj|Cv^{PO7=8q2YM_yrI0VE@A(hxhkUx z1Pnn@PC`WwuRk3;ho>WO(tPvn2#t8HA=Pq@^lgHUf`cZa^)dE3?ukvF!$@@bs;)FA zRaV>R+kmu`>@QD|*;bpW4j#-KHZpB1yS80m6z#PUim%<`R)Y2HPqqHp9Eu?qu?>VC5`{*Cf@OXO*KKi#y;zP zFrxGAc3M(amOLXKsChRRlpswi`!`-aC;e;u?~1nF_z8F%i17{FFav-98Om;oc){*z zWs#hJE+zEWr6kr;r}xaR4i^>DS>cPOWnsxd5EAJ}P=D+j(?pWoC(MaxLy<$I3^oT{ z-JRaIHRW8<&At5b!w$)ziVV2!ntA=FOtuhde7J2@d+HM`WM*dGEU!cRbA^19U;h{A zBP65BJX_9q-&ahh&uWf?>m88o5nmWE(hZs@G`YYjR4o5SIS_77NAkzihj3qo-Yg6V zOR1`2_P=>DbklgDei)ej%OKidT$g3P+_?XV_`0A4wuyaZYaA@If@NeA z!uO0U9XGI;k@6o9ThsmrZ|_bb&2?f3IKpnhyC9ENSdO(bDNSZRU8wjEF_pys!&Xf1 z2|-c}e0?W)4vW#w8pbE#teyl&i;Ii@g9UY%T^Q6bp5FO+wUIK8?9YlYqKwq|`nNhh zz~G5k$+AW{FZ%_0I6`<&!XfLpZ>sr*OY;wV-0C3<9XyA|*4FZrf*O0GqFl+{=RyqQ zBuYiK6Cw;#Q&UYBQ}P6SE|d-SFf$y?@m!O&wY9Ag7dWt6?%#Hy5g$fzniae_lHa0f@I!Tf2@E=HFJPCP(xivmRY{z%<&pq0^L1(O<$NDhfk75f8 zM#4B>FpaPFJX!mjb-Jvn{|5&WKC$a3yDbNmPl-7t7IK6Aa{uQSC|36Nihq4>_g~Uk zpaok^d^Q;$ki4>@AH(*(9IdBc`H%=<@0B-=8xO24Pg;Z8RoM;b;*AHTQVDy zj*d>>ZBkMpn-?=}L=tAY7=ov82lG_}Fx8zt=|^ImK@Rbcrw$S%<>rpJd4u1uo4tfX zLMQ&X(H(lYRL{^H^ygNyE&q7~2R#o@nzG*}wwZ-Rq73CijX8>Z8uRy#4&lGvkj?YI zqLn{>d=WTqLVyJioP^s?(3xSGn^#-Q@vkWU|B8;+Fb)q7H(k!@!QfINUlotVa1>?+ za*TNLe|hF1_ph{E=3xuBy(Q?{fyu16SrmgZyD%wxw{ujSUBzEt)u{&={z^oKW6s9F*kq1r&t;*gvN&jlZ|63!aH8DDp zmcH`~7^3tv*b@>F>C~7Z!!)WT_9ql7!2f5=vYrPOjqH9mPIk){Cu{AD`b}Sie6MK9 z|BD&q|B1c8wON0~3l#g|!-tPLc(95rhZ3ncxwxqQ3&#=y-v5OwKANrVZRc4HEmdvp z2(~bML$9Fk@@ZJ{1Anns22k|R?66_?sG*_pBu*GZ!ln-`)|d-k&Zz$r<;4H=LjYq3 z*(7Q<|2sEGfCwzxXVm`jX|_!3FUuteEBS5ysklTqsi$7Zb z6N(m0{7*rAFtdN^6AnH;g44~ZG4wnQ2z%e4l>Re#G{y5zM!N+tUlYD8QBKInh-3?c zg?DFz6!AZ2W|IHe2k}2mW^1Ua{edo6h*_;2qh;tFip!w+b8<4_Us0U@73FqV;oX@4 zD9g#cIyyRfia=n&D{SoNf0D}kCn<2DVpc!QKw%a?Gdp|s1UIGwac1FEPmVlg`47c* z1%c}m-_s0-w}z6c?Xw>4uU${tuhoo<0RI|){=ddyi9kk12CUBTC(3=|$caFxYfDQ@ zB5}@>qYpMK|CQ+;HVku`n$lr@ln4OCPwy4f)!{r*$$#PXxc9gj(jRMicWxL%$Q2b9 zhUh0umPDhh9qgNU$iZY4zAFobpe{|7d6TF9H5vSGPtdIp6=Uz`J)3*?;Bp-*^A_QC6)H za-WQgtIF<$184>#>vBaN+}GSj8aXd+$wfs)HJ#sA!3M%=-*z{ooot86;^N?HoGuzw z7BrVt1$d)7KN>W$HJH4Wl$0EJ&~RQQ@vN;T_a4BFp96!522?qnZ~%AXfW`TYa_yxX zKvw@1uZScLZpwMadV6j`x`adl%ha>(|L#c^>%_+5vBSUj!FWGQK$cSAt1$i2tlU@^ z!r}7#@TWqjnjStB)M_UI_i*$dj$|{9VX_yq`f$$tnFoA70?EQ#P+^bx!(Y5EY_1P( zV*8YmJ-B4F6A1)%Z4ADia*2|?rlvt>b*tl4(bHRgc*JrxseXeDD(GNJ{O>;gxvaz% zaZ-e2@oHnzU2$6X=VzbkDnW+zX9YW|!gi==&FF}@-$92MAgGXrUtkv?L(eMsh?0vV z?eoPJiFQx4@{bm3DIarTaRwwz8BOL-9~>Z;ScUWMG%X%Nk8efp&Xm2a=WoBX&m>3oVI1F3`YBV`@`?q8x5JrH4RuU&ez{ z6rTaVya1ku0ul9l4LwcCq!|t>dH&aXU^|i#^)Dg(@dQ}H&h?OY@+TpGO36*E92Yyo z?9qnMx7t#EFAOGHdVchMhFVTI@>QP;04uRxRFv_@WnfO(`$o5+!dP8VtA>KlvA)u% z>paK)Ms1ov*qAY6KY|5jOrHvovHm2;wl+7@yCP%lj$w2pLTOcgU~uyCz1MN%3&D;p zDsIx^t_@VR4}5Vt;Hr&8I&m2Rc15r0E6dwyA&hFDX^(wf>;f|!HoxKTD^5N7h?aM2 z9#ygTb2VNYCWg9TYTv7QthmMJE-rK=?5R4gJ8brL$hnOfD9aMd3-wT{T>Xy3`L%`a z4)O54n8h0o7g~CP?gE0^bRmD#Mfhv$v|G+epE*XO{v>5!XQ91svF$PCu@g4xwu+i? zGK%Gx<=o8s3w;2GhZ7y3V{hP4>83c-2jTI2m57$NPYH|U-h02p2)qpJP_X^Txqf@Z zlb#BgY(H^gVj#T}0=Dm-a9S#Ch68V2f!LR{ovt0dE;8I_DCKS!c10%KIl_MlHAwOk zUY~BN%WFd+HVudT5~g}MT5=IV!KE4O{&;EQZ^Q$ZmLCeD)Eh6UNd0fva=o_|Z3qQU z3%1qNxH5HIcR5V;`b~UK9k?X%P#{b4b5aU#(NaNm%Eaj1pFAezLIFregFtf5C0PuBa%^ zk>iY1(nTysALg=AUX~%0zbklQP=3>wcH5PoWmV>#B(54uVVJ*=Y4vZ;m)@uMzr1pprnmba%_tp=!08BO0&9C0>g?Hr z#+stS)GMXvWKnwWzF-0_Z|Yi>Tm@@~C?BV&2$>W1KS=A6ddMS^o@&}@PhYfVLF((B z(hPP@%h)Xc0CMJwF*jx$;dZE6H%l|H>hL^~n|>3Seu)v#6T>jX4G$RLB}uJj9N{H) z0HG9Qom(4mS9ww@)dIO|HyZ(5`Eo7_th0_Q%th4|6adebn0YeR#nA1Y9#6=U9Y3+~ zHr|qLW9H-SxO<_`$3j`fGlIrxV>=XtH_IEGuqL02dt02(u5(o#+VgF5XEri%cb%w&D--Xx~^U>Go@d{)nVtXb1yUqmR_5?p-%mreWK|EbQ;W#e$S+e@7PIwZg zv+uc30_>OxG)$({+N9$MOqZ2FXW!Ff+Awz>9|pw0JHbY*4y@>b4b3~Y7#W4r2E)@) z87=k`=_f0^V>sIdSvY`!CgO%_MpW&7kEWP;eAc`+@|~rsbyE)>*kLX5Xhfv!WB^@b z_G$Il`BneX)pf44v%6^p3y1H`d#xB*2pdVk3Y7d~=j#D;F$`ne)^x%k7Y`%Tk($_% zBd(IYW((L8-BEuAPr$jK`{uS0YIyN;WY z?}a54K2y8vUN`Hb#X%*AtVze(-oqe)oAbadhJjRfvUR=rnax42%Z$1hJC4n%iOd(a zHcG-HlW02)8+(XTqu&9L1f7P9z|ru+@%ikzAN-Lzn24#5fx=-e~fY#Ac3i3*?OhpgSwz!-0fb^ zfkL=7r+lDyD}iRVDa6q8`a0wIL|x9NA>%v&kY0gCQiM)dz3S(y+1%xlKFqhyz5H$f zupF`2_WRz#h7t%A{x=uEJa>qAzev6r?@f2v-lef5 zV8?6>BTU=y>j^HmgPuJeZtE;vjOtw5KHyd=B86o-rQbVLK#sHzg#=ESwoubqUtthz zyc;?-_}^H1ZGZQHD_oe&0XH55wq&9DqmcQu@X#(x={qa*)0upXYNtMG8_)7BU?4a! zxshc@B=FS8uD-PCOrFd{Au=36&(N%^M_vcm8gw)Pr7^l0uNQm($u)zGTyasE{3 znbFODJn2_qn^XQ@eXW@gvTaG&58PM-$SWm~DH;92N zt-986s|Q@Dnh7duwm?ya9>ohn53>XxPbY4~4AR#hc9utr$Av4A9J5y^gu5|1uGLe4 z9xp+ss{WH>D>svTA40Qdj(kD~9`E1+@2}D#^#xAdRDldRmjX9Ez<>lY$oc`L9Z%ov zbkpX(P7Di6KY^|JK)!Z}Z%!+rp#3#)opy_Js z(ht}(S0Gi5nQaNjPi6U4g6{!dI)B_IGQeyDHYG9iaz6w;jnmedoIFh5^!%@Nr=nulgsGmCCL5y zdxf*mH3a&4qGDBiG^OuX*P_|B`7hz~9WO9{fY<#I5S`;D+Jgl)Upqz=)}I=Up}>^~Cg?7PE$thgtat%p=Zj6Lr_VEo_%cl6~8;$q0W0KM! z=3MVha?-$kjWxdwM?WyY0B6+|zg7y*Dg>5rT*R4KQv69o$I0AxXllV|3;iHPj=rA4 zjFXkxDNf>fI$*wW+3g+^cFcUYcJ3G0B-D(Jw7{{pH7~!DjflmI1?92iCKG?^!lC((sm9(Dqk zz5p(s*l{ky_<5YThbHfvZ6WHVe6aJu+U^*S2!B@rKT~k)3}kB?5>oI!WoCG9Qy^GyCXDm7w2Baj?Ti%jM24pnYMh&>QW<*G#ng(C=7e zG-Tz|nU~sFh%M06aBb2~X+>h@(04n)wP!{RRKps#!Z130DYQ1(GP&Xn4yFFp5PLMl z(Fj>ySG3>iz2+>x4{r8zDy{yZc=bho)G>F-f9pP(HMT6!ycE(7veN2RoU_=+VZb@rqa#n}>+BWki86 z+g^~gaftL0V`n?qd0PEGmujaa4;~?Ph{UJl_GCL;smUQyduGLV`3*vP%zoLZQR>Nl zb!a0I!D}A(th6i^14HBNk8ODgI|qR}u4<^%x{j&P&FMne84W+|)O|LNEM}btvR{fg z3JWt%d@|3j)K^y%8iq`>!Ju}krI2ZX4M$7dA%sn_scnGQ2>~bFuJja^g z;StiOZh>6(G)GJh+^g4A>TfRI6csH%?6%L=>wUoURr(H7?dYbhHDkMhtzFsQWH@58 zPI$E9hdJr!_;#lBpsVFVH=1AX$1qsN*?zI!itlDV2H2d)nyUz|*yREr^(=J+=0Xa%8qkaN}4L6)5mT! zP64U2l#_r2%)J4vRRh#q?$AgLNiVyILxX`-@txmgg{DLpkLCo+`^#M#gB9zoNeBIw z0M6a|9NjU?jz=_$)aSp;bq1!2a?P*vOi@z#R}A|N-BB9-_qm~GS6S&FG$LxH9S=J{ zO^&vBAxdT#MjRRsO)(9$6K?;6_SDt8!7EW4dE+7|Rr3a=utzKhT%7n_Mthzv>Qxn$ zcFJxF0j51&%z%@M<*Nb_tpSe=JMp6@Yyi(}rg%uMNQHgxhOFg2E&#+qmLnH--@tY5=U7$8o4+tUX z$1U{#nt$#imku79ILnyuOJE7Oqc4q`_PMz8RAY6)N>d;bFPx_i@WNHDh|P8y^)(8J zl4Nlx5K4S&*^PfQp2qTS#C=nfJuEP>wc~+Y4&{}Mvs<HZtxv)4HS*v6NY=7d@HOZK%g{1^11;Y8_Q=&8eaDKLFIWk z8aVT%S*&;v`VGd5MBGV&!3gR7_&2kTfc%luaRsEZG{&txcL8LYHieek_1mkWet?_M z+nhb4TRNj`tsn}ukuny+vCK=PNHTo!M&_%Ns(ibpOTUL{Ej8lbiwMF|0)a2*S5IZ1 zMx)PDs#eEC+L8i2?xQWh6Fkb@{Xex`KaCOb09!%cJmJK)rXx!86OUKwjyLQ^ z*#eL)9)59sml6Eig%A@~WE&n9i%Ip?xYp}zw{;#wQ|aRDb8F%2p~bCir*p=dXzJ6v zX45m>pB^8Hma_;WucoSrLHvX$mCt)Dpdt=!CcJb5xHjnPuZ7(n+@?rgTU&QAH+^A& z^rYYvku;Ki&gqX}!zSRWdrk8raGD?eg3)fXzU`u$TDSF^mn+NW=ZyhPtge|Fb7iIk zt7qYjQ95Z_xi0M~ANywg9;Mf}t^}Y#@%qAHjMoV{=?3MiE6-EIKPTGs$I$ayE5a}5 z^e<%afLYe>2#s#{?e*C?vD0)NV8fPaR+(@AcoOB)f&&4MS5#f3iWd!8Go$a$r}XV? z6jcN_unN&pb1%FFn8Ldc-#Ua#YSrZ~Ng+tCR@FNM=IqX$d=<*<6uF_VZ1wsj8~Lfx z3`faqTvA*c#^71=?OnN!@>o^3V4)J+ct7&cY`GKYJfju2-EJSg+@L64He%WPVUdjP_kk`t>Q1%=| zwct<%07tmkW6939YMC(>a+eC!TP4Avli}|loHym0$UqJ={@937gKMmO|m^9?zsJ-+#++FPpDE zQ9(h(pRRg**>|iy0aWMP^$5TLgq{_tYwCm|Ma)-O?8&#b#?#a$TH|AE_L#&Nu=jSM1eHW6gRLiu_Y$i|I7~UC^JfsB-2yOY9-rys zK|HhZ4ISRSkl{Cb{IdBDB}G&GCaLqtWeZHfF=;!7EcvR|^hfO5#MbnWiAo!JzEQ)JN2ZQo9u7k zVyUgA3L_yNY2(Y6Rpz_YsYgiBcfEZX0NK*y*Uj`g`p#9Sul3$1-gQfP0@TgtN~a`r zyR~S@qC@pPBpdI(=ZKS2GJ@t;UFbLxj?4t;bF}4`<$T<=8b&em;34N_P7j~rT)~ts zNj_emki(I|w=BtV17TM!51b~yns9XMJSbSo*TuCcyS||8sCh&1`_HjaZ>sHO+>SPH zEj2l|Th7d`v~O2nfuE6wfJjrh^r_~T@~=o&?rN=$*tY8nu;0=D_VyOcFduE*17uta zPrycr2lxIy*GYU%*Y!3O0Yz!@)Oy3E@E4djh!$a3UiK`v)O!{-{L)>+^j7Mo$)PXY z<7ivdl*9Qgm4M9A9akNo5S|m$pn7Z13-zE@byOlqoG6 z9+bPx-ERJ&4jaVcEV2P9*EyJ8&hf($r^d@Hb8A+uxn>@PlsIyEwWC|{jozV!Zw$LA z2r9UaF{9T@btMda9TpSJovx3vV6#x5i}RiH`ytNGmWh6}Ijd3TWjf-44qKozN6J^J zKT~ULIASlyQ3Kc&ut_()DIYuiArq)0y8%`}HC) z^YR`Wl?-ylG@fuLez@ZKrJ=Y>2_vD{U|@fG6}8{#M~`CIz_-GO*8uYpS22FEG0yDa zu&P)Tl)S=@xceO>e5APZ@n?G8^NMim2oJSZPo#Q-Ft_!{_D6rH*f0ZF*}F=&0l_m0 zqp|0+SGM-TPg^9{^R?4LJlKLj{%za1WKMm&Uoxhms-z`B>d8MGL<|8K;pXotr3$3W zxro+3f}lMTvX)EPD9G8THt5sLIlZ3-w9YJ64WSpofm^4xX>9hxy!|nRL%%kO+bSFH zl~SE92bi}U*L6mNm?qAr9sNVmYAswg3aVkVk+RR*Fu2uV59_va{+guAoDOV~rrNWj zeI&b}?al_KPT9BVQ9aJ3)UbmV53B;`ZYERLX%*2F-P}BsUrb;03;A88N-Hn_a!|-_ z=tl@a>(x6bv2{2(p0!1YWNkGx7-R`JH)0HQC*rz9tE=Z4B!2L2X->%R=TD$qq`0Ddq%bkpG+0Q$?!I-dc%g-e_ z(^Y1y5#jSiLEU*YFYVBHw+a5&bIMMm_`;}P+{G`^F(lB^o*&x|STmSBmXf8PZWDXt z@G2`A!l!Ox*9>GOOsZ`_ez70+0fARZs#7k$g(JDD(O;QVAoo9n@UVmzA@GwpH z7Y;Rn=XHrRf-oDCAj`eEGs5 zy8gHGV%ldbkTZ?i<>BdMYx@8J8R+Na+@PB}D4 zwlqKN0~t$-=6p8y93&&u=HhA|=Rn3&`OZXVDk^kxi($PfIA5H8(-QDW{#wo>5wtU) zPKjx1lK7l2-nKSWf*Kds&pV6^!h|oVtAso`+^baXwll3Rygslg>L#bE*s+Yb@E%$u zDv?&4nMaRFnm=w}@yZ=7=zo$6H_Wf3wnCMmd(fmxiwZTE4F67FQVF`8BXpGZsAM%C;D%o5M^WKPf+)-%G$$0!23|f%zr6Q}qoGPnO^&E>?^1W<^C%Q%U}YK=LgK})i`bNC?R=yz6@ zEXTEWK>om**)V>7#N~Zpl%QtPC)GNBx6+!4p3In!<6(g2wXvP5StBx>3N>Md^&s&G z8-_ydin%3&N38CY{?TgCV(y1eOGTK<9Rj(Yq(m}b&dv!|EJn|OrZdIGAAph-Qu!UM zWy@05OrF)V^qDo6bkE8)IpP=qYC#=s&r_FL;W66z5|pLTDn3*}b&F?hW-@DbjqUDO z?=ckfC%HOwUuhs^km&fPb9gc@$A32+$a?R{Xu0NVuxh7``XUsw9$j<3+ni}Sc!xpHS7`fL)uzGZ8@~uUzAy7Y;=wWy3SYA$ zgFGIS`R%!RZ;lLw$g-m<`ewBT?hHv4`WR6AVgWBrR@m@{9HfiZ@T2g5!cy6q> z(Uk!Fqu)xZrkMIM`W&bOW+z6|@wGJhci6vWcD6Y2{z%p>F=uQwnQjwD2GgM^2}HRL zj#L>l708!x{ce9aQ-S{$0r@-?UB*f8n&84s#DiUJ+ndmwV7@#BPr~Gjx;>tC*DU)S zt`h6~6_~DGgITKJjo=yhOsqtLDry$u7`22OY!;Jd^p97T%b%}_F=e$SzAOg{HkFqU!%j9kgxFX#wI1^7A1{B!D4zHlK5%}ZJn_0j zi*`s6B-3rk&MYB2TUw)m-W@t^7*#*>z!ZftRzO{31e-5(L?&6=(gBy8oV{~e%~&dr z^fFCUe~v}6qK|_YClCXd_nbE;J!nkvH7T4HH&T3d`~KCEdR&t3;j?;tO!ot9()|t@ zWou2W0j1o$uXQet9|}d^iHV=hl!+G9vOx7y{P7w%Ju3CaN;M7^{BIcXkh~?;Qa7~NIY47-Rp>EVgAO?e>VNz#W{;wL?66ac`JE3<>w%xg*hfa7fH` zf521l%iU;PA0NaQw)8YXXBO3}VrkdA2`-B;y$3D0@|FyD)-ydmkG7on6%GhA9hn>@ zv~MXtFO@#nQAEC)40^z+1sX|uq+oiz*X^e7xV`hmE03h%Yb;nIxI8YNO?HH$!DeJf zaWC=Jo=F#03i=M^FyK1ffjH7oikxPfmk04utS57lBYGK@<*tEP2i~jl$9&ZeqiVRRPc_=AGxS&s= ziPe=hRqNdQp}I-CoJMikX%mpnAIVY#84ao{oqJw#ivF^|u>GUkE8g-x?NXUSIhcj0 z*$EEMQ)jnKS)i$QgaOLd$ z894Q+AFU0Z#@bTJWz!66PM+e3S)c?t>(*wB+wQjmrIYXa_g@?|fGhFfx-zFb}JTKuUWkN~wp0hxsfaaxu^)7mizoppskFIkW zB%|rV!4x{o7xSkpqS6P;$D3hql(WBw9_n%h1MrUC7H!oKwb&I9>kQzNwe`!h0DJG% zwZ3S$k^d+nr+gQNeq_Q*|E0wdejS1pzg?qk=sag^p?I5Mu&1Tfi!7?wh^q?Kb;{uL zhtL*bfs1)1`Y7!(CbXut)XUL2=j9Q2hh&DDF6evR_9PoqC*N?svOZfs8=Ao_Fr51+ zf9^pYz?oypXMr;zn%Q6@{^dQq`}4*Xo@AMJF>7P$G7DvM9S9#iqu6V1^z!=*0RAz> z#Jl44QZzQ>AS*b@`A>RM=v3XsU!3iTL>^e9g)ChdDn3->Qdj%TnXUPQs0{tiG%N=2 zXUf+)hQqJ??|ybT^XjG~t-7vlmo=YlwR&TsC{>w5i1NKIXI1^q$DS#f&v}R-;lg(X zJ%4`p6;8HwzJ}($<|4T^9YnNqcDy`2S+_5iuJoR_90xyxuDvcK;h7W$6Md&{va*Nj z``8g#I$dSL`U81DT!K}OcX`$&3GleMjji^_b`7|ZEWQ4Sn3n!s=4xkbdpaVzzN4~xOw)3Cr2qW5rL($({C#s6UKt~j2m}L4r5GDR(bru6FBiV zYM26MChP>0?KF?IdPA4dvKKkx=W~@zd%nJRvt15(jlpUOFxhQEE7xw#4K8v;wwX&{ zCeeHS+dFT^?S}kjY~qE~LW^%`!XI z>n7-a;dHu@aiaPQiAatkKBwi!TKwiYCM)E;u>`qR(QprddvSp1$3QY#>Zr<##?(*V!Qat#2 z6gU(k;p{p)?fT4>>-RJ~6w%HN{H!&?f7cd+UuFC%vhcc-9MW;d>%2R`dN92!BN9M_ z;M+((s;;=!EN*95n>p*echQ!I9lcZDL*1z{QuE8^yV%lH9(({#wFq;3=>S<=5M8j^C|LMjgCt9^Pru%^#n+6cv9KD@K#tyLs{+rTm* z62NeeUF5_Fer?oo`y5#>{AZ&y5@ATX6JAl$51!oZk+fRZN7?M$$vTJm45Qayk=fR+|m+Cn}0(@aG|zIz~`134|kL zX;r&ffHa{LirxcR|=zBKh&$CH7RS!SL52^HO^`z=5@@+ z^+=XQe;Xz;LGWAT9>*f1MvEI?8@3|K8dorVDx=<5WVT6N5Q&$~#dKZ8x0xAWZdu3- z7>U<~9Yg&Fj-L}*vZ_Sz?)_Mct0`b@#)q&(PHQLJy*waj0SLlUt zLxn-tKAQB8gJ7%mcKoBP6ni-Rs(AxcTQ-2~*$`tkgx(rSa}sn{$yr4fmL~g=iGJ%Q zFUL;1K9Q+433IJ_g};r4Ja;~ICmF^T1<@gYX+t(J!H&&AG#yTI#(L3cbj{quHO3%2 zDvJhjzzdl*BCDSfKSQ!|IJ{Y{Z-(X`*{EIa>kKY-!!nDAD9$bk{A((p!e^1VJE-b-M>syV!}z$3~6kU^}D?fP_=UZ&?NSLKj7@@G`0J=*!M{kGN33X zAtAk(*yoV=w4#^sM-0OE_VI%(ayaXPlfZJO;?T6fA6DKEM<(OrcE&8@ugie`hMXvD z$SNV4C**z*h~!6=FE3xc!hv?Ibr;OP6b<1dpe!sGB#*Mky|-mpp)owtQnnJMrB~Du zdG<_F^egc6iuKjw;6YzgA5mXhWPBuTu-vaj1Beg(Q9KGSM_>1la)gghis-zIU(LRL zeg0MrZWIZ49e>rN?L~2jrXyAdH0T{IulDm7h%Z?%+Ep0nHwc#G1O)=BdDAR$D_<#k zzz8(^#{5wHUH>{Q&TE?-*_#`rh)gpoBIV|vNr*!P<|_<`8B z4q+|)B}jM?zDp_X>V!GrrzkJ+^78UvVifiA@rjn27opu5ph9*%M?AavR47&@_Lco5 z@T<%uXh*AW4#(0PF!s*)((;?U*&=UAJ>tgR5d#F`7up!ET8t}68`bz5{1bmuv_+Da z#a7z7i|=eK`a$wb<)Ohekx*zA0C)<%#FNU=rHzsb>AS+m#yiBkrNUk3NSh{SS8~8S z5n2&{PQWFmY8^TRJL@zRSO)Dd?Eb2O@}fQB=pk9VhDC>$x%Dycg{kC$kKwb|IYtX= zdwhIy=Y8WwM%ebjvD*{FlzxzBk}6M{I>lb24ps?b^^uMYUw_od9%sT#Ll2$KeP_5w zNGnQ}iSDIaE>G(r@|L+(W|>1B^?;bJjy^=r^mPaRK(CQkM$Eg?5ek!`4jkiJ%V_6D zDHPG-dZ`Vf*NmBHx1!l24KK;{Hz6H--yHqp&nM8jM+UTRZf~MnJNT(WXmOFVI`AI$ z37@~|JtC{bZ0<{ISfH{?{ZPHXoF>ug~`8MEaq-XAD1UHx_FWF-4S!Vl5q)g)!}sw^Xy{ z#`%I3(?$gum87q2IxXIzuVKd8Ib0iXT*;)A&;&-ATq(e^+K;56VZzjD7&fA{>>_8o z>N4z>&VQ-E6UBs{=9I49$8xepD~KZjdY|8SJPkWddzLP0$}>_~$^&!h93U;F?6`ri z0%eBTqLCv;o(6-M=_#hrNuZIPKn@Mms}4OOsYy(5t}N*1Cly<_?w)0>=g$!%zkYp- z`Q{f(n_!GszFG)fQ>547^zG)T`N_A}V#G$b6~C8z^*%|ha0_?fP3Xe-`>ra<{PSO+ z*kj56s#Z2>#c9Q9lT2So!a!R*60go6moiW?LpZZvV_QN`lK=6-zW0HwV)Hc5J%)tq z^HprH%Hrr2K5mc}>(L$h?t``bVzoQDGMaU0nv%iBt2N__H$v_NwbZfSl*?MI>?G4s z-)#*dT($4|;qS@-7}ZoD{ub$E*WTErAW26KLO$#@xQB^m;Rk7Y{_h*zKtIHB&i zzo5Hww}}9RN569=z1>l(3)pb`?TG=hEVq2@pb`}RN-kyJH*VFg%VDvBx8rxq{;mi6we>x3?CgpwkH>2AB@Lc!-*@;Zxlmo#4IK@Ub-hWSN$-UN z#&yDhL+2_N(_JaA5@MV!T-A3MGq#IaH0#-;cT5NAr<*GKcl*pl6fY_)4IIdXGR&g` zwn_w$ezFdRtlA-_;4@VLvxY=i%y*EkrzrW8MRO2SY~pF9EJw$a6`EFyW|057DrPjZ|2yrCL(fU2=0X`?i%{mi=`%S)qt`Hp9NFSg?*^i54AFO;i2zg%Ng;oHS&72Ni&ZMmxsV1MFq#(L)vmn?6W8^s8M;KUQ-&~I1 zH&@G3v|VVvLP4pfqu%E{>8Eg1Fz@N`SMUXMe}kZ=Xuc?(*`C)bQ!Ry@+q|^*#SmdK z9Nn5f&JzcT+I{!NS$u9B+j72Q>AKK#h=N#;E?suE+l9P-I{YIps z(Mt~GELCuM7zOU}#%(GWeETF|BrU4t=t5d>MwgeuIC*o`NCp{7L;5Z^g z%y&&y`;r#kSNV%PqydxUOV4Em*~bsettr_tI4)6kRtivw zuovIvp|GtyJjya+k~yR7p2dG+6+>vdZEZbfWO~a)5&aDdzheXK%In%dqd9&e8GFjj~`HswrvZ)%U96r73Fov}-Irod+!)1DUkdC%e8$nwY zw2d#}^z~#N>Yw@_q(IT>6apW-rIhtW`HwO@-2{5_nU$|)()g=w2$h9IqUr~tn(ZMT z0shsn-Rz!zvKJVF+75}YE&yys7a?L15y{8%evb>pwMjOzAhs6 zyZ60to3J}V;63OOUv{xJ(bC~q!p@Gdv7-YgtH*si$;Nu5S0FMr_Pc+TUU~~ezhaz; zNyc>L!2tGM`(YpxK`n2y1wN*%LZB%nNhVK)SFA;jw+Fyy|39kU0w}JedmqL+1=mn_kOo-O-pmA!QUNihA$%t7!h3|JN5&_6@Rr zD;6`5gKFBd3*xvp$$`HgN7P%y>i1er5g$U;(}IA-^Llq<@9iC@^oj8)OonSAp$vh!^>@6|ITjYQ2EK*p>D^)D~<^0 zpRq3xi57~Jomd;Q70UITwx0}YySPCx_I)Rgar$KbFrdV0B!>%8_>h*Vzy#USQ2pLW zP42H@HEAlWb#P#3hI&0KdM*v#F``2K15t{Omwmis%y-DF-~6Fq4sfmy0rzhm7qU zF$7&P<#>{T%3#4RGIHH!U1nV*x(KAg*3LJCK+%uPOF^nC*oh2^nB8udi^vPOVjqX! zs>_~|{PZt{=hn)f(+dYY>NwhASQBsOc3VByLXOkW>^BXwNuGQAI-uzozE!*(?RR7$ zMTjL$6sRvW;rw*9CZknlf@!o=0x64B3gLZ3XZ};Dpgv5fEBOY?oYL%>`IS4Ynb}?Y zb77h9UI-iR`)Q`z`!Y$El{THTSgbRUvasU9WI*J^M(k7M)sxyV2!_r!0S+(C%}qf;%#;8=liqQ{h?u>H}v9t z5xMH(?0{7GFb)9>Nm}sL!ymBCY{?v)ly8>iA+e+iIx}NS=@WRfNBR&{!}eJ?8$Vh< znA>tJ7r1Whv|<&pGK;yw4S-prAtCK>!w0fQj$(npH!V6=+AQepLo?Mobi^ zJMI8NkqGit9aWJ<_#l;_DNu^H!ZQ2KYs!Pul45)v)3Xx~kq_YE=lE?qYlBZ9hopLD zA?&Ch5Z=0hu%Uxl2~ZP8mO~a+{8_F&qxkE`TvjJ&rPY;!6MPfoqJF&D3wk75>X1yK zw(zO};jsYwiZFz$Ke6;+GAALGQz>(sYh_-p{o?|hZCV@3Jj7Px~S zee}f9S3m1tVVL_1M+B~Ff2Hk04w?$e^;S6ax^{W4eum&PCrSzRKOJ&8I4Kw3)(YLs zw}?;77_2gAlc~aWW3}R(J${4TXCd&Gwjv)w)B(TdTM$eGDW{AeQ*W$qXjr-lIg9sm zeF#K+C@t8>co_!LtK^#p1&Ai3(LDN;s`_R+>6H|gf=}Zk5mQK9&iERcUVm7ek;;Sm zH$91>EZy{BB)Rt=^J3YI_Oum?cD5a{E-J(84bBE~)weOGGc}4%a#`PqkM{umgL!%- zct^4CTUpv>(o>&U!;|{mOc}=RLuY@MO*(1;ra-gx_JJ&D;8cMOIXx1W?9+dVLeWKwFTR`pc|H*arfmU5u10&REe8I_Vb31d(Ke7tXD_}61-%~ zP%lf)c*&D}p7@BRSR2Ygy|$pQc$n2v5HRN{H3>NJ(_pK)Y@geS~(ttsDqU5QDUAQO6 zJ{?=*JWj4&q1o*tGHN!r%}9+r_3EGaJ&L(&hiovTVz+LStwpSlizCkqo#r` z=v1!wa%#Y!=2DrTA@=Oo^zMvv4_CQrq1pG6VhTiaRarI3xu#- zEf8vAS*$Zyms?C_6K^W@2gVxR(MQ7IM=S{wes}hSIM1IZR=Bfp4iv{+AA2VPeuY!? z*3mS8VGCjDe?OTanG7gUzM67-ud`AdaZ*uy`J-Y@{&d3(09y*x6*X;_@`&v9J^5hy zej{RU9vqW3UeA^Y&SSRIk=))cZI3ukq?cJ64Ly(E0##^%L*THKiy=FxLrhIG%}34? zmTJr)bqsQPQ!RcdFYL!YmE6GHAZ<9SXr~Szkd zy}YK_3dDu>W6OAI;z#!!Qx{@j{2ib+Dg8Q05M6{PKCOh34}@kn5+ z!xpO*M7q_^#==qUhTpIn{+@4rs%*~WuAMkD>X*h!WAziF<~M*6qqsz^{+Wyjrlj>c z;<0jZkkR%uEwe2BpnEqOu>^Fam}ujVX?E#LZG#F6vyX~RK{c8%T+*njaq9DyT3d<7 zRG9-FQ0>bT&j=Ir1Zxou)zX1OLol%Cg88*^V&W;BzusSuXn-Ef_T;l49Wfn*Cqr}n z2h1t|-A4Q+!_zquG|;c)-vw3&63-nd>{fv*7vN8yey~2SUbC~TEI_ls$_J7sjn|l; z8cq9*$lRR`$~k-}(5u6TYR~)l!U@tCwdjAorP?RkDZi(gDt=mUMSZ5^Et$6zh1{%n zGG4$$9VnjK`r&gh*(MC|#!)a4f<(Wgh_TNe2_=&^eu)$OZsOx~zuGiYrz3C#_Q}<} z=JPm$IL4hYIjiMu9QR7uKP5ExeZo|D;ha79#WFE&busL>Ji`Z~mm3#c+c~gpmfn?2 zZ4lu{%@Zih{3-nXcA-w11wb%yR6Xig>PKJMm^E)QF>p>245JEi({x6 ziiGojH1(;G+Nl#XSmMBLy8d)G6+oUSFtl8Wly0s66;lOiqG{8H4I!}a&Sc&lOt$Dm zfo7tKN9ub*>fLA~CQ(hx5Smn9fMu)2A9TKFzkP8e>r1R23x`Ek*kLgSHOzc%1xUN0 zAyd+kF7@DS5`JW;66OtXbXX0cq#G6Njk+Xb^}3_^B1Fgz?f^AgiIQpe!{qfTx(~~4 z%`=&wIWY1zn_^Dvbx&LiZ?;}63+YBTo_MBkrGUS2@Rd1FxgVII94w_t-9D@Q*2-LL zN}xstn5|aM*n+(%uuRf9+|>L98}P&))W=V?h8I1AP5+Eb$mfv|2w$N-dYsC*HuFUE zh+Pc@+3Ip<E~;Zp)uhmWQ8?vWQUR6+sIx|4VS&tNtnu2Buz2RDS!NyRe46S zQm7+?^+1}>Ambu`kDpt=Fz>5mRM;5-ujy6$_EaOrxvLvb&FAykz5Nm!7PE$9a{Ik` z6{Am9xHhOX7d`L}$|7ZK6R1(Y-6$mgSK=S<L4+C&LkS{(Ij<4SfRHj1mY}JjyUAxjU=miL}1P;7|3Rv%Gw7;G+nq2++pJu5)x6 z&gGjFqg9-9c8?nniM547a+1+DUw}j=7dN!iGdY>)>$S@#5rpRf{G2i2Ed{hRzEB$_ zIpMXH83-TBmGY4W)HLP?B=v^@drCQd*>xcj_3tIS>;5?cKK;4C0&_qp^TJe(8BFr~ zF=RI}C=Owgfq>)Ae2dj(*o-W0qGAvG{oe#f9+8EgJrCymN^l^G{ipRLtFYosq=zB)?}0-;H|~rKQtuECePG6-;Y4KJ z9nj-k9P}d)yYrImIJThH^pQB*s~#^4YIuHP@d{Im-5=NHF1yd%a&*QacKbGN^*~HEK#*AC*KAiGfz(#7HM79%y<>HaCNo8Hh z}t)WceoS6BMoXN1YHl8y-ds|(nl+#K-@97nuoK+=X zC4F}&x&105iB5RLB#}+(|JhO$I6F@SycxMm^EL_H(FO5KID7GeDBDQdm*=I+)i+&t z9BJ5IYAJ_*tnIpPQKkN&JTLYeEewZ%fF~FNY5_M{shOF^o={9Q*XL6?Q#!e=pYvNU z2gA-h4`vrXS=nmWN4Y-bfY!?pij%H=G-`~cF}d|%c%tzCe9$9QlYxQAz05UQ(DAzH z=RV+Ma323{G?cE|(2+BiuJD{Jj$IBFW``^1**w5izb2_X0Pl4d6Y<`6AG*W@e2%eU zJ>n*-%iba&CTFx|C+tcEPyK|Dto61fi%5W{EENGlSe7!O{839UDt_uFZy_ zJWlzGD2QJYih0z_DpNSkX?IV6UF&WxwC%DFDqc?L&~5*?jl&vd?8s9CylKodZhrlp znraV(7~Y=k6N*-(5++^fhZ_Z$LTP_PU0y&FmBaw;jcv&MnL8y32*`zF!gn4)Cp3tE z@BOgNa;k#N57^KpSE20b{b2+RJIViu>IF>RXuB$|7@qJ$h-~WtLyv(9iuoeupbIPi zoOZcH`Dff<<1LX46TMAU`2~6>lU!F!M8Jg<3jT6VYYG(<1a?Dqs^SX){|>)z`C{NQ z{&b>`{&Q5${+Pw964@j$&tW%6O~3vK6lAHy#2gwORVOXWVX*6x@UN5imx_8#dUtC5 zQ%ewA$@(-tH2_+|4H@P%43xJU7>ChNWI3RVGu zq|!#Jq_ZX>+WEHk=HxS$14*|P?e>j+jD=c5;Ze?rS)G&fg!{NQajKZf;Yu3@0PY_4 zD|Us5&{M;Jba}rKhl}Sr;L4hSgJ~?<0H- zE;qsdI5;v+LCqB;(iqzAXb`gT7;U-UNG;6Iv!LP%BiTDysfyQnd+?>_qu#Cw#3a^+ zhC1o+VYR9)eTNw6dXaq_Yb_OwY~k|7O2`xiON3B%2BGT9`Pb41hzyVHfspXjg2kDVoFx-FN_0=xSzKZ31lY*BRnWplEhc9NrZJz`aD zMQ)+~j7&Y1al=lW%1_DgTwj&|WLGf!JUQoVRr)c+qU>^Ayw=Qq9Sw7~NwMlX&q()X ziEja&k5yTVI^q+a;`S|?|BkXV*3W(zNfa`siT)8Z3pS|RM8BtGOa>#Eh(z^AFanv52I~0; zYo|Cgvn*u>K@QUno$p+Gc+8(jNQR8Xi|4^!lpU_x+UgQ3u}P&%a+5PKTv(?+!|Q!? z^DQS6H^`~&=d?=2N%xPWu~$hCB}P@0RK-uzD*N>#6< zyVw@=URHdfrwNeOS*S{624&jtkc3fELd#ck*n4eIwgLTC`LnvBrFsE_=1V&ZTHGz> z_n){j=$YxDp6NbuQbI@;8eVZ4mau=zmn!BlEHUPa9I@YAEXwhGimv&znh>SOwzYj6 z?I1%JNO()8;g%F17yo(4pzdSw_cj;!w8zcsPy8F^u<^qQcR^BDS915toe`%07p3_} zr`^0My}K6I*qjV@I4s}04(ZmL7YZdq9+5aE<}7E;0_`@Tim$7Xo=YA1M~Xfl`yEaG z(xUwCd&9-6BrY){)sVh)UfWw|E{$oOFEUlb6o%L_|3$}|bMAK|oxrasM@Z(vEBq2{ zHA02LX+gY22-HS@?kJrBjU0I= zY>OJZ8Fo%>G~bstI=WBBOSBUgUe{i2uByoL_N3vCyuwOI%fIWy}xw*MhYAG_R%JfH(rzN6`vO@KlN^5V4>)Qz`Pm)u|KQai|Y|-t~B`|l6 z!z*ns9MgE5l@{PNbH1&bgWg1J`}(Lz`DJ{46?f6T343ypik4>J(Eb19-9Y+%sE@Ig z^*Wv|LSnITXeMgMoJbmtzYwdJWx1X({4sWdK(cPY4az&>Tk@xoWZO8@a%VX|$Zq4< z#Da4xtGpSXV_XDAkkG3Oe*bQ{R>TCD8~st0h8a;Yx8PEvIr8OCNj?7!zhBa4|NG1W zvh{bgQXLsCfeRa7WHN<}QIb=!71Gnf*^e#cqWc(P3!gpMN(zGv{4+uTGy_KbJ|}ZZp#@mu4$e4P7@PxTeM`I0{2s=`qo&3!V}{u2GH)mp5#@?GAW-pMRE58ma`AT` z!R1pVZME6fehT45D2^Z=;Hs{*m^1%s$8ZG0m1}l9XtN#&iW^!|W8|!ARa7x|hEo)^ zxawUP!SnEe(WpqAot03`8IjB_JpJiIFiTMqVRFsu*FQFTHbUnuvb=UdcOK&v9}}l& z91Sb@+%G?^_}ge}z(Ccbo6*%yxklu%+Ok`4?mZh$AwZk*%NWnoz=ftzn;H1QMV}NG z_;K=7oRPYdjx2Hxu>`T4NM%ivQuvP%_~@IdRxNMJ*QjHLqw^;?a2}Hq9QOW>iYeBH zJ5E^A^Dh)AuIML;&iVTs*oTqkV+@Q@I=ge z*PT87XZK1~N>j;~O#k9TPssFHL0ffQ?!&xk3=NeDa~c0)s*fX@^p#!i^ad7&oNHDm z%|gMHb-2|M3>oYfc11^Cwvb=LPIHmL?ZL)6r}@BcKzh=#62&b4ca!Cr-)lM5WZyYL zvvd^ITto>&?+Q1e1pWLFk&%8E!F33revw12!4`mk-c;GNEMK(vwX>oP0Ht~NF_yXM z_j20EU8jC@{h{o=E|Nagqm$>X$=AF|+wllsvp`}LHV86s(Uy9GD9jXg`o2@YVy%(3 z_~m5o+&~u#mE%x0JX6V|lUr2tT1HlpeEkGM&~l!i5JK|wv!*AC+xKWua$w_W&sK@> zpgm)y;Q2Zu!w-HMuI7_e4ou#RJ%C*R-8kiLFZuYsI>3qq6<$&jH#30kW1^#oAI@&X zrxVS_zyf2f$iD*l|J}}iY0ny6-jKS-TEVwi_bVunqia{5)M?%nP)*V*RthF3S+kMS43hbrag|1yXnaLK#K77&cSr|E+0Fwm5f|t z6S7~JKk?We|BrydZ;E5<1gP%ew0!tQ;C%rIQ)q8T;*Nw@qH!){Yav2d&yV>g%=<&e zWSOL%D*|S+|3r7sH;1y5QT>4)9#``&k_isKL%`_n>D-*1Qj=76K+tG?{>dU>R6ziy zrPN}n-do_EFq~wrY%X}<$Ur#bMl@iqe(*n zhpHU9deR~NDhT+U_z8(=fnVrRo9;cDZ9G^_RGR-@;CF#s)d>vv9X}%efV*YkJHFr9 zuX=>;8GLK9xD6ujA20|JfE&E6KWAfVbt0G28Q8;GLIeFkTW=VcDG(hsb6`AzcoC|wDX zBD!~0<=+5sPPEqyFjHC7hre~MI3nk14e=(M@AYm_TdViP{s^>w;8|OYJrEVTdnRdf zT%i0d%TVfyY@sN~vig9|(R5-4+T$XgaMk?{Q(&2XdGWH42RlkXkb1w0Jx@GV{_~x! zHeT~$S7&rNJx1N&A$r>D0ez_i1E38ny^IUc@*)nc6H}4_3B;yklZZQ;vi#t>g4ygc zRwU;tPTytwZ~47{nf8xa;doCn&K4j?ix$zm--fqIKIJtXY^*-JNLP~~fOfiCAhqir7y zw-BYw#=qy|nXfVu9!=_P%%XMT)%BEgEtEsvo)i9xo%ya`Z1);3`K8)%yH6%^azPy} zD}v3m(cgtwEr`u_zZ)!h(tVJ$qi7s~IP2)-5pK|r%B85)a(TQt8;wb@8R7?X1^Lik z_VzSk?iT-a@+K?yHyA#v<9=+vU^++RAKfG4aqi6=UiQklj-$^y=D*F=0H!jUqe7>z z_oOy8T_4z7%S60I*BCV9y~4*%ajpb^|Ir%#biHB|8~1$1iCS#GnMMTU@Yz6r^souc z8Im1eg5j>v@2d>P{>`9d>>Xvgl@Y|Mw+n?*A&o%7uNTT}h3kQ`CcjP|bhyHaVqwql z#LZ-S`3}&s%n9b{2;?y!4Q@J{_Lz@dYZ4iy3{_%(-FGX8qclnJjD|O*JHFq z)yu?mgiKNicz{4Q*W;@a(MLF#4UmUE#z1Abx$8Z(-$yC3&w?%1BL znKbPxuiU-2h?H|;vX(hc!Zp0kk{1ab*lpzm2K#%47WI&(vfw8dw~ypt5JQnu+HC>N z#y3Uh2?mp^JvnIRl_qz18G}4J)qFVh-dKScAKra)GNsNJT)+G(`8qh{ZBHv-)wG33*It8Xt-7_Ut*(+ z6>PCzHJW3!_lMki^!L(&WPJr)h(PY-j26|>f`J)9Ue}Pz~I$wzGpsE0u@yb!0C(cAoO((-Qr5sDVHc;2s zqnZ_{YTD5H05{9kdJf7Q|7h|GN@YFn0_(Ru!P_(No6UL0cKN4s;TZojj=KBrFbGsp ztUXdckeCzsA#vcf?dAql8r-c5(8AM zt~dBJSxB!$cK%0ey*GP5COpmaIadew0`f0^*2Zh zw4tI~fdy8t2Qp0!&9Pdq*jj)VX{XN-4cGuw3EmShIgd+j<2M)}@r;`_=JPM9hR@`fUr1iuFtpwz<0nr`h(-NYO} zhkK1ICD;I7Sm}G#40mI``u5AZiXjEjW=V*tJ=x)7hy;V)E?8gI0kL+HTrea?R8++r z*4F%n7+I6CE|twO`dpvkauO9>L&ZJfgm-Mu9%nSi*Q+BMj+<08wWY*WH$=094tX45 zuxMiP4Zikjr2B|W;`Ri)?EmDR8c0n`0OQp{e6m0hr%~KbH>6oRh%=R%?wl!zuoGKanq_?%9@(q znBDZgBUR89j*!jlWD>00gFlWx?WoS%k6ZZbVf7Ozezi7`lF#fO+78{QTpdco(-W6a z#F1@*t|m(i)T}fu(tj56{y;hrKQUihmrLx>^;zDS@C9y{-D#M&)~A0HqMP;w&Hq8} z({+k%@wg2wn+Z$;e9<=kX^NgM{*Y)To; zkBh#6M~DL=69JS58NQ!dYEvS<8-HOqMj#Y7Ib}Wy%JcVV`S<@i2mJLjd{X3%%#Q|p z%#Z8P{=nwVB@#jIrt_({xx}mKs;d3$ec?Y?yq2Zu%(xDJQSAJ6#cj(O1%$aW-W7b# zblOWx4O9DZBR3zr;$-OZgUxWXH1qI^xUuiE;>3jsQEx=<#3Y-%K##1;#m1j}0=AD? zj(T+e{0>H(KjR3#NlZt^KRDQbfBLFgK^pzv^S}DCSA6g5ze|RvnDuX}gMY@RAVU@Z zACUULUut@c{y)X>-u7@0`yY0Tf110xApOG{`A^$czJUe30Ak7NxLaiX%?2}Ib@vRP z#hFKHJkG6~1}r||-MRVe^+ZigxAb~~Ifum~J|;z{b%)wSghuvmg(sX{@lW)2)YLx2c%$ik0aVAl(SDgB&)5z=vHSYq;8tb!;<1+0(iT5NfzKl^ zMOO6Sr~!T7oU2y#uc3Oq(HaU=SI5jpj91v7_Cr!|YpNPUekbg)d+c2}tg!w2`hyG7 zMqP+w6P2+BTiHHeYpydNzfGHQfLHgV4#R58V1XfG80HnAp ztAMQkPTYgkBeei>%SmW|Gbep|q2iVCm(J$I6RP_Kz4=QszAlU(BfH%sI3dRp zL;MnotVW1hy59HgD}vNnFF@hls?Il(a|au6>&V}@=YNTU140NSZHcmru!GPW&z@gB ztiy@y^J@(myC8X#!(z|qz{luw;aAAH+Ycub1_KTGx3v+^9yZ_;eRgBYLzk-wde*&M zCfrTL{FePv0}cl6uJLaU*NX-@l$}GaeE;x(zK`_aJ~mutn3#SevraE^6?0KH*+|Pf z;M#RvKF|mq!qCWr_njw?Hw*P-_4=b^j7pfo2+!Bmt-f*;Ne=w8 zpfVV+YQ=uv>n6~ILe7skrex~z?7=ufOEvg7y)tRpo>de$u;(*+y z;%APF`b{kL;ao2G+%Ctr>uNPgbKH_9(+^Sns{kAs4R%3?EgH!EEYH=S>%$n} zgqer!vh-$%R9^87h2m}K7ETP3<=gJlVgqAN?F$ztw^z*xGsQOMLEKdAXXvLmV!TTh zS__4_haJ1+FHT+`qSrp6dQgQA9ikA%$-O0-yfHiyGA=c_-~l7Ql-zP|BIB=YPW4jX z<{I3I)^eyKc)0%Np8eW85Gicp;D)t1M9KH|y(ZY_n0~P#I?G3{q|Bj<%o!agMMi2p z5QShdwzq^bYxbkUH|mqcmW=pXBx|BJn5gLLFwOXBc6?ULkABm}PVQH&p`F%5*CLwY zZb2#aMjX8U#{70nx7a6Z{gv&KYI8gd3z!))QhTC5P!FZWBs3cE+p=Fy);f~(o`y?o zZ2O!g&{HzMte+6WncoWTxey^WD!2Lw2;AeUXl>^$5p_8SV_@Y-c%R!kJ3q#w8=Y%@ zu8!UsBfDHH6I&UAPUANtZjbM=ELj}u9}@tbGdiG$3Pc3&puolAOSx-*nh#XnE@w2K zyP82ot>4=mTJ|9X@+Uk=WrlJWzjp#&Cv5eDo6&iw2c zH`DMgx^?_FS1<_lxXZ*9yad7d8J-MPX`@bcEh0WpK~KId?Z($)*#L7=vUis$#_#ll zkwMpn^T5w(%B+*kZNAf!G+po4Qqw{SSFNTVs~&^8=>69_>?-ExfHpm9wK*;fRz+jX zuY<(AnH(1DgQx3RirV1MV@9e2@fK&>jeqO4k#qR*Gb)se>Z@A|uh(b~tp+dn5VNOJ z2kV|QBwFTD_@y9ej?sY<6M4CrNz+F!}M7`&V7{km5Yp5ez9c zW6btP6vG=?)fVv8NGg9Vi&2cfIcfgKKAW`-me|fgX-4j!247{x<$O$d3#G|^L<^-w zR<*_0cG;5{JsUE@W(aS;>HB1%rTjM20YH9pi}r+u^N{!yUP^#6Nbsk0U$?tKBU8cq zCNFDK`5o8wbycsew(%#}sENbX7%8Mmczos>x6Wxmn88{IEROnXTlGMIHD$(Jw|h<_ zb7E4Tq__mh`*^YKnMB|3)Gqn=@@U5vruC7|B@xl4%4NabsHx+b=XjbQtVSl!kJO&- zaM2-lfd9RcR$bGN%Z1Lq`aoga_kyH}_7`$5fveIIyZ2RqNs=RG{-!&g?Z>yE>n;ra zwFj-7O4RL-x4zGj?3(5cfsO~Bs@{6kZWIN111dehvnu4EcLc!rP<9qRZcx(V=hENHtK=nozKvaf5XHLmx%H_(N z`NnE(ymXFtTCB#tikiBtxDAA~Cd!bN-%yq#gU0$JrFpahbZ((9Ba6@tN492L>|`Lh z(9_y(<(n5?HJkJN>dl$RO(bjAS&ZRi!8QKOu^%put?A{opt%Bpgy(PdjsJEmFx^w=?crCb89R4Ilw| zU_~4b_-UX$Bk|~CjgWR`fB^Rt8A!)Yw5F`C-LAFXQrqP$W=}^+pA6bk+HQ{*RloLR zdH7}+3B}wL^`=0rS>p- z8Tg)mt;N(cNS@v^diiAm-fc&_9NIH(J5%ddX#Ke)?!DExOgFLKJ-l14d9y4v|66}3 zdsrHLdb^DvaL~52%G_G)?5}@3>5_OZmqFiRpQ@zPmZH%cWXa+tuduHjM*!;3WjiGP^T%r!iT5YaoxQUhoE-v zEiKLoceC_`@BZj~#$=LK@OGLa!a6;CICa=x3hpt*bDi$UrIg z*G<)T33J#hj;KP$+rY!+e|H)bS1cUPVx?=38XOe;_SLi*S|Z-l*qouLpdN=iz}>GF zL(h1~3wT8DdxghRgvj!)6U5i$8r&HZ_b6&iTnh?EcErhM6bWz{ME-Bd zOZsZ&)<;Lt1F8q=e*sMUcaay!ky6U*B_7i0E0rK+MiBA3W~m|HMS}=_a{1|$2sZ&``YYK(dlKRXu%y}MR)+_STVBhsvNZxCCac{_z)`l{Fu&f+<+ zcedHqhdVAs2?45Gb^{;G_d8gsG~CQumKw}ET6Uk~Xojr_q$QMGj;}#zrPRvzX)W$z zA|_3&?iT5X0@XPW^B!-e$@a{wyHDlv3JMLSbWE(}xPpc>7E*-O@}}n;qm<|NY!wEx zn5>1MHEs=sK~_Z~8sTHx>y0-iuBR{M@_Ow9o=3+DW|HAr*JlP}58K`ZDP!yy;oGBF z$2zE`eNCrYF3xX>cRqFZ2prxU$}YDP**rvd*cmV1xQgyXnaG6v5{6=G2|lF|a2@ZP z-*)T;p_cU7dLEN<2>!9_vVY8a7BPRVwJU0C9rqOcP*hnoeKPX2xbn1mXm04;=EQ#r z$0}|vY+i=?svR;sHX6r+%5)MM>(VDMKPctNfVFw|*{;5*s;Ytj(dr$> z9WLH6h)pKd18F)2%=T|@hFzXI849PZooTXKvi(pA+-K6}a^m?`*4FGy6?Qb9i%OrX zTNc}V*QsfStO#^wd9N4aeX)3-_r?Bmz#-lpk5nO+ajrPreo~Qc-?tj2=;DOE>?Yr= zmi;o>_X*dmu}FP@jn0a}`K@nQbRWT{iJHK5XMHVuxj!b?sr6VqqTrgkx~QvS{>a3V zQ8wNhM&3!ka+BO*=@KHe@l(9-2K zt15jOx(}wEv~B}!KMjGXKZ4Ns?D?sq@e4A@-_sPfMb!@Zk^xW zwZOv$D+KG*3k$bHCClMrCR#(9S?rqSBUOEzb(EH>CYH1SW`0P_{3&^g8zo(@Um|H9_NBK)fBy%`;CqKGnzg8Aei| z83u~FvdY}8D--e0OWA z_5Q~(MuYvN1}=OHsGk0;p`mT|1KT2MA5$_#zFjpqvwjn?!nTKD%kFereaK57VydDyQ}b-Ti26lE8tvLon9}1L zR|$1aOH72wYx_Ol-WSm!O6*nv!2)Zg^nkZ*r3{?BVC>KmhA5@iapRViC0rNiYk%l< z$_!@hAgKr8%m5ng`05ab7BgIqK#=UqOtsFB?@9)yl9KxiLV^rIS_|V8lq+j_xG4hZ ze|jD_AeITOOKq$u91SxjfYDsXUsyG7NQASUplibq9LaQgQTfA5u|m;7L*1Q|qr-h8 z^rcsZ)h_*W>lR|^`7@>N-Nx~J54Dkl5%t?kz;rX6`{~K~rFPt*S*?8zX2y!`#IMN- zCzqGFiqw$nh3OUCUXqNV8{}eipIo*> z#>MWvU)tZv9VO6yX=H{D5C2dU83OxB6r2A%sHH1i?B5eZf%B2d5@sUH;jlK^Yg zt6iPbX(~<=7k|44v;`m2F==%eBZSSxi2?OBREY{$XA0vOLd*IT1E1zMi_ux{vWqk< z4rif;U0Nzs<5hOBg}o6KNzTRwC(wXxuPOW4l3Qy4JAY19P5FyWBv~~+r#%d!p8Ua? zt0b$dE$SK1-IjoDMrTF*hht;}sG-Af36S`#y1F|XPg^u;yN_|578rE2R0|Nun;GzE zW>)kNY{7DF1w%Tblg#A&{w?uaZ)`RZyQXt)$6J@y-I)oKG_0q z6C`4Uj@4S)tc({iMQ6@YHumVBf!U%6NLLRLl2@hVeLvxD+&^8wz8Jt5bhK8S(AmK; ze%II1qN4F22I{f5@GbR9wU*ewSDi*);?y}wlSeZ_RwCA{01SIyH^pBRSmDvA(1i43RlUKl zho+zZH6*Qk?}j8%>gdQXKvL5bCXNk5?<|d-DkZ!H`oUC{ez#oTLDlwD)cP={F9LCScql>El%(>qbN-1EVi9ztb-(GdqS{ds zxd98sRA|doIRFtY=~Hq+P}?1whd(p=YK>-RN8TknF?z%7(Qx9vH8UMnqoYRh`VeS* zm(&QMoYEOXOV$w!TazWyj{5n?@LTEIV=Q`&ghM(8tr|MPOm(Pd1n!rW2NOIDYPv(;6$P zV2@`9%T6<0MPwlC>qp|}4PaG$YHK6=n(Xi4dh2tu@u zT*!3rMk$cque>~Wc=D@8clM9F?W)R>Uln5$n#Hxbm0}Xy4Jsq z4fNw|QV24jAY1;vMpwiAFQ}}ijPEFRIkmjJc3KZQ<;~O+5psw;8krrUe0X}snLS_c zCAz*!Y;)xUG8`dbj98`UeOa$&0sdiPs(=YPO<46T=Vm)UR2a}Sz#1D9 zW+f4baSw$a;kRG)?ozU`VfQxv&&B=SdEJRdJ0ccCZQ%%RR~iS5-!hvZfP zE`}PVOS*hP`l4%Q*=RFMIkHj>JQe}mTu?*XMh#B0KW(aatypc@~xTpTyV_3?m-Mo5ufwG?bZt8x#4(edrZx52`Q3mMkHMF-z?*a zhpr7F&>)o5MsymPP*7KQ_*gAO1a?i&oPEEUJ^2wT%Ho-li(o%!65bRtFG(QY!iB<2Syv&t0T|2FgU zYSjw@4;cW)77I)wX(&|TrYOlz%GG>VNPM$CMJmqE{>^*;SCHK5J*^pxDW#_7ldwRB zFg@?Sv(!uJqp+13{_-$Tgn4w|HUfX_uQ)4lyE_j>;u@>oR;J;0?s%UM+c$MA1qLe%F6WCTTVd6Z^_#a3 z7i62qTcuXN8Y&Ws!9B)d(GgunL5%^ChPl6q%^C@^&Nbe0Ago2;nPERV&~kmO~a6)(qB&P;B(2R4pLT=w>_oq`*96zqpkdtXnh*(a9Tq(=y_t2Xit~iHiIRl}CvMxv#ZtEYZpEUCq-1M+4wd5P z44#sL{Cm_fSD)~Vl{K}u8WCkJH_*o3&kuD=S_IO|c>A75BMb+#4d8)*^Rl4anpHnrr zbhlXfaiNK>6ymoFRBXWEQFV^sfD_I};5ii?pI&L_HM^XjxQm&J$Zg5F(L7se>b5ZHej+~{1scSwH*VvTgjky^THec-r|$+R3(@8guO*8W7-r!Q2>T6+MF2Mz+(yDI)I z8#kBg9fWGtT>$GSa~Ln4R##j@XzSU@&w6Lxrx=`w=?zSp*%NlFiqv8>=K4)J*q{e> z^RyNDa?9%%ON%|lW0MQ1+ZizkHyDSxv^DBZ)0e>eRkX+)_30o(&li@eZMt6D#fysG81i zRpNc)IM{nhFnLwoMOB&e5#*~HX9IZpBOQm}EhUy%j;=HTZjFi*^6KIjXk1uvBcuT2 zV$)NKS6-)gz|Bj}-WYNAM6&K7WcM+8`=AOq>8h>!;x0_=n&Xtd^bvZ!2m>+!{W9@s%)yB#iekTJ$riAek zLW7W87w}B~#GQBCa-00I`bqdWNrj=D=0L#-ujH^fO`PTJwOo_69)C#m?*7-+&K>bD z_>TdL8yc@Vyg{C6IZ}1lrf;@Y6*Y&`D6#b#!Lc5u%3+1un+RfS&$nF~P*R$lEhr>E z*W#ipf9Im>ktjU3QBPm0cx|%0FtD~;4ELj*B7~rd2|3`2KN?o{Jl%kGW-F(Q_gXThXT6 z%6&5ySZmSFT58dDapBfG8S#5V7Lg*trU`~lLbNs#e$n!|_)t57 zw+?mVsk&0|v{IjxeA5h1O*2+QBpf5Xe!&wg@2xh*`9eY`;AS_nnCRtOEiNqbHD1;a z>qJ%a@M$bF>POj|vRk#XP4JlE;wfzJA4bG-rsk{UY`tZB)DBq?yT+cJ4~|Km*@@6y zOJac)`|iGcRJ3!}_l-_v*!R)4=*35sE@LB?YP;ul4%-&T0NPm%t0WRaA$WRn=NBMA zB2PEI;jz_9r=v<*WWBfL{sBknawxuAhMS{C%RfwtYx0Qc(}K$8^cF@xIXxEmsBUVb4HOJ5<6edSZCl_ z@(kjdM*n9NayKpLG(obfe9nrV-<#3o6!v+&-eC8Bs1GaU9TuL&ayHkA=()Lb%J(Qz z4P6*z>TE`>nSL=bnl>$J=XzbE9*HM!iNiY@QoEOhV^+BIfxEVC)4ZeXd)aqon^fOb zk}9P+K%m9(j7UUt3JeMkSdUn=Ehew)!jMBLwq2Z5%a?PnpmRvvFGNxXE^}-N_ja-E z-3ym&n6o)hg3|qF1#J3-NzqMVwZ5}KNwE*I4|ZPY+NUP&cTg$3d-@r_>6W`#+xC8Z zHT7)|j4(Vea7O#+ON#nDG7?uz^42Sj@k(}|>!4{9FKb9NAq*BMWI zM;myjK^tEODM%Rd^OM{V)`&33QWi6+ZVB2YAvy->gFZuL7HZDx!cqj(QvIg>tNg zmJ&Vm+@*ppBrPNf4LZKz?e4YgNFv8~&^zu|EICpt7q@X!rE=4Cf0Sa>*JP|*2|fu!yQE~8NJCehprIK9WkrHB=hDyji~fvdAZ zNwpOBM2m|#_lwM8?~5R8)Gf9YPXmfU$aN)k`KsYT{sz6dXV1&Y!zp7+;G?GjHBJVf z>Q+HLq*?kr=Fs=t&~8e2H0Do;cH4DbQ-&xsEwJ0c?Ltsnvg1p9X&o&rSwtk)%HB)b zldK@q@TmGp_QZsdWMRS2Uk7;VYK@B$?^qs{$~|WWKb{F)tUE(>Wzkj3d&N5>@-OXi z&KlvuJ9zx6G=S|Rw?obEQH^iE&HLG1K;>;Gq!xUWG!Ym;PwqJD1L!Hrv$Gxt7{zlwtVf1!88h}P;PBy3sRY))GebDPX8&M zgK&ktm$k;=Sw_a&oczy{tmF5GSNOhUT=G5_Iq|6Rgz3h1|5L8)zjS6?2HI6FVr63o z8k#OS$K&cBy+)+OZWH7@8OFB(d#ruAupe1Aet+Y45$Cz|nerD3iI3Zcnz4)3CT4_3 za|SH)46AY%59Z>mk)9p%&eif9yQ@wnS*kE%!kt4tAtUzo5^0a6@nDI%3eyDtMF0$#gYCM0o<4dWWwx?z+=|b#||y1iVL< zox*lUm+oQbN8efe4$l552sM25@Mg0%iGzv`y!P!2qS)xM3on%YIb32b`{nryv`d^{ z&u3P9DpY=DwiU^7=6QQIQg{9XXH!2JTgDfCs?V*v;H;=K8Jz?xF^eqQ{$6v5cq^m5 z;HHfumjjeQqBWK9dbdE8B`SLrH>xS!eGlB8p;*}?Q9u#W^-{!v-zPJ4{4c=KP6YHj zngIg;mvH2r{r{c{{2#>W{~43{|I7aCHnUOmz5QUP_*W%+GnM Date: Tue, 19 Dec 2023 14:19:09 +0900 Subject: [PATCH 093/276] feat(run_out)!: ignore the collision points on crosswalk (#5862) * suppress on crosswalk Signed-off-by: Yuki Takagi --- .../config/run_out.param.yaml | 1 + .../package.xml | 1 + .../src/manager.cpp | 1 + .../src/scene.cpp | 43 ++++++++++++++++--- .../src/scene.hpp | 8 +++- .../src/utils.hpp | 1 + 6 files changed, 47 insertions(+), 8 deletions(-) diff --git a/planning/behavior_velocity_run_out_module/config/run_out.param.yaml b/planning/behavior_velocity_run_out_module/config/run_out.param.yaml index ea63462b32d84..5534228c1b86f 100644 --- a/planning/behavior_velocity_run_out_module/config/run_out.param.yaml +++ b/planning/behavior_velocity_run_out_module/config/run_out.param.yaml @@ -3,6 +3,7 @@ run_out: detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points use_partition_lanelet: true # [-] whether to use partition lanelet map data + suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet: specify_decel_jerk: false # [-] whether to specify jerk when ego decelerates stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin diff --git a/planning/behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_run_out_module/package.xml index 7bd27fca3407c..809579b383461 100644 --- a/planning/behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_run_out_module/package.xml @@ -20,6 +20,7 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs + behavior_velocity_crosswalk_module behavior_velocity_planner_common eigen geometry_msgs diff --git a/planning/behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_run_out_module/src/manager.cpp index 09c87ed81cf38..3ba9bf8bf52e6 100644 --- a/planning/behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_run_out_module/src/manager.cpp @@ -58,6 +58,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) auto & p = planner_param_.run_out; p.detection_method = getOrDeclareParameter(node, ns + ".detection_method"); p.use_partition_lanelet = getOrDeclareParameter(node, ns + ".use_partition_lanelet"); + p.suppress_on_crosswalk = getOrDeclareParameter(node, ns + ".suppress_on_crosswalk"); p.specify_decel_jerk = getOrDeclareParameter(node, ns + ".specify_decel_jerk"); p.stop_margin = getOrDeclareParameter(node, ns + ".stop_margin"); p.passing_margin = getOrDeclareParameter(node, ns + ".passing_margin"); diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index 7a13c0c4f1052..92516e7b4424b 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -14,6 +14,7 @@ #include "scene.hpp" +#include "behavior_velocity_crosswalk_module/util.hpp" #include "path_utils.hpp" #include @@ -23,6 +24,10 @@ #include #include +#include + +#include +#include #include #include @@ -110,8 +115,14 @@ bool RunOutModule::modifyPathVelocity( elapsed_obstacle_creation.count() / 1000.0); // detect collision with dynamic obstacles using velocity planning of ego + const auto crosswalk_lanelets = planner_param_.run_out.suppress_on_crosswalk + ? getCrosswalksOnPath( + planner_data_->current_odometry->pose, *path, + planner_data_->route_handler_->getLaneletMapPtr(), + planner_data_->route_handler_->getOverallGraphPtr()) + : std::vector>(); const auto dynamic_obstacle = - detectCollision(partition_excluded_obstacles, extended_smoothed_path); + detectCollision(partition_excluded_obstacles, extended_smoothed_path, crosswalk_lanelets); // record time for collision check const auto t_collision_check = std::chrono::system_clock::now(); @@ -155,7 +166,8 @@ bool RunOutModule::modifyPathVelocity( } std::optional RunOutModule::detectCollision( - const std::vector & dynamic_obstacles, const PathWithLaneId & path) + const std::vector & dynamic_obstacles, const PathWithLaneId & path, + const std::vector> & crosswalk_lanelets) { if (path.points.size() < 2) { RCLCPP_WARN_STREAM(logger_, "path doesn't have enough points."); @@ -189,7 +201,7 @@ std::optional RunOutModule::detectCollision( debug_ptr_->pushTravelTimeTexts(travel_time, p2.pose, /* lateral_offset */ 3.0); auto obstacles_collision = - checkCollisionWithObstacles(dynamic_obstacles, vehicle_poly, travel_time); + checkCollisionWithObstacles(dynamic_obstacles, vehicle_poly, travel_time, crosswalk_lanelets); if (obstacles_collision.empty()) { continue; } @@ -309,7 +321,8 @@ std::vector RunOutModule::createVehiclePolygon( std::vector RunOutModule::checkCollisionWithObstacles( const std::vector & dynamic_obstacles, - std::vector poly, const float travel_time) const + std::vector poly, const float travel_time, + const std::vector> & crosswalk_lanelets) const { const auto bg_poly_vehicle = run_out_utils::createBoostPolyFromMsg(poly); @@ -338,8 +351,8 @@ std::vector RunOutModule::checkCollisionWithObstacles( *predicted_obstacle_pose_min_vel, *predicted_obstacle_pose_max_vel}; std::vector collision_points; - const bool collision_detected = - checkCollisionWithShape(bg_poly_vehicle, pose_with_range, obstacle.shape, collision_points); + const bool collision_detected = checkCollisionWithShape( + bg_poly_vehicle, pose_with_range, obstacle.shape, crosswalk_lanelets, collision_points); if (!collision_detected) { continue; @@ -398,6 +411,7 @@ std::optional RunOutModule::calcPredictedObstaclePose( bool RunOutModule::checkCollisionWithShape( const Polygon2d & vehicle_polygon, const PoseWithRange pose_with_range, const Shape & shape, + const std::vector> & crosswalk_lanelets, std::vector & collision_points) const { bool collision_detected = false; @@ -420,6 +434,23 @@ bool RunOutModule::checkCollisionWithShape( break; } + if (!collision_points.empty()) { + for (const auto & crosswalk : crosswalk_lanelets) { + const auto poly = crosswalk.second.polygon2d().basicPolygon(); + for (auto it = collision_points.begin(); it != collision_points.end();) { + if (boost::geometry::within(lanelet::BasicPoint2d(it->x, it->y), poly)) { + it = collision_points.erase(it); + } else { + ++it; + } + } + if (collision_points.empty()) { + break; + } + } + collision_detected = !collision_points.empty(); + } + return collision_detected; } diff --git a/planning/behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_run_out_module/src/scene.hpp index b1c49189267d4..def90f036c440 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_run_out_module/src/scene.hpp @@ -24,6 +24,7 @@ #include #include +#include #include namespace behavior_velocity_planner @@ -67,7 +68,8 @@ class RunOutModule : public SceneModuleInterface Polygons2d createDetectionAreaPolygon(const PathWithLaneId & smoothed_path) const; std::optional detectCollision( - const std::vector & dynamic_obstacles, const PathWithLaneId & path_points); + const std::vector & dynamic_obstacles, const PathWithLaneId & path, + const std::vector> & crosswalk_lanelets); float calcCollisionPositionOfVehicleSide( const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & base_pose) const; @@ -77,7 +79,8 @@ class RunOutModule : public SceneModuleInterface std::vector checkCollisionWithObstacles( const std::vector & dynamic_obstacles, - std::vector poly, const float travel_time) const; + std::vector poly, const float travel_time, + const std::vector> & crosswalk_lanelets) const; std::optional findNearestCollisionObstacle( const PathWithLaneId & path, const geometry_msgs::msg::Pose & base_pose, @@ -89,6 +92,7 @@ class RunOutModule : public SceneModuleInterface bool checkCollisionWithShape( const Polygon2d & vehicle_polygon, const PoseWithRange pose_with_range, const Shape & shape, + const std::vector> & crosswalk_lanelets, std::vector & collision_points) const; bool checkCollisionWithCylinder( diff --git a/planning/behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_run_out_module/src/utils.hpp index 6afe451f72f73..5524c0f76049d 100644 --- a/planning/behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_run_out_module/src/utils.hpp @@ -54,6 +54,7 @@ struct RunOutParam { std::string detection_method; bool use_partition_lanelet; + bool suppress_on_crosswalk; bool specify_decel_jerk; double stop_margin; double passing_margin; From cff9a23aed53229fbb51dbaec5879297c52ce063 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 19 Dec 2023 16:37:38 +0900 Subject: [PATCH 094/276] fix(dynamic_avoidance): fix drivable area generation during LC (#5902) * fix(dynamic_avoidance): fix drivable area generation during LC Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 26 ++- .../dynamic_avoidance_module.cpp | 152 ++++++++++++++---- 2 files changed, 135 insertions(+), 43 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index e37ef27d44426..779b7c6106eb0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -143,15 +143,18 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::optional lat_offset_to_avoid{std::nullopt}; bool is_collision_left{false}; bool should_be_avoided{false}; + std::vector ref_path_points_for_obj_poly; void update( const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid, - const bool arg_is_collision_left, const bool arg_should_be_avoided) + const bool arg_is_collision_left, const bool arg_should_be_avoided, + const std::vector & arg_ref_path_points_for_obj_poly) { lon_offset_to_avoid = arg_lon_offset_to_avoid; lat_offset_to_avoid = arg_lat_offset_to_avoid; is_collision_left = arg_is_collision_left; should_be_avoided = arg_should_be_avoided; + ref_path_points_for_obj_poly = arg_ref_path_points_for_obj_poly; } }; @@ -245,11 +248,13 @@ class DynamicAvoidanceModule : public SceneModuleInterface void updateObject( const std::string & uuid, const MinMaxValue & lon_offset_to_avoid, const MinMaxValue & lat_offset_to_avoid, const bool is_collision_left, - const bool should_be_avoided) + const bool should_be_avoided, + const std::vector & ref_path_points_for_obj_poly) { if (object_map_.count(uuid) != 0) { object_map_.at(uuid).update( - lon_offset_to_avoid, lat_offset_to_avoid, is_collision_left, should_be_avoided); + lon_offset_to_avoid, lat_offset_to_avoid, is_collision_left, should_be_avoided, + ref_path_points_for_obj_poly); } } @@ -307,12 +312,16 @@ class DynamicAvoidanceModule : public SceneModuleInterface bool isLabelTargetObstacle(const uint8_t label) const; void updateTargetObjects(); + void updateRefPathBeforeLaneChange(const std::vector & ego_ref_path_points); bool willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const; DecisionWithReason willObjectCutOut( const double obj_tangent_vel, const double obj_normal_vel, const bool is_object_left, const std::optional & prev_object) const; + bool willObjectBeOutsideEgoChangingPath( + const geometry_msgs::msg::Pose & obj_pose, + const autoware_auto_perception_msgs::msg::Shape & obj_shape, const double obj_vel) const; bool isObjectFarFromPath( const PredictedObject & predicted_object, const double obj_dist_to_path) const; double calcTimeToCollision( @@ -327,14 +336,14 @@ class DynamicAvoidanceModule : public SceneModuleInterface const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const; MinMaxValue calcMinMaxLongitudinalOffsetToAvoid( - const std::vector & input_ref_path_points, + const std::vector & ref_path_points_for_obj_poly, const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel, const PredictedPath & obj_path, const autoware_auto_perception_msgs::msg::Shape & obj_shape, const double time_to_collision) const; std::optional calcMinMaxLateralOffsetToAvoid( - const std::vector & input_ref_path_points, const Polygon2d & obj_points, - const double obj_vel, const bool is_collision_left, const double obj_normal_vel, - const std::optional & prev_object) const; + const std::vector & ref_path_points_for_obj_poly, + const Polygon2d & obj_points, const double obj_vel, const bool is_collision_left, + const double obj_normal_vel, const std::optional & prev_object) const; std::pair getAdjacentLanes( const double forward_distance, const double backward_distance) const; @@ -353,7 +362,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::vector target_objects_; // std::vector prev_target_objects_; - std::vector prev_input_ref_path_points; + std::optional> prev_input_ref_path_points_{std::nullopt}; + std::optional> ref_path_before_lane_change_{std::nullopt}; std::shared_ptr parameters_; TargetObjectsManager target_objects_manager_; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 99d7931dff907..a3e4e0e4f3e86 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -137,7 +137,26 @@ double calcObstacleMaxLength(const autoware_auto_perception_msgs::msg::Shape & s return max_length_to_point; } - throw std::logic_error("The shape type is not supported in obstacle_cruise_planner."); + throw std::logic_error("The shape type is not supported in dynamic_avoidance."); +} + +double calcObstacleWidth(const autoware_auto_perception_msgs::msg::Shape & shape) +{ + if (shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + return shape.dimensions.y; + } else if (shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + return shape.dimensions.x; + } else if (shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + double max_length_to_point = 0.0; + for (const auto rel_point : shape.footprint.points) { + const double length_to_point = std::hypot(rel_point.x, rel_point.y); + if (max_length_to_point < length_to_point) { + max_length_to_point = length_to_point; + } + } + return max_length_to_point; + } + throw std::logic_error("The shape type is not supported in dynamic_avoidance."); } double calcDiffAngleAgainstPath( @@ -404,6 +423,8 @@ void DynamicAvoidanceModule::updateTargetObjects() const auto input_ref_path_points = getPreviousModuleOutput().reference_path.points; const auto prev_objects = target_objects_manager_.getValidObjects(); + updateRefPathBeforeLaneChange(input_ref_path_points); + // 1. Rough filtering of target objects target_objects_manager_.initialize(); for (const auto & predicted_object : predicted_objects) { @@ -498,6 +519,8 @@ void DynamicAvoidanceModule::updateTargetObjects() object.predicted_paths.begin(), object.predicted_paths.end(), [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + const auto & ref_path_points_for_obj_poly = input_path.points; + // 2.a. check if object is not to be followed by ego const double obj_angle = calcDiffAngleAgainstPath(input_path.points, object.pose); const bool is_object_aligned_to_path = @@ -535,6 +558,17 @@ void DynamicAvoidanceModule::updateTargetObjects() continue; } + // 2.e. check if the ego will change the lane and the object will be outside the ego's path + // const auto will_object_be_outside_ego_changing_path = + // willObjectBeOutsideEgoChangingPath(object.pose, object.shape, object.vel); + // if (will_object_be_outside_ego_changing_path) { + // RCLCPP_INFO_EXPRESSION( + // getLogger(), parameters_->enable_debug_info, + // "[DynamicAvoidance] Ignore obstacle (%s) since the object will be outside ego's changing + // path", obj_uuid.c_str()); + // continue; + // } + // 2.e. check time to collision const double time_to_collision = calcTimeToCollision(input_path.points, object.pose, object.vel, lat_lon_offset); @@ -590,10 +624,10 @@ void DynamicAvoidanceModule::updateTargetObjects() // "ego_path_base" const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); const auto lon_offset_to_avoid = calcMinMaxLongitudinalOffsetToAvoid( - input_ref_path_points, object.pose, obj_points, object.vel, obj_path, object.shape, + ref_path_points_for_obj_poly, object.pose, obj_points, object.vel, obj_path, object.shape, time_to_collision); const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoid( - input_ref_path_points, obj_points, object.vel, is_collision_left, object.lat_vel, + ref_path_points_for_obj_poly, obj_points, object.vel, is_collision_left, object.lat_vel, prev_object); if (!lat_offset_to_avoid) { RCLCPP_INFO_EXPRESSION( @@ -606,10 +640,37 @@ void DynamicAvoidanceModule::updateTargetObjects() const bool should_be_avoided = true; target_objects_manager_.updateObject( - obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided); + obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided, + ref_path_points_for_obj_poly); } - prev_input_ref_path_points = input_ref_path_points; + prev_input_ref_path_points_ = input_ref_path_points; +} + +void DynamicAvoidanceModule::updateRefPathBeforeLaneChange( + const std::vector & ego_ref_path_points) +{ + if (ref_path_before_lane_change_) { + // check if the ego is close enough to the current ref path, meaning that lane change ends. + const auto ego_pos = getEgoPose().position; + const double dist_to_ref_path = + std::abs(motion_utils::calcLateralOffset(ego_ref_path_points, ego_pos)); + + constexpr double epsilon_dist_to_ref_path = 0.5; + if (dist_to_ref_path < epsilon_dist_to_ref_path) { + ref_path_before_lane_change_ = std::nullopt; + } + } else { + // check if the ego is during lane change. + if (prev_input_ref_path_points_ && !prev_input_ref_path_points_->empty()) { + const double dist_ref_paths = std::abs(motion_utils::calcLateralOffset( + ego_ref_path_points, prev_input_ref_path_points_->front().point.pose.position)); + constexpr double epsilon_ref_paths_diff = 1.0; + if (epsilon_ref_paths_diff < dist_ref_paths) { + ref_path_before_lane_change_ = *prev_input_ref_path_points_; + } + } + } } [[maybe_unused]] std::optional> @@ -765,6 +826,25 @@ DynamicAvoidanceModule::DecisionWithReason DynamicAvoidanceModule::willObjectCut return DecisionWithReason{false}; } +[[maybe_unused]] bool DynamicAvoidanceModule::willObjectBeOutsideEgoChangingPath( + const geometry_msgs::msg::Pose & obj_pose, + const autoware_auto_perception_msgs::msg::Shape & obj_shape, const double obj_vel) const +{ + if (!ref_path_before_lane_change_ || obj_vel < 0.0) { + return false; + } + + // Check if object is in the lane before ego's lane change. + const double dist_to_ref_path_before_lane_change = + std::abs(motion_utils::calcLateralOffset(*ref_path_before_lane_change_, obj_pose.position)); + const double epsilon_dist_checking_in_lane = calcObstacleWidth(obj_shape); + if (epsilon_dist_checking_in_lane < dist_to_ref_path_before_lane_change) { + return false; + } + + return true; +} + std::pair DynamicAvoidanceModule::getAdjacentLanes( const double forward_distance, const double backward_distance) const { @@ -840,13 +920,13 @@ DynamicAvoidanceModule::LatLonOffset DynamicAvoidanceModule::getLateralLongitudi } MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( - const std::vector & input_ref_path_points, + const std::vector & ref_path_points_for_obj_poly, const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel, const PredictedPath & obj_path, const autoware_auto_perception_msgs::msg::Shape & obj_shape, const double time_to_collision) const { const size_t obj_seg_idx = - motion_utils::findNearestSegmentIndex(input_ref_path_points, obj_pose.position); + motion_utils::findNearestSegmentIndex(ref_path_points_for_obj_poly, obj_pose.position); // calculate min/max longitudinal offset from object to path const auto obj_lon_offset = [&]() { @@ -854,7 +934,7 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( for (size_t i = 0; i < obj_points.outer().size(); ++i) { const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); const double lon_offset = motion_utils::calcLongitudinalOffsetToSegment( - input_ref_path_points, obj_seg_idx, geom_obj_point); + ref_path_points_for_obj_poly, obj_seg_idx, geom_obj_point); obj_lon_offset_vec.push_back(lon_offset); } @@ -930,27 +1010,29 @@ double DynamicAvoidanceModule::calcValidStartLengthToAvoid( } std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( - const std::vector & input_ref_path_points, const Polygon2d & obj_points, - const double obj_vel, const bool is_collision_left, const double obj_normal_vel, - const std::optional & prev_object) const + const std::vector & ref_path_points_for_obj_poly, + const Polygon2d & obj_points, const double obj_vel, const bool is_collision_left, + const double obj_normal_vel, const std::optional & prev_object) const { + const bool enable_lowpass_filter = true; + /* const bool enable_lowpass_filter = [&]() { - if (prev_input_ref_path_points.size() < 2) { + if (!prev_ref_path_points_for_obj_poly_ || prev_ref_path_points_for_obj_poly_->size() < 2) { return true; } const size_t prev_front_seg_idx = motion_utils::findNearestSegmentIndex( - prev_input_ref_path_points, input_ref_path_points.front().point.pose.position); - constexpr double min_lane_change_path_lat_offset = 1.0; - if ( - motion_utils::calcLateralOffset( - prev_input_ref_path_points, input_ref_path_points.front().point.pose.position, - prev_front_seg_idx) < min_lane_change_path_lat_offset) { - return true; + *prev_ref_path_points_for_obj_poly_, + ref_path_points_for_obj_poly.front().point.pose.position); constexpr double + min_lane_change_path_lat_offset = 1.0; if ( motion_utils::calcLateralOffset( + *prev_ref_path_points_for_obj_poly_, + ref_path_points_for_obj_poly.front().point.pose.position, prev_front_seg_idx) < + min_lane_change_path_lat_offset) { return true; } // NOTE: When the input reference path laterally changes, the low-pass filter is disabled not to // shift the obstacle polygon suddenly. return false; }(); + */ // calculate min/max lateral offset from object to path const auto obj_lat_abs_offset = [&]() { @@ -958,9 +1040,9 @@ std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoi for (size_t i = 0; i < obj_points.outer().size(); ++i) { const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); const size_t obj_point_seg_idx = - motion_utils::findNearestSegmentIndex(input_ref_path_points, geom_obj_point); - const double obj_point_lat_offset = - motion_utils::calcLateralOffset(input_ref_path_points, geom_obj_point, obj_point_seg_idx); + motion_utils::findNearestSegmentIndex(ref_path_points_for_obj_poly, geom_obj_point); + const double obj_point_lat_offset = motion_utils::calcLateralOffset( + ref_path_points_for_obj_poly, geom_obj_point, obj_point_seg_idx); obj_lat_abs_offset_vec.push_back(obj_point_lat_offset); } return getMinMaxValues(obj_lat_abs_offset_vec); @@ -1027,19 +1109,19 @@ DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( return std::nullopt; } - auto input_ref_path_points = getPreviousModuleOutput().reference_path.points; + auto ref_path_points_for_obj_poly = object.ref_path_points_for_obj_poly; const size_t obj_seg_idx = - motion_utils::findNearestSegmentIndex(input_ref_path_points, object.pose.position); + motion_utils::findNearestSegmentIndex(ref_path_points_for_obj_poly, object.pose.position); const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); const auto lon_bound_start_idx_opt = motion_utils::insertTargetPoint( - obj_seg_idx, object.lon_offset_to_avoid->min_value, input_ref_path_points); + obj_seg_idx, object.lon_offset_to_avoid->min_value, ref_path_points_for_obj_poly); const size_t updated_obj_seg_idx = (lon_bound_start_idx_opt && lon_bound_start_idx_opt.value() <= obj_seg_idx) ? obj_seg_idx + 1 : obj_seg_idx; const auto lon_bound_end_idx_opt = motion_utils::insertTargetPoint( - updated_obj_seg_idx, object.lon_offset_to_avoid->max_value, input_ref_path_points); + updated_obj_seg_idx, object.lon_offset_to_avoid->max_value, ref_path_points_for_obj_poly); if (!lon_bound_start_idx_opt && !lon_bound_end_idx_opt) { // NOTE: The obstacle is longitudinally out of the ego's trajectory. @@ -1049,20 +1131,20 @@ DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( lon_bound_start_idx_opt ? lon_bound_start_idx_opt.value() : static_cast(0); const size_t lon_bound_end_idx = lon_bound_end_idx_opt ? lon_bound_end_idx_opt.value() - : static_cast(input_ref_path_points.size() - 1); + : static_cast(ref_path_points_for_obj_poly.size() - 1); // create inner/outer bound points std::vector obj_inner_bound_points; std::vector obj_outer_bound_points; for (size_t i = lon_bound_start_idx; i <= lon_bound_end_idx; ++i) { - obj_inner_bound_points.push_back( - tier4_autoware_utils::calcOffsetPose( - input_ref_path_points.at(i).point.pose, 0.0, object.lat_offset_to_avoid->min_value, 0.0) - .position); - obj_outer_bound_points.push_back( - tier4_autoware_utils::calcOffsetPose( - input_ref_path_points.at(i).point.pose, 0.0, object.lat_offset_to_avoid->max_value, 0.0) - .position); + obj_inner_bound_points.push_back(tier4_autoware_utils::calcOffsetPose( + ref_path_points_for_obj_poly.at(i).point.pose, 0.0, + object.lat_offset_to_avoid->min_value, 0.0) + .position); + obj_outer_bound_points.push_back(tier4_autoware_utils::calcOffsetPose( + ref_path_points_for_obj_poly.at(i).point.pose, 0.0, + object.lat_offset_to_avoid->max_value, 0.0) + .position); } // create obj_polygon from inner/outer bound points From 165d2af269073b62622ee0e0fdea43dfa713f9bc Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 19 Dec 2023 18:32:45 +0900 Subject: [PATCH 095/276] feat(dynamic_avoidance): deal with forked path of the same directional vehicles (#5901) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 2 +- .../dynamic_avoidance_module.cpp | 16 ++++++++++------ 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 779b7c6106eb0..36106f32158b9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -332,7 +332,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface LatLonOffset getLateralLongitudinalOffset( const std::vector & ego_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const; - double calcValidStartLengthToAvoid( + double calcValidLengthToAvoid( const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const; MinMaxValue calcMinMaxLongitudinalOffsetToAvoid( diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index a3e4e0e4f3e86..eb6724a453f1e 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -962,19 +962,23 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( std::abs(obj_vel) * (is_object_overtaking ? parameters_->end_duration_to_avoid_overtaking_object : parameters_->end_duration_to_avoid_oncoming_object); - if (obj_vel < 0) { - const double valid_start_length_to_avoid = - calcValidStartLengthToAvoid(obj_path, obj_pose, obj_shape); + const double valid_length_to_avoid = calcValidLengthToAvoid(obj_path, obj_pose, obj_shape); + if (obj_vel < -0.5) { return MinMaxValue{ - std::max(obj_lon_offset.min_value - start_length_to_avoid, valid_start_length_to_avoid), + std::max(obj_lon_offset.min_value - start_length_to_avoid, -valid_length_to_avoid), obj_lon_offset.max_value + end_length_to_avoid}; } + if (0.5 < obj_vel) { + return MinMaxValue{ + obj_lon_offset.min_value - start_length_to_avoid, + std::min(obj_lon_offset.max_value + end_length_to_avoid, valid_length_to_avoid)}; + } return MinMaxValue{ obj_lon_offset.min_value - start_length_to_avoid, obj_lon_offset.max_value + end_length_to_avoid}; } -double DynamicAvoidanceModule::calcValidStartLengthToAvoid( +double DynamicAvoidanceModule::calcValidLengthToAvoid( const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const { @@ -1006,7 +1010,7 @@ double DynamicAvoidanceModule::calcValidStartLengthToAvoid( } return obj_path.path.size() - 1; }(); - return -motion_utils::calcSignedArcLength(obj_path.path, 0, valid_obj_path_end_idx); + return motion_utils::calcSignedArcLength(obj_path.path, 0, valid_obj_path_end_idx); } std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( From a6494e81266cc6b46ad36ed4f146667866637a8e Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Wed, 20 Dec 2023 00:26:33 +0900 Subject: [PATCH 096/276] chore(crosswalk, obstacle_cruise): add maintainer (#5898) * add maintainer Signed-off-by: Yuki Takagi Signed-off-by: karishma --- planning/behavior_velocity_crosswalk_module/package.xml | 2 ++ planning/obstacle_cruise_planner/package.xml | 1 + 2 files changed, 3 insertions(+) diff --git a/planning/behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_crosswalk_module/package.xml index 3830aa9edddff..9eef11e72239e 100644 --- a/planning/behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_crosswalk_module/package.xml @@ -10,6 +10,8 @@ Shumpei Wakabayashi Takayuki Murooka Kyoichi Sugahara + Mamoru Sobue + Yuki Takagi Apache License 2.0 diff --git a/planning/obstacle_cruise_planner/package.xml b/planning/obstacle_cruise_planner/package.xml index e724ddb3e6bd7..f6263521bd337 100644 --- a/planning/obstacle_cruise_planner/package.xml +++ b/planning/obstacle_cruise_planner/package.xml @@ -7,6 +7,7 @@ Takayuki Murooka Kosuke Takeuchi Satoshi Ota + Yuki Takagi Apache License 2.0 From 7d7fb140548004ba5d2081f1a746ba92ca5a19bc Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 20 Dec 2023 08:11:11 +0900 Subject: [PATCH 097/276] refactor(avoidance_by_lane_change): update execution condition (#5869) * refactor(avoidance_by_lane_change): update execution condition Signed-off-by: Muhammad Zulfaqar Azmi * fix lc parameter Signed-off-by: Muhammad Zulfaqar Azmi * fix both lane change and avoidance by lane change both are running Signed-off-by: Zulfaqar Azmi * trying to set maximum_avoid_distance Signed-off-by: Muhammad Zulfaqar Azmi * fix avoidance param not properly assigned Signed-off-by: Zulfaqar Azmi * fixed avoidance not running Signed-off-by: Zulfaqar Azmi * fix root lanelet Signed-off-by: Zulfaqar Azmi * removed gdb Signed-off-by: Zulfaqar Azmi * add debug Signed-off-by: Zulfaqar Azmi * fix unnecessary changes Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Signed-off-by: karishma --- .../config/avoidance_by_lc.param.yaml | 8 + .../data_structs.hpp | 6 +- .../interface.hpp | 2 + .../scene.hpp | 3 + .../src/interface.cpp | 6 +- .../src/manager.cpp | 18 +- .../src/scene.cpp | 79 ++-- .../parameter_helper.hpp | 364 ++++++++++++++++++ .../src/manager.cpp | 328 +--------------- .../src/utils/utils.cpp | 8 +- .../src/planner_manager.cpp | 16 +- 11 files changed, 471 insertions(+), 367 deletions(-) create mode 100644 planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp diff --git a/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml index 9518185d30d63..3e8907cdccdf6 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml +++ b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml @@ -85,3 +85,11 @@ bicycle: false # [-] motorcycle: false # [-] pedestrian: false # [-] + + constraints: + # lateral constraints + lateral: + velocity: [1.0, 1.38, 11.1] # [m/s] + max_accel_values: [0.5, 0.5, 0.5] # [m/ss] + min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] + max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp index e177244930da6..8e7d1f67d3157 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp @@ -16,8 +16,6 @@ #include "behavior_path_avoidance_module/data_structs.hpp" -#include - namespace behavior_path_planner { struct AvoidanceByLCParameters : public AvoidanceParameters @@ -27,6 +25,10 @@ struct AvoidanceByLCParameters : public AvoidanceParameters // execute only when lane change end point is before the object. bool execute_only_when_lane_change_finish_before_object{false}; + + explicit AvoidanceByLCParameters(const AvoidanceParameters & param) : AvoidanceParameters(param) + { + } }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp index 016a6b2977701..897956a392008 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp @@ -40,6 +40,8 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface bool isExecutionRequested() const override; + void processOnEntry() override; + protected: void updateRTCStatus(const double start_distance, const double finish_distance) override; }; diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp index f22291c99b8e7..7a82ba60a1eaa 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp @@ -16,6 +16,7 @@ #define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ #include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" +#include "behavior_path_avoidance_module/helper.hpp" #include "behavior_path_lane_change_module/scene.hpp" #include @@ -23,6 +24,7 @@ namespace behavior_path_planner { using AvoidanceDebugData = DebugData; +using helper::avoidance::AvoidanceHelper; class AvoidanceByLaneChange : public NormalLaneChange { @@ -46,6 +48,7 @@ class AvoidanceByLaneChange : public NormalLaneChange ObjectDataArray registered_objects_; mutable ObjectDataArray stopped_objects_; + std::shared_ptr avoidance_helper_; ObjectData createObjectData( const AvoidancePlanningData & data, const PredictedObject & object) const; diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp index 2e451461abab7..efdb302a58ac2 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -45,7 +45,11 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( bool AvoidanceByLaneChangeInterface::isExecutionRequested() const { - return module_type_->specialRequiredCheck() && module_type_->isLaneChangeRequired(); + return module_type_->isLaneChangeRequired() && module_type_->specialRequiredCheck(); +} +void AvoidanceByLaneChangeInterface::processOnEntry() +{ + waitApproval(); } void AvoidanceByLaneChangeInterface::updateRTCStatus( diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 61b0a36ae0fb0..3f810710ef37b 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -14,6 +14,8 @@ #include "behavior_path_avoidance_by_lane_change_module/manager.hpp" +#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" +#include "behavior_path_avoidance_module/parameter_helper.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" @@ -37,7 +39,9 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) // init lane change manager LaneChangeModuleManager::init(node); - AvoidanceByLCParameters p{}; + const auto avoidance_params = getParameter(node); + AvoidanceByLCParameters p(avoidance_params); + // unique parameters { const std::string ns = "avoidance_by_lane_change."; @@ -139,6 +143,18 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); } + // avoidance maneuver (longitudinal) + { + const std::string ns = "avoidance.avoidance.longitudinal."; + p.min_prepare_time = getOrDeclareParameter(*node, ns + "min_prepare_time"); + p.max_prepare_time = getOrDeclareParameter(*node, ns + "max_prepare_time"); + p.min_prepare_distance = getOrDeclareParameter(*node, ns + "min_prepare_distance"); + p.min_slow_down_speed = getOrDeclareParameter(*node, ns + "min_slow_down_speed"); + p.buf_slow_down_speed = getOrDeclareParameter(*node, ns + "buf_slow_down_speed"); + p.nominal_avoidance_speed = + getOrDeclareParameter(*node, ns + "nominal_avoidance_speed"); + } + { const std::string ns = "avoidance.target_filtering.detection_area."; p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 0299e839996b0..619cbc515f816 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -20,6 +20,8 @@ #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include + #include #include @@ -41,7 +43,8 @@ AvoidanceByLaneChange::AvoidanceByLaneChange( const std::shared_ptr & parameters, std::shared_ptr avoidance_parameters) : NormalLaneChange(parameters, LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE, Direction::NONE), - avoidance_parameters_(std::move(avoidance_parameters)) + avoidance_parameters_(std::move(avoidance_parameters)), + avoidance_helper_{std::make_shared(avoidance_parameters_)} { } @@ -49,48 +52,66 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const { const auto & data = avoidance_data_; - if (!status_.is_safe) { + if (data.target_objects.empty()) { return false; } const auto & object_parameters = avoidance_parameters_->object_parameters; - const auto is_more_than_threshold = - std::any_of(object_parameters.begin(), object_parameters.end(), [&](const auto & p) { - const auto & objects = avoidance_data_.target_objects; - - const size_t num = std::count_if(objects.begin(), objects.end(), [&p](const auto & object) { - const auto target_class = - utils::getHighestProbLabel(object.object.classification) == p.first; - return target_class && object.avoid_required; - }); - return num >= p.second.execute_num; - }); + const auto count_target_object = [&](const auto sum, const auto & p) { + const auto & objects = avoidance_data_.target_objects; - if (!is_more_than_threshold) { - return false; - } + const auto is_avoidance_target = [&p](const auto & object) { + const auto target_class = utils::getHighestProbLabel(object.object.classification) == p.first; + return target_class && object.avoid_required; + }; - const auto & front_object = data.target_objects.front(); + return sum + std::count_if(objects.begin(), objects.end(), is_avoidance_target); + }; + const auto num_of_avoidance_targets = + std::accumulate(object_parameters.begin(), object_parameters.end(), 0UL, count_target_object); - const auto THRESHOLD = avoidance_parameters_->execute_object_longitudinal_margin; - if (front_object.longitudinal < THRESHOLD) { + if (num_of_avoidance_targets < 1) { return false; } - const auto path = status_.lane_change_path.path; - const auto to_lc_end = motion_utils::calcSignedArcLength( - status_.lane_change_path.path.points, getEgoPose().position, - status_.lane_change_path.info.shift_line.end.position); - const auto execute_only_when_lane_change_finish_before_object = - avoidance_parameters_->execute_only_when_lane_change_finish_before_object; - const auto not_enough_distance = front_object.longitudinal < to_lc_end; - - if (execute_only_when_lane_change_finish_before_object && not_enough_distance) { + const auto current_lanes = getCurrentLanes(); + if (current_lanes.empty()) { return false; } - return true; + const auto & nearest_object = data.target_objects.front(); + + // get minimum lane change distance + const auto shift_intervals = + getRouteHandler()->getLateralIntervalsToPreferredLane(current_lanes.back(), direction_); + const double minimum_lane_change_length = utils::lane_change::calcMinimumLaneChangeLength( + *lane_change_parameters_, shift_intervals, + lane_change_parameters_->backward_length_buffer_for_end_of_lane); + + // get minimum avoid distance + + const auto ego_width = getCommonParam().vehicle_width; + const auto nearest_object_type = utils::getHighestProbLabel(nearest_object.object.classification); + const auto nearest_object_parameter = + avoidance_parameters_->object_parameters.at(nearest_object_type); + const auto avoid_margin = + nearest_object_parameter.safety_buffer_lateral * nearest_object.distance_factor + + nearest_object_parameter.avoid_margin_lateral + 0.5 * ego_width; + + avoidance_helper_->setData(planner_data_); + const auto shift_length = avoidance_helper_->getShiftLength( + nearest_object, utils::avoidance::isOnRight(nearest_object), avoid_margin); + + const auto maximum_avoid_distance = avoidance_helper_->getMaxAvoidanceDistance(shift_length); + + RCLCPP_DEBUG( + logger_, + "nearest_object.longitudinal %.3f, minimum_lane_change_length %.3f, maximum_avoid_distance " + "%.3f", + nearest_object.longitudinal, minimum_lane_change_length, maximum_avoid_distance); + + return nearest_object.longitudinal > std::max(minimum_lane_change_length, maximum_avoid_distance); } bool AvoidanceByLaneChange::specialExpiredCheck() const diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp new file mode 100644 index 0000000000000..212ed04ade6c6 --- /dev/null +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -0,0 +1,364 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ + +#include "tier4_autoware_utils/ros/parameter.hpp" + +#include +#include + +#include + +#include +#include + +namespace behavior_path_planner +{ +using autoware_auto_perception_msgs::msg::ObjectClassification; +using tier4_autoware_utils::getOrDeclareParameter; + +AvoidanceParameters getParameter(rclcpp::Node * node) +{ + AvoidanceParameters p{}; + // general params + { + const std::string ns = "avoidance."; + p.resample_interval_for_planning = + getOrDeclareParameter(*node, ns + "resample_interval_for_planning"); + p.resample_interval_for_output = + getOrDeclareParameter(*node, ns + "resample_interval_for_output"); + p.enable_bound_clipping = getOrDeclareParameter(*node, ns + "enable_bound_clipping"); + p.enable_cancel_maneuver = getOrDeclareParameter(*node, ns + "enable_cancel_maneuver"); + p.enable_yield_maneuver = getOrDeclareParameter(*node, ns + "enable_yield_maneuver"); + p.enable_yield_maneuver_during_shifting = + getOrDeclareParameter(*node, ns + "enable_yield_maneuver_during_shifting"); + p.disable_path_update = getOrDeclareParameter(*node, ns + "disable_path_update"); + p.publish_debug_marker = getOrDeclareParameter(*node, ns + "publish_debug_marker"); + p.print_debug_info = getOrDeclareParameter(*node, ns + "print_debug_info"); + } + + // drivable area + { + const std::string ns = "avoidance."; + p.use_adjacent_lane = getOrDeclareParameter(*node, ns + "use_adjacent_lane"); + p.use_opposite_lane = getOrDeclareParameter(*node, ns + "use_opposite_lane"); + p.use_intersection_areas = getOrDeclareParameter(*node, ns + "use_intersection_areas"); + p.use_hatched_road_markings = + getOrDeclareParameter(*node, ns + "use_hatched_road_markings"); + } + + // target object + { + const auto get_object_param = [&](std::string && ns) { + ObjectParameter param{}; + param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); + param.moving_speed_threshold = + getOrDeclareParameter(*node, ns + "moving_speed_threshold"); + param.moving_time_threshold = + getOrDeclareParameter(*node, ns + "moving_time_threshold"); + param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); + param.envelope_buffer_margin = + getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); + param.avoid_margin_lateral = + getOrDeclareParameter(*node, ns + "avoid_margin_lateral"); + param.safety_buffer_lateral = + getOrDeclareParameter(*node, ns + "safety_buffer_lateral"); + param.safety_buffer_longitudinal = + getOrDeclareParameter(*node, ns + "safety_buffer_longitudinal"); + param.use_conservative_buffer_longitudinal = + getOrDeclareParameter(*node, ns + "use_conservative_buffer_longitudinal"); + return param; + }; + + const std::string ns = "avoidance.target_object."; + p.object_parameters.emplace( + ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); + p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); + p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); + p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); + p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); + p.object_parameters.emplace( + ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); + p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); + p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); + + p.lower_distance_for_polygon_expansion = + getOrDeclareParameter(*node, ns + "lower_distance_for_polygon_expansion"); + p.upper_distance_for_polygon_expansion = + getOrDeclareParameter(*node, ns + "upper_distance_for_polygon_expansion"); + } + + // target filtering + { + const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { + if (p.object_parameters.count(object_type) == 0) { + return; + } + p.object_parameters.at(object_type).is_avoidance_target = + getOrDeclareParameter(*node, ns); + }; + + const std::string ns = "avoidance.target_filtering."; + set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); + set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); + set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); + set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); + set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); + set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); + set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); + set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); + + p.object_check_goal_distance = + getOrDeclareParameter(*node, ns + "object_check_goal_distance"); + p.threshold_distance_object_is_on_center = + getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); + p.object_check_shiftable_ratio = + getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); + p.object_check_min_road_shoulder_width = + getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); + p.object_check_yaw_deviation = + getOrDeclareParameter(*node, ns + "intersection.yaw_deviation"); + p.object_last_seen_threshold = + getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); + } + + { + const std::string ns = "avoidance.target_filtering.force_avoidance."; + p.enable_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "enable"); + p.threshold_time_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "time_threshold"); + p.object_ignore_section_traffic_light_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); + p.object_ignore_section_crosswalk_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.front_distance"); + p.object_ignore_section_crosswalk_behind_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); + } + + { + const std::string ns = "avoidance.target_filtering.detection_area."; + p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); + p.object_check_min_forward_distance = + getOrDeclareParameter(*node, ns + "min_forward_distance"); + p.object_check_max_forward_distance = + getOrDeclareParameter(*node, ns + "max_forward_distance"); + p.object_check_backward_distance = + getOrDeclareParameter(*node, ns + "backward_distance"); + } + + // safety check general params + { + const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { + if (p.object_parameters.count(object_type) == 0) { + return; + } + p.object_parameters.at(object_type).is_safety_check_target = + getOrDeclareParameter(*node, ns); + }; + + const std::string ns = "avoidance.safety_check."; + set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); + set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); + set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); + set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); + set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); + set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); + set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); + set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); + + p.enable_safety_check = getOrDeclareParameter(*node, ns + "enable"); + p.check_current_lane = getOrDeclareParameter(*node, ns + "check_current_lane"); + p.check_shift_side_lane = getOrDeclareParameter(*node, ns + "check_shift_side_lane"); + p.check_other_side_lane = getOrDeclareParameter(*node, ns + "check_other_side_lane"); + p.check_unavoidable_object = + getOrDeclareParameter(*node, ns + "check_unavoidable_object"); + p.check_other_object = getOrDeclareParameter(*node, ns + "check_other_object"); + p.check_all_predicted_path = + getOrDeclareParameter(*node, ns + "check_all_predicted_path"); + p.safety_check_backward_distance = + getOrDeclareParameter(*node, ns + "safety_check_backward_distance"); + p.hysteresis_factor_expand_rate = + getOrDeclareParameter(*node, ns + "hysteresis_factor_expand_rate"); + p.hysteresis_factor_safe_count = + getOrDeclareParameter(*node, ns + "hysteresis_factor_safe_count"); + } + + // safety check predicted path params + { + const std::string ns = "avoidance.safety_check."; + p.ego_predicted_path_params.min_velocity = + getOrDeclareParameter(*node, ns + "min_velocity"); + p.ego_predicted_path_params.max_velocity = + getOrDeclareParameter(*node, ns + "max_velocity"); + p.ego_predicted_path_params.acceleration = + getOrDeclareParameter(*node, "avoidance.constraints.longitudinal.max_acceleration"); + p.ego_predicted_path_params.time_horizon_for_rear_object = + getOrDeclareParameter(*node, ns + "time_horizon_for_rear_object"); + p.ego_predicted_path_params.time_resolution = + getOrDeclareParameter(*node, ns + "time_resolution"); + p.ego_predicted_path_params.delay_until_departure = + getOrDeclareParameter(*node, ns + "delay_until_departure"); + } + + // safety check rss params + { + const std::string ns = "avoidance.safety_check."; + p.rss_params.longitudinal_distance_min_threshold = + getOrDeclareParameter(*node, ns + "longitudinal_distance_min_threshold"); + p.rss_params.longitudinal_velocity_delta_time = + getOrDeclareParameter(*node, ns + "longitudinal_velocity_delta_time"); + p.rss_params.front_vehicle_deceleration = + getOrDeclareParameter(*node, ns + "expected_front_deceleration"); + p.rss_params.rear_vehicle_deceleration = + getOrDeclareParameter(*node, ns + "expected_rear_deceleration"); + p.rss_params.rear_vehicle_reaction_time = + getOrDeclareParameter(*node, ns + "rear_vehicle_reaction_time"); + p.rss_params.rear_vehicle_safety_time_margin = + getOrDeclareParameter(*node, ns + "rear_vehicle_safety_time_margin"); + p.rss_params.lateral_distance_max_threshold = + getOrDeclareParameter(*node, ns + "lateral_distance_max_threshold"); + } + + // avoidance maneuver (lateral) + { + const std::string ns = "avoidance.avoidance.lateral."; + p.soft_road_shoulder_margin = + getOrDeclareParameter(*node, ns + "soft_road_shoulder_margin"); + p.hard_road_shoulder_margin = + getOrDeclareParameter(*node, ns + "hard_road_shoulder_margin"); + p.lateral_execution_threshold = + getOrDeclareParameter(*node, ns + "lateral_execution_threshold"); + p.lateral_small_shift_threshold = + getOrDeclareParameter(*node, ns + "lateral_small_shift_threshold"); + p.lateral_avoid_check_threshold = + getOrDeclareParameter(*node, ns + "lateral_avoid_check_threshold"); + p.max_right_shift_length = getOrDeclareParameter(*node, ns + "max_right_shift_length"); + p.max_left_shift_length = getOrDeclareParameter(*node, ns + "max_left_shift_length"); + p.max_deviation_from_lane = + getOrDeclareParameter(*node, ns + "max_deviation_from_lane"); + } + + // avoidance maneuver (longitudinal) + { + const std::string ns = "avoidance.avoidance.longitudinal."; + p.min_prepare_time = getOrDeclareParameter(*node, ns + "min_prepare_time"); + p.max_prepare_time = getOrDeclareParameter(*node, ns + "max_prepare_time"); + p.min_prepare_distance = getOrDeclareParameter(*node, ns + "min_prepare_distance"); + p.min_slow_down_speed = getOrDeclareParameter(*node, ns + "min_slow_down_speed"); + p.buf_slow_down_speed = getOrDeclareParameter(*node, ns + "buf_slow_down_speed"); + p.nominal_avoidance_speed = + getOrDeclareParameter(*node, ns + "nominal_avoidance_speed"); + } + + // avoidance maneuver (return shift dead line) + { + const std::string ns = "avoidance.avoidance.return_dead_line."; + p.enable_dead_line_for_goal = getOrDeclareParameter(*node, ns + "goal.enable"); + p.enable_dead_line_for_traffic_light = + getOrDeclareParameter(*node, ns + "traffic_light.enable"); + p.dead_line_buffer_for_goal = getOrDeclareParameter(*node, ns + "goal.buffer"); + p.dead_line_buffer_for_traffic_light = + getOrDeclareParameter(*node, ns + "traffic_light.buffer"); + } + + // yield + { + const std::string ns = "avoidance.yield."; + p.yield_velocity = getOrDeclareParameter(*node, ns + "yield_velocity"); + } + + // stop + { + const std::string ns = "avoidance.stop."; + p.stop_max_distance = getOrDeclareParameter(*node, ns + "max_distance"); + p.stop_buffer = getOrDeclareParameter(*node, ns + "stop_buffer"); + } + + // policy + { + const std::string ns = "avoidance.policy."; + p.policy_approval = getOrDeclareParameter(*node, ns + "make_approval_request"); + p.policy_deceleration = getOrDeclareParameter(*node, ns + "deceleration"); + p.policy_lateral_margin = getOrDeclareParameter(*node, ns + "lateral_margin"); + p.use_shorten_margin_immediately = + getOrDeclareParameter(*node, ns + "use_shorten_margin_immediately"); + + if (p.policy_deceleration != "best_effort" && p.policy_deceleration != "reliable") { + throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); + } + + if (p.policy_lateral_margin != "best_effort" && p.policy_lateral_margin != "reliable") { + throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); + } + } + + // constraints (longitudinal) + { + const std::string ns = "avoidance.constraints.longitudinal."; + p.nominal_deceleration = getOrDeclareParameter(*node, ns + "nominal_deceleration"); + p.nominal_jerk = getOrDeclareParameter(*node, ns + "nominal_jerk"); + p.max_deceleration = getOrDeclareParameter(*node, ns + "max_deceleration"); + p.max_jerk = getOrDeclareParameter(*node, ns + "max_jerk"); + p.max_acceleration = getOrDeclareParameter(*node, ns + "max_acceleration"); + } + + // constraints (lateral) + { + const std::string ns = "avoidance.constraints.lateral."; + p.velocity_map = getOrDeclareParameter>(*node, ns + "velocity"); + p.lateral_max_accel_map = + getOrDeclareParameter>(*node, ns + "max_accel_values"); + p.lateral_min_jerk_map = + getOrDeclareParameter>(*node, ns + "min_jerk_values"); + p.lateral_max_jerk_map = + getOrDeclareParameter>(*node, ns + "max_jerk_values"); + + if (p.velocity_map.empty()) { + throw std::domain_error("invalid velocity map."); + } + + if (p.velocity_map.size() != p.lateral_max_accel_map.size()) { + throw std::domain_error("inconsistency among the constraints map."); + } + + if (p.velocity_map.size() != p.lateral_min_jerk_map.size()) { + throw std::domain_error("inconsistency among the constraints map."); + } + + if (p.velocity_map.size() != p.lateral_max_jerk_map.size()) { + throw std::domain_error("inconsistency among the constraints map."); + } + } + + // shift line pipeline + { + const std::string ns = "avoidance.shift_line_pipeline."; + p.quantize_filter_threshold = + getOrDeclareParameter(*node, ns + "trim.quantize_filter_threshold"); + p.same_grad_filter_1_threshold = + getOrDeclareParameter(*node, ns + "trim.same_grad_filter_1_threshold"); + p.same_grad_filter_2_threshold = + getOrDeclareParameter(*node, ns + "trim.same_grad_filter_2_threshold"); + p.same_grad_filter_3_threshold = + getOrDeclareParameter(*node, ns + "trim.same_grad_filter_3_threshold"); + p.sharp_shift_filter_threshold = + getOrDeclareParameter(*node, ns + "trim.sharp_shift_filter_threshold"); + } + return p; +} +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index f4997d2af12f1..68cee1aa2b523 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -14,6 +14,7 @@ #include "behavior_path_avoidance_module/manager.hpp" +#include "behavior_path_avoidance_module/parameter_helper.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" @@ -33,332 +34,7 @@ void AvoidanceModuleManager::init(rclcpp::Node * node) // init manager interface initInterface(node, {"left", "right"}); - AvoidanceParameters p{}; - // general params - { - const std::string ns = "avoidance."; - p.resample_interval_for_planning = - getOrDeclareParameter(*node, ns + "resample_interval_for_planning"); - p.resample_interval_for_output = - getOrDeclareParameter(*node, ns + "resample_interval_for_output"); - p.enable_bound_clipping = getOrDeclareParameter(*node, ns + "enable_bound_clipping"); - p.enable_cancel_maneuver = getOrDeclareParameter(*node, ns + "enable_cancel_maneuver"); - p.enable_yield_maneuver = getOrDeclareParameter(*node, ns + "enable_yield_maneuver"); - p.enable_yield_maneuver_during_shifting = - getOrDeclareParameter(*node, ns + "enable_yield_maneuver_during_shifting"); - p.disable_path_update = getOrDeclareParameter(*node, ns + "disable_path_update"); - p.publish_debug_marker = getOrDeclareParameter(*node, ns + "publish_debug_marker"); - p.print_debug_info = getOrDeclareParameter(*node, ns + "print_debug_info"); - } - - // drivable area - { - const std::string ns = "avoidance."; - p.use_adjacent_lane = getOrDeclareParameter(*node, ns + "use_adjacent_lane"); - p.use_opposite_lane = getOrDeclareParameter(*node, ns + "use_opposite_lane"); - p.use_intersection_areas = getOrDeclareParameter(*node, ns + "use_intersection_areas"); - p.use_hatched_road_markings = - getOrDeclareParameter(*node, ns + "use_hatched_road_markings"); - } - - // target object - { - const auto get_object_param = [&](std::string && ns) { - ObjectParameter param{}; - param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); - param.moving_speed_threshold = - getOrDeclareParameter(*node, ns + "moving_speed_threshold"); - param.moving_time_threshold = - getOrDeclareParameter(*node, ns + "moving_time_threshold"); - param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); - param.envelope_buffer_margin = - getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); - param.avoid_margin_lateral = - getOrDeclareParameter(*node, ns + "avoid_margin_lateral"); - param.safety_buffer_lateral = - getOrDeclareParameter(*node, ns + "safety_buffer_lateral"); - param.safety_buffer_longitudinal = - getOrDeclareParameter(*node, ns + "safety_buffer_longitudinal"); - param.use_conservative_buffer_longitudinal = - getOrDeclareParameter(*node, ns + "use_conservative_buffer_longitudinal"); - return param; - }; - - const std::string ns = "avoidance.target_object."; - p.object_parameters.emplace( - ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); - p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); - p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); - p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); - p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); - p.object_parameters.emplace( - ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); - p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); - p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); - - p.lower_distance_for_polygon_expansion = - getOrDeclareParameter(*node, ns + "lower_distance_for_polygon_expansion"); - p.upper_distance_for_polygon_expansion = - getOrDeclareParameter(*node, ns + "upper_distance_for_polygon_expansion"); - } - - // target filtering - { - const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { - if (p.object_parameters.count(object_type) == 0) { - return; - } - p.object_parameters.at(object_type).is_avoidance_target = - getOrDeclareParameter(*node, ns); - }; - - const std::string ns = "avoidance.target_filtering."; - set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); - set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); - set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); - set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); - set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); - set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); - set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); - set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); - - p.object_check_goal_distance = - getOrDeclareParameter(*node, ns + "object_check_goal_distance"); - p.threshold_distance_object_is_on_center = - getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); - p.object_check_shiftable_ratio = - getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); - p.object_check_min_road_shoulder_width = - getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); - p.object_check_yaw_deviation = - getOrDeclareParameter(*node, ns + "intersection.yaw_deviation"); - p.object_last_seen_threshold = - getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); - } - - { - const std::string ns = "avoidance.target_filtering.force_avoidance."; - p.enable_force_avoidance_for_stopped_vehicle = - getOrDeclareParameter(*node, ns + "enable"); - p.threshold_time_force_avoidance_for_stopped_vehicle = - getOrDeclareParameter(*node, ns + "time_threshold"); - p.object_ignore_section_traffic_light_in_front_distance = - getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); - p.object_ignore_section_crosswalk_in_front_distance = - getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.front_distance"); - p.object_ignore_section_crosswalk_behind_distance = - getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); - } - - { - const std::string ns = "avoidance.target_filtering.detection_area."; - p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); - p.object_check_min_forward_distance = - getOrDeclareParameter(*node, ns + "min_forward_distance"); - p.object_check_max_forward_distance = - getOrDeclareParameter(*node, ns + "max_forward_distance"); - p.object_check_backward_distance = - getOrDeclareParameter(*node, ns + "backward_distance"); - } - - // safety check general params - { - const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { - if (p.object_parameters.count(object_type) == 0) { - return; - } - p.object_parameters.at(object_type).is_safety_check_target = - getOrDeclareParameter(*node, ns); - }; - - const std::string ns = "avoidance.safety_check."; - set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); - set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); - set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); - set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); - set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); - set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); - set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); - set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); - - p.enable_safety_check = getOrDeclareParameter(*node, ns + "enable"); - p.check_current_lane = getOrDeclareParameter(*node, ns + "check_current_lane"); - p.check_shift_side_lane = getOrDeclareParameter(*node, ns + "check_shift_side_lane"); - p.check_other_side_lane = getOrDeclareParameter(*node, ns + "check_other_side_lane"); - p.check_unavoidable_object = - getOrDeclareParameter(*node, ns + "check_unavoidable_object"); - p.check_other_object = getOrDeclareParameter(*node, ns + "check_other_object"); - p.check_all_predicted_path = - getOrDeclareParameter(*node, ns + "check_all_predicted_path"); - p.safety_check_backward_distance = - getOrDeclareParameter(*node, ns + "safety_check_backward_distance"); - p.hysteresis_factor_expand_rate = - getOrDeclareParameter(*node, ns + "hysteresis_factor_expand_rate"); - p.hysteresis_factor_safe_count = - getOrDeclareParameter(*node, ns + "hysteresis_factor_safe_count"); - } - - // safety check predicted path params - { - const std::string ns = "avoidance.safety_check."; - p.ego_predicted_path_params.min_velocity = - getOrDeclareParameter(*node, ns + "min_velocity"); - p.ego_predicted_path_params.max_velocity = - getOrDeclareParameter(*node, ns + "max_velocity"); - p.ego_predicted_path_params.acceleration = - getOrDeclareParameter(*node, "avoidance.constraints.longitudinal.max_acceleration"); - p.ego_predicted_path_params.time_horizon_for_rear_object = - getOrDeclareParameter(*node, ns + "time_horizon_for_rear_object"); - p.ego_predicted_path_params.time_resolution = - getOrDeclareParameter(*node, ns + "time_resolution"); - p.ego_predicted_path_params.delay_until_departure = - getOrDeclareParameter(*node, ns + "delay_until_departure"); - } - - // safety check rss params - { - const std::string ns = "avoidance.safety_check."; - p.rss_params.longitudinal_distance_min_threshold = - getOrDeclareParameter(*node, ns + "longitudinal_distance_min_threshold"); - p.rss_params.longitudinal_velocity_delta_time = - getOrDeclareParameter(*node, ns + "longitudinal_velocity_delta_time"); - p.rss_params.front_vehicle_deceleration = - getOrDeclareParameter(*node, ns + "expected_front_deceleration"); - p.rss_params.rear_vehicle_deceleration = - getOrDeclareParameter(*node, ns + "expected_rear_deceleration"); - p.rss_params.rear_vehicle_reaction_time = - getOrDeclareParameter(*node, ns + "rear_vehicle_reaction_time"); - p.rss_params.rear_vehicle_safety_time_margin = - getOrDeclareParameter(*node, ns + "rear_vehicle_safety_time_margin"); - p.rss_params.lateral_distance_max_threshold = - getOrDeclareParameter(*node, ns + "lateral_distance_max_threshold"); - } - - // avoidance maneuver (lateral) - { - const std::string ns = "avoidance.avoidance.lateral."; - p.soft_road_shoulder_margin = - getOrDeclareParameter(*node, ns + "soft_road_shoulder_margin"); - p.hard_road_shoulder_margin = - getOrDeclareParameter(*node, ns + "hard_road_shoulder_margin"); - p.lateral_execution_threshold = - getOrDeclareParameter(*node, ns + "lateral_execution_threshold"); - p.lateral_small_shift_threshold = - getOrDeclareParameter(*node, ns + "lateral_small_shift_threshold"); - p.lateral_avoid_check_threshold = - getOrDeclareParameter(*node, ns + "lateral_avoid_check_threshold"); - p.max_right_shift_length = getOrDeclareParameter(*node, ns + "max_right_shift_length"); - p.max_left_shift_length = getOrDeclareParameter(*node, ns + "max_left_shift_length"); - p.max_deviation_from_lane = - getOrDeclareParameter(*node, ns + "max_deviation_from_lane"); - } - - // avoidance maneuver (longitudinal) - { - const std::string ns = "avoidance.avoidance.longitudinal."; - p.min_prepare_time = getOrDeclareParameter(*node, ns + "min_prepare_time"); - p.max_prepare_time = getOrDeclareParameter(*node, ns + "max_prepare_time"); - p.min_prepare_distance = getOrDeclareParameter(*node, ns + "min_prepare_distance"); - p.min_slow_down_speed = getOrDeclareParameter(*node, ns + "min_slow_down_speed"); - p.buf_slow_down_speed = getOrDeclareParameter(*node, ns + "buf_slow_down_speed"); - p.nominal_avoidance_speed = - getOrDeclareParameter(*node, ns + "nominal_avoidance_speed"); - } - - // avoidance maneuver (return shift dead line) - { - const std::string ns = "avoidance.avoidance.return_dead_line."; - p.enable_dead_line_for_goal = getOrDeclareParameter(*node, ns + "goal.enable"); - p.enable_dead_line_for_traffic_light = - getOrDeclareParameter(*node, ns + "traffic_light.enable"); - p.dead_line_buffer_for_goal = getOrDeclareParameter(*node, ns + "goal.buffer"); - p.dead_line_buffer_for_traffic_light = - getOrDeclareParameter(*node, ns + "traffic_light.buffer"); - } - - // yield - { - const std::string ns = "avoidance.yield."; - p.yield_velocity = getOrDeclareParameter(*node, ns + "yield_velocity"); - } - - // stop - { - const std::string ns = "avoidance.stop."; - p.stop_max_distance = getOrDeclareParameter(*node, ns + "max_distance"); - p.stop_buffer = getOrDeclareParameter(*node, ns + "stop_buffer"); - } - - // policy - { - const std::string ns = "avoidance.policy."; - p.policy_approval = getOrDeclareParameter(*node, ns + "make_approval_request"); - p.policy_deceleration = getOrDeclareParameter(*node, ns + "deceleration"); - p.policy_lateral_margin = getOrDeclareParameter(*node, ns + "lateral_margin"); - p.use_shorten_margin_immediately = - getOrDeclareParameter(*node, ns + "use_shorten_margin_immediately"); - - if (p.policy_deceleration != "best_effort" && p.policy_deceleration != "reliable") { - throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); - } - - if (p.policy_lateral_margin != "best_effort" && p.policy_lateral_margin != "reliable") { - throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); - } - } - - // constraints (longitudinal) - { - const std::string ns = "avoidance.constraints.longitudinal."; - p.nominal_deceleration = getOrDeclareParameter(*node, ns + "nominal_deceleration"); - p.nominal_jerk = getOrDeclareParameter(*node, ns + "nominal_jerk"); - p.max_deceleration = getOrDeclareParameter(*node, ns + "max_deceleration"); - p.max_jerk = getOrDeclareParameter(*node, ns + "max_jerk"); - p.max_acceleration = getOrDeclareParameter(*node, ns + "max_acceleration"); - } - - // constraints (lateral) - { - const std::string ns = "avoidance.constraints.lateral."; - p.velocity_map = getOrDeclareParameter>(*node, ns + "velocity"); - p.lateral_max_accel_map = - getOrDeclareParameter>(*node, ns + "max_accel_values"); - p.lateral_min_jerk_map = - getOrDeclareParameter>(*node, ns + "min_jerk_values"); - p.lateral_max_jerk_map = - getOrDeclareParameter>(*node, ns + "max_jerk_values"); - - if (p.velocity_map.empty()) { - throw std::domain_error("invalid velocity map."); - } - - if (p.velocity_map.size() != p.lateral_max_accel_map.size()) { - throw std::domain_error("inconsistency among the constraints map."); - } - - if (p.velocity_map.size() != p.lateral_min_jerk_map.size()) { - throw std::domain_error("inconsistency among the constraints map."); - } - - if (p.velocity_map.size() != p.lateral_max_jerk_map.size()) { - throw std::domain_error("inconsistency among the constraints map."); - } - } - - // shift line pipeline - { - const std::string ns = "avoidance.shift_line_pipeline."; - p.quantize_filter_threshold = - getOrDeclareParameter(*node, ns + "trim.quantize_filter_threshold"); - p.same_grad_filter_1_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_1_threshold"); - p.same_grad_filter_2_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_2_threshold"); - p.same_grad_filter_3_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_3_threshold"); - p.sharp_shift_filter_threshold = - getOrDeclareParameter(*node, ns + "trim.sharp_shift_filter_threshold"); - } + auto p = getParameter(node); parameters_ = std::make_shared(p); } diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 9ff4ed95e09dd..df73990b770a3 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -244,7 +244,9 @@ lanelet::ConstLanelets getTargetNeighborLanes( for (const auto & current_lane : current_lanes) { if (route_handler.getNumLaneToPreferredLane(current_lane) != 0) { - if (type == LaneChangeModuleType::NORMAL) { + if ( + type == LaneChangeModuleType::NORMAL || + type == LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) { neighbor_lanes.push_back(current_lane); } } else { @@ -782,7 +784,9 @@ std::optional getLaneChangeTargetLane( const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const LaneChangeModuleType type, const Direction & direction) { - if (type == LaneChangeModuleType::NORMAL) { + if ( + type == LaneChangeModuleType::NORMAL || + type == LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) { return route_handler.getLaneChangeTarget(current_lanes, direction); } diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 36d5c7773fd24..e4bfff8fc63b8 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -751,9 +751,11 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptrname().find("lane_change") != std::string::npos; }); + const auto success_lane_change = + std::any_of(itr, approved_module_ptrs_.end(), [](const auto & m) { + return m->name().find("lane_change") != std::string::npos || + m->name().find("avoidance_by_lc") != std::string::npos; + }); if (success_lane_change) { root_lanelet_ = updateRootLanelet(data); @@ -837,9 +839,11 @@ void PlannerManager::resetRootLanelet(const std::shared_ptr & data) // when lane change module is running, don't update root lanelet. const bool is_lane_change_running = std::invoke([&]() { - const auto lane_change_itr = std::find_if( - approved_module_ptrs_.begin(), approved_module_ptrs_.end(), - [](const auto & m) { return m->name().find("lane_change") != std::string::npos; }); + const auto lane_change_itr = + std::find_if(approved_module_ptrs_.begin(), approved_module_ptrs_.end(), [](const auto & m) { + return m->name().find("lane_change") != std::string::npos || + m->name().find("avoidance_by_lc") != std::string::npos; + }); return lane_change_itr != approved_module_ptrs_.end(); }); if (is_lane_change_running) { From 8f6020816f9fd85ba776c861bb016131c1b7bffe Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 20 Dec 2023 11:25:56 +0900 Subject: [PATCH 098/276] chore(motion_utils): Enrich error message (#5665) * chore(motion_utils): colorize error message Signed-off-by: Takamasa Horibe * enrich error log Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe Signed-off-by: karishma --- .../motion_utils/resample/resample_utils.hpp | 29 +++-- .../motion_utils/trajectory/trajectory.hpp | 114 ++++++++++++------ .../test/src/trajectory/test_trajectory.cpp | 14 +-- 3 files changed, 102 insertions(+), 55 deletions(-) diff --git a/common/motion_utils/include/motion_utils/resample/resample_utils.hpp b/common/motion_utils/include/motion_utils/resample/resample_utils.hpp index 87a0d54af6619..8bb5f13e3fb78 100644 --- a/common/motion_utils/include/motion_utils/resample/resample_utils.hpp +++ b/common/motion_utils/include/motion_utils/resample/resample_utils.hpp @@ -15,6 +15,8 @@ #ifndef MOTION_UTILS__RESAMPLE__RESAMPLE_UTILS_HPP_ #define MOTION_UTILS__RESAMPLE__RESAMPLE_UTILS_HPP_ +#include "tier4_autoware_utils/system/backtrace.hpp" + #include #include #include @@ -25,6 +27,8 @@ namespace resample_utils { constexpr double close_s_threshold = 1e-6; +#define log_error(message) std::cerr << "\033[31m " << message << " \033[0m" << std::endl; + template bool validate_size(const T & points) { @@ -58,23 +62,28 @@ bool validate_arguments(const T & input_points, const std::vector & resa { // Check size of the arguments if (!validate_size(input_points)) { - std::cerr << "The number of input points is less than 2" << std::endl; + log_error("[resample_utils] invalid argument: The number of input points is less than 2"); + tier4_autoware_utils::print_backtrace(); return false; } if (!validate_size(resampling_intervals)) { - std::cerr << "The number of resampling intervals is less than 2" << std::endl; + log_error( + "[resample_utils] invalid argument: The number of resampling intervals is less than 2"); + tier4_autoware_utils::print_backtrace(); return false; } // Check resampling range if (!validate_resampling_range(input_points, resampling_intervals)) { - std::cerr << "resampling interval is longer than input points" << std::endl; + log_error("[resample_utils] invalid argument: resampling interval is longer than input points"); + tier4_autoware_utils::print_backtrace(); return false; } // Check duplication if (!validate_points_duplication(input_points)) { - std::cerr << "input points has some duplicated points" << std::endl; + log_error("[resample_utils] invalid argument: input points has some duplicated points"); + tier4_autoware_utils::print_backtrace(); return false; } @@ -86,20 +95,24 @@ bool validate_arguments(const T & input_points, const double resampling_interval { // Check size of the arguments if (!validate_size(input_points)) { - std::cerr << "The number of input points is less than 2" << std::endl; + log_error("[resample_utils] invalid argument: The number of input points is less than 2"); + tier4_autoware_utils::print_backtrace(); return false; } // check resampling interval if (resampling_interval < motion_utils::overlap_threshold) { - std::cerr << "resampling interval is less than " << motion_utils::overlap_threshold - << std::endl; + log_error( + "[resample_utils] invalid argument: resampling interval is less than " + + std::to_string(motion_utils::overlap_threshold)); + tier4_autoware_utils::print_backtrace(); return false; } // Check duplication if (!validate_points_duplication(input_points)) { - std::cerr << "input points has some duplicated points" << std::endl; + log_error("[resample_utils] invalid argument: input points has some duplicated points"); + tier4_autoware_utils::print_backtrace(); return false; } diff --git a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp index f2e0c1c0c184c..d81f75815ecc6 100644 --- a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp @@ -30,10 +30,12 @@ #include #include #include +#include #include #include namespace motion_utils { +#define log_error(message) std::cerr << "\033[31m " << message << " \033[0m" << std::endl; /** * @brief validate if points container is empty or not @@ -44,7 +46,7 @@ void validateNonEmpty(const T & points) { if (points.empty()) { tier4_autoware_utils::print_backtrace(); - throw std::invalid_argument("Points is empty."); + throw std::invalid_argument("[motion_utils] validateNonEmpty(): Points is empty."); } } @@ -82,7 +84,7 @@ void validateNonSharpAngle( constexpr double epsilon = 1e-3; if (std::cos(angle_threshold) < product / dist_1to2 / dist_3to2 + epsilon) { tier4_autoware_utils::print_backtrace(); - throw std::invalid_argument("Sharp angle."); + throw std::invalid_argument("[motion_utils] validateNonSharpAngle(): Too sharp angle."); } } @@ -214,7 +216,7 @@ std::optional searchZeroVelocityIndex( try { validateNonEmpty(points_with_twist); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return {}; } @@ -246,7 +248,7 @@ std::optional searchZeroVelocityIndex(const T & points_with_twist, const try { validateNonEmpty(points_with_twist); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return {}; } @@ -336,7 +338,7 @@ std::optional findNearestIndex( try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return {}; } @@ -401,12 +403,17 @@ double calcLongitudinalOffsetToSegment( const bool throw_exception = false) { if (seg_idx >= points.size() - 1) { - const auto error_message{"Segment index is invalid."}; + const std::string error_message( + "[motion_utils] " + std::string(__func__) + + ": Failed to calculate longitudinal offset because the given segment index is out of the " + "points size."); tier4_autoware_utils::print_backtrace(); if (throw_exception) { throw std::out_of_range(error_message); } - std::cerr << error_message << std::endl; + log_error( + error_message + + " Return NaN since no_throw option is enabled. The maintainer must check the code."); return std::nan(""); } @@ -418,18 +425,22 @@ double calcLongitudinalOffsetToSegment( try { validateNonEmpty(overlap_removed_points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return std::nan(""); } } if (seg_idx >= overlap_removed_points.size() - 1) { - const auto error_message{"Same points are given."}; + const std::string error_message( + "[motion_utils] " + std::string(__func__) + + ": Longitudinal offset calculation is not supported for the same points."); tier4_autoware_utils::print_backtrace(); if (throw_exception) { throw std::runtime_error(error_message); } - std::cerr << error_message << std::endl; + log_error( + error_message + + " Return NaN since no_throw option is enabled. The maintainer must check the code."); return std::nan(""); } @@ -575,18 +586,24 @@ double calcLateralOffset( try { validateNonEmpty(overlap_removed_points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error( + std::string(e.what()) + + " Return NaN since no_throw option is enabled. The maintainer must check the code."); return std::nan(""); } } if (overlap_removed_points.size() == 1) { - const auto error_message{"Same points are given."}; + const std::string error_message( + "[motion_utils] " + std::string(__func__) + + ": Lateral offset calculation is not supported for the same points."); tier4_autoware_utils::print_backtrace(); if (throw_exception) { throw std::runtime_error(error_message); } - std::cerr << error_message << std::endl; + log_error( + error_message + + " Return NaN since no_throw option is enabled. The maintainer must check the code."); return std::nan(""); } @@ -637,18 +654,24 @@ double calcLateralOffset( try { validateNonEmpty(overlap_removed_points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error( + std::string(e.what()) + + " Return NaN since no_throw option is enabled. The maintainer must check the code."); return std::nan(""); } } if (overlap_removed_points.size() == 1) { - const auto error_message{"Same points are given."}; + const std::string error_message( + "[motion_utils] " + std::string(__func__) + + ": Lateral offset calculation is not supported for the same points."); tier4_autoware_utils::print_backtrace(); if (throw_exception) { throw std::runtime_error(error_message); } - std::cerr << error_message << std::endl; + log_error( + error_message + + " Return NaN since no_throw option is enabled. The maintainer must check the code."); return std::nan(""); } @@ -684,7 +707,7 @@ double calcSignedArcLength(const T & points, const size_t src_idx, const size_t try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return 0.0; } @@ -727,7 +750,7 @@ std::vector calcSignedArcLengthPartialSum( try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return {}; } @@ -779,7 +802,7 @@ double calcSignedArcLength( try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return 0.0; } @@ -822,7 +845,7 @@ double calcSignedArcLength( try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return 0.0; } @@ -861,7 +884,7 @@ double calcSignedArcLength( try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return 0.0; } @@ -901,7 +924,7 @@ double calcArcLength(const T & points) try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return 0.0; } @@ -1007,7 +1030,7 @@ std::optional calcDistanceToForwardStopPoint( try { validateNonEmpty(points_with_twist); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return {}; } @@ -1041,17 +1064,22 @@ std::optional calcLongitudinalOffsetPoint( try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return {}; } if (points.size() - 1 < src_idx) { - const auto error_message{"Invalid source index"}; + const std::string error_message( + "[motion_utils] " + std::string(__func__) + + " error: The given source index is out of the points size. Failed to calculate longitudinal " + "offset."); tier4_autoware_utils::print_backtrace(); if (throw_exception) { throw std::out_of_range(error_message); } - std::cerr << error_message << std::endl; + log_error( + error_message + + " Return NaN since no_throw option is enabled. The maintainer must check the code."); return {}; } @@ -1118,7 +1146,7 @@ std::optional calcLongitudinalOffsetPoint( try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error("Failed to calculate longitudinal offset: " + std::string(e.what())); return {}; } @@ -1166,21 +1194,25 @@ std::optional calcLongitudinalOffsetPose( try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error("Failed to calculate longitudinal offset: " + std::string(e.what())); return {}; } if (points.size() - 1 < src_idx) { - const auto error_message{"Invalid source index"}; + const std::string error_message( + "[motion_utils] " + std::string(__func__) + + " error: The given source index is out of the points size. Failed to calculate longitudinal " + "offset."); tier4_autoware_utils::print_backtrace(); if (throw_exception) { throw std::out_of_range(error_message); } - std::cerr << error_message << std::endl; + log_error(error_message); return {}; } if (points.size() == 1) { + log_error("Failed to calculate longitudinal offset: points size is one."); return {}; } @@ -1265,7 +1297,7 @@ std::optional calcLongitudinalOffsetPose( try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return {}; } @@ -1311,7 +1343,7 @@ std::optional insertTargetPoint( try { validateNonEmpty(points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return {}; } @@ -1326,7 +1358,7 @@ std::optional insertTargetPoint( try { validateNonSharpAngle(p_front, p_target, p_back); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return {}; } @@ -2192,7 +2224,7 @@ std::optional calcDistanceToForwardStopPoint( try { validateNonEmpty(points_with_twist); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error("Failed to calculate stop distance" + std::string(e.what())); return {}; } @@ -2331,9 +2363,7 @@ T cropPoints( cropped_forward_points, target_pos, modified_target_seg_idx, backward_length); if (cropped_points.size() < 2) { - RCLCPP_ERROR( - rclcpp::get_logger("obstacle_avoidance_planner.trajectory_utils"), - ". Return original points since cropped_points size is less than 2."); + log_error("Return original points since cropped_points size is less than 2."); return points; } @@ -2378,18 +2408,22 @@ double calcYawDeviation( try { validateNonEmpty(overlap_removed_points); } catch (const std::exception & e) { - std::cerr << e.what() << std::endl; + log_error(e.what()); return 0.0; } } if (overlap_removed_points.size() <= 1) { - const auto error_message{"points size is less than 2"}; + const std::string error_message( + "[motion_utils] " + std::string(__func__) + + " Given points size is less than 2. Failed to calculate yaw deviation."); tier4_autoware_utils::print_backtrace(); if (throw_exception) { throw std::runtime_error(error_message); } - std::cerr << error_message << std::endl; + log_error( + error_message + + " Return 0 since no_throw option is enabled. The maintainer must check the code."); return 0.0; } diff --git a/common/motion_utils/test/src/trajectory/test_trajectory.cpp b/common/motion_utils/test/src/trajectory/test_trajectory.cpp index 22567b569d0ad..6664e6154bdfd 100644 --- a/common/motion_utils/test/src/trajectory/test_trajectory.cpp +++ b/common/motion_utils/test/src/trajectory/test_trajectory.cpp @@ -1883,7 +1883,7 @@ TEST(trajectory, insertTargetPoint) const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertTargetPoint(base_idx, p_target, traj_out.points); - EXPECT_STREQ(testing::internal::GetCapturedStderr().c_str(), "Sharp angle.\n"); + EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle"), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } @@ -1896,7 +1896,7 @@ TEST(trajectory, insertTargetPoint) const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertTargetPoint(base_idx, p_target, traj_out.points); - EXPECT_STREQ(testing::internal::GetCapturedStderr().c_str(), "Sharp angle.\n"); + EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle"), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } @@ -1909,7 +1909,7 @@ TEST(trajectory, insertTargetPoint) const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertTargetPoint(base_idx, p_target, traj_out.points); - EXPECT_STREQ(testing::internal::GetCapturedStderr().c_str(), "Sharp angle.\n"); + EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle"), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } @@ -2310,7 +2310,7 @@ TEST(trajectory, insertTargetPoint_Length) const auto p_target = createPoint(4.0, 10.0, 0.0); const auto insert_idx = insertTargetPoint(4.0, p_target, traj_out.points); - EXPECT_STREQ(testing::internal::GetCapturedStderr().c_str(), "Sharp angle.\n"); + EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } @@ -4317,7 +4317,7 @@ TEST(trajectory, insertStopPoint_with_pose_and_segment_index) const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertStopPoint(base_idx, p_target, traj_out.points); - EXPECT_STREQ(testing::internal::GetCapturedStderr().c_str(), "Sharp angle.\n"); + EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } @@ -4330,7 +4330,7 @@ TEST(trajectory, insertStopPoint_with_pose_and_segment_index) const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertStopPoint(base_idx, p_target, traj_out.points); - EXPECT_STREQ(testing::internal::GetCapturedStderr().c_str(), "Sharp angle.\n"); + EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } @@ -4343,7 +4343,7 @@ TEST(trajectory, insertStopPoint_with_pose_and_segment_index) const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertStopPoint(base_idx, p_target, traj_out.points); - EXPECT_STREQ(testing::internal::GetCapturedStderr().c_str(), "Sharp angle.\n"); + EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } From fa8e6d7869c1042e4709f67a524ae991b7a0e647 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 20 Dec 2023 13:01:05 +0900 Subject: [PATCH 099/276] feat(intersection): disable stuck detection against private lane (#5910) Signed-off-by: Mamoru Sobue Signed-off-by: karishma --- .../config/intersection.param.yaml | 3 +-- .../src/manager.cpp | 9 +++------ .../src/scene_intersection.cpp | 10 ++++++---- .../src/scene_intersection.hpp | 10 +++------- 4 files changed, 13 insertions(+), 19 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 997addd48d7f8..6fc136c512689 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -23,8 +23,7 @@ stuck_vehicle_velocity_threshold: 0.833 # enable_front_car_decel_prediction: false # assumed_front_car_decel: 1.0 - timeout_private_area: 3.0 - enable_private_area_stuck_disregard: false + disable_against_private_lane: true yield_stuck: turn_direction: diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 789708abe98f8..e859b15b345b8 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -74,10 +74,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".stuck_vehicle.stuck_vehicle_detect_dist"); ip.stuck_vehicle.stuck_vehicle_velocity_threshold = getOrDeclareParameter(node, ns + ".stuck_vehicle.stuck_vehicle_velocity_threshold"); - ip.stuck_vehicle.timeout_private_area = - getOrDeclareParameter(node, ns + ".stuck_vehicle.timeout_private_area"); - ip.stuck_vehicle.enable_private_area_stuck_disregard = - getOrDeclareParameter(node, ns + ".stuck_vehicle.enable_private_area_stuck_disregard"); + ip.stuck_vehicle.disable_against_private_lane = + getOrDeclareParameter(node, ns + ".stuck_vehicle.disable_against_private_lane"); ip.yield_stuck.turn_direction.left = getOrDeclareParameter(node, ns + ".yield_stuck.turn_direction.left"); @@ -201,7 +199,6 @@ void IntersectionModuleManager::launchNewModules( } const std::string location = ll.attributeOr("location", "else"); - const bool is_private_area = (location.compare("private") == 0); const auto associative_ids = planning_utils::getAssociativeIntersectionLanelets(ll, lanelet_map, routing_graph); bool has_traffic_light = false; @@ -213,7 +210,7 @@ void IntersectionModuleManager::launchNewModules( } const auto new_module = std::make_shared( module_id, lane_id, planner_data_, intersection_param_, associative_ids, turn_direction, - has_traffic_light, enable_occlusion_detection, is_private_area, node_, + has_traffic_light, enable_occlusion_detection, node_, logger_.get_child("intersection_module"), clock_); generateUUID(module_id); /* set RTC status as non_occluded status initially */ diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index e036fac13fd3b..5909d607f6351 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -97,8 +97,8 @@ IntersectionModule::IntersectionModule( [[maybe_unused]] std::shared_ptr planner_data, const PlannerParam & planner_param, const std::set & associative_ids, const std::string & turn_direction, const bool has_traffic_light, - const bool enable_occlusion_detection, const bool is_private_area, rclcpp::Node & node, - const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) + const bool enable_occlusion_detection, rclcpp::Node & node, const rclcpp::Logger logger, + const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), node_(node), lane_id_(lane_id), @@ -107,7 +107,6 @@ IntersectionModule::IntersectionModule( has_traffic_light_(has_traffic_light), enable_occlusion_detection_(enable_occlusion_detection), occlusion_attention_divisions_(std::nullopt), - is_private_area_(is_private_area), occlusion_uuid_(tier4_autoware_utils::generateUUID()) { velocity_factor_.init(PlanningBehavior::INTERSECTION); @@ -1056,8 +1055,11 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // stuck vehicle detection is viable even if attention area is empty // so this needs to be checked before attention area validation const bool stuck_detected = checkStuckVehicle(planner_data_, path_lanelets); + const bool is_first_conflicting_lane_private = + (std::string(first_conflicting_lane.attributeOr("location", "else")).compare("private") == 0); if (stuck_detected) { - if (is_private_area_ && planner_param_.stuck_vehicle.enable_private_area_stuck_disregard) { + if (!(is_first_conflicting_lane_private && + planner_param_.stuck_vehicle.disable_against_private_lane)) { } else { std::optional stopline_idx = std::nullopt; if (stuck_stopline_idx_opt) { diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 7366bdc1bc0e6..2f8c296a348b9 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -74,8 +74,7 @@ class IntersectionModule : public SceneModuleInterface bool use_stuck_stopline; double stuck_vehicle_detect_dist; double stuck_vehicle_velocity_threshold; - double timeout_private_area; - bool enable_private_area_stuck_disregard; + bool disable_against_private_lane; } stuck_vehicle; struct YieldStuck @@ -263,8 +262,8 @@ class IntersectionModule : public SceneModuleInterface const int64_t module_id, const int64_t lane_id, std::shared_ptr planner_data, const PlannerParam & planner_param, const std::set & associative_ids, const std::string & turn_direction, const bool has_traffic_light, - const bool enable_occlusion_detection, const bool is_private_area, rclcpp::Node & node, - const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); + const bool enable_occlusion_detection, rclcpp::Node & node, const rclcpp::Logger logger, + const rclcpp::Clock::SharedPtr clock); /** * @brief plan go-stop velocity at traffic crossing with collision check between reference path @@ -314,9 +313,6 @@ class IntersectionModule : public SceneModuleInterface // vehicles are very slow std::optional initial_green_light_observed_time_{std::nullopt}; - // for stuck vehicle detection - const bool is_private_area_; - // for RTC const UUID occlusion_uuid_; bool occlusion_safety_{true}; From 81b02f2bdabd330dff1ad25ec0bc880bdaee0e88 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Wed, 20 Dec 2023 14:01:47 +0900 Subject: [PATCH 100/276] fix(run_out): do not insert stop point when stopped in Object method (#5911) Signed-off-by: Tomohito Ando Signed-off-by: karishma --- .../src/scene.cpp | 21 +++++++++++++------ 1 file changed, 15 insertions(+), 6 deletions(-) diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index 92516e7b4424b..b14152863d8d0 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -615,16 +615,25 @@ std::optional RunOutModule::calcStopPoint( // vehicle have to decelerate if there is not enough distance with deceleration_jerk const bool deceleration_needed = *stop_dist > dist_to_collision - planner_param_.run_out.stop_margin; - // avoid acceleration when ego is decelerating - // TODO(Tomohito Ando): replace with more appropriate method - constexpr float epsilon = 1.0e-2; - constexpr float stopping_vel_mps = 2.5 / 3.6; - const bool is_stopping = current_vel < stopping_vel_mps && current_acc < epsilon; - if (!deceleration_needed && !is_stopping) { + const auto & detection_method = planner_param_.run_out.detection_method; + + if (!deceleration_needed && detection_method == "Object") { debug_ptr_->setAccelReason(RunOutDebug::AccelReason::LOW_JERK); return {}; } + // If the detection method assumes running out, avoid acceleration when the ego is decelerating. + // TODO(Tomohito Ando): replace with more appropriate way + if (!deceleration_needed && detection_method != "Object") { + constexpr float epsilon = 1.0e-2; + constexpr float stopping_vel_mps = 2.5 / 3.6; + const bool is_stopping = current_vel < stopping_vel_mps && current_acc < epsilon; + if (!is_stopping) { + debug_ptr_->setAccelReason(RunOutDebug::AccelReason::LOW_JERK); + return {}; + } + } + // calculate the stop point for base link const float base_to_collision_point = planner_param_.run_out.stop_margin + planner_param_.vehicle_param.base_to_front; From e8dedb2f93fca6778ea15a340726b0c70d906a7b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 20 Dec 2023 14:03:09 +0900 Subject: [PATCH 101/276] fix(start_planner): refine shift pull out path to start pose (#5874) * fix(start_planner): refine shift pull out path to start pose Signed-off-by: kosuke55 * fix typo Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 Signed-off-by: karishma --- .../shift_pull_out.hpp | 4 ++ .../src/shift_pull_out.cpp | 54 +++++++++++++++++++ 2 files changed, 58 insertions(+) diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp index 9012504ed2e7a..2d50ae189dc13 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp @@ -46,6 +46,10 @@ class ShiftPullOut : public PullOutPlannerBase double calcBeforeShiftedArcLength( const PathWithLaneId & path, const double target_after_arc_length, const double dr); + bool refineShiftedPathToStartPose( + ShiftedPath & shifted_path, const Pose & start_pose, const Pose & end_pose, + const double longitudinal_acc, const double lateral_acc); + std::shared_ptr lane_departure_checker_; private: diff --git a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp index 73952ca02f558..35281d5bedbcf 100644 --- a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -158,6 +158,58 @@ std::optional ShiftPullOut::plan(const Pose & start_pose, const Pos return std::nullopt; } +bool ShiftPullOut::refineShiftedPathToStartPose( + ShiftedPath & shifted_path, const Pose & start_pose, const Pose & end_pose, + const double longitudinal_acc, const double lateral_acc) +{ + constexpr double TOLERANCE = 0.01; + constexpr size_t MAX_ITERATION = 100; + + // Lambda to check if change is above tolerance + auto is_within_tolerance = + [](const auto & prev_val, const auto & current_val, const auto & tolerance) { + return std::abs(current_val - prev_val) < tolerance; + }; + + size_t iteration = 0; + while (iteration < MAX_ITERATION) { + const double lateral_offset = + motion_utils::calcLateralOffset(shifted_path.path.points, start_pose.position); + + PathShifter path_shifter; + path_shifter.setPath(shifted_path.path); + ShiftLine shift_line{}; + shift_line.start = start_pose; + shift_line.end = end_pose; + shift_line.end_shift_length = lateral_offset; + path_shifter.addShiftLine(shift_line); + path_shifter.setVelocity(0.0); + path_shifter.setLongitudinalAcceleration(longitudinal_acc); + path_shifter.setLateralAccelerationLimit(lateral_acc); + + if (!path_shifter.generate(&shifted_path, false)) { + RCLCPP_WARN( + rclcpp::get_logger("ShiftPullOut:refineShiftedPathToStartPose()"), + "Failed to generate shifted path"); + return false; + } + + if (is_within_tolerance( + lateral_offset, + motion_utils::calcLateralOffset(shifted_path.path.points, start_pose.position), + TOLERANCE)) { + return true; + } + + iteration++; + } + + RCLCPP_WARN( + rclcpp::get_logger("ShiftPullOut:refineShiftedPathToStartPose()"), + "Failed to converge lateral offset until max iteration"); + return false; +} + std::vector ShiftPullOut::calcPullOutPaths( const RouteHandler & route_handler, const lanelet::ConstLanelets & road_lanes, const Pose & start_pose, const Pose & goal_pose) @@ -303,6 +355,8 @@ std::vector ShiftPullOut::calcPullOutPaths( if (!path_shifter.generate(&shifted_path, offset_back)) { continue; } + refineShiftedPathToStartPose( + shifted_path, start_pose, *shift_end_pose_ptr, longitudinal_acc, lateral_acc); // set velocity const size_t pull_out_end_idx = From 2da6c2d3844b82190b0b151e769242ef2a717a55 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 20 Dec 2023 18:09:09 +0900 Subject: [PATCH 102/276] refactor(traffic_light_module): boost::optional to std::optional (#5912) Signed-off-by: Muhammad Zulfaqar Signed-off-by: karishma --- .../behavior_velocity_traffic_light_module/package.xml | 1 - .../behavior_velocity_traffic_light_module/src/debug.cpp | 2 -- .../behavior_velocity_traffic_light_module/src/manager.cpp | 1 - .../behavior_velocity_traffic_light_module/src/manager.hpp | 3 ++- .../behavior_velocity_traffic_light_module/src/scene.cpp | 7 ++----- .../behavior_velocity_traffic_light_module/src/scene.hpp | 7 +++---- 6 files changed, 7 insertions(+), 14 deletions(-) diff --git a/planning/behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_traffic_light_module/package.xml index c658f0890b986..39c454e59dcb2 100644 --- a/planning/behavior_velocity_traffic_light_module/package.xml +++ b/planning/behavior_velocity_traffic_light_module/package.xml @@ -24,7 +24,6 @@ eigen geometry_msgs lanelet2_extension - libboost-dev motion_utils pluginlib rclcpp diff --git a/planning/behavior_velocity_traffic_light_module/src/debug.cpp b/planning/behavior_velocity_traffic_light_module/src/debug.cpp index 9a0ba4f37c3c0..b3dedaa29d6ad 100644 --- a/planning/behavior_velocity_traffic_light_module/src/debug.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/debug.cpp @@ -26,8 +26,6 @@ namespace behavior_velocity_planner { -using tier4_autoware_utils::appendMarkerArray; - visualization_msgs::msg::MarkerArray TrafficLightModule::createDebugMarkerArray() { visualization_msgs::msg::MarkerArray debug_marker_array; diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_traffic_light_module/src/manager.cpp index 908627540bdcc..fa1a516c107b0 100644 --- a/planning/behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/manager.cpp @@ -23,7 +23,6 @@ #include #include #include -#include #include namespace behavior_velocity_planner { diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.hpp b/planning/behavior_velocity_traffic_light_module/src/manager.hpp index c36c6af1128ce..87213d8a5ed3f 100644 --- a/planning/behavior_velocity_traffic_light_module/src/manager.hpp +++ b/planning/behavior_velocity_traffic_light_module/src/manager.hpp @@ -26,6 +26,7 @@ #include #include +#include namespace behavior_velocity_planner { @@ -57,7 +58,7 @@ class TrafficLightModuleManager : public SceneModuleManagerInterfaceWithRTC // Debug rclcpp::Publisher::SharedPtr pub_tl_state_; - boost::optional first_ref_stop_path_point_index_; + std::optional first_ref_stop_path_point_index_; }; class TrafficLightModulePlugin : public PluginWrapper diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp index a74ff8c0cb5e8..d2d18d74a5c1a 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp @@ -19,7 +19,6 @@ #include #include -#include // To be replaced by std::optional in C++17 #include @@ -31,9 +30,7 @@ #include #include -#include #include -#include #include namespace behavior_velocity_planner @@ -52,14 +49,14 @@ bool getBackwardPointFromBasePoint( return true; } -boost::optional findNearestCollisionPoint( +std::optional findNearestCollisionPoint( const LineString2d & line1, const LineString2d & line2, const Point2d & origin) { std::vector collision_points; bg::intersection(line1, line2, collision_points); if (collision_points.empty()) { - return boost::none; + return std::nullopt; } // check nearest collision point diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_traffic_light_module/src/scene.hpp index 6e46709267427..c7b2472289bf5 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.hpp @@ -17,7 +17,6 @@ #include #include -#include #include #include @@ -81,7 +80,7 @@ class TrafficLightModule : public SceneModuleInterface inline State getTrafficLightModuleState() const { return state_; } - inline boost::optional getFirstRefStopPathPointIndex() const + inline std::optional getFirstRefStopPathPointIndex() const { return first_ref_stop_path_point_index_; } @@ -130,9 +129,9 @@ class TrafficLightModule : public SceneModuleInterface // prevent stop chattering std::unique_ptr
}*Qr}mf>J(^U|(W09n3 zPB@yNSyz%UwxCr~{Sgy2q5O$|Xv^bKQdIEos53kt3Vf$lKj_j=8uw#WZB9jD4lbZ1 zGBoMM3)9L6qgJn>{YP8q(BbAS>vwn5VR^7bpa>9Po&Wyp)8wCVk{9ZR!DtBIp_P0H zepVR}JXl+eQsT7;<}BA;VB)pI9p9W_z0O5rA-v}d`N=cxhnLgx?*D$OC4UHJb3<^gX3?8{Z+i!sTHA6xWO2U1Z+=|}?cDT-f1H=|%ai6G zfvkgxCx81l>F5W3lPn-Wmtu&o7CE?@Zz`fj8#}PG1ltH z+GZrRPO6~o1n*)#mbnw_W+H@p_1Z;}{mKml(&(%iP--=%`A2!hVHMp;id)9SH7w1J~b{m1Lf{BTf|3fp+JwwNT=l6EIpSyECmY^NzUvlMk z_g*J+N9Pim+qQ3iM*7LS)7i?pN*wi{XMWa4eV50VG8Bo0L{eWJzq6V;5D*VpsijF% zS-_OqXcx(XNhxRXm!+nxQj$SgLqk_QG~PE$^YQiN5zR(59X!}X^=)>t*iEH|fb4ID zBhcSJOV=(>K$&Td;&7>+$8#sWaV>mvvxaOfMlv@UP~s;SNhG*=bpDv;~jVI`hqbBGf!Z# znlmAFH{C3!yu=X5Dww$NPoDzc;2^cW^kpSB%ez2uy2p!gJjL3lV#-ahX9RN~4s>Vdy|5Zvrp zzDCdc#3zgO7L)zj0D-K6iAUdgpGZOJYHKSJ(5Tl#bLY-2axTsa3wrx8=35-6+T$m3 zB9m5;z-Bq<1XipsJv&I3&JV#rJF@bjj2BaDyO|E(2EA;#qL(GIh1*@c1YqvcWe&|+ zlpN~oXrR|g*RPCYH7-ngt%_Rf*JdNwc&VnzN)7FHGFW5@RN-b)UO63sfG0>J{WEm- z>=;BO!Xgu~UeiFCsiE71GCpZESL%0AB(^}K<56;XlXIQ1(OmLJP!u%r;>vs+=AR=z z@{IT?9$C)Prt=~AH?z9IB7%tOdTYkec~Et6P5DKz2cfi+CgsVuxWTR$9uZ9~(y(zi=O|y-;!MPpBaTws<%!3ET!tb2P3nm#NKl-G`e>tO>-OJv&`0d@*! zu0>LY_AIe&e9e)gOJr^~(vvNB2(VM^nJ2Hq?K2F0_8^o|mdgoLkWy?sS`B^n;#z^p z-RLXeOpE*qy;?_2mS*CI>jKIQozotg#S5Izg$M9DjbGxXVTi|0uiZTjbl_lP#`VM% zfT|qg4iR9^mV3r4f(V~;{d+KViE(5pRCNhz+Y5QuMb6I-FE0--FaoPfnpStmpjT2G z$n=&)b*|LEC$q0ubw|(;azUAC$S26v%dJXyL+HRC;MIz;~t8Ip!$R# z>&3LO3hvp=r7+lKmSVg37SnMmg^KD-b!63nAAuFTRJ}TvKsjgqG&1d5zq@!)o1lKO zr>9Sfp9oR*RM^}5D3*i{Ko8Qv7z*2ec4u{)d1<@8meiut|+nO-=jh2 zfCRe45nx`#=)_8uxzv#CHEL>aQm-|i6VD(8%9#8@-ZdIX^8C0d@jIr&0*OYMls0D` z1e?q?bl9`Xq$VN}8vgFLX%NoU)}DQI;2rmoslB5l(e{rF)6*z-deLX@FFIaFNdlVZ zPG=NM^nK|e7)d3l2hpu;xkq3j9v1;c$~=!rQq}tpERne_on5=G`JDSv?(P{mOEC;j ziV;XLCUEcaLp+v)GwBCbK0TIWN)s{3Qc~882#~&sQ+tUf!byr9fVf{ z`(l-PJO8P_CqqLc?S=P+Y{iX0M#03>fB5^#;eF`V4C}c(bvP~z_(e>C=QcgBA zV2gM!CMsHWRzcS0GAJKPQZ8Mbpi!(S$AZfN730@8M-dhJCF zhwNIG2yiLN#Hfp|U7e(v3HJ&`o%B;_K=AKqG>gE2vk?3O$R(7K1cHWGgu)0MIC$Vs zCSJ={UI@6o3F;jR(`F@2i6}TVP-SvM;&ncjB4@AULoh0K{N8jNY7t%$Sv7EWCLTLU zeP4c3$CFXo9t-?j`Um`MESuir;6`OgQS z+b>O_3NfF-sVNauh~VPldD57nzYm^8E&MGw$lxCl*)~RiiMqpACTQg9gpg+B6~aIy zNDf!>0k1?bp=dOb4sx>XaL~3{Y{6>93mD)SIHHM5ZJT%E13 znPGruTmCLFzk*kqIj}IHY(=*6MqqZvM^`T+fIx{{1SL(IHe|DEVV-#SI8=2k3K1}b z@w*bmmTtgU-iXQ3F>hkcA{3IKF=QWHC}r}D2ZT@rx7Bwr%E_ zr|J4bUqp}+2eJCzq%Xswq;|IFD(3w!f9^9-KvU6yUwvmWceCRAwq-Ce^XxM;@}nQn z&Hv|5Djuw&0DvWE2l|Cd6mM>r&zL(p5m+So7B-Ye$)IojnexLm``U8@#Gh_|gq*%$ z(nN}DSy7^(YB7@nFO+5z2Nh~E=qs71onP`|A-+on4NBXPv9MqZ1Y35aX2B%p8F*vQ`cdshv|$1p~*1mA}?B&?2}@i5DVN zCMDH(n5YH{JzBYjlR3~8vS-*EBR5FZzNz4nr^sqPgi@shp}G#rOpUmQmdoTag~$yK z>*f1DCln(0yzx!c`jVHH^)sKx`Pc{FOV9u0Kas4;$n-AR{r$EKCa&P7)z{YxgA>_` z4}tk;R2b%^Bxpl3GgNcv@DiEZ)Ye{noi1RH_=R8u(70MMFYSluKLzX@jaKiF%X$~CBI`b00!ig8iegqcAg#@u<@m9@%RYcBK7-~&Y z5o#;2ityi~kr=!n+%$*mRA|vuj=MRJ734lHYeE?$OTHp}5J7|j@}Aa4J+*Wj$!y77 zma_k_SfZ%rp z$>TuT2{v}6<{*KylI%yrpK$~b{AZ^pPQlPT)MM0SY0^eU$tXPpSfQ!f z3Tf6&oT}4DCGM*!1Q8%rhdoJUC-#oes5DFd5d8o2FqdnE$y{R>#2vQr`w*BIhvD28 z$#M1!b-e1AsOy(sM=C>Qm0iYzK|1-qchl{E{c$ojx0K$^RRKNTG??H>@W~JV7TtaS z=PLk;@*HAdY;2LteNJRB^mX-1Sqs*1R%$bM(JVWJP{}iLEt#cYF9Ih541YKRrIlp8 zG?zRno6RCik%@z8+2K=R16s|m;9!DRubl`i*mXO-`9m?9bgVQfWAbfHy@i@V#%=AW zAuHq^Wh)E<9tbXs4$YA=79;PR7vJw_GHAeen*#@4G+5o#IwdJB_&qdfsJ1~XGm?dw zx?R6&x_dR3xE|=<{F%4_WhVEypWFx{Vj(V*O$HI{4Z)cR&U|t+*^JZ%Wv2Sp8tjn$ zup-Vm>V4=zntbXBlrsGS?R~?WNo}!Yf1)xuf_*c*$jTi5o!={y5tY|4HVr1&HIa$G z$A0U>e6>|en=8xdHbww_JOrcfHi8LiD4YsJ?h zxM=INBXd!WRmsZxZtd26!DUH(1Jg7zG)oRhxbk>MQO!_4VprSe8z%M%pj`Y5C4IdEVaN(2r#)$ zy76SOu~f>xf=e2>jZb-L809oGPy`Ahd$Ex@-fDw0CS#gx2H|wepGJJL>6vWH2qcZ( zl9H>zXb|N}KAJbukkG4tUWtaYautyTq|yTe>HU038T5~s=Upk6mR4Q-=l$V ze4R|Kt#kl}bC#~|a-D)5jcWlJ$j71Vbo7HCqUr+&cXTd!aBdOUFqmK~^Ru7$TYCPd z{wcRtlxHgq1n}eO8y*6Y8zoT)EZCvj)Y7`dx2QgNh!pBVlm+Ype0ZZC@1LfD3&>KW zJ#_emh7G9LOhMasR_jX-o{$Vua)PV&t8X&$OUsn!Wk z0yQ`l8#dHb8_jw$SP@)cWs?Jp?Y^88D`p$@i+vfQP*htsd5e(O?G;4ns4qrgY|$V} zQIIi=;~j8%c54H;Dg+FM8ZAmqbky9TC$(AzYNd8xP3@uIq;whA`F9G z3e1MYeq83bnh(KhOwD^5pv=@jyfCnx#%0IjKYfJyzWOE7)!3=$EpHRPQL=50z~tkP z(a?9lO?Q0!?<7=3gusTu#L#!XMJzLV@SX1}qVCGB6bb=eJ#j(bI^}QS9~%`b1DuZK z&C=Obc7{2uLC@~ltN@d0yjtpyAlc!YrbJ%1ND$!iCoY3BYoP#!7Y}YR zy!B4aB(oOYSs&HI5HV$5l}We9X8gqK?rdhoyo*}YU)N!?pj@hyTWmfCcj#ocA>|Go zLU~8n8x?^=B!IvHpNS>6;I*Tjo&%9OzOtl=RkSo_4H@g;M%}C^O+ED_ z^*;O{#66VYM7)(6Zo7S3r>fM0p8A~+QBRqTkKV)W<0M zp9chDev}-rBln_tUOXHUt14U)ReStIS((d-EXDbiSqffB4aS3{uhCHB5o9SqkwavdGG$IB@WXeInx!jE2bx8D_sHiV`JcA&_Z^1`{Ak$EeNGgQnqTlju9YenE~R?m*;CKa z)&Kery6aQ_T&hDTyMC`5OmO<`kzaW$-Tm*Mhu(JfHt%JJk{r;M2n44lmja8q3l~TO z2|GLZ7J|%;AVaAyZJA8YQd~bZM6Man3M_mPA5@>>B1>UwH__FBh)@SfJ*?{Sz>=nS zTi!lpx5Ik;iu6IU)GQn1F`3(s&!89TLyIMK5pV%UrkAr}nSj&NW+RPOO%-4*zdA_!!)O9@o^gmmHAI^?1BAJ?Er&C_%9Zd$_DW61xp6z}n4&i7LGOF>zXJ zR?$34Ow>mBK-jidUXlr(a-Z@-fR&rhUr8ELrt>0FqjdCn$l32DgT^4#nNrPM4SClC zO;pzcdDk5@4^$Md{Kx&M_L!zUuYaRhsI5{-1H>IbNc=~#U=^@L{vJ9$=cuG<^87DwPZZg(v7^qRJ5*y2}a;a7#4u@!{+Hmk7oTBlWU^2sETawMi z=>w6KUL5O<+hS6Z*|>6bRwDujHPn{yX;g{Na&J=nAip#0aK(j8utA@Gui+-;($$#= zO`M&DPlTTIydmqi|Hdw%ytb3Z<-qJ(%_YKJuX!zXy!thj?d`M^FjpPRm|pnwC+V(F z|7%4`+UF3;oSbUiV50Y-2gJ)Br{QFi2<#MrL0QJ3}>x4lk)hncCWS zdWl^yP5KQ~BD=-Ha#2 zRRPT7G;MlnF2}FG`4(z>*((aw1$o^?1lA2Ee*V9Ij}H9GuaZqlZ^;`a4+yZcdNQy` z1{d4}ksF>S%(o~NDdH&@Wc8mLS&^l1`C)G64bTE!@Kh}ps#@eyq+n##kghh!3#yCh zWohdd^MY;CefN(}mwFF8(WslX!{aHN8bWZ;n=e9T87pBhOB?gDR2^yYgs2G{O+lp=9?-V8Dv zsmwtpW7sS+!KG75DAFiE3|DIq7(wkOffq6lWO3D6a5aojY9jxt(vnQBD)*5Htd9Wm zAI9MoVL@qJCgr1?HLgl(ye2haH)w-TOi>KN0M(Fu=62IB91#-DnKUL;4}9ZmH1fmm z3(*=@8q(J{WOAt7XNL%!|K#73xvPu1e))AfJd-?pCkU(wCZ?bMIgLO12;KPmf4GzL z%3~!0+d_cJ|L*J81mA-FExbd6WZl~%f(zzcSoiELO7)BB5eN01MV10DZK)Q3g3X)< zE68}cQnzxJVkK|l*g=r}iYh~~ttpcS6(Is_sS#Fhy+toHbUfQ4*g@8c>4)}k9f02QDlq=+Q#feVp_$UM_Can?cp>5#}w@b~Ayt$V1U-M%SIT*5mH&x65lf0NjI zY2Vx40pq#0QiHan`^zO|Kl|uM=mr1$8B!TC3;s%az(v~mHNnK?&wYlBEiKgX%2yX@ zmu0sq34uf?B!UWuD2X~xoJOuWawMq|1+^$cV^h(sQ%4Q24KW;7x$=J-- z?Q(&PJV!Yoke>Be$?r(xdw}O5oWXH}U75LD4#SpXC;$Siz%(%fGsDQTT3C8F3=p;as*y(SXcQQy*=jVjmwLxPfdvi4%xwB{Gs8PZ?@%TybA|A%G#w1=|Yfs!*0A%DP z(-DZe-Sot7|0a~3{<$dL0V;8JRs<7aheM=`?!N!?m57BLbEzQ!l^8CAN*U*|RGg`$ zHOWt{GnD`UAOJ~3K~%SZ1T8ysE7XONl;kW$-`QcB9djt3;W2= zrbQ5JhT226jA8tvwLt{xnX z3ggf9+6psJwu{K&%X~`Fi34COcoW?2dfm0H@2I;X6yoc`m+kYUPeRHl$F0Lofu@Zq5!Nj>weuC<6x>-63%Dbd25QzDGf@i@h zQ4Xj@C881G#+{O&-K`%SR?_K5mSTEjZVA^Yf{COC|2)-nTdB6kvMJ{Lkdl z!Xtgu{lDHo?Jxhuf@QjQGNwv8mKC*v6BBgg{U5BPVHd?%R|FG}{L0(tu7CVzsf%0` zQzJW(YXpK*lR|=)$=uG17sY)pT)BnE#W7OqR~pUb`ucO6r8qq#q&m5YECrW6C1Rw3 zQCH(pJ87-Uo&u@sGx>0QIx0xpEe$aBk_u3{o*H>RiGW0)NDxT<-le+3zkAIMD$>EF zy$YPO&Hd)LKM0nE9Xsuy2n-?@MyDv^bkc#FyXb~{UrS0|=BAC??}0pWrwGiW%;~ZB zzlU!5v%er?bIVRoCy&npfu&%=huZV=uqJ=rCq9+M;c{1rK#3v%BAutd4}k@U+>oL5 z^!1XZt2>#w0N=v4Z+~8VRya#BaDIfQh8#=4h2vogMT6q+HG8aN?*f-XfgC;-;MQBI zlR?Gq-gA|>LY!NKC4$?>v+}Ux-@MCxVbWmHq`gs11{fS}Y7nt~aK({{=sYG2_A@SO?WR%){tc}|C6_5P*cCf6pV-~Pb`1l9kD^y8M z?H!di{DO^lDVTWfFaL}>U-e5;=B!{-Aun7^2(X`pkf2@kx8N*6lE{6WYLU6%5~-aw zb|dcREXCmL(y5q75s62HVYaQqOqymB4Nt($cmq|F6@)~kR2JFkoUC`e3?_Dts>E>T z7*@m?_$Mrn0R&^X02M&rWQb<3Iw{mYMzM(*($&_I4d$pR(=%J0h4!B4AfqL}rLPq+ zrv(_~B;!YjB_ERL7%s`|hWamN7RwGN%1TKZ2lr(`1MFc7N z^;$MTg?zEgZmJ|++2OVR-V()Jpjc|>NV!(qYg8L@y_f^R#)kdD0f147YJw)`U?f(a+g zzu3v~mOuTA{9jRCK_XD%2(bI9`}(yc-vXO&c!;c6)k=}Mg%c`s9!eKx%S$b*_nyvTi#zpV<{})!LcvH z1pif)S%--;e*&iMsbK4STn}#kryBJyA(-JRGrE_6=9x&ax@{!TA<42J(eh7;|BJ-z zva_WCN!B+Z%qDf9xi5;dHA^7aR!vk6c7t^G@83r9v$>)kZKNUts_K$ zpHn`fUQlq8X|XhXxEPe4!cpBJ^;ecA4jrsW+t48NNuKhq?n8vN56DKga5$&a>7Ms@ zJb2>9@1jFQab^oulQEgmZaH$?BWqD5G^jBQZ>G5il?=m%onA4!;1l-0yYrXocQsW# zyFY1;bo_i|z<4MAfd?i%)Vg{$i9lVwPlWh87ngL`(8?Ue5;+BY?fkUyShc2+&O^k# zyt+4T@CMP(#2OnJ?9^k(hVezED|UH)l_^sK+ewB`V{|MUBsFxx17;L#K)t{TJ17GY zr!2d2Qgx>xGR#W+vx8=@@=Y(ai=ZZ=`NKb ziMgnQ6IF++CwOb;A^3wSs9TzSjm|gk{1O*8bXyLtFT~dk&Hz1aUjjPneOj&_p{OwJ zAzC6?W$Fu5hPU3Iz=c0r{5e0wt*23fzjc{|4 zTK%)HCA|c2Ba|!K!R#QA>Kcy{vXhQ7eeG$5e@0q#r%rUF{9dp0kAb7|yr&gIx^u*- z%14p%0~~Yy6Cn98E28_B+_Cews?hbM@BW%x`GLfUCvrt`w!eqP<;ah`k%t)(GsSFE zpgh!Ei~QFDOPJG^xEoFy5h1t^KYe9&rj4c)#t*Pc^DKx#v=^#@?A)wnVLJj}Yd>>* z+2(T4{}qvoKjUnEW+WZ2+Si@X)1&@mzgR^D`h`9o;jniiaK|1yEwWlMk!8})k&jlS zvU*LQ7TM1;L%DH= zB~KLTE&nVhmJ~buEvra!YajUt7lt8EP;OnUTcx4#5Nhj2OM))odO3S1YktD;q7rE4 zpLQJ^+xT+YL-X0rW*ylipu4-}zb0 zrQmBcLOyCF&*;x1#APL-B(Z=_b`B4ZO+0r0Uf)I$@DGHN4j0+y`tdpj<;miHLSlrd z`D?qS&FW9jH$-v6+lS39HJE&eq7&KFP+Pc zBmZ$=r_;-QL}Y49OTF_??yxDNvu(7b4-O)afSL zz9hC4NXdplxo7G#b|b}s+s&CAQ3UoO>^s}ld|LyPw?&9CQQCayI%TN~S>KZ|}5oACMo>Y`iy`d)Mo_@1rIWbCEd+hy7{^m*FvV948z2;{_ zjoLi}2>jY5sW&N!i=E8=scpXsygfEmJFR)Q8=?3q{KyJw<~wI@$;+w1kuW~>Sh_mYB&-yTBii|A%zc`{%V|6*lky>Im{(zu}>yrtg6}jNz;Ni5e+^9 z1TTAk6uX=&DJv!Co+K$~r5GJ1Rj0v|q3x9`EbMXXVntP>M}i{%Q@VPOsYTu&;Yu={ zi6q0!B7iBgT#J3-j=y{zM<8?wJ2uBh{a-)tyFXqDZC%M{0XL{b3nMzm8859`n{fq1kWi2?#+3heXe~YVC?jd3d!2BBs1M!-v9u8tTfjN( z?(S zYwDYerkdGzHcaZj^5X)znz*I+A;8q5T6W-S`f9YFO6#jZo@%E8jmzup8rrr z^WxeB{1J$aj6C^J{AgfxSf1d=Gb%wG<5q0_R=Ys_AGbUrkqK}(#sU^6h4M%cnpRG& z&)WE}Ch)G7kG^?Hl8>U$wB*UA2#>s1p;3=Uao*F-qDXTy_`Qy)q7hf#FeJ$NL9>Jh z^Bb0&beq9CH+Uo7k7Nv?X(D;B4M|z97rFZ1N za41wl*!Q_pJzNpDtuE9vuWnd-$A>|Kf&ph3DO5TjdzEKXjM{0dAAFA2hmYt08 z>t)<*F7gJ5&c&IT;MDFs|(2W{Wx;!fD=~&-8T#pYlgU)B1ihfss{~hw@JL5^rEa>|f+pMrWk`k}z z`Du-KSz;A_gm!$O_1WnKR*xEj*$cBl`|Wh7@2Xs}&!>lBT}_k|L(V!9f{p38VMBq* zEa>e5OQEa1@wg!w9`P&0SMor(R~~%%RlJwfkU465wlrKCRR5kmzG?Hbr3i|raEyU9 zYm)MwY;L^ciIYY3uSANo6*6l^9W+aByRy!>9ZD0w@C6j-r+XHzF(`;sQG(-=T2Tf~ zXj{ram)Tx?6Wb$_Kiq*jI&ji7pLFA1NXRYHOKNggG&#o8-Qn?HfmqRVjmWF;K1U(9 zjhgt=-ag|@!|Vb$6nxe+c}f-Wt<_d zNt`&zbCzv1KW%;jcZN*+BjgV9h>b0R9@nPB$D-qq(txK7Xe^1Q*8XgI0L2xWE?kq9 z%D{mGwibvViy8&10KfR%Tc}A#;!v1AtPve?i?ieQP^?)Z_ydC6_6k?#^{)Q{~prO*z@CZcg@3;@_`N7 ziAHNdIFlBc*Jxi>y&zuopjYZ*U*m9>gW!i4)!U5I%QhaZOns39^xBa}_wepA zVOu?m>9hax0~&@D?=21&@37e`fe?lWg%BsJ=i&7s@F7||>yQwnSHv#9D%6>r8~Xaf z)OC>fB2JRQ>b?9oFsT56+)kDD)4LE$b;8w$;`e2D)r7<0+hi6-2Xpu~0FIKTueCLy z(W30^*$hoHjrjVU`;s=sOr8ez>bo~k(C#NVWZZ1Q9u!u6DD$UFMvazNUl3WO?=oFH zhII0!>l9-!&@|8jqLJoAJU@hz2xDlk*na%`o@>P{`S-~Pmkut7DfkmJCOxFdWNjV1 z#5&sF7a|i;D@H8v5l288TR{4eD@ljF`i=864-TEVR+Kq)y8GtK4>kgUH0OvRxPEz| z--_{{j;O3Vu=TOLthly64wi;pkMpu(e^K1S`^{>BI9Y zO-uTu@IX52nuHR)HLcGa=T}EE8UtL^1rxSqsBoia$?74%@xX=;8kr-c??HCd=))e8 zlK3WvN}I9o?$&qNa57q@%QF14u%wtBkC;^aIwe%*k81si0T9SaNo~xOVSxmrObUF; zmAD{l)n;mEN~usvlD-IG+wG{*{E(yb7MB<~aag1hgY0JqoM$)1`xn<~a>^HBARLXq z8<65u@@Q4y^%V0WQ_Z4RdfZe~Fsb*HurrWyXq{@xS?5U8nw^1hr5^#rbux#{algjp z%KYqKoiQlZVu*y|Fj9a8q_(`NoI-Og{a0nQ@YvBlZYO>EkphZ&$4DnMPK>_(T3@13 ziXb{UPnpU+BbvQ7&PH{}Gjb%GGv0raxP%G0TTg#N%m>>>F(XxmCRAl+OZ9yLiz?Glv24eJExQ|A=MajXmWLb3eARu-hE|jd;%V+!wU$| z0%S=TYA+zm^V{X9gHIxnR{f)4l2hha*|<6sjaTXDv94dPN2O<1!Z5B`>A86=D}Ked z#q&UlzSj+N6knbsN5R=q+uB;~T(Wm)^Wb851NpeifeQn*kqsE}Lmovc+?X`>A;A-t z1__SwL=&A6*TvfI->K8z*3NG}xbnuWSB@Q8U*-QEx$Vkux%(}aSYIG0ken&X>RstK@LmUc1KW&3w>m(o%oR-m#v~WZP;-%Tp#%%W(}Pc97XUl zl7a=cMqTnR^?>wmMHghEa-3$o#-wv}N}4yWnN;A6e?3w(&9v~A zU59%q0jd~AWs=CMqeyJN_q%%eB$HJl`10vIk2L7P_fuPP{V7?fG@azY#uFb#&_jlH z;05;S`xW8g`Q_#-yfL06G7td)fH(4HSD=_6dYn9B97?+9{vGc&7)3h(x>-Xe81X$c60Y`^B~JLORnLm*RAsW!gZmu7R?EGUb+& zeF%yhm3x)g2+MLQ@wK93h#0tn`>o!xjvJZ2Mic^)uJ-l`f+yK54<>O6V-Ygu_t!E| zOq%QBend>tE&kBUjCjg`9G92HjnM~pWE3}ZzWd*l8ZW=PY2;5MgPztbEp(elWpeXB zL@mrwxC=>aze(INrW!WaDK$)zUizBPdh`!fGh-t8eaUdV68I9JVhAR7i`|dRu)(bC zy3H}!0(X)~x+-SeT;`g@Tn!~fgyEGN+4|EOhLtFGO~=%UtII_lKgTHXb!>rPHtG0b z!!m83GFyaU=d9gSP^5Nq=pAO9or!h~!SCTlX(nEKpEk7=raUl?#E0;a85tshN?`?* zG>VsLf%zX^SE)RvB>myt{Q`7=6c0)MCd-iEGPOi9?!Fnv4Rp1t zG;aO~92IWUy*v9!eWacw|IRB=XAT88e^9RtNR%=sD{j{IeVi1zYNSHlxQkMQ3?!v0 zQ^GF&fQ*)q3&g{=eKsJ0F6)xN+1i%lg*>@WI)cd4@GC-e5}56nVWqcjvo}nXoz-M* zc7#icb=L(qR2gTp*V1ubLG393I{L62M16ur*iS*8ZgRwL)FqJo%FTUEel#E!jRs4RzgDT zu>knW0J%WN%$Q&0i~m)_*PxF=W=|xJmdLhCd@>;$e*Tn?G(mb<>URItq2Z3OCEt#d zfUP;}CNjbn&=W2jSf$=W4DTiKFoyzSmhl)06Z-hvlOq+ty0qAz2M@0oh%f)q;(I?Z z9igd@6B=uw4gEN5V&*=YFH{u|MUs%QpOkpbql{#d=`4CvC_1gu{ z`$Vr_B`-SNM6MS+y&zt_O+#`bO1w8XfcFVyny*i4tnK+W^xm6TdB@%*OiN2LO!tC~ zJzGvR&mgWf(fW*3-iCAMK=JZ5Zs@3VFX^Y*&BD~;EQx3d7ruyInr+NzI4f_bYTj)b z_A9cdH)4s04(~$d5bRK$pD#^b!IyzDRNzefXI*OGb zyN*z^7;?pfWURM_nR2K){B2_aR<`1kY5hSZO~_&?Q*H1lmrzl)b~SONbMe)Z*bAOx z=P9P+`#Y9;!OD|c4CT*rH^|*o5GBF)b2no(iMaPRV#mUixv-%5)-q2m_*DEQK{1Kc zqp|oerUs@>{8)UEW!y zPBpBzRQ2m|2=! zUT;x|5??P7b9%tBo{6oFZL1ppSh2W|juD{^sy}+G1XTu7$hHMo5iwInM+B@rjr<=T z4(2x=p|C6gmb?di64BOP-?w1nh|IVh)W%GAxuto!YR))dw#LCuTvzWIQw<>(& zO35;aCG?1)Mi*?@#%{UPFoEJkLB^mV_#td=2=!w+LX1yhbonDS(M}tW5Vcd0lVx0S z7IERhjn=zRBdWDG)~uNMbZC9y{f+MC2{VX0sy30my71EXA^aZYs(Zu&8@0wsgA}jG zUKMjPdK5zg^&%S)>)q zE8bs2^tkCN3~#G(#tn7G2HJk{+3(tKloB2~r0ofQ1fL3)($YbqR)HJtpv=bRBQg_( zY*`w0K@>OQ`Nhf{f5W$fg(uQvEZ^}I+6)M-ZT9D0UCwH3y-XERt(IRns58hPrWY>!#^I z&fKm+%ZI&xhX!auG}dzrIfQa&C)Dp70(`7LKvSsuvT` z#~^0!*pIx-BDY&pwM(|RE^`?~^zMr=*U*XO2DNgv9fWs&lhG1X1p02@Eg`ag1#>J= zI|6-CTOG!AFA{l2?kxf%?+?k2CrFwCa&a2U_fvz9Z@5p+sc)WDOQl0yHBwmxcIys?(4` z)*%YrLk7{U#@2GpVJ2;-Zu@+EE%I%pL-5RQaK3y{k7r+Mbj9oZew22FD?*?K;0(8eX0K+*a}^YWc= zni&wD+%%e)%kzEu?t{s3X61&Z22?QL^p~okI{eCR>5PS?Zni$KzSr}B^&bVgqJVxA zA)6Y11ha*`LOg0Yjk#=4-qX#n`PMNAGz)79L8+a0J}=GKj{CEd8kH9JZB3-Mw1G`2 zuoxNQ119RLvxu+T-0c7Gs-U?n{`EuJ@S4hUS5{o^T37NhsNe89)%H#|M@(Y9S45@& z-D{gO?9CuX7}`WSV~WMZXJnJwI@6bP4WQ+b^)wwKDEnnOBkGCPdW-^ok~2GCs^h>f z_=O3U-xC~0BWn3~-qVXb!ZXSZCBpMolPBYvX-8DEa874-Eul}ENsThwr+dr7;@b}n z&XehhbhHPJe?|Z~_ep79RwwQ2{SEwuZ7x&Fq22Qe)A`NRKJ!wd#ydF z*+Rw~o~9DWc9|SYm6n|eO&HqTp*xh={E5~*WUAS+S%heSxpeszu7bmTb5jm(3p8aO zRYtv8lb@}6TAjjp>NR-v2l42=_2+9x(ZgEz_gkbpj#sK~HmUp5C$GpKs<6&?Udy<% zj?FY|k&Sho`3+>0o)VhU?;gZh+K#s10i7TV+Dt-%-XP;E=$(1)P?ADdx}TJA8&f9P z+n6l0{G+SGTpJ!>Gq20k`>f-b)9u>r&gDkML1U36027i#Sf}qXPr9NCO#+v zR#)#E2$}l$mx*}K(FPauJ_&ic6zs@)MSLK7Si3m|YyDBGf<_8AR|KNxtn5{@B>2gn>yJOjGXXS%}xMG-y#r3g8h^~vs z)9y;7UISTfx?KcZ1YtBu^W=fg&yuV6Hog<_luseWxj|kmqgl~STo#=#6=r!elrNuv z1a<>*`KqJ*S-$?NgJ?lkI4yXj_x9s90smRpvD`k|||ApaU>LQ?hbsNpiwzC?wD78wLS|4T7x-PN~UboR^VUhL!D zDOftDDF4Y29BK5IZ+iW=M<0WpmN3vGj^zF)|G}hM0JmPr>Wm+d{6%uNbsO%~lvfvp z`E=hgGTUV*x1WTp1onsmyhe{GTjCrRPQGUOy*CWpMD5FlV8{=dy)Zrbr1leCj4>i+ z!Pil}?I`aMG)mD!iC)pPe0}+BZb<=ti^;mZ$cjSmc*Be)9-T5)-0Y})mhB#{e%~NI z`VQ=}8f19U7GB&bTLUdxk}r3}Gca;4th1N5(oXzYNE54|!u)pYiG9)xU4yRvMnFs8 zWTSu(s#uRB2vi18pgq3)odgS2H?;ru{X6rya7MnKZKWRST5n_2Y-1@&H8~4LL&mgb zQnHuq*9E<1VtPp6BlAGXJA_a8mXIJ$g^H@A26e` zi^qg1HeLvBTU=vlU$ZXSpAtG6R_4|o8T%U&k6f-Vh`tm`qrC7qkeS6aTu4kme7ULq z__BEd?&FiZbCPW2cYA$`JHG-}?%6pZFRULwk_YAwt+=x^C*R_^3l_@Bej_7mLqS^8 zHm0Cr2tK`bgKtIo91;@%HRZE%OU#jpNOa;a{;q8nak!tFqe8i@&6^zkdXE1A`73>W zv^-c~Xk_1eIw725tcYdeZ_tq-XYbDqcjg#cz{zk#pl6A5sGgRFg9Hg*hgpJdwvf2rC?to*ovu)BPt zy@6Otux$5hdF;_>aU#NF4`=s2H#0V65otT9mJJG&@c-%Sx1`D5{Ge6(&u&hR@c=5g zqcW<^<;%?{UQH#(qOaZBIu%}#w2^7s?xFO{p6Me!gs3_smF&@wL5^dRo;`*AayCKc z@qsl`T5yMih6EH8d3a*bU~Fre{j;s%>-UE_{A)*VI#RQa2;fJ$gk)V%uRW)tOm0_I zQiHBGF4rH~e$FZ*w>jO&>k(FU?ins{^dF8qpEI?v{8$nBI6HWoHLfReat#z#IRUMzYTh=w!&p;meG_i%_~t&cL|Z9ajXN#fTz z&-P_5p~vA{9kzV0O4C2h6&fGX2xkQx-k^#r?oS~o>8AKKL9%N}E%uTfa?bRDP8%50$q}H}<0hKx#udq`)8RJ(sKkWOr z==I#=$cEqv`Yzl)THd>PK(uj6WDr>bcCb7d_B?v1qdPp+CiLx`pQQNP5-Bd^mXpnN37IW1K%2mVy|u<14H1x6m}xUz#m5Pq}M|_%o!__`pP4Lt2I!LdeSfd6Ue>_^2Vn zU`#7(#}_<&JUh51Hd)>sngurp4Dbx~*-UCZ4WEnr#po4a`$!?){X2 zeZouP7KZ&cO=n}0iPK!t2;#OO19!R!z;WjZNtGY#+W{PmbNQ3 z-R9jc@GGVz4nG2SuKn69RwHc(sgmW@AEsWEysIHAUWbNNvwmFSy^_GHvNopcnngbr zto8)wxJZzmALd=$V`z_TORnZer*gCifhw`UuVlt-9tnW`;D-tM()v zb5@-tDm3%^oh5`-{&i%zFppfzW5?$`|E3^GOk`!B=Ng&vt$oXu6CuVC_aXC<=h<{H z0+(!cM=dz1W?_pe^+#UNS*`u)!n=Sl!yG}0ynJpCp+&{ixeU4qRN5Z!PWST@8)b1! zPY@*mn@F(Q*O4exp}!esT4QQK<7V}M@;FP=C~xrvX+a8#1(&n43m7Cq$Gdz z9Q%Q%O8CPrC|{(y~EM zyG^{JX|o_;Kz8wT7s5Y@1losk#%E5`5E{GA1m=e4|7hK#8D-L-El@mB+A8bG&vYtS z9HLi?|EPzCfkVTTtY0)JCmW|6g?G4=hgB^xJ&0tq6@4)s9`Tq-OUaCu5EWrP+fYmc zJ@S3b4EQ`_A0}ibqF^IqXogz%k-$m+^CKP+B}IOT*dxE!%-U^f*vVX^01t57YA80a zEFbwA%PBRR_2)G{t|H%=u~ox?mheK-hO-H>9cVz?IUKx@^7XKxA@gI6UK-0q^h~dZtdpUdZC>VIERIfRSFkn!!~2P9caPq~QY`N@j8|6Jd+!qi=hpNS`J1 zN^AJ&5x;tAbvC`IDekdhl$UbtMH*3#Ieh=d)$jS+OU8WZz^N%E&t@Mj^L!kqarSFzJChSACAOpsO-;!fUds0*7KjBj0eH)%0 zjCf?d8U{gmq4HjN9*Rlwr!v*wSsaDA4|V2-zR#b_e9Am;H*HA`Go6TT@mC?JT7GpE zWqhi|x9{+@q?Rn47$D#DsN!0jtYitPL55w63;zj~<&^#>w=n22LZbg? zATj##Gs1(;o0DsPj(?2~KK6f@vC~-KN5oP|7!~xAkWz7nP=3|?GFer0blUfiYUnnV zk5>d};}s`y1YIJ@&puvkVO+OUoa@-H9d7=Pt9leR31%eKIy`6klx zvSNz(g(bJ_Q>UHmB(IX?7E_t-THTH?c#sc09GAuZ+K=Tac`DIKpHyV5gP~Q;MRL;) z)ti>M?|!4SB5FhVi@4Zup`Liyg#5|Xtw#CL9S#W_tHE&#c&!dQNB4fkBJK=_;)$Vm$>Il+N zVNxWZ5ybOzJRTkl>KjL)9gdr{6~(XFx0>T4fW>pEz_MQ`^>AXC2>F3u)ln$Vzs`>D z(IQ;&{1*6Wx0+qCH8?b-xTwf6oG?Yx-C+7eY4A}34y>#UXW2iP5m`nU(QAK;D(Z-{ z)REd*RCJ#~csPE_{4Fau$U^r+MOcV8O6JH=mDetF7X`C+3t&zDTym)dgT;HP064v> z$4QG&KvgD)QCvopW3!x)D=jQek=B;4vrq5zOaFQItFU6QQKB~qtm^BI_Z#t0kVglL zz}WEZsJF!|K(a6!_+RBb8}yUFFZZDYIFR#JMYV^=lX@hf}+? z$7IZ%&V=_A%K9latz*F61z!In5>yZmecb1v*B0?3hmiM>Dt+yWmN@oa*ryPw+>i)c z#1||@9jPfny+c)S4`E7Sa42bCfX#f^{0fhc2i`qGGko<#lGZ0x1|4#wfv(WwcK5nN z?iHZaJE$8yVM{%)cYBP{Cnt_V1!5$W5IB^OUKYTj+x!9-3c^tz%3qCBGPd6#au!w0 zTX34sAS`P`sWOb^=RjO0HHLtbVpb@8+{YdRRR`tD0<1pZzMzw|B=mT|Q-uQG1c$;2 zfPNK;${ZWyU&koNwxcqx|5}oO6bg;TYHpRTE0y3wo2!L}#!vnprD@;4+h+`_Pi0?n z?_m=(pMkA|n-J^^@TknyK_!GS?VWEX_aUi_F4;do16szG)9F@*ROTii@}7GrMpM&F zM248L$D;U!_>eJIKtkljY~!)cT8=9B~vYPr@RQ9;q{FcmC9B=`>O zcXt)OGux-B>I*V84Pyy)ssK!}1sGsYrlK;J1g2gpAme@%j_(usYvFi1ztIPgflEla zm0Ot@{7N}Q<_YiIkKg2P74k5-^e+d5bNphMN%j>$(H;&TJ0j?g#;sgm+u8nhTG~>1 z!9e@9vo56ZIXXJPgk&EPegzwQ;3EQ7PzHPZ1I0=uF*@MIz=dAngro^jQa@6FmF3MF zA3g#m%2J2kO+(tzC>zayj<$8bj>RaIx;}_a><*{s`}fkb`&)b;npPp$suO(z01(QD zpamb=i7j8k^mDe7mHpx0CtgZwg%6tX=*@X-6-G*!sVp3+-xVZ!6~WJ55Bv5D!s|uP zKAhrkVBqx{SiM#}@m|~if%kB{%V^11vBhi`cgRI!XkpA*7CeR+dW9GFX;6!@HR^f0 z18d-9^Re{;z!p3yF#XyYTdOiEH+s;BJ}WJ2;kspufAk*i5a4}!P%~)~QJMRK7|i_R zmxJ#-+c*CTpL_uwBf~`3!wyO7#efG6!a~N8wZeCliGyhL^DpucUu;bS(bo4s@z0s;IXZcYzq&Q=nA3K2d7Pk!ikdCibE zS4*M1&g<6)Pi!Ean767ZV=XlBZBxO)$8v|!=c1NFyA~?{fsO%KHqZV@!Ve)`sGntM z=39{M1EKY+YAWkcpa@41;gCbcXB0N9fNFGO)cT&JOdY z66hxp0ebFT3x#4R=0iNLDMfNK^BOJBCd#E+=6=`lP*<)Mg8!~Qcr$O*#+TQ$&K9!t zHp1pk6%5S%@(08Y3El`#{_9s3iM%5=edAZY6eVs?{<||AL#t5UCTG>tT3%Y#buw_a z|BFibaZ^wIEE(Q+*8ilZ0A?^w>uih$K2bIgc=t&reBS89l4W@*`HP$0Y%pg_(+K66|ub1_iC8bcD|+Z_FAKHm5i z*1{@zv~xFMU|VE-q=<{{c7@05FaZyeAxd2i|`G z9`Bc|XaNA6H@i$=*o7Dq1Mt?4Tib~$>M;jgXlnN(v^x2nC|mmlFJh|@J1UGpzcT>m z+oNdzD~Vno7>Z?Xc@KwH|0H&m!|C!){hnOyJ91p%>I>V?3Ar}#yDUCFymSo)@}*xM z)!_8NFhTHOg7nc_M8mMUeN|&L?Xe??*1{qHE%#`Ev|Xe`oP0q!oI)e*7*gBta zI=gqInEavzkZ?!{FU&KtqO3#1t|bWFvLg5A@=e;fAYd~trGbT@P$K4zn+UL2`NY6q zM4l16w|UR~eS_FT8vYxM2pepUR|m$f<$+g_Ar=UbH<(tO7*ck9zgYC zWbY0gMspJo(wNQbX!SSv4s~oenm%>wI2}M>5oHN|!djius2tLMNNEYfh3P*8ZV-G1 z69W66C+P5x`;l0!86n|7){o@e(xhhySrcPfnZ~3B(O=q&2ctKVu{n>g2{`uO!vR(U z?8%j2?DXCVfI;9u#Gu~;Qst90^{K+1S5`vl*64=SP3Gv!qZ6?^EF8!zq}W8q#|5x3 zRQqFJq;styD-P^C_GIBKEnOZj9DzBY;}MC@6tUVDr3o+3ORv|*xk#|kAjFPWw%z^6 z2?)!eKPyscS+|`)wA6udK%5l70fHZ+w15*(Keg9dNaX|D#AuMNv%S@$x5Fvg!fUnJ zd`WMo5qNY%rB%3&9v>_=`v3yAwi6GfO5_+oX1LG*z(^WqFv%nZtdV*cc7y%b3V#_5 zs{JjG@JnW8FBJBzZC|c;YPs*v?)>Aw9CVI(88L0JcJw~>26*gv77#F7CEk7on~(U2 z{z(!dTZwEu&=3?F?Zn<$^v=pLV#T`lhVk_7`>%uTnhm>%L(4C)539QYlSkYDDFe&c z8x4;5>V2RQbMPFf-RP!4?^vfG!Os5jnaR06Vt4C!8!Vxk4aetC5$sfb|)OFiG$NO{Cdc z%`-HLKl;H`ACdD2)mjt^v$}$cBLv3mCqFOB5rmx?og0>_&*_WkDT}?#pR!#CO%^ z7DdMUa^T*6G1;+qRo@DMfiCSEKsseDSc$+XR7(~*qCn#8v~a|>7}lIKR}h`bHs!Uu zuDs=av*Xsm*5XXddT>Fz!H_y7SF!%AN~??va24=GEf{4C@mVAQtLX!!D&v1b{(C&M zN^6p({XI<5VA^9ozp(gcwY^98+5VdwclOTbknNcNkV+Lt4miLk0$Tv}JeQ%NneZ8HW3hf$u+_OPZ2utX&>Q^%a=egweyJJ%f8 zc4!e4fMo*!sqH`PqQ}_JnO-J`x3S#XF8r2^ZZ`>fS>>?&z~d$MAa~@y=i3N0Q*7yT ztdj;Lz#fLpW3_HD9j4OUTrmBdLo_d?hN_09D~^*x@hkz$%`+sgy=f-|@s#-1ext>w zG^uXa8U24^h{D7$*h>FT3}#T7bXfkww`a`@wmm|dcz@%#_fb;wKlt~v1+rM^nfbpwpFnzXEK(edjp{Ol`P$Kizflf^! zifts;CnuNi&5OZ*TemHUmE^yzD+z2}_Ri{K95^^IlY+E__VtA!OfF6?7z-Qfxzy#_ z{3wOvAImrzHR%pQ5bQF=t6_gAqkOojvELlFaQwGo)DVo5{of%%l?%XWQ}#dIV&?*Z z7!rVqIrb<3JabpqVY_RLM9!Pa(+xyh{Sx(^%SShpifJ)({GUA#rw42&zoD2!z;6x- z5kxKAb~n+Nzm{Zm7$R3ZVq+#H9WiU`%|sUt{JBbZ5k*>Epyacvwyr)*;?&Rl-;VnK zr!nyFxS}~L?v{T{mLV5^hfEuSgw9|Ufv4-HI4N$CKA!i#0#DD6&oGu*FrDrOHy)eCb2*=W2O9iw?M_F!KVRqlW7w`uX~+S#GkP z$v~Nr5r(jw@+;VY&oFOnxZ^_`%pV9rMU@YfvF7iPR#3zTU~OF-m!Xy4?5ttZ9?LoV z`}g%uY_N)6z`2Hpzldxa?jG=XI8ZSyaE!OJ4Sa;5yVn>@rX&4&S(Iz;s><0>H#_Li6*#ucD{sOjp&ay!)g(JRw(E zl&+{(J$uCV52dP%_J@eUG)2IH@XoGmAWKbPhr)ryxBtW!0mT2lf;Wx=lg3$!ikI*E zOf-F0nlQy-0ooT`dA&2Vvq^H}`q!?k&;S1P6vXleYoijuY+zvfEdge58aaO_8f>sQ z6&5(5ZjlLnS@iwzmIrX(;2Dh0zW3LSj+#)a`f6NGOj_^FBT6o7X=3hHV%6lhGEtJ!!Rde=>MUZQER*_CPHYrtkR{*MZ(CiBaCs(Kc?%&gCp79 zf3ChKpn&P;7lr?f5e*n4d)skx{GU{wxM@V>3yy5sT(|5lZ}=s5F)+&0Iy{tU?^p;k zZ*J7OUg!a0<9Z-Vl5CDY~fa4h$wern2My`gM7qjpadU{H< z2xF@!lD`T1Y}$Sm<8|0V!8y6Zg$H{mCljE@L>IDR3>YM+++08(~~zr70^0J8?;ROxl#Z?z5QqbsWO%71lF{=@t6 f>OW9zf}bh9tNcB_TcaSr0e=cIs?ybx=3)O2^vE%1 diff --git a/planning/behavior_path_planner/image/drivable_area/dynamic_expansion_off.png b/planning/behavior_path_planner/image/drivable_area/dynamic_expansion_off.png new file mode 100644 index 0000000000000000000000000000000000000000..49b4b382c344b58c224ca9cae6f10ae7054fa9e2 GIT binary patch literal 38731 zcmaI8WmH^Ew=GNzl90fIJ0wlx?hcX0-QC^YErvsIx6rr;cSvw2(6|P72*Ld;c<%e% z_s6-1F*14(*t@D$t(t4jSt|*WlM#LSobWjk64Fa?F_;1p(jz`3qz7-GJ_LWWU`crb zKAzc$sXHPe;b7kVd2sjz4+jb96_PmYt&*G0&YZg!(Q&HK&8evfx%%JNx(A8W_B+34 zgQU?OiobfcD5x+!vKwcOTG`+oqg$F?seLkI-OykikK&|R9pf{j@Lc<>`a1)~tme}P zQ4tYeBKYhvyS`#+HZy2emkjr>pLTT-hKrUj^OawF2p;`1Tw}|Oq*ou2Ot(zvTZMqR zy@J61)TB?8qXuqRre3m+i9iZm7<@XF6)sz3J$26OocHAoVY3>X$XhCsbgI)u+4df3 zjopG}=UU=krA{pfJl@$T1n%>41c{}$;@`Fn#$NJ#inO;Oei4-@SEmluD? zUwcE@ypT)S2nTPCN3Os{dhztXC!p2-em86!@*&9Ye;EHiBPCdn_Wa-;%}2g}QZH}3 zNZpVj>7V;?<6qR^B0>HC`)NjadEFqGb=m(kYa}t3`{xuT<}AGGWZ$~U--Y4d_5No( z{C<~?|GP5p%AJR05&4`a3lHsR{ySN9WBLBy7Ts^oX~xzx)rc{E_{$_zBXZ`)B|6g?#v_#5tiJ5~T)$Tp=s% zrhOM=e_AT4E)DkA|I@Z?WV_?4g&;*ex)0Wm@9s@H|C!}~MtWqS=uj-&v+E>Sf%`M& zepPzPMb(-i--H+%erP;ie)ivq^}=Mn4ht;*+5eQ-|Bv0!+v1Mk8MSqp3$Jsbiq2>* z0h30GNK7>UPqKYJXuL=O8{YbF8oZdGGurthW39> zMs{7@l*0WUF+1}|eZ-v*r>CIk(7^uuUoqArth@T#N9Mi~xt`{^SCM{QGB)=Z$`ws?ODP^1|)pd-JbO+iNVW zhMl1ed-dD9H48pR!=fP}A;rm;bPNnlw>Ou%?yIr;KBo=i*36GNEy1?D!R#9tXu3X` zQ7zFrXS)5%bl~mHNJ~y`cyo20ot=$>PFiWh)+4VO)V=8xXIgKzsn9!6wa0Q`#o0TQ z8%x(?k~yjbCZb?P)1jWWn$~yyx`n=He88~XrUnlOr&z7*o$}b*q{GL#2p-eHl-}On zxH#NxPW*>=IhP<+US4ifw;HEhs3HJBj9kphbSUk5Zr>+9HrDxQLw>uOCabvNcp$UX z!y9jFde9I4dfO!7%UuTPjp&8eX_fRbHiVX8oRkW=?rCXjlNg3N+RSm5bsq2WJ>2D! zZE4s(@=Q6SxRunGdIbRQhnsz!mb<(A`T02j%V4-!67CCRO-)TALc%Mb7BS3Vcz+T{ zVP)m${;8_6va^#DK36<6zqZzGzR^8HZlgbu?WdkyPZR~6Y6(3fql)tJR$(b46H{q^ zett>GR~V$6J~ubllRvG$zdt4hyECDnKtMo%fq@|`EbQZ(H^gjIRJq{gs}5rm6X}B9 z8rZCz&rwlBf`he4x%%t_I0S?!0yKD$`~5aI*&Qhd65cZ6iDL>wM#qG8m^j!Ya@1W( zA0&tIlhV?{E7>9NHy@IcX-=q)db+>yIOcu(z^L^ti7-hh-NBL0K`sm|_lI?M#1a9K5 zv$IRD8Z8_Pe6cN8d4oepFU1XN@~=xb#<+o6pdR2 zuLB#{zkfP0HpWAY7T!hP=iu#qoycYyy1cTwI*`QCXHz2?<+NKhf&B2}+L}q}#0&y~ zaP@`3V$#xdw6s!EQ+J(stvNN>36C$YbxJ3;k3}-&`v%{CygOUV5C#V8^S`STy1v)S zs@lqGY8!UkO3J%CJN$OPe^{0_RfBW``8ZhDw_3j%r%CGd=jZzXwCmp}LT zoHrk~w$AwWf2H3_nGVWv&+b#U8P_P9(=@D;)}Ltf4pAv*cZy8cgzrzjjcYcbpx9}? z+^C+}IA1>}yX_|Ricl$OY;nJBY5Bt>k9*Uf)F9+J*2E{%ba;Dxla`FTaN`%ITVgJ7 zxa~^nx%+F}2j#U!g~@>T=^Ph0$X#T?BM!^)S+B!^zS3ISu4VgaXpUuL z!}t1nUZquM;jA~KgsuFfLw{HMxU44S6cnOByk8)rlL=m3F5LR852k8sYd`YijPFy{ z(P=hE`sG7A00Uj zx`RXnIIQcjncd`h>f+*p840Hbp+0W8o@pWBaafV{y->8bKS*_*H?NpV^FEmhAoU0g z92psjqgQumd&y-r-#E4F(pT;^z%fx-S-CUcbUCJ~d%ckv?j@LBE83|hBGP$rylvZb zJnn~zXJTrao0XMUF#YS-ck7vIq3caq4i1jR#oOq6fSHVjnz#AC)VQp;I*|iu6Z|dVzdRH%iTz^mAhOJ742&F zzVz_$D6gon1^7sIy&)P}MlSl5nA`3Z{)@Hs_4xSs1<(B^A}*V&k@#k(vpOmQ!rI#lXxp3kwQ%(6SfiH#d(C!Yjyb6SNo$3gE5_*>66W z48T|Wreak`I>W9&imdcRPE@jpbad=225e4S=H~_oo_(;epcY6~DK(kUmECWaEYA<7 zBg_{2VwCtCb*kltjzKdAQ?*KL0gZ($ZN^h_Jmd=JPMal%WcXy zer$AfXRaYW5a00bNPb2aR8vq;nE7=kFZrDgKHxlDaMe#&+Q=$!J3Ib4Lm*5buD%p7 z+;8A3Ki_;PO@M%aKr)WL4%D{s5^c{RfzzGYI<`gB0sO+EqN`rj=5qJLHE;&O83rR6 z85=7rDS7>kPH)^QC`@x(3ZhDLgJ2W73-NbO_Quk++#HwcIu39Q3=9OIli65Ufa0W4 zX3(*4J-5K1UcQ3Ya@LW4du572Eu7=ZO{`gMMMFc=)7RHvxA=+sD^y%n$9?q?I=`H{ zI>8I%CLLQ<)rmUCb(JDD`_nnsQq7t@Dxve95T<7QAXs4cqTQ^=cJadP&1pqNg>1Uu zHArm#cNt4dOJGz`{sz*8ZWnH^7r-|8YkCLXp_ifUT7Tl{tm9BH4&6L>`1Ydome=k# zz}wKWqM{sx3;#nbUZdGwi!^yXJ@bCTdpYZUj(kB-7J<)smE zOu9ZZ)-^$`x>rkh@bND!)c}B)ycSWp=A00B;|l%x@yMrT!9hw`zNB_3cp#YzR5GEH zNy8QuT0#W}?qROhfKnZ~T9bjK%1ZWv@ZHp?cOiHcw`b_R{aIu;5x0xzN~#l@I`ThB zJwwNf^nFiVuT)#$NlDF@_;EW{^%oZPd%OzDAmoT-TLn`p7Ln}ioxO%lN!_jZNvBk& z)D#&|xrotxPUo5{$eNoWPP}YNQJT{=M8lE(;e=jzas3*Ct|C*RM~yipB8G}SJ~xf- zhpcRD+gn>`B)m|M=RV6s3kiI#dyXJ2l22uQYpqb%V+^8w*0{a8NL=ZYw$*owOaJ=K zyl*;Cjmqj{YH6&lKGD5B)?EOQrpIhnF%`$CeetIaok^o|W3ORf(D&x5%&;relYM1v z&F7>deXiDidA`Zh_b#CTlUhoLQcE=v2%*bc3uG1i%22 zzy@UP9Y(nB&Gzt^hBAP62MAp)g7hn`TT9YzaN%HQw;RkHre5~~vIZP~0B*ip`MHFI zgzVDfaDZ{8KF5Wzv9YBsH}ym7haOEShoWTO>`YAi83Cjk4KBNJ44REP`(H`;pyItf zJ?DF_Ey?lmr-cB4T5c~}Kwalq2V7@+y!dk0*4Govv*lu|@a4;w0C&d&_^A84?ow^P ze!GN@hK2`Bv)Xz_5OA@yv@|_t{HKoziHOpDZ_Wz}3MeGwiZrTvr`Nct2kXH11;MLg zP|W9k?KMRkPB>@*LTA4pr4Qjfef;p_8(G<*jQ0UP7l?G9!{i08zdck~Dr1woCqy>2 zuj%Nve|&t@;JPokK!OH4)>A@1`hrHvKRG>JAS|V=UaX`o{SoQO z!_ncl0cZ#5*P-lTHVt7W16vI}cB`vpVMIYJ9*5G?4e=Tp)c9F?9|{W2(r;jRj1hGP z{*Fs2DKfnSt3sCqyHlB$Nv7#L7hM98g)GByDGgK%WZ7t^z4{~A+0?#6fIO&#Jt z>_;K<`ZYff*v*yCZBI0n?`gw=d6LVRvMLTXwwS`F#xngjfADacknau15YIbq;Tz@e z?=N(75RQUItX6BcSns@D#6<)sP;^w($o%{bD6YHHRfV~^qF08*f?j98e|}C)P4)Bh zqoANLFqKEBXlXV2-rmIPc;x5gN|uz{?psF2Ys{cPov8Jp zbYHLoLn%BJ1|7j5^HTyrf&$!uM2aaYB2IQ^0P3`-R##W=&D88~3}>bs{{8zmC50H# zMjZ8c=oN4Rr~#51nVP2aI&ZZHVTqLbLPprFZ*Q(a9*MMAA;Lr$v7euN3C8z1g9HO9 zKVwr9^7qXvyNjdEJERBie3lF|R@Z6vs%u;1cK^Eqq7gc;4tMl;|Nb-K)05rQRB2VM zx1k583%UNt3d)AIf6q5kU8%9*QJA!}kZfPgtzUI>m2NENgtxyRZEb8=YKOt{n$u49 zbH9+ZzIzSO@9%kNvGGeU6<1xeWi27KQ+;dAFe=YMR@rQM85o^PQG$S{i?j3b$44mK z>q$AFK6qWuEZi&slwV7>^{?-B9ktt zt$6q4c(OAE66xf`W&5Rpk$M`BV-B3!zzA+^DJmLZviEw=LEfB(rIXVpOTB{H?73rT zBtl$1v(6J#T(qAa}0gdJ#E(t3IzIJQx3so!SaSfBm+e7%MLR%E*PX8=47|9UUuHNdXchM@0el83i~Z0h`G`@&Mzm&JTmc;#U9ub!eDN zOHAB!X#hMxQc@C7fst%UTR`MLeR{}(tP*Do=k&I(2~Sc6N3;f*F7cv(ghC01BShnO*B* za3~AQ9@9ThVGs;pfi!XuqivT-P(mQW8U0cQp=I@-dB#{PBIO z4t0UlgkiYYM>jPvNF)G3PA;y#a(ZzE6_s&NB>`mw^gt_lAg7?9Rxx=XE-{hkQxPT9 z4H?)VB0(&j$Z6RsF(KYXGZ#cl6Pnz_f<9MgzBlW>C7LxQ<>d-5j_8<}bSq4x!Nw=s zHlMd+$r20sczyGiKafN5sPx7s7l&x)axJV-$s83Lvhg`}YY1>Ug+|gxmz-{wa&k+v z2}OA`R+om((N!3iMY*pZGw@t>@b6}wy2YNJHD3K4b1cOUvYxAV1`Y)okfI06T^;GR zH8Z7vkd^vgZv*h}`bsiWacfsal}!it(peJ&2D7Q@@5DN>;H?-g}NXIM){#X!jm+XcGWYGxnsYD9nYA;BW=BWl&2%FFH@5uY(ReU9aI?7ocr)ea=@c0U-h>0I+EBhPj(!TW>lar?idF6tteOu#m*I z#fbi0-(hNJXL%X4g{lx8uSlur>#qbDEyQ2v>)Z#dIO8JU+7Dr35FG3|`RtFoI!;bk zHVdqeZK01UWV$TD&WCX*3RU~nt!sD^3^c1Olr=P_0pF8J<)t`rs?*XvYsCZnn;hBN zYPq7Ga{wb5w~{QK%T}kgKmwrg?O(8%t(8wdzhxuKZ0zj;^QWq+imB;n1VpVUxvLeJ zZ#wew!+?*ED#~8poVIXHoW;e)Y6Jf*#~TGPHkNHZ9fU>YvNQSG!p~c9!Pe)HXxj${ zPWkohx}d6((h=AwAp3--TYOuF$r$FOVG_9hbY> zvvYGB=4=|~_D(NnW@dQSm-y(L9mApGAT>gVyl_KVk_XnDc*Evr0f+EB-Md}|Zbj<8 z*ZM@ujkAZx1(wKpav=1zlwoDMN-QjfssDNjjEBv@#s5m$Ko_M>sNzIq&} zP_s5QQ1RW}-DgyxIJwWe!3>9nYOJE5G{D<25;z*brB{ncO}*1ody{2t#1q)UG_M0xAv=2bi4)LNENy z@|gGm;rT_v>(sq|s12w9MOi-93(0s!25Rb!&CLUkCTnZ!l*7F}8|?|8r9Io6cZo6 zzPg&o#nK5>l`+?XrzsT)_nRnKGMA!>i7pSu)NZBT1J7NKlc8HF$F-vwcKW$FK!~H- zY3X{rCPL*!kc+ivYz3=dn@MIMDhw8mQyRk4tOe^QtYtM-oAnRNiGWuISo!Cqn~JU} zE6&b@jY(7NoJlAknaRmSWZd|MY$p9cGnJgjf&hRSM?-0_p96D}O3JD$oXpnRI+e?I zeyJmbA=$yvvE_WgR`BL*84$WAW5oBs7N9aU)?C!9t)}3@A^vHTf)^X)ED7JffB#iZ zBP4X&1=uZlI6uTortQQod@j6Q&*u%Rj^nO0flwsuJIz`nzd*|cRT(?}8 zW1b-=RvBkvWE5B`GI$QA+;RzQWWexBii+4LdV+%1ggL^+0y-(*Dvxn3cvUnsc#ah) zgUJj!o~XRyAwC%^R5dj=?g`G9$S;d*Il}aNS84RDVVjXQY(SxqT1jWn=ZIXRHX>!P z{bl_7(UH~#&u}Zw`c2A$B50;aZc(WBNyVs;BHAz!+hkke%2z89STm~W47$(n>g;*J z!!64=D<|H&qgPy9%;7T5UR+(RqC95Y7e^qljlee7mY)WE%+td|Nm*LaDA(Kt9kP_- zdvlnsTWJ>QRt6QPWn{d$S{Jgdm~z>lpPQUa_)cSYd9s@;lbQrJ=u%;7kA_2#;Wii;O&|D)qKTWo1kA^3=)N7!VNGG5FQ_(+v&CIk7nx}feoL?*0p?abw1>KbCfG&JsK8dUdhYH$HvNfGjw|{ z1eVPUiZiIf>e|{(Kn4*3t_2j6fY;gggym6CLgIj!udi%sy1qlWs}&MhR>9VcZOa`@ zfO5X)n0`6?PGGx|sXvgjVPt*Hcx-%}k&%7}HS{Br_YubR3e{0;=`U^9GC$PK4f*-G zfxn0O@K14!*;rI(eN2k)KW~!y=V$xPdxQuc(`bDE;JxqZgpeNn^(H@GNk_)d@2C~^ zXj3+v9z#%`(%O9Oa9dNOFkIx*oaB0Oq?S2Hl`~LjEJAGHPT_n#or#8Ks?pui!eVQ9 zjnr9PU)(>F9wD!*yLx&_M@t*G&MU;pRWU~P41=YUU78OtKY-XkjOc1>?;d;1*|-V| zcYss|vLYRrn}_Q|$)sZGpdMch-CoJMxSW(5_uXu!-Ic+5+C3$&!kPqOs$^;o$>dOs$p! zzaLySRg{)hr)o1*4$4_>K|!yF?4!G@<_~3f&;4#L zCR+U47Pm_pWZ2a$k|;k-qzQOdgV%dsx(vHYOdJmm4uZ^I_dVqDRg{-6vtRB6+6b6| zARrwN(6s*33m|m4Qvu`xxEgCnVE-5h0t$Q{1XxCptk+U7T?ugQfrSfd5)fmu{0A^i z%^464d!Xfm_?A*a%<<-dT?CE^CI9-zl5Oy&aG@JFL&N1eqHg1IvC5`!U9h(IoS4U< zef^NZsm@59QXFFc>0=!3&8Xt&R1XkP<*dN!3bOZGWN!NN(03JQx+PtzjmDn=Gb5Vn zyycqca;7Ca_<8*z^48|-mh{2Yjh#;l&gnbXsmMwnOlkbbz`6HpB?xuA)Vfi|TkEj{&;K zwhpLozzxBbn@)?*^>mdbI2QHw^-0OecOE#D23is^u8%u!OZPf=Dt8OVD;QNl#R$%N*Ihlj_;sz3(D#l_7vxPq+D&B>97!bS_= zOE_n88eQ%$Rb^EKCWh2@6*w~a+ z^`2oD>&(pNpT&7?<=BG4&CT5N#Wr?VMq}ehs64aSz<|>ZJ_(=5T7^cKlq*-$1+A@h z_7haG6f8JGG*<>uX1L;V2+UXw4UfVD4b5{RTRBI^D|4xtN4xuJUVRe?oe349uP4W^ zJz2t=lBfTiHuyBGjlLz#sPOg3&C6Jn(e@P_Kg%=M0I~oa3Ga#}w7$_T=TsF)gCl{CLU2|#a)Q*nB z=cs+Hi?1-Ad~Tu=2F4m}bZUxEskMLmSVIDsa5Xk_8o;$sP*`%PgOTh4(hYVQD+qR{ zB0y>Ye>^FPP#OVdexsbLZl(v8Xj00Q2XDH=XLKHgh?1w7S)q9Q5zm~8GZoK-}xDv=-Y9&tc+)xN$%=6s^O>OW9RsM z(7uMHg1ylOGWqpV2>hkR`o-Wp)jCRDP4JV6nh7G$uf@{IHr)eFZn;fjP$?K>1Vi50 zdF;DIv4|eH76mz!{n7LkKO5j>upe-Wju$@h-gSrMFTGilyWDI^=o*b^%nt5l4+~`F zY2hVgh%?SC--WN7h*%C!=9jiG$F!T&@P%4J2={AU%wHb+0S)|tX3brk*N`w+GsoPO zl5kWU*0J?r-Gl@^HMLDJ(#+d?>ENXz@_mN}Mr89Q=+I#Q(+F*{Ov0{_LXawreRN1p z9Mv*qAmr1rwT6yxB~HmzR)!h`?iu~tgHpU}up=5A^}Sqr=S;ib1? zgLuq+SI7s@F}OYZxy|b&$RvO@i>}&d)^S&@Ud_F z7C@Amhfi}ds>=2CK3Iy;>e3EN-!q;m_5#{AoD5_GLUzd9CjDPzTaIGQg# zqdWJD!~WSOTzkr^dHmy`CU3{xT_KW`sK#MOvRu{9CsUJw+n-^+3*Ub~&$PQP5u)0e z;#_<9;P&^+OrMr;%v2dCiTkdb4}=b z!q#z~AR+z3KJ?HMBO!%`en(7psQ%YG9|+t%MJTVp)ZdYIBr*u5)Sz7!hdEqH;P@(Z zzXBvN(gCG~e-+DkTwJwp5252w^;;QXUJo5xhL`+&C1#kZXont8@4H!;Ukvpp**>#= z&yTbD^zrA99|=Xgo5wd1P>Fxrs@~6S1zpPcnv7qO4eCb!QOYu8#13u`$H&33LiDyb z)q|m!W1;*w`R144a^Y$m0)agD`^295pFM%AS=Znmh)*9_&8iQ6jp#X_td4MTJ`e0> z?Fv}fNA>dnio4FP_r3$|L*%vqU#nYn1m#XI?$gIb!po&VduXuB-{(>e`R<<%(_bX@ zXSgFQ`BsM>mK~q!=#mpg4U7FJe`mASm#Jw0W((%AQ7CcHX`wSNE1T3frhpy0E?c~r{QD}wth z{Lzk)3*k@+U?u*!T^z>XmTMYKec#_C^}haALFP$$NZByDXoAgsP$>t`o@75tjNaiB zX!dh@+=h`8E`G8FnlPoZE|v^H%UhTt)E#PgHS*hyV8HIn=6%cFhd{AD#_zb&q|Sv@ z2Y4P{#+oDk)so!q`%s^c;22QGM=E`Kxy#w(5?ru|*@h9S7>Q=g-RgAT9>u&VT`yyG z;KIULk_$=Qp}a-~*~%RB4QuB2lBO7$lJX1DSNGu#V)2Qzn6dW8FtzFdEroFWfr=j* z>>~7S7=zt^OVlhko$i|ie+^B?MUO)g?BL}CU6Y5H<!^OUBw$ z@f()ryCF$T3Uw`T-v&tU_{g(JE!oEag0hvT0KiFjkZ-i-IKQ~0v@^dC)zQ?^nfExn zjM?Yh?25PSt-}3IZcrq_!c9yxxI+ExEihB@ttCpTo>Jo8w}_SYOhPYeNJq=0QSUdn zDXL7|NkMhs=j8pPuL#%W;ma$SE(VB0{&5Jt?ENpnmS>^CN#!(@j$XWcXbj1butJ2exIic3dZ4Csx^eVONggBKwy73;E<7q=N^jc_~vq;Z&r`ERb#h(zu);^ zIV(kmL<&WO&vyURk`Q*H+|5kNb$J5HTT*7$o;vAt`<+bn>$C;Kr+@o15!0tm0^)R& zX5UXnhn){{v zjkFI_LSYrXc`4Ygk7AOzwUVsk7EExy4VJ;2Z>>DGVvXLEAj;~WTL0obnaek0JhhPD zn0Mj$uxVznG@X|OL;0#4|7S%Bx$ds-vJ>lmzM@$FOo&)2+1tLcAZfm!qG$w*X5J-6 z4=5HkwEq3PoP{|_#)|y=+ucgspI?%H#S;T&7)3NOjBK*3C@R7Zvg>`WZT*CX5ybkk z`2T+^ITpg(TI+C>ny*ZFzE$-$>q|VCW==?kRNRcy0LM67AJg8t631$p@WMa;4zqrK zxtA)NOCROBHL!D=YbQ0@MU$I5#{*?$gxmOqV%OC57=j~bSOjKZ_rGbbeG5y=+}9x~d%SQ5Z`8S4yy$%xVn@JHoS|`vRmmB_~3Jk7I=*ct`-z*f~6&;bkWediRLnOf7S>U8Idi z2nS=+ozxOTi}xyEKEq>zHhmQC{EhbeRpxI# z5NLOTkl(gvvqLQE*OCBCkQXwXoJ&kk2XAj<^&hZ&f80fa0!WhR6qJ{~^BFp38vHpG zf5JWRF+U;6W$tMY5;K&Nl`}W)vGDITO{aigfRPmhBZAD)v*l0qGWF5;@QqljH;eA! zAMN4C4^{VF#yKzK8M54Q8(nU`tT%Ou8MX)F+ovXow0k-#BRD2@wCdTLhY!cMEHEbg zEgvpTQ+s}Y)<)=}7bvv&AZLh#YIAdQ9D;RstP;Fn+={ANOe$f5e_=-^WAoAtWaNo3 zEpnOmKsJkdT6;Mxh79sP3v%%{cod`+J&$Vwbg*+yYN1vl@2ftIaf+-armeFC zRJhruO*d>Zof6m==l>;yOxL;5U<4JJe0?9{-CPxbzTR>uQ}oKjEH|65^yF79`B!l* zqP;irh8E#xJ(D>V;8xah7*^(2a;eqwux~3Sdd0aedMThUixl!@0gBY~LqT0{j}=D< zW%4)1fYs;ey0fEOc82C0!IoM|zV*BrjZ~2)4x36dC-tySrjibV=o2}@n>WK5Lc7c? zIogG0QMag+=WSS{=Y>VW(cMb7(oxW;tK4BZ=;BcB%553D*dM|}bS{<;Wop)V9B(?m z=-;{?dmP%pDr*s@u$m6Rg=zADL)YduxcA(&$4j0<=`15N^sw|$hVxsT+${6>NhH08 zq308a?UJoR`VO~hgd7;damX_A@E7{kwSBJanWZiup~3>kNqJIk7x}WV%(02yOJrdU zi- zw$}_n(%UMRIxr>;Gu!0gaN`cCsqGVm)r_m)agAZ+UM=rOh{TqC8z-u24}2_=WuNns z&n?VWi|x3AsPIHiU+s}FOO+^Q60x&Yn|GJYcc`!1yZowGb!y2hdT{9ZP{y<9FD(sG zyQ(U!>B`G^jr3j;Ki`P{p?MNJHy5IThEp>>v5p;5t2nE`^hp^3w+xK7?-4pfV}Vms zZM_spxsbkMfwfJ$yGhwwzo47+=iB*Vr~0i^V^qVE;o~zF9sqBl(I138nQHXXIs)H^CET^*Qe&ZKoW%f zW=E6*hab{q$*D}jB9pdP>aj+u7f4%JckC^)a>bSs7uo_Aa!fI`xJd*Ghy*2ztloX*5*TYY=BrQUzdgBolfVYMIj%>k2g?P42RxyvW4hVFrdomJEr6Kl$fUkkiW2s-nlFfhDRurN5RC*^ec)%>))Jjmg_ zrfFq6BG?Vd2LyJn@|@c)N7!xzLS?LuB~FYs-I)C{l(F@`bgqP$J|~)2ef%TBx=CVA z2|L6RVnR_QNn{jD)oZba)De6+gRQAX0rDPnM1g} z;FjCY>eg&?<0EVl9!Q<6rrT?Xm<*IK6d+`Jb`PcO%{8zEcF|pF)irjJHg)My=4sop zC_5;^97ApP$74vaF}I@!IU?do+pA4$D=Iy<7jz{U$75eJu{6u?$$rLp-um94`1+Tl4VoNvt7@Hy;aVKArPB@G(}o4ey%TMKv?Ptt03$orLX zQ!CaY$VrctIC~ z?|VZP$+hS!6N6~k9X `Mv8ZofwDXQ*WI()udszN8vV%J;pjDkhvj$&7UHp6G04$ z*4U2UDP}gg7-J>*h+Z=_&o z5$=$fEt#p)Z?=U+>|V8}rxZ+AO)9WjudcLHnl{7k z!t~1B`dZT&p%n}9_U^;%Vmd6SGy0=!FXc#x2+W!+|4GfVlxp@Gr;mKl8V0M}HXY4QK88RPob7(sJ{a2i zm3r**$11_ibQ@Om4*JSzC6IMNw)BRYnMDL0si}l$hZp#vQuJGx3SMk_lwLRm$!u(-&A1Fc|5`R@j?_dW3Z(`GLA`F}Z)ia0ee?6SFt z_b6UmG&Wc#+GwtUB&aO36wOe;CYuu(CzZ&dlsAmY8-^C7%+lfJFc?n01${@^NwF{Q z2s8ztrd7u`A6XMVJ0R7AVP133xn)W{E_Q#nZxbWp z!l{e&;Tido>Vk#NLP5${4Sn`0!@~ZeYn*unn^W*V`AzC!m1>SzwSm+0%LdTmw<8Je zLmyQPQLil~LZv@NPPPw7*I*WE5xJn6&sms%dtUuzFyB-x+xurKSM6TEyu)mDv!F7( zN@=AUqb7h5@tr^#z82&dyWkzYSKFqR>L03)0$N|9#>%WMFmML!4S0MIZ`QNLh};l% zJuuA3u4jjj|k&%M}G1A6B_@_*h;EuDws? zWk|H;=w5~My>Q~Gp13+^H*vbHC3YDh_{r>oop=56^wT5^h&jb?lJ1oCwXqzMULn45QT+QN(iMq>r1{#(AN%3 z?@Qa1SJ4&9N{s@Hy_LySbhx8SZVp8RgC6?!6qu1>RtmNTh#(W(6YoKMeaWjm!g1lo z)i5$E1LrA=fyVb&#h5xv;aDxUlI&7bhm7TSo z5fSz$w>$iH+P~K5MPUk>V8c~+Vb?Wh&Zi-@eD?H|>9;H61iw0OKFnh0eS69zeWAh* z3Efis+ak1>PRx=d$@X$7tuP8Ud%HvJKnHp16TEcSxOcdg{nFh^%>WD{UmTJ^afR${ zJ{HUM_nMGq>J3^0iH*+x=M6X|s7x=&YY0qpSkoo3rQto4&oE~?Zq2a>HW*k)rNY0T zTv4&jj!jLWTm(l=%6%GqEJlN!ZjI;8A6HD{Hy-r`)&ESIpwLq&YMHBpDM7t@ZQhtc zyjJhKl|s{qoC{}OPM!sRWBVC;RbwLDK2iB;xG?e){4!syPN6D^!VKjZ5G6C>DPyoLPkr-R4L%fimWuz)fASF7u>6u5#Fu zzKH;PX&8N+`XvtLu=b-JTMfCUsJeFQ@X=$s3gXvpya&bg5g55mrKL-udF8MLrTk-+ z0^wzgVPx&q=PZXt#A~-Sq;x@&hM$XBAz}FBBY`2hTx-5&%V+&crzU8oamtwy2I1!8_cKKTop^d*X^ti$&+ zMf8PnIaL{6XXTo6s;&eKR1aCnd_E{_Nu1u3kB|U9a|jB zw#s&@Ey{=EVnxHV)Ku^Y8oZ>_{jXz$Nv<~Ui5s)_)H{UNF+?hz(gp*eaQC$Ncd{8a zdorzgr4M2b)%GiIFp6s?G_(xJ$;u+~;%ki`R+mALi38PKKx;T?8pOXYf!Ppc<&Wm+vB|diQ_8a)e*b)< zNvZUgg7fEk#$UYA&r1K4;jL}wj_f?PQ(HR!~sO5DS?t)-hj=c+JX&<&@53#5s@vCLto7vt^rl{1 z4n!SGNw1P5z*TXb=c!F5v;LFh^L`~W%V{ zsY0&COD53Llpd|qH<%etP$p*<6SCd62f@8$#Le$eiwN{+j4Go)!9z`THt;Wfz%)?i zVq{NuNO|}OKhJBu!(qj_&_gy0YNJV5_=p^?o^vJ)d*auW-0v&aYH2UtEoKrY*&<4l z=#i^knIyg4qD(n>NhW=z|12F@J}u88j2d^MeG2>W!JCeZ{w|}OcFM1M^QPbGx!!tJ zcD$SUXXbqnwJKvdZb!STjU+erT%HUYSL}sXa}~Jp(QX*evkgff{VauJWritD3nIT1 zvNtVC(61{~hbJWziN{)Q6KnKl?(I7Q^swa+MmB6{U+(1=9 zyEwXrW^Gm7qJuu}#bT;& zl6&Y&ojHE><@lrHYXu8Rz3^;o>2g%hP zs6&M*0uVIDCX?7ih8cO%l<--41Bn9qZA?@aNC&QpyGJm>J(1Lf`mF)>Q*#=cd}uZ+ zO)oSEY5fDpk?zldF}WJ-fNPi&iY3hO7SFLV=6kKhsZq(%#lHRRRz0kcoZDex(6Ql0e4Zw?w2Q=8rIt9wcR_N=0JGgGwlhaA|B-t|)yVR!y zBPeEK%%JZyMoprF0!7K?r71)>O*INzB%e#}-lSQfup|p$#!8sFv$Bp54yDufI}b1( zikW zrcz1s8{fCd-6;C?H6HvBSmpzDv`HKya)YRL0v3a)Cf9cX>;XC39ugM8IonZC^CS^i z!92dgdl~b$^$M6#(-fX!GO=S~Y7$khO4%#8IFc_(d-B;$uh~zE9%*?jSz6YLxD-kn zNRe(mg%AA`wh)P8D&xF{N{*TC0D~3jN^EnD{=go-pd94jq`4lP8&tn-89s~QR0*@p zgpnVZ_k~%o9jeH;1_oNN8q9U8X&GRl+H-9-jbGwfDAicG<#K(4NvE51jxVMyzItne zN_?&JJC7w^w93+6H=3GuGO&9T@6QMt-!~Rns|OTSqW0AV!(xLeA|k2kb%M6u9_+v9 zr;L3~ze=O|SFz`QMtL~9_)RR(aj>qnuEbtC&YE!IQM>h^k^n8>OC}fZ)#QPn7eh7#T;HHS7LJh_ z(W}G&pCp<4_=?=2{^*UEtu-p0O8_(=keY+RMHF+))17)WH7znSGEqh$BG3t5>0|?~ z&MT>5ud_apvz9I%Bw=9CvY!P19NB-Sc)OmykA_C3*wwXs3P(IHTkX2J9bX)C-8FgQ%mQ8%hNa`*YrqIlG&c_W(@Heq$!E;1YFff6Z)>w6Can8rBP2-xor|6icSvl5s!)5 z`G#p*(=x(auD}3`9mMU2XDY(R$@1O)P9Bdcz8rd}t@H}dCw0D7`L5phrxi8sAgeP7 z_A*Zo>+V0;px2$&M`2e9Vn|rBu{UO)Nm)FJ3yh&%&7oV|OR=k|C=^!KN}0(V&aH>$s#_&o@VSB4H%L zWT#h+n)_$OnSw)lyKF{K%Tn{7uWo4^f(jj( z$YM`#NtZ1GW%vJaC30+&wp|klAQ=n{>^{?CJyNa+I(Qre(fGuv7#ZB3KC&i?Nw-5T zap5zE6<&O@tEa=s2~)7o^AA4GdXka|D)*~!zyjRHon7T+wJTo z+wE-Iwq28L+pfv3Ns}hqnrgBqbKdb?p4U%m$y9A9SN_8bC+GT)K*4H>`a#j@C_xG5Z=70#AGB#?N zVrS4I#|+Q$kB-;)C~w9jm0d!Od*}EuJP*%sH%p$9?h4w!aRNP*lj~gw=-^mIQ_3KO zQ#?Fef>3mlJyIMzZ9d;stz>b`7&*6@O^c{kM}*!w%@bV}i>1pdY4Bpe3r4!KKQ^mO z(xNSw=T-!GLXC@_ymVBiAA|GKD!FbMD=CitH`0JfNABV>@^1<575vOcOG{BIMgS-w z+J*1?$ne%Akog5F%QUW`-vocXE@e*pgUrl>h&@>erkf;tjYe-bd_Q3{ItxTOMxH}A zkWHbx-vZ2fc>H!6=#SHrg%I^R#@Q5Vk)AzDig#F&Adf}RL13++e+~jU?J@}FOyart zFxyy7!xB%4-1%mm#>?{yEJ2N8ruqsT(35G6Kj|8AO-NAKcmSCOe>g0ruwv@5;hC7m zmK|%Q*Wa*B*x8-jyx1#Lu1z&BVV_&ww{Ajh*KCuJ(Zx#{a7A)ZY#zE3-$hdCB!I-Y zvctiOXn{FQ<>e^K$(R!7eZFH#*2p0e6$&m1vL5nt^!^&RI;q5nW#hHYtu@RGGRYYZ zSQ#vMOz@SIMPzr|>d!S?&-?HwW`?0=uR^`9iuD&0od!pEB}(NQKshS2H3wvsQEXW+ z$7la*L3nsnar#I3LKlb!mM{wjqaD-J*g80^dTj4ruDb6mxzD6$OyJ46@ZhHsovvp) z!j>|g1-R$Q#LR@4YWPEgXX|rI%1-%cCQz&-N_D-Il=OPOVxe@jK_6lpG` zM6$LxKA(Y)JA#ra=Y3CapNhS&+b!%ZE&Ol$%vx9y(J8b#6+gOKiFCLhB?jz<5Pk!j zk%zR_`t#q(@E}6qo@NnMo{nHxF~T}mogwj(!@naFioTavjAK1YrpU;aNHdQUyLx$g zd0KfIe$>>jz8ofkXI~67wimbW*0R@M?VEhgmKqfEYwF!z`TOrSJhjT11y^krndExB zPjR2ONzX=}z716fcPJ`w)r9-b+Joe0RA?SXg%jkT&`Me`DzDkvhEShe3BT-9*6diz z>5*#`q5;a++<`f#;uWKj)c*FpSIm1jp{%Xp96!DgELjZ+I7IsuWtpm3o+}?}T2W9ks#uVk|(*#LTR?+A{Iho5^N19p9;M8=vL!)I@H}BZQP_ zN-%P?jKeMT3g6m3y}Y~aCvi2QNZIS&l z*^D4T7pmIyhpiZj9CFBon4Dac3$_ehT$XP8r+jssWrsF0L7k&Gth92^B9kVg@-r%= ziH>?MInon7EIFW{0Wrx2573^Qkh4H@-}EqBGM6VpDdHU9;8}msS&n!-=?FYJt_2Wg z?3}tQOhUViJ%Wde+>YzhwyZhvYO1kQvaW#{bGczUUJj;j=Vr>hK9l7z6n^)?!oC}&t+N2IJzEBLJXsul~I^i@zgB`nvk6z#4 z`~N16+Iv1ERdHj^DZ=n35;l3U9XClXBk|L>aM(;XrWCVo+56gJhk=l>-{A2&lWL}x z3-6&xE_LNDMl%_JBIoN>OQmWh+vX+=O6Ywk=SR* z4nx!N8sj&NWMxBeeghIn4q!~l|BP6R_znfcf^X-OFEXUCFX2MC4u`L>&_05f&iMUs zISougCHYjF_bt)n>2=&a`}OvEl-kziXi_0qis={#(Gpl7PfziXH#8C)AWHO=A9lt) zv*7A`C}r}H3BFKPWWSbHHgmprx^y+JU(wDLUHi9&wlE{6K7Jm3j%Wgrnth3?yS3Sq z`-R=<`__?bokQhI$->j^te~D=T5x1u4u5}Sk zJZMOH=o<6fWlTjsC;)CvNsomOvS&VKi(9S%8;+%lkPfek?xrK&O}bz(LU=R1O2iR| z!DMB#%|y!b7j(FA(`59iLIJvX-c5_%!Hp3&u3(AGdhv1b5qFMsk?T zG=aPGoFVsJ#!VWGSh1U`X?nS5@mdDcS!;F<$w0WIRaRLl8HiH?{~rB%>j*=Bm8`-B zCgvqzQ8obwV2*LS(cPBcwBmlJCPy|N=lBOc#FE%*j-@p)F)Ay|8U-3I2?)T^0n)a# z6KjjHVDo#{&aXZGSlNC$!FZw&)yH}2M)M$V`UnYXJtOgDEQhVaPWFz;rF}55d zSzk}@Yvv>XX&OQ{LbEPy@|Le&n_d>sD;qs4##ZXZVGJWO{GD%)6_Z8HfJcSd-l?OV zbR~dB+wP3Y>}m>f+xyMar!K|~Pqbub6Wt?pEY~bBw8!eCL19Mm;=B}*p%7lhs$BR$ zYO#ty#vvO99%F>w2LV~OwP4Z#NZm(xPnos>lS&SS7POdZAzNS0bfBD3$<(a1u0~fj ztmFGcSje&D<3c`P!NkU*-WqRs29R!#RNP2s>Wewads6eXn|zH?s%1sQcumB0lnX39~Khn(9LG-S$# zz{`g>{zBJR(zX~fgO@DUM$37->gn*<_A+3hgjYpCg>L*?>(UUOp%cwT9&<*0^peUR z^$DbeoWHn;*6key;9+SaotSE-5I1~EipYMi2CK*N626~SQaYFD=hKyLJ8QOYdX_TW z{~cK`r1>~v`!oSYZzDS3xw3gIoNG7`5?sI=h-v$n9w zbgwsK>FrKeB%tJ>qDe!^4}94KM6xlQ)e?1FSV@OR`fQZ^GHLNE%X4VZUoxbpVaCV6 zbr_N)i!(e6;y3ZL9xg*Jb%E96fZc4=0D*@#uCQZcakVssim0X_E8Gd_)MSUJ5I^^w2l!Wb z%07pc0Ow)gE%TwFg3l>LdNv~hiPEkM5SFL(`ro1DV^tT>e&&ZGOzSKJ4e@r#}eP}{g&|);iKW@ zO=Mpeo*xV8+>y0zfFo%hQHqnUEIMoWV_Hf#vV!XXS)+-{9dut1FWA}Xmj=$TNHvlr zM$`VbNzn7^Lf z7tHJc!{Pobr&Xq|q$u^f@9$3+kHJGJq^Yndn11zYUbE0K(*gUb8&i;i`j1qC-i@z! zh%^DS+zNLO@foOOl>>`G=3IA-|NWYa-v^!oEMV&2KfM{|IFi_e3>38xIT`C({;#gBe&@qQ5JD z3I9p6`+C!+>b&y1Wgv2V@e$?Bf)U}5fTQ{Q#RXLOs2U(|!*3iaGG&-O+Ee_Y@!!Q| z_NO}9o?k%#*+bnst01MAFeYJZDy&Cb&6Cc462w3=0dpu&U-^N*?OfwH)n1E6Lw}-RkVX?o9 z(e0Im-%v!Fv|p#JzTM8nv_GrDE^Z%vV=2%E09uudnC*9*mXzw!6tS**`xU9^4!be! zxpfy@8r$fyB|0qdEsL!~is9q4V?%0a&UC98Ign|TzI|?m%sYZ?U_^lv*pa^&v3|7_ zLw$pVoP$8Uzk%QofrXocfKULCNTYorKADTd5WwOXuoDMBM%)0!$Ezloq!cYB*KFw~ zfEu&+CiIZTSahC6Txx;O&d6Agt`rEu<+=#5V5J7aSYjj%TWHn4@u0t>5Kq^FKkolX zSa>}8XG7ubn+G|I?jpU`cO$85mOHl=i2y?3lSp_CoZ9&UKPf7m&-e3@F=z4`j#ouv>ABthtbTLiF7Q=6|C?F~ zt~V?I*NoeBxfSah_lN`l`hq0Y_6;Vwa+9nPF_Q{I2MyaVi@#kT{%*3jm}je>8lr{+s| z90c($_vZ;jHRUMe)XMg2+Awp;_E<4AbjHTwDJFO)t!YKkpAf~3K=KA{2E7O%dK!Ji zHI;<+>XAFUe+dvG=x;)J{fvo z%R4r_ymT1-)jd{DYOyTbDSeS=3y=`Y<+$7H3H*z$XSq`4)Az<%_qp+#QhT&>>$JtV zh6cLYdcL#q--(Ds7Wa=xHpAsSJE2Q^4vCv&?JK zr&FJmS6Xwx{18*StIFV`O;5o#$a67*^t;vJ^VzAN-hHYnf(Jl98^BKeykukdbydJ5 z0FWaO|Sg2+v<~M9vPED!$?554i z*>n~Zgidf&6J8f0CUCpUHdWglT6_8blmqjg*KN6fGM<3;LAUy2Mje@Tw~hg{J^nYm zYHln_LcW41N3L(dT`Dzn`4evvKNAWF(2lX?_K zl|#SEG$#wlLDB7?KOb+!&3RFRE{&Jo6p1k|yHIc0vrCYAwbRx_OR`i(+zN|2KdBpUi4eaJurU6ieEnxQmB64YC0Lx2&@W!7}Qt!zrZxjIf9gv8f!EY`sa z$lhGF9Hap5EVd|vTsSd76mpSj0Y{FlU&d0ZPstGg=s$omzD-uNq)q!)Dmkuvb}Mkk z@sHeRA=y;j!V?JE{Yf!9p8R`WsC;5U%)(}G%FF0Gld#dbOvhNv^WE;W7rO9jf=x3h z2Q>pH!!Xd-;pL_6@OXK?l{yv@eqpp&M_x?gEJl6~$vBwM7#EFouY9CcOaB{kqPp4q zYcjl<2W?1m8-e=|)pHIfKSB6`tAj0gwSl|EeYf#W zlF^{PH0>sFZ}iGdV%zOU?oPO82{ty}D8_DX;@&8L zLva7I_%j?0-6KpAWS^CT^A&<@c>)b}u|8&?K!rI|Oao_vJ;t2??W#Jzv4`N57uCRK zFO*ExH$lg`>EZ0xV?d#|2sO2%U=I;0n=^vwPr6n4!HDe(Svn;G(rD7coT|S8Ti)s& z{yYeS!<5Z}+XnJpnt9UQ)Bo->?IvgSC_Y3|o8K;oDQ{EwXC{f(hvOG%Bne`J)62vC z3bY({K!E6BWB;oLYP!@pT?*h@fajn67p zPq$Dq-43hUixMZ!(-0{}NfBWTO#-#8D#3mqQm@i66rN%cz8H=EP$q9Q1OQ@9l*@hz zq8^5yU@XS3DpR+`WdD=)88t71W4~WSE0pn*( z$*D&BBW+67uEE=1)4V;CIVQTmRiMvnTTA|up#o>}wjM4c%94k9;}KMUDdlIK1J)Y! zf+2zPx~J^y?6X2|_CMD%9Pg(n$u_7R@OoViB-w0T_j!eXE86pu!{J%EO<0s}p5ja# zs_H~1tvqs}+w|oCU_sC!z%~w%wU=1CmOot}lcj<5gW*ZLd;G-c7}p>2sA*1s(B-U& zr?9fuCTu7aD!pfPLyn82(IDFk=$5pUa`Oy9(J{7*Yp$$$^Y(RAQ^StrD#93>eKeUG z6TZ02KWAS6#(NqQ%Q=2R-~+*2QO*1t6YKzl(G?Ht{yf!g&G)QQMIW2uAFa->Jzq65 z3mX(^wFn?tcxA0bs=s#};~a=)r4=u0m|aKjgN2fNU+n|GB3y&Z*&KJo zY7B=|`bO#2y6@kKoQF=LzIjImyBPH(+{b9bgN#??5k-p5r!b7sl67H%qC|jj3aNdl z8J~|4n)QIBZj~madm>jIWp%o$UT5x@I8S(cliPy@a{vZoi8X){ zf<+{#CIBu)G_1-)-2skb0DzZ!PAq^w3I(t)Lfa*kouzglRMr|AcpWU0OR=O`vvzM6 zc>c({N5TjW-l|Bbk-`n2p`YrVwe~8MHnJE#j2KB&dZj;rCdVLI9!h*ALFIkBRsL94 zJdd`heBAlA``K5~e{5uw26PiXoUx>0%SyY9UwD+X@i`s2Q>rhBw%nyc0|M~hKs9RP z17Y3bIE3*!q3k1q5ADgxachN`$qMQ-=^+S!pWIt<;X6+;g2{G6-3N92NB zN5Zas8m4@{Dbs5W9SuSElADNQvCFP`bGoni^h6p<6>y2s+>y%~U?BUh`SQl>;{`3) zP9aGLWhpGmt;p&FE}h3zmeFHNSPF)4B0!owKL#TRz5B?-C8|_^8nSvq)e#6 zlp>YIyMR9}TVU;>dc0WZV3|L(u557iAC;l`EVt^bg_m4oVd-u-jdDvw*s&kWx9NJA zJ`K~|Poq=Kib6kiTbaM57^CFtXi4L_uzI)3={NKLyxJPk2m`r)h%yMcu^>x=G!p7Akq$@QS-Z z^*fLXtb=?T217B4>PQ2@tZ>(tz3JR_cBn*S$E&6N{gJn)Yol&=Iv>Un!>)Z4w^Z6u zE&HEs9x{>+)V~`k9USe^k_o75^yTK?h&|0HIxPpCdjN2u)A@p6WQppDpU4kiyfAYb zBLAf1ScrY((m2(&4V8Lv7H!!DIFSY@LNr@$3!)lL7)o}D5atvQ6R1;>BfKO`W&dVWO%z#WF5C>St{Cb~!&C z#VQGOA^f&?+6$X{68M4h5Ux9FS{ls`FAdjVXwG(?os73%jtSUnr|DZ>G5os_={0F+ z!-7yTeU!thTt{3#K9Ur3Z(-k-kMw%v~sUem-!m~H02J!OL5qM)5mRkQBU-TBNE zesksw2^@*A)|=KYS3sfArC(|^4ljWlAq)*%~l zFdg__5ra^u(GeQlyXo1`h4Jurw6@}IWcA);-8$maZ61|tO_b~7@f=tr{7&4##Q00E zZ^uuHg$1z6%$c9-!f#9b*Z!S-eM33WE_ExhO8Q5lPgcS+OMZvUdamr@ zeA63^^8k@^1kJ}cuXfS{7*9oWv8{E*yM4AGnN2~=QL}vhQDhR9YCaoRxGgth(ef2J z7xxK{PC8#~<7Zy>O$g_!XbZ?RWwl!yn0g68ZoPN*3Dcj=UN4`e(tqeoy(z~ClmPE< zFrPK4eQWh=dUX+^T@h>6p`BjHejNE@SpwivzlK#knhQYswl;!Z!c@16WyTeEmC_l? zB#8Hz#L{O<0qE_|!56W2fT9gvX(=_tFZ1kCTa1QdtUC0?A2CC-!6^#?h8A7@;0|63oEOH7lBZ`VaUA0 z6Fi|LtekM^va{9EYk*d&l?D2#$?(@<6E}AP8OLDUDuYdXN9W2oM43<*<{TF(I!}&Y z>!_nIwj>Py{i^6gYXg;^!>F_>tYJMmBeh0U_n%p6qqqCn_@pBsx+)Q@)J|Q2{9!Bd zb&hDcDv?&Y{qjK<&sV06tRq&;*Csh{x%_1+E?bRI}NaQz2_#;SUNl`u9RB@Ze6eSZsMO z9ozo)l)AkUVZ%8BCjOSoWu`Q-KH3_hj(`#0;8(GNI6oarPW7`I;u!=C!71C1g65(jp3r!iz z$$7z#`rX+-u2^)j-9KlR_RXx=oX8D5l)aU1eT89M{H)#(l?xKB9SV4QK`t181XMl66(Njh#xHBq__76!BHUjEmaNd`L_MS`3j_xGrEF8(9VLoB|l`< zOe_6^0=iqVgq|frHY(3hoCxHc*$(G2eU0Y<$ZH{#RRQtTLC?QG^tH1;>7e;o7dZ%A zi1zgV?U{GddUat zLhVf&u;?lcGN`Y4z;|pFKSmAzr~VQfBhsXL%0bASdg#Z&v#gUdfEpEsCI%Kzuw?0+ zeVLwAw$J{>&VJY8n_7+JTsOzLJ(8N;Hi$Aj79**Won%WApYW)ku!TzgO&|R*I&w+V zFT{B9PM?c1O70JlDCQ)fyVr9Ts^^~P zLduesYhKdwb>0pQ6;!Aq(px`omFF!_zO_D)wNc6eUUOTER)-sYCES_WXM-6&(Hy6n z__i6IE!FA2>DsAgPQh<9Z*^d08S+$CtKQ=ed=7H5)n?d8lJENBwi8oEsqKTx@k~BzQ%{; zRGjv~PG78T*Hr6~({suY^nHK$=?0?>hePyiFl`4XZteUkh%Nc!xP}KqF)d*Jo4BnN zZj3?cR!r{wSd1c6uoyZHf?Ajtp+!tItxF_*#Im{vfL-OJAa+;QY_r;GDY8cb&Lk@b zsx_zXOfitg(x3GJefw9`*JBro7Xl*S*qffS75}E7*TxAyaezDCV!p>sS-NrvF*14D zAaWeXhglJ47s5-gi`+odDu9L$_d1b67vd)Mqx)HpgokO*l zHAsTBh12Peol%2sQRMg<2L+~#2=ub_2E&d@t@RZ7yYL8uC`{F=7y$u@RB&o%h^X+J zR5v5Wn7j^R2s$QiqUn-F#GD^K2|jFUFjVKTHHi-lN&#%)yPv$KGbwV-1t}80p`BDH zkIR9#_ibt*>67_L?)|7z;2L2rkKp2WC-H!hQ4FjPRZzAZ3m*QFXXhdJ4p(1Sfe@FV zU;VPsUAB?`$3vj{p1aw}9yn!PDQmu*Dg0Rf=XN+@Ra(6PF1cU-PJX4iR0RW@@`M6> zK|?2wJoG4BNEv-9ShIOFJqBq7!1-G!fUcd~Dd(XWq&S#S#`qQ^mROgSt%Kz?5~bRB zFp?&!i7-w*PXeNpuG*vm*mBrkC;6hCP|=}%L4TWMCJr@iAT-LGy0DT&5r=_*3jtYF zw4ORpqh5pD>!O(nXwK(JXu&@KeU@fo04~>T%6&GlyM+XPsF{!PTmO3MDr3Pfo;~!N z-x)GLsTb`Bf_#xn30Rg1Zazl7!!Q|j)#iWJcSX7?a8#o1GkEhw3U7qfTamMe^9vMuFcrFxRJ){ zbGnf;BH%3{(UUn4A%hma8UsE&#Q}YjIg-$Sw+2}DdQ?IdlXQv>khs?*Qmtu!r6n>U zg~9&(S6eZg<>RieVD}SCk{uIW^i_8jZ#qJYc!!?vJwi+=*SyFI$5NgR03m+D82&c6 z5V=CrUfM!J#_`wlG4Z53Q2>fJG3@jk3yq+i>f81JzX7vjV<~IIW+MK~);{i`Hjg5? zS+?c)6lT!_fn+He+|uU4=;`wy&cf#AzTUOnu78q{kMETMA$PDVJtS1W_MdG$L5O_;wCW?ErrlIgHp&)U1?LN(t!FTD( z%gf`qC1+Q;#rND#h<3K0q;zDNVsse7yU%{eGq>^5ZNIL=9fF*@nP9qnxjy%!UH!3H z@~8kzB*EaK)m`M21(0)0epZexo61tOfi$hChs_ED`}sR5yejAs za)??&j;%n0iyvo-G1R@EwT<*MAIENAy@LQBP}FxT^3JSsiey-mIH=Ks?Hz3PYva+< zuWP+9mxlbHl`NT;w}+E+pEwP z^Oy}h4wp}b`67`j~9YUzsPY@sX+NYp0)pT1qg(&e_d@)6k3 z41Si;Hdoija47Gm1&<*RrQ)>~;C4-FnE8%n7>j;lrQoN>9 zV4&LD`|jE9kDf^{GRm{&41q>Fw!<8Re~4C`%&U$W1@V(@KX>16A-)skSb|H#EL|p3 z^8adW@BWz9pxm_5L*t?6nCT5i$deRW1QW14RTglhG&5EXTDp)5$;zgBn|AQ*nUXKy zm-iUf#2zqTU^19EU=5X$NwAkDR&|ZOuw+=$D~3L&ngGD5ctsg9vXkd?(eC-eM9X91 zh9wJTu)Da~l;|Te13vUTyA4WdKkDtl|QWR##izt-LW!vl#0$YnM?1j;iCN2 z#cZO%-%JIKn!hg)bmVb-_gq|!S*6d`%Ne(?svL3$+7c?jwSE7!nY&*e$notw(yz4s z(ac+P7)<`-mak{}^?027&q%+1gixF`UElBZ^mt{JG_GNpd=%FqI$~Z>=fl8-lE@y< zs0sUusZ_o8)zQuks@t-M1W?!XrO`>(IEcI-BTX{dI0&i*Osg)#D^*s8x$R_}3=M(7 z3jHXcuu3K z^Nal&X~UAmzykA-kw2D~cPRTRJr}Gk+e1HcID^d638O(q4UNpL7LRr?&F!Sd6o(BS zUEY-2Wfl5|`^xQfIq22apo?4$&-QNg4AxP;c|TpADEn3oQY6~}9Jjm=M&r3tnhugl z1o^ywC~Y;gPnM&U6r=W-aF^;=8tad&^tJri$OpnHo|^X$)KZnMa&+{ptMbwUzq-XL2=rKc8tQ9z{xIE3MuT9(#|j+`tS8=lcPPi8e>r*Er<1 z*oihF3xh{kyS+Sp`1i+Baq$Vy{?H$I-b6wEAF8~ODaF{6($s=>+8SJZ-$Cgc`;p-7 zO6NcxAX&^tXiXMh-LXk%dK<{z-_^R=VaR3E-$np)NKn{)@qzmHH{(33I;#M)&T(8smM#>yhQuakns{O?T%P=xIDkkf+0pLc<9ch~r5^A!_@vh=V7+6N z7nwU@KXWj{>PMAub!ncl>uvs1b%~3;{~sM9xs%UJAXYlx+oX z$7j*j>bkBx**Ec=cPk$IohCEaJ&7FuH4cty+8~7 zMC>=jL{p8>4>PIxcCho}8w4zmtvHB+`gzi9yM30Yy}eCy)oM$2es!9j#m&^SZrR*Y zlGYU(o-P|gHNF@?1RD;S#SNA_(b{f^G%vMvX@~Kd@J!h%%?vSCPw zYXa`3?|s&PQA0R8!2zjfgh*S~0+&)?0N_8?Y3Cr?{ z3lFg+4rP`$rr0UY?o+moox{Y>5;*_UH!-Xf3p;zfxMYKF+LNGpPsDQ7-6l{o6oEB1 z)fK>4wq8=Aafo_;hcip33P(v*3l$Yzr9sieQu=6zDf#tljmt*<71+20Gp#H=2&r?~ zF?|xdN3AIi7KtOT1D{rl9*IR9vfPy}DHu9LMEA>LYv=MQv?##AIDNr!RcCh#E2k=* znXk+N)(bwTLx8eH7mEg-P9!%!_e8K>8(ud^osY>AP@9F=N!_P6Q9$dn5xvA)d$EZcd+< zx~+lwonZSCFkF3ks@n#9U4DM(I%u)alB&QGQmfi8Y2Up>mzV{1*Y_XG-~pV^Kp&5x z3d`dROB`pR*-`2(`6nByoOr%7u=Niz3>ma@Hx?SvjfU!>9R{=D!kqx})UF!^ zx$hibA~rtcoWH^*cuv1hOCa!U<>S$^#m}|Rb#Lqa&FRNma^*~kCk(XkjfVp4Ap9?u zxJG-Z`s3`Hx^`TsAh6^i%q%JwL>Xo*0zch2nFCYdrw(;trR|DAhAQx?3IyyS= z_gU$zM6Y8;c$;oIa30oBVh!(4tsCD3Z~80W#GnrA*RQ#f;F5eaTm=vDZ$DUvKF@E5 zVOG^J2B?qF;EmZ!5wZbL0gk)4fv?1uyM4(*PEJoeoZ$HnnzoyMRk?+E4EraFvCM>A=9i(4%56wK^C9*3j(jD3J=d zbd6rdFt4oUGUz_tNBcGz>tvj&pGRy`QKP|OK?fiE05s?=$X)ek;RIF?emV*>rsq~@ z#_Ow#w5eLwu2mN_#%PW;k^LT8MJ6Vw?SmT@(y=H6K)UllASrxZ4#OHYUW5j0ZB}jX z?Bvusd4+_hwmhwJG3U`0Zfs!5p$Pe)fCXq6m-US4wEB@Kz-Es_MVcVL{MR&o1wdH5 z0$8~eat#Y~_t&OADU=XR^87*5)BzYyG8ub_%azJm`Lw<2}NRvp0i=gFfnoyj?THGOtB=MCx;e z)@yOuNKtXd{o*C@{TcqR;%F)I(){!B^YEoq*g)$OZWuZEQrKNkmQG_J zTntD#wY~`e(2QZyOs)0^$yTn-24W(?P0dWV^I3tl<>&6J+#4e$NyFe9ece&k5=M^G zJ&h7-iZNTGCKw3-En0M%W3EGw4Z*>sg80@F|I@=@^GZnH$cc+E$0UQH{3Z3yGC50{ zP0hKTNw0n$>0RVRHyLNb(d1y8*MHyRBf8(**qA9CUIp92(j%KaWb8ef_{?bJ;AcV# z_!%M!9f7gnXQOy@isNu_7a9eei}+{pVXn0Ox0fbP$>Po zxwCPYr7zbJ7SmxA?+HPq#Z3q!u?e1~3(D7w-A$&rG#)C8sryvg)p^V8*XX`2Wj|Eg z4!@(>T9NPNlKaV|Nvd93a1AR8)Paf9HrPg{Di4FhfSswxD2f5lZ z_MqQe?LC*e3Ju~I-4NUEin^PX9fe(2`JV@CnHhK9$)EAEV}FRS*_M^^PLU+5>Zfj= z%cwHR^VKU36D%hgLW2IiVaEskJB1A^0P$lav_k)tGkOqusvW#Ir9Fz>d938SmW;&* zE@R|m*u@;2Sq>FhtJRKNOSTf*fUgD(`;E~{$y$wkL4(^rIMP@Xs%&WfWx7ZqzXv_l zFsc&_Wb3Py6yPkewiFvb2fClrb}rYLb3mS}qLs)9*tu9lD6=cs(Z$8*9_2|8klfBX z&a0O&l1)uM{cIh-2d(YvSei8GdFrkBnU)i5avUucd7KG+th)JjO?7QHJ7%_j9tOF_rueVyexB3XcKZn=XB}d8VF`5u_Qj)z z-2^{Xwag0fx0&*vp>P3S9h{c3au6k(O%(pEC+3pA4M#uZGK6o$IOZc?*mi*^g@m*k z@L%JXJ>XdekjQ}2dE_qxOOpjzOavq@KBtu#7B)HUnvC6Ih1iY!T$n&Sv2jij#N}KL zM1ux1I6A0P0*{F8wVfXwdubWhwmFj_qBq;rh%4!97)cn)y{9E5(?JAJK=9e_+k5s> zaKKg+Vc=?ADv2C4D0n*BJCB6~=)U6LuH*M=2a1GfYVE-g+`S)GS|YJGI<)EPH&PXon*Ho@7`e@c?Fc|0NySVF+ZffsC~w=n}~>r06yZD_#CW-JAujOto1tqa^J?C^|h0kDJ=O^`gEU$!_)37 zr?=TNW^{<3jOhdK?3uA6Xewd+!?`SEs{;MUgau zM?1!X$Nq3plss`C5Agi9B3YH}F*$RWgllubm|{%1#k}5GfqVWfc$>P~8t6qtr3=!n zEzcEAx4Yz*?9Xkvok89CR|-x~mrP6H6FPD)!7k0Qv9YqQ)!|Y!9x237;6up)TLUb9 z1zT$U0MC%LJNyItW}FLy9aTHPZWmy~nsQYcnGVU)!71C12F1#Qw{Nw}^y#v7mWysg zi_QA0`PHktE<|VpA}xp_%@-S7E&h1WQ;bx48Rh4eXwcI~XDg5G=3U(pmWZTG>~vB& zwqD!Oq=6z+@}T7!9v@Zk)oQab6dA5LnW?Jkgp(3QyA1LVGrRQ_3@1~ zGp6TQ=)_ANfK594jJkbN6&71B6HM@+7m!Q!>2)=OqmUMtI3dEst&oSD4YXus!s@2$ zJU8pr={;9hIov+BV-t>d^>uTyJ#Z8YTJ;PsHhfsRn9|aRVjK_=lRa%5Xbn|njO=`Oer|VYcoox zBNcV(Xw}{Fh@;VrW$WB+s(Ofp-a$$uu&?~Oa4MELLkQ*NWJlUZv*WMuR+!iZij}tG zH1AsJ)A}c-Uu#476i@o$(c1hLPv{hf<1n^19kE2|a9do;k70EGal*I8l5hGp+5bMd z`#!zf>hK1(`+m9IbTaC5ueR3CogUquR-n>B8fs*$Ri|flYtyY$2L~rSn=syCnjFav|cEM3m(iV~LGUZU+22Qms}->fUaq2CaG$=uKOy)vew>Zhojp@c%s%T21tN6Q-5Xj3DK6UFt7j zrII6fIM;}iS%!P#th-qU==3|&kNVQ*(NM>XBNaWxN;efs-ZjcD#5ME5fZJVw3%k(; zQ){A80lTa-0vr<989pjsmFw*l$KL+}Lh(Cr{aE)zIr*vq<~R8E#%=G%P3+R~<~{6BNBX(f@UhVVc1peC-~G6nNL3Pg zNUl6vuCeAA1iMKdJv?|Ua>$jZ9Q*WLJ2^U@bzgNAC>RXQaTb3O6#}+n#Fo3RH-CS5dGYKC0J~Bxe6t9j7jAAA+C>G4THG z@2+;%$|s_{LLVaA`+}rFKE)X3Y>)|_K-RkA1E|U#s>Lxo4GnOML0wr}8w> z-r(-=toJYKZ=d(tK$O+kSEM1E?u$CS%{wxPtG zD}?~SM5{j`0!Pg`T0E<$u9%n6?7Q0c>slm;rIbb9(J_a`-DwtvAp2r}8*T?Nb+0|* zbR>Ppl~QqL9_U5SN>TxT2zVotuCLFK2{ydlZt{1tmi5Cr4sG>%m||q654oA0s|c86 z{X>LSsa{Nf?4k9SY54}W!1H!D6W^LgyH!i0)a!N+lX23Wj~I%Q-4B` zH@w-V$T1b@#6BfCQS7Y_z;#lnCxukH2?I`F?fX1NsZ{Khe*yuR$rAldFQ=G9 zI%lUQ;^2ag*u64321P2R_69oI@EJ9hN}V7`@0>BgdE)+AhJRBciQL+Ph*B5Cw~x?1v|Ytv@vp!;M%PzE(`HU zr%U2*^PE6Ex+1S)>c5&4t(MT&^L+e)3S&=g0kaVBsQ{AySU)fCkP6~D?5z~J?k~fnSBk1a4W=%bqaTqFuQ8s5xynLxPw{r9(D*Og7u-$|ZVM{d2h3fd zJyxg8-H?=Wm%YUCi1)vAvx})imBR(6B>1kAG%2obpRMDl>%f z&dfkYD!p8+t*vbjM3XiSk^&)p(&8P=ZIYnqJ=0OclR_-h6%t1v_;D}PplcG2NGZZf zRu)i-r~?BggB~uUq|&M?{OUBqe#6hIA~!Y)>A`;Fn^WllHy!XI?Td4T-LVE?H1DA?qT`1Mh!qbu=M)$+9W-;5`7t)$2vz zy)k9<)2&6rmuJ@dBTmBCEnW}2<$lIpN0h8~H-rk|I1?S%u7PPx7+()%oTnFv{{lk(bjck=2Q(f-*U86$W$0VYEj>0A9&IB?^R}%aUz!DejjXG z14yJaWwc8#^I9jX>eGdS( zHi)&!5nsOmQQ8)@I;ZE)Hs%M}UD;Q;om&9+p+KaQoz7$ocn(`(g~5lg^UoNk`45*WfVvyes@~nV1RqDy+nItZtlfkdQ7BSKQ0OS z>{fSP+LM?8buFi-1&(A`)fJDmB+)s|kFZRNrfrypB*b{WwW~`Y(=6f{;+0Ga_dnW1!R;*D1Ix&>ZRij4O#I|Hfb{eR`0^)7XBV zFH3SayepUt6;acq074c+Y3PDblrM0EYxq`qCoS(mZYyL?3)n`|t;(X5#t8w|CHjqA z^X5;h%u%R_29R2iX;yeGLuDyU{J?xfPSm|~y*37?(uo1_TMpQM?Nb%{%Cb$ZAe=}1 ze~&-(?9+B@bz9CedrsZFKCMfg4qzKDx(^j`NNwBA?NVZkSZe<_5squAygoHr%Z6tv z2Tvy{#s$6XO3|orQ)nBCW#XgzZ9nHm)VJ1Wws?$hcb(4{U~nfowE|QG8+??b_vbif zl$IwPv0fEx_PlC4WWha!9i`ur4slJh9e!IspJ)6=`W_34>*T&@T#)y8dk{eJ_KZ})$vavMN=)DpF7 zMIk_MIw$Z{j8%BkjfTs!f!-jxz~rKu74BeY)AqhiYGt+~Lh6^GZa^-aIG(MEXJ(kW9O3o8{CKz zkd7%+Q}eWe{_YM@`z9Vgm*}#wa~}2p97qfOs2CU?q}2j=r}yv8=u2jQ)S{%!lUoFK z2(1p`n@w4k1(Xd?P3O81jTZIV&9KWA#;oYHTfBt_uzAt;RpxFsUWGcsRt%CmCN9E5?MaZ{ZI)}&$ zxyW`wMdv@gi8w4*`0s5W=3ng-z33z?)Zk3W-RRLzESBj)O$6Wr zxv`Q?SOqhcS$;&!M&3Kh#LHCg^z5Nm_{-y&nid)Un=<`7#+|oWoJm`cXOiCEO%0=! zrDDgH{2eVV@m14th`Q!4)bmYqR{gRNwI|4R~=hs0Z&Dno4n&y0VVwHCmY>TlXEm znI3m|bqPX_IBZMNxXPUTIvnFRS8^lwzad#<%Oj=~Ybq<1DK?4w;e?P{=&?W3_{Q37 zLpd8#7DFt&GV$*4Hcx`9$J+PSM!FckIXd#81&B5~`2+Hgxa4K;eFjH0?2VoI%BN8o zR_xN}5hEmj?8%bOTYwsrW*|?f_Kjmd9?fv3vU%O!v-%dCckQUfp}M{uwS6O7z4v<} zGj$*WAzw3HG{quexvpH2yHRS(-jOfdB+U=XwFmlCWRM-#D;dsl!_G6I^84Sj#~joA zkgP?2x{xrDSNBTzYR{+_+*8i~YL{(68I1kWeyDf7&f{{WOcqXxyWTD{p8l4Js`=tC zUK<1lcsu4(F=1Br?mQg#4+i?D}G=hFf`%g#v3rflp_fj@^=d8ep}u}9m}tQ zjnuK1+LwwCUbxqCrn+Q?UUH0!yj%X=W+#EWsbx;A8Uj%ixs1?ygm-u6tKFNWjPLJl z(iaD7)dCns0n1fCx7<^%Q)XqW`JzQhpPicF~U+sMWsBs zwb^E3kcA?b+D#=auC|B*)ptcB-mH8@u5VA$9{!%0TmacrJkf9ho;FpQCy)~npuxC)FViHpC#V3Oz}QJ~dy zTuuPmow_IclNm)59(jDGHmUWIyv9VINzMcvPHC5u?Ll^1XMJq z6mzLjF;W7K)rV#cz^-4b+v=4qUBAdt_S|qN%r{ebb#rr0r2!ep1f;0lsA<`h--5^7X0t3U)-GWGiN_RIy*U*j9Lo;-DN%uGK z-v77mowZn;Ip>KTzg^GS6RfH%gM&qa1pokW$JLyGtao|HuUF!6={v;>yYh{vBp+YedPH0-Yvh!bLTPj59XB~ydK z8l_iz9F~)5VEVX{l9J}}_tQqDUi&&U0r!^oN$4)vtx&yM>-k1v-5HH-bFYmGqYEPv z`0L;oqB4EmwdWoQy$AUqi#SqV>&Ab*%z%)=E}zO9^{ zWTHDxyf4Q`eg*{Scpir9_B;%aezURm>|}%1#DoTUGtujD_}@c{3V(nS)=N_4czE%b zhi94PwxSJ;#t)YyUmYAcfs!dV$8lLw(OeJ9WmYl|W@mC?U+^PmyzBPvjwHl?_boU) zC@83V8EP0ts5TNmh5Qm^M*grU{A2vy-&Z$7ckWd|1dn7(a_#)z1MtH`{Wq0K{vQJD z>=6EPkF*G6%?fH)1)05me6FU?Ydsr8sD%FbEj)CTLh=8ZC?DqKR+C2;Ppj?FCfMV0@$VeHg~TA*LV7 zLfYNq;fhQ zq%B!4JW?~yK0iQ1UV2@M9mv(uH~{Aau5=0j4FW|lT#kU8GVR-sHQ{lg-ncq_aEbw@E zd9(fx(~j$02a1JR`E6p3FCPUtHaR$`T$LX=#_6rD;XH_q#GcY4_BQ)H`scz4$?3_) zmIHZkXT>_i*4@3|XDM;WC+GS&HblL2LL?Qg_BK7CaJNrSP1_F@WM@fRAT zSz0?Ye_!sb`Y8+1cabtUob+^AM)CFEqysNgzInjA{5IGJFc8wn_^3YWM5jl&t@Qf* zjU*hX>DH6rsXOB^M)+6058CH?G?9Ta7{qCns{ZdIE=Y9DN^-yP-l#trx7x->%9Y?h z0M=mzi2qMsgR$#oCM|apDYaQrkV-+bUQhX5P9#_aD%FSjb%#(%7Lsh5iCGhAAH{8_ zbYM{vTw+8U}M0c97kQ%pb_@kRdiXRc5RVb3>=|KZ^i zp+Ml!UTP=jMH0SsW>kp%i#asY4+$VO(wztQ)BQU_=#AdZaO@{3@)W}VAd(leXM$Gy zCQ0%gx72t!-=3J??_#2NNb1NZW+9bjFxWKAY~8W8>Fhe`#pzF^b3uKuR`{n8hYxR( z{z44xJ2prjEe!O8;O^1KJy-VlN%hD}dH>`gY`^NqP|nv!*}*rT;$`+(;QelYz(1GA zCw%FYM@UH%5evJVh4XmsFX|5Q2kpNK`}g3Ee&PFE%)-l?A!f66b~HdP*8fPh_+D=J zB_44I>$V`5tbH&oy0Axgvdr`f3r>wh(Cf#6SxIqA4i@u|TZfl;e8?~05x^}-IQfpz z?Q4O@7i6u@_wpl>mrZxvG(oB=rS)Ylfm^!Y)xkkQ`FZO|I;k})YS{)jBt7gEe`1o;?|bj4tCGqNX8MgJ@S>=|LVt3c!prd=?&^InMJ!l z2TbH{C{v27@#V$pLlDq!6WSulddB6KstHN1b%)1FbgB0tdO>GRbk;p-307p5DL-kkNBk$I`^SFjD?&#^nFOum-YR@T}~?*P}=f_soi zD{E`%P-Xl_@#CkYEIIU~sW{{h$Nrt#*W&R}54nk2oHvrZi^A9T{p)a#bKwxe)8Fzr8U-iICT%w<%XLp5K`t=S z-7Q^}A9aPGxuk;9CbVM zyq+73yrE~F-bj>Gb~N1RS1~-r-NTpZ7ehSdJ5#SQvAbSeqyoB=JmM2)@743YC83Ys zp7SC@B3Iq#Dov*4DiwN?$CM*e*U?tBcszo*W+jX(*zW=Cpc-1PSeZ^f36JDr6r3#c z?4fTQrD>E%O+J$sS;2mBGtg{-yZ0-4U|?obM4-fiKnQ!q{mr9YNGLcV2~oB={=KBE zpIk0dI4)N{^0>#loAjG$qx24*#U9@8vKVRX2`CqVklpf0t*v&}(U zat>>ggnh{$XR?wx>LG+E0LyBoLG>txN0n1kIJjgdB+p40yAYRGR zWSX#Cv#cgz`*^wwLV57P$y7x+n2-)<`jmx;Oz9zoX{H$YD$qY39-d68(GLrhZ;?C| z5U__z6|PZhInKE|zdCK6%(9)ZvYzL`UQ(FuPp2^dTIdgW)P}A4P?#(E%qvIpI{rVV zs9Hs@zmrJ&3uFBMBT_8xF8kn_D@eNI?HuORs*(zf1vQYO$=lYTMY`6Y%RL55E6ALb zM_42$U%t#^;se5@!P~P7yNu8pb*}F@%^$afQ$N~3qA3y(1MU78k;*Pno0rEMSyFHR zld-Jx`x-`2|K%_R$VGT+nqT6$*(K>(jm?hE(IW63 z=vNEmc2PALY&Xwx&>zXxV#-NL!2s0M)F?X_`afVAUS&Io`jAoVI6mLAvsIm)ZG^oe*#yP{Ok6_e|r^*s1bja-1Mk7+o+hQ9}ZspNnLco4R zZo0~2&HZZpU~G9p=?ytvr(cv-GkDCcO)I<;7hni3I_ z`Sq|8DKLQ)Wf>W@506TZ;GGVgq8r`wRet&CfJO^WdbF!R+r@&�oC^FlJLx1MfgG z)SW*ebgH{GbV`}nI~i#pJ@Gws@adMI0llU-tch;)d@D~L)yeVI&*?LL$BdvU`{v0? zW9Gxq_ez;dVNr@rQ?weREc%_&&rBY2A+X^%YHMH0eaa{!5X!zZWiDi7JES{|P=IcY*C@x>wViT#t!C zqQJ8|{@o8l!95DQgp-`z%Q2o@H60*!mM0#E1)~w!!A!+T1mDa9= z}IzV{LY6+nk=Bkb@5%6m!rjTxJ8xu^by~b=xYhH+)pOm)xpG{y$kJZ-`Aia z{V`lKz~^^|`LS(a1ueVQ-E66}0>OujjBGlAd9i*)&WL@ZO>YDAmzU8Uf_7)|t?me^1-nIF1Td9-$%lLw1Uhr5$X%kbR3yC3+<1dn5`%FKz-3VF+D$T^% zEyWwSm(3D6*GJeLvse4>kAN3uAAVTkk<0ZXt)sTG@+B+DU&;HGRZS$OGHFIj05k#? z8YF{X+Lw(wdD?F@0TUAwnNmk5MW1uB{kWV@EPT zA)Rj=^|m$=(tE6Nbn+XSon>COUPwjPnR{RQght2H!E<~VXbBP0LEw&1e*W=4bGXu} zPrZE^^|jo39~OR2_dYY~6si3f;q&XZfw<;V<|XE-5FMA;<}^>mU~v3*UdgDXlS>lbM zvbWL;%*BcvvD4_X9uBD7a`-w>-pXftO1_K$A2Cn8w?tys3GdV%E9_(Zq3UCVAP9!o z=0+HI<}wHFilDCIKK}LBiNu3_9rAFLb`1lx|&7$VPu@Pt$NNUezi^V*LI@+qSlhFyE0*O zEvFce1pc+cd?75;%=zUmZ%*}|nBR|4llJ8KJ2|;k<1M$sU171)kECIjm)$Na-QgQ) zKFwtYt-QiGWbc?p39cS^s!}eNw@N-6o+6j}5|JqAU*AIN$Rg;;hE2({r1)d_lKR&d zkBI(@os^?IbKBv;N}8L>Ih(8Wg4>T6bhkmrS4nO>@!+ylpF1~47uPX9*XE0T=7k2Y zrJZ%NcIo-gje^?EpK-V?_y3Sf@xRfV`g72Iu?wt=1+Rk}gFu$K8Yt4y>5C+n;o;#A zu|yJk>yKqHDF+FTdH$K|BAP(Rpj1jb8F9H*bkO>sm9{T_c=vbCsQzICA42;>PmVWv zUn;}~-sA~!)no{eg;}(E2v(%-t#G}0Neb6DL4T9N?T_FUL}q7)PrHf)0dy2&xkV=} zcqvo4vuciqr&-4ymLxZGNetHtGd>ioNkUTQxnOOV9cuP>GGz?}*KNO$ zGFSQOsuT_Ir=px!GLjskyv9PWhRwP1@UG?fI3xQ5oGy6zSsST+H`&|I#h1F-u`D)gtq-I?G$Yhz<5)@|=TaNixr@CFzPtU= zU0Y)`epgX$a~0GdXN$&GS;Vywtg^l9sF+61qghY9p7wtc+Vef|vQm-6rZelEgSnwk z{k`K|*p2Tj+l{jI^XKp49m6{|9<_4TDNT2E$~zQ0aH$gv>2kRgG33`-7+UA#_SSP+SDlFL&ZDhdr6 zOzdL6-0&`cdUEjfFcj|h-T^iP^MFn-U{e;8zx(*oNnnOKuGt8ar!EYf_FIJ}Udmfk zXcoYMkmxBeCWX$39a4(_r8~GJN349k?;9Sx)n1VHLS`+~E_Xw-0Ymlhklm)w{Sme0sp?IN_jjo8be>rQaz(|AV2+td{brqL-2x0x#8_YXWvhd(cT zsPGc)BJaNlIZcPg(q$U3o(`yZy#@%Qr)%lBthJd7Fs;_p#T+Qx0GcnCb!d{R$%rPq zSLcb#-5BeFSZDEEJdbA-T`C@u1rQsn_g|wsQx|nRNcs#>^L*jYmx~&$>@^?sWgIN^ zhQGUC4z)OXy6>1KWAU6vSl+BL1habL&ma#1_{ZK;9=rZ^C8MA5PkKo7*ZZHDRYwr^ ztKJW5|L{0sXv!ELs_Fo3L00RY8duf*_-oL~Q;Vzu_#T3HA|5^QSi2%|8 z2xT$H#s{S*r&dtJ2iq%CZ;f<9W66wVy(zoRlZlOg=5QX6tmf7=~&v^@c z&^cU!#@{wv4*{MlOPMY|0O!wFRPEEr5EJ$%_vD6G+L86OwvHYrQ%ydNw>m2PL#A5J zbM;kwb9gpx#dhob?{%OFC{sVk#X*NsR><1TtSV^vAydsvaQLUY_le`j>ZSs~OY_{U z#A7GII=5&`W=oJeTBP-Qsk(;*)*;pj)q}Pv5pYZrm8V=BPCnAXY{r#;3Z@|EuX392 z(?35OAo4IeI&;1H;F~u()MV6jN)#jVtdzvKzmAY%GRtA$NO?`lO4gC>Cmb2a@Zo=x z;Kk0xza;e7#h^0^3wM6^6eTz5H1$F;O=qOj3-dOFF0(0Za7Z#P28cJ9q=P3obpn}s zHqM|tCc9_@GOE~D#3#iTr1Fj5k?Lr z=AOU(=(*W^o_*{%59}`rFiuL-zhVSDtSJlLinqhbSZ_(`;Di-x-`+E4O-VwT5Fx z0^gE=9I`k&>W;6cdQb<0xtTawrFo5o#S-t4-A~U&EYo1$>frP}d1Z`hK@~o^BT6ER zg8S2gJ>Cb>YH>g9i<1o~YO*5q^BG73V7bWmvgjM0W*Fb?@77{v0F%gBzu)hrKZ}tr6k!Gl$)$ko}a2 z`84}X*03GzBI1(``xdmtf?YMo_pm+fqY0%jEe^uYUusVW9}aY+@}yJ`F4mDIjf@8= z%z0l2^`sgiiN9k>fZ5q={egehVzN#quGxb?LN+z`RZr03*sIlnhvpS?nZN*b#YQ)W2W$G1qUHv59@S-A*v6ieW z7CbowH`xO||30gtI#G=IL5l$nGu7Zp6-dd(N9{5S z1%@N>w3K6mfP9!%0O=0US-WT)yJUx-)7E65$;h7DAbbN>rx36l;lGVDt{2L@TgbPZ?f3Fl zB8)H>Ft>ClMsCp(lX|{)1sUUs6%8Bv^9t}3Iu~)qHb+B7#$qe90ZZ>H#7-7uTG`d z;-g|OwvHtkLOs~s6|%FwJ%eMN2sqNywec1#lw8I12p_BBneRa>18=18aH#~lPrQ04 zAk%~S?z?BLYVU=dztpO{*^A>QZCYLlLz6_hboC)JFI&3g&xx12XgIGY!}d9SR$2J_ zFCXCPx%vTV zNgvZPott+*2_<5`Y1kx8VOmp!rm78wY#69(8#3#mT5}qd>XFoMfvKL0teFygj*Lp5Dm{jRU+MP}2K8T1 ztnz%{?(hG%Q`&OZO=@#O`ighTwW_9N6hRv@XpNBq&b2%vnDNz6b=4~SXnegC(~BGZ zL%bSA&DIM$76(OAB6#AgNrq8p-@+<8c};!|et$lp0N$BNB^15(vl?`}7Ek!rnQQ8XDNM0* zdk)!etJEu%I+iuMwpD<;op#hgrh)sRGw#k(cuarWm2$dFj$(8S-PU4s>UUbwk;a>&sy<-D?Zc1`1G>8sJfzN?XSOw_mThP;Js`{^sR<&J-N5UdcLrg zVJba-N?CB~WOo=?nzjn3a!6JmwJbZfgO{c~u7X^!Lrite8TqQ%R%5HEv>Cyf5U$Q<2Jse%!NXglB+^ftQ9;!0={ zg$)()f4_>XPmVgj#)?Ud`@8zqO--r%6wdIiC)pO<^D;C zx2!At5%oJ(&Hs7l*L{*S+oB#4)S!glVcnfpp%ub;-~@Lno%pR zMQ+Hwz!*$^sy%T2p=5(RR^hVIfWMfpKy#vEFhwPlD{&yiREwqO zDV4lf`de*zMWsx6kJJP6W8$In81>W*6ws9(PHn8(5G$V!*m6>Sytr|VXPYSv;Z0xZ zzQy5mUlHTvtaE36d=ad$ZN=lSe58<6@zy6h$gH)sPWvML-1KV?woZ-Q!Yyf6seq7R zx+AaG4|H%~%2K+KHMV7By`I9#n^{_c1Hbd_uMOl>N1fVs|4iu{_IOCaIyGq5%sX8J z9-#xh5-}C>*Wem0s0a3RRf(pfK)AFL7+RfGePA(EVWo2Y8YGx>PNY4eEF7l=e4A5z z+QZJmQ|mxvA4lQyF-}3OO569xGp_Zi;o)K52_V398IQ_WoIw$#^>fZvwz~ZGi@&BH zF)fwsl5pr_go`z$ehys4B(^kZxQtljSOWfG8-mmPJoM_dMfCOcflMqRTHM$A`Xk;u z7U^5pcoZyx1qckv*)yjrIL%(RMh%3WmEEJ+Mo(KH>eO)u>oxP*r&x4+hd)gC3~M_S zfpuq;W_yy~&J!xnpu!Le3yGMOjxpP#kJl>i#F2 z`&D7d1&QAWwCO4j8@-tb4TjaXw!7<}yXIz)tCl)7*bm;cY5uW@mk%N4lykK6Om${SaeR>Y_mah zV=wQs^ZKJs&zcCXGKtV28nVm9N}p4gwW5})Dj-TLZc}fY8GMDiX~?ql&*n+ z-X%Zn)h`{dR{HubyU_9NnAhCbR4FZSSP?ELLpJSxc;RNKHD5c4-n|xUn*TF{n4Djl zuZjBWhF4qI9HVrtDqHl=xl12Hc*V)9 zWd6ay@fiRF%_@)qe8W7$+uqq2NjCsI}n6McK5>srMrT zs0r#8@2uyb+VoZINms6Cj{Ok=UQ2E_wFn;goPhT=?%7=IT8`Z)OD7pko!{MAyMPwhe-#pkhF}aK7nykI2_AM74 z@JtQbH^C6X=T{@ohd(tQ4pvhxyh>hxwdk-Q@Vpr!MN;mMRMMCaa+w0HnZ|vA!vo1F z+8f#q)3YMc+r1Se;fWBrTU9WWc`amzC)$)hA}hlSnn9bQ%su;Kk586Ac7XxbeAeq- zxj(U;6j{?djs$4{7h1R__|CN)@k;?UHwSJ>N%{l?`X&kpBIvOUnIgt`hf~!jh}r+z z;ss9C4Aa1!R5Y+mV|x~c9UFdnicY!Zh+x(!gz4Al7i|3~`nES`uyC#r_-<$tkHRzF z;7_P5Pf9@k?y}`)epb*xesPA^+J(B*CM-{#amJ3&lTtLJd6~PZ!`{uj_EYJk3x(ER zSlr;(k%VH1NH3pT+nRs31mxN}%PK-WshztPMkOC^Gpu=VM(HqoJt!=O3G<@m<0bgxb~*e z__L-~XhwAF-+}lBeM`M&$=dMq2bO68l}m!YX%&sm^;7)??Vr&rqGd*fNfLRlH-Je1 z6K4!e$yaFMxz+Wtr46vY$PLnFppo8pP)|AYIFKpDZxc9B&9bvEbM9$G8H>lY2!`C9 zR$22H)Ed^3_Z)i$c^@u*{+t6S=xCVowib$?%$Q+kNg60A$U8ZdP0DWLCm5ko%Bx1=_<<_ zs5$g?n+-PoOAsUUV-|7O~YW=wpE2O1V$Y?otmf zBWqe>zs-|O?5yen&_Tq$#&=17so|d8{B~GE-5i9?pV$$JV=|ViJ#UqO1x0d-ZO^+5|(dNQGYF6cQytu3#u(qiS>*; zx}TPtcBx0RW5!rE5AH3{{X=HyJL>%?UB=fuY=0cnfx(lL3DN z*2jz^Od+wpT{+^T;GiH_thK|=-AkQRRe6iqq8KN(IHxAFf*SH!_$XizynvbxKWXeh z9UA1~oVF5(vF4HF;;JHqX6VGmc^Ma!HMX=kltGy9Gi`{9rmrXF|Gm^1Y`Jd>92m*e zxYrcAg-*~DCGj%`5dHYjZom*`Lj|u>)K)nBM8aMqmUSngbs6y+9U_E&a7(2ijT663 zWxPz{YvnwQN!5czUujFdwI6MZtScrBJy@rx-n*(sx|JGtu!Qe?ejYa!B63wJyAl1n z0h=feyKimJWAO4ga-)*k{u7J0d4uccw`ukUDTCT`-H8Vc1JVLX1{E9isQbnE%UD%}Oim<&Yq4V3}DxUA&fs9EM7|{_#lc z$Zx17E}r~#iHEC=gJ9C@p>xHS@7hLa9DkodX+BBrP-uB2IM(d*bI`QNc;ZW%+r^j_5 z#!R2}oQG1#VBdyhWeI1Tb^ZLWS(ZduF+5q ztH*SonHLB%SrLn;YJ?hS1!d*B%`Lr=u0+8;HERNvvJu8k4wVMK%S>mD$9K#~r=VEu zAkdCYv>uSl+dg%tOH%MTr@=hj0s~DmR13EBl_iHkz!LC=y*w(=RPl*_`ck3eyj?XO zRa76t_{CC#i&ew4ZALY_yka|Npfz&|GNS>Ba#2y&dv*Ix>}+7sg`gZtNq#kTGPQ7% zLj_7SR^jnkYAK9c5n9bg27w?H8P%Vm%j^guK=CS(&Og47`3no|I=Gg-gCel2-;f1F zrw{Hy+nXB()c5uH@UTQxZBo7WIp3~bmT%rDf<~o|^x}wJ-h3SYR#JtKK&9agLmurE z^%!a_7)%p#q|1#V=17KV>&xv-9gdx|ZOsPS>nOTyg9o&#V`R?v(>%7LibyAJ&p-5S zcp|rDTJR{-IE9~l+`A?L0^<%t4-{U6GsgVYYBH-_x|999&xqmZx+==X#o+*VHHb-Qx|m zv6{0&1!gcdm{e~lr4JQ$QqTXp65FYE3m5^(`;0oUp0PKT2?j{&WTfBJ=Zq3E0jN~- zFPaZLnqg&%q1r$(iT?g{vy-1^;zCtLRRciC9kQG7MuI&C`Io;L&I zYEhb=Xwc;?Qb2y{DGE8w&Cjq~9|*hJZ*fM>PZk{O6mC2Bc!5%#d@zt*c~q_atKaYw zzHKv931!^QMeLeBPu*^1mr;?!T1r3(k$J7x+@jelfp^8 zy4@b%Az~LkN;$Z3a_nN+iqlXTeh~~kTBR>;cbjgWIazD-4`fdfnRHAl(A*Ym2vlNN zu)#`~vYO-${JF-HUS4s(No6D(ho^9G)8ueB@+IQc!2#j7E~%ILokOgfngT5~bn@F+ zMUh57#3h2GDkcc+>3$}N9PKEzY~@(ti^{Quo2?8hPlrnj#i$tFO!>Js^zmQ!25`L^ zo<;EK1c+MVRrOk61JnT@8CsV0bQMs%e^yd?bMJjcZxF6nA67A+l-y6Oem{^~KS%ux z#n_J#O*P{Wp|XWc3N9C5&P^WXa*!3SFqvpLO0p~wL?EhQ@Kf82jBhUw8gM#$1?#8x zw!NOwJ>bw2c{&?050U-F`FXQiSz_q;y?>u>rQ_jqU;iAJEauJr#J%Dl!e3S?0%}UI z5lcj7{UzCy*fRk_B;C+h@n6}!F zO1mjYz=13k;4U{xjdDnSVlZlqot_c+)LfRJ_jlgMM#jGR;9#uj)?cE~FnB-WuGJ0Vc?)y{OfcP++rX%?2|def*OjCr=@mfFicCZ(PbR;M*3TKNQhN))x? z7N8BD<(~5O%K;EkQyZf56l>z*e0{YTn*sPn!{%9A?ScY;FeMDUWu^AjcB{%g`k46+ zTXd)RyIBxNVy4Y2KGCZ6clBFox{;>HaZum@I8M928vG(-(QE>{;lqUhs;QgsD7+hs|i} zs;!Na{S)`?SitFN*GJ#lg_hc6`5fHyL}F~;uR5L!A}o|w%?Er1R&*Ml3_t3B>dhug zF>0*Q#_Zt+#F}Op4qy)Fw?0YqMU6+WM~#aEoq)bv%mOhxpFC!NnU#Ft>|3WV^opbi zEC>RD#I(`@@q-zeT`UZybm~E~c}}<-&v1aDuysY63#BojxkCm$tCnoj^oiznKFgJ+ zfJJ)NHZEXMVZ6N}zFR}hgnQH;MOi57R6A85Zt#Xzq;*mv>73`n4rAvCmq4k%_j&`R zxbfcY1A;<-oP_KpARtB>2yMVhj$e!0N;j!UZcvZF76Jr>Obg^nfY5t z>A6p9gNx>hVAIQ)GC#vKq)eaZELwZH`|Om@9vcl9;KWhtwGn>OYZzv)GHCG@0>0{K zYildJtj9GI>l1zt(UZxnB z`X##Ye>05qc6{>Umo|EG{O|-5nksbS!?fZxn?I&+I&Ut*HT!RD+m;oI^hkV{A=SGAb%q=_e@l8Ny zj{zlG%{JDCMV|NAqAw6nHOr8V)6bZup4^J-vBi-tF*W)7M*uT^h2OJ<)5V3RZniIb zKPx01>Vwf2D(vW$d}Tow^)-XyLbbATt6?+VT+On@)@_@NS@AdEE=Yr3asAf$=tjRmCDs0U`qeCbTw`IiW?5BjbRYNLD_;yHD0i`RQ}r)VMNtcMOnm(8 z$`>H|9Ld3p{>?9t6pSe~Wq~tCkJ+coI`tu$=%PE8HNFSexnJ_9ry5HpZh`N} zm$pEo6H4)|82ITi|Ku^kjs0mcjRh!!67Zh*vWNToSCo3mjk60mtL@$DuL@@+-1wv@ z>z5AQxMt0PJsqy-(u!lwhe{iLyhRA z`<_ikQJbeb?2bBR==Bma znA70=zJJSaI49}Y_I1Q6u+^FMP7x{n_Chf=R-~=-^Ck8>qVE?27>-*A@qdL>NJ{x76RLs$1``~`7doE5%MGi?3i4FGs)E(! z0s$@!5ClGb+R2?ISfy1&4mH%^^hXwmb}y4wU?ll#ge*OSQ?X-A0#OQi1GXmhujQyV z^BoAj{(}Xe17g*gWi%=&X&P%OO!jk+W2)W5aOLEx%g_Mp;v5_s_*C{v3DQL_e%4Oh zm{3a_OT&<-xOjpBzMqs2VwX`$?OU1BPfN6laK1$usOJ3hCWLc}4V{m_L57j>+u3>r zy0@;;TOakwDvuS-jFNdYNLX502w1nj)XfqGgWl7Ro*8{bb>KANiTG}}oVe7)u0Fgp z9P6sDP$*P2qvN1+Z+ST?wUG(aWq5_`c)OJCFmcH;SNS!}W7V-Kc+iM!jhz3U38B_p z{ke6nGqjNc%!&QG;oue}j(dJC)oEGtW90p*l6?OdAlKxXyM@;5580ypm0un0fuM^G zjtVliUxN|?FPf+CQLgbF4SRAcDPq4(e6cu2L-Vy3BIY!RS-NgMxJKAu)N2QEjw%u( zcC-Dh-7|o-Z^RSoy5bUbN1LZ@KLFBW8h#q-TYbcDLWL)E@{Dd_+Us%EOL^-IyIDu3 zk~U~N*}O;Xjs#1)#z%f#L4=d?{)XT+ZAgMqn)g}mlh)$=SUxel>St(Zd)lLo#3&eH zB9H8{wud`=GTAqtTsz>NbEzJCs{M8X19ly|&rj9Je+Ln8?n)I!C^BMSqH|Em*KZ%A zsTU=p$8W<_lfKBDec+wB51DaNOT-sW?dTIaMTpWML>b@fS&AkVifn3&paP&buP=KV zF*%9^=Vdvt%|zB!#vx#iy6L9j5qAwiY&gscOA>IATIvNjgo7wn2fX}SCX~f_{e3*{ zPG2?#G|l%F$X`7BKA)ND1Kna1$3DL1jtcNhbl{^O)c8m%xl}J_sKzNGnJr*Dln%9h>p3p=Cg(&U7oBn>iFp%r;;@gBa6HaR-1nMO!fsoJ*!bE#ws_R|(Y>)Tc1$y%Yu;Bd9 z0%H#gX83hjuC3VeeuiW&OV1Ur&Auf71I zkvE*bV6zZXo%D12*2eiP*8lfmp~bfM?7j}-_K63{A#k}EE4E=<)j}E>=4Mpp*L#O3PE_&_`b0X< z(pYrZF6q=lZ%4u9S-LM&^_{MMb3VNxo4zvPyR%bq^AJXBtJbsat8E+$fuRp?$zTw! zIsc__<26ZXyQKKel|-Z8-GaT>hQF`F^qbF+>AZ7EWFN9^rfEEM>L6`O;5yKIjoIiK z#TB9&e0g&Q)oYS@N`Xu*+q=7CpipR$PO0>ylUyN_b!?I(zDRk2^!QnqE|cpXK)T7O?{!6ZIuf<`$l$)bF`MeA*{>O&}Eu-k3p_uY@e+ zBNq4akg>}}jJyzU>AFx3L`OLDyo9q2cY3ymR&Cpi;x=@%)=0y97KMO&_l!QH1~?6~ zCkj?nKpaD}ru=4q5GNd3(*EtPmix->*j*ie9C)_sb2d3=j$v>z?eJ$7*|qglWpTOd zw5w~@rRCbtG3%~yymw+^4*8=Vz%p%(e9lm{dPn@4FoyJOXHA*Ds2e49Y|f1|x$l`* zJQWrXx$PGSfubD6(?nW#AZ1+E@Ib912#$4 ztj;%MPNo&2=ZWeTB5@QJ>VDrmRbtL8L;KV}P8k9ZW`>G(ww{k11bUZ!KKQVE)+6s3 z=uo;KIAXUu*o3e|7aiW877*wtwO&lfE`{%NM>Be&bu@;c_?L%U

#d$)tJaae0TO zX7X{WcJXEu|B&<`9TPq;f@dlZws;8v(ExRB$LlQ@L`IFScI2YMY1e<#Zs4^G%}tdK z{mE!c#S?4=6oQvx)JmD0hHXDCf(Kqu#SLYp1SkSujy9WZM{rSrCf{x42BCX#$z1W7 z?6yT!H5^*a)vzu!`KTDUXA0@fVEWPg(NA=dM9r*b#ET2ydB!mWq{3`xUaT+K<1_Q` z%87Q>KEN05PT%{teVG&D(^6K)bgJoSu&3{h#Bh+&FD$*bjjtN~o*eh7{k(V40`Kb8DUsrr{AUnAs@GYs@9+fj zx6<)ASzoY_EvWBZ4;(vHte&)1T_w=)an+)vg`^Xl=NnUK|;7_PWdI5kQToigb^#X+= zJMQk}{$3yuC*{Yg=@G?TfuQ(ck%4R4buTzcAVzpQkhz?^=(OgC<%Zw+9n6PDH!md?Qdt(UjHBiw|-H&Oz3as-;sW=Luq)^Hbt!{ z%t?f6f=dHz^}*}%QLG^5Y75SD$69yCIE*Rvd{<@0w@=jKY2^WGA;ul1fFtu2WJ1ag z-iaFzLpuDnVAcZU+XFkci=?W$U}&R};>;oNnG}_YZtTR>CbN~dgkm&GVSzs5&V`bf zx%q(%dkMOplq@vFidkWAb#i+kF@d$M0;*`usxh;bFaz|G5*%{3SH0a7a~}^|+W1sf zY@#tCBgCEfChwQj1}21LDSpDc4WD|r{xpe+;Dlowh?<$fIjt5kJ})vdw^s}y`LkX@ z42H7#yHlJt-MnsFjF_QEQ;$I0gw(S5>SGHg%Wmd9So1hLW=Imtp zDU=Y#VPB=sT0ZAi3fx;LUo1*7_>>=wO9C8G(h&$0*jeWm!q17WfXq0PL8}kGveeFV zzH&Nde?6hIOF)aaxu(cEH}y$yU#EI9RS(H}=oLtZA4@WQX57GU!X69(ujJdhwLqll z1jZdnn^!_NZ|rBU8b71kC@#1#sG-j1M1`o*pVpb{LaP6Pgpi2d%v*-O;h$em-RTkx?YIrZq^B5h8SBQ*IeyMz8b_G)Dl;F4&adR{rEjrU$4!!f za;ioQE6rdSz1p#3k#tERM?yw_d9~IWn%#Fj>({^HbreNhg+z!`?d1-r%0DBam8!Ky zFI7ckAdC4RT*7+8t~PHkSkLAA5{d&xfGFcyHVY9S3ppEG&uz5Iw_xdfK9AJRmwbJS zs@OVtPUMPQjCsOo0ptdy6CB-Zo4HZr!>=d1a4;eZ>D)(^tnu^*w(tpnysV zNVk&G-5?Euz*4f5bSxksjdZ6V-6c!OBC&J|EYjT|D3Z$((*0aN-`}%;-o3ATX68(s znLG2o&8USF;;Z|JaNCeZg4k~$>V$`HgXXptPOlfAfH--+6gCuBBA1Vj3FJA2G_$vMH05Dj{|G?{W>l-7=4T2t|Y{?pIz1x?sh*q$lBfe~o4- z9YBl0NCGjZyig?f><~e|+fhE-DIA@TTblZ{{!e&=zn%?f-c5UT9M4UFLD5K|xD~p^ z_irj35PuKuZ|^v`w_Y+@0na+#MmESr)lh!fJ)`6kg}h zPKDugiF0PP&9;DF_e8!APz_NqkF*(9zZ0?P(k9yKc0Z6($X3AD8G`j%af4bs472Lx zGU~Zqo}5*L4v!N!h0M;g{u)jn*i4A1bwXX9_>p-Ew4O<6k}6DFFgEISk}R-16+cO7 z$zM{yn%bi{q#FAnA?yBlI6xok5MV)9I2$EKBKzGH-E^jP*?&*N^>~MJ?)zNjN}G>_ z_xEtQU%(v3%JMQzGlobK;5jI(-^t(fZtkJQPj@W_;d0k+9#=IB^=Vp@0_C5gD&t8t zd{7p?lOYpP<1aCGLF#S-)}ni!KiXy!zaA+t*pxNvTO0l1O<^eYX!{sUIjisl^c0_q ziO74T7!HcW*|)gYpSa^G)0-lLI|Ho=;~m%qYivf)nTxgCrG-xi^iI=5LCVpVhbyHd z#@Ld*?s>8W*EO)42T^Pty>(P9i$JDlfeosA z|H}L03IZWi$17TY+Lpq#08B%YpBs5JHO{HqPAy8XrGlF!gWSy@Rw+zceAa0FsgY8W zHNvteV^E@0=EVK68e&)W`%ru8J`#SQewaMvYhK8^$g$4^f>6^t(Jwy$adOgmJbY`6 z$Nh&olPuR>Xc2RhFSWK_X+@&#@BGxM>8;bJnXPtulTYU{5lI)Ua_(u(*%cRhw&z~x z2kTjW%BlC`ZzSO+?Y=9$LeFzzO#RRZ2A4Ro6DkY!_by*u3cl*Ur2lw0`cLnGiP+HZ zT_b1pM=)E|@t6$#O3~EC$`jwLVis*6&^aS4<|-Ek3-L2(u)Ex-aUFah6JHPoh*?M} zhxM_1abdfSZF>0Hd1*V5Rf6^l&)(DVqh7)B%dBEX__5*x6w=!%)MIa6GN+0h8kvWh zp$)VTto~SiGV(5TA}_*umG74~U9jc}p5S?b6O9Y^D zJqMz(M>a+L2o*I2&LPYK#93uzN9tdHvug;{pTb8pIRNAY4~?x7qBCk-+kU;r8z$F0 z^BXD)T^Z!sBo=;9U5t>!LdP3<1vi^PhkiVn*|D)ri|=@f&c(9{DfYp{q)xP{GxU8y zNbj^ELZ{HUPa4pe;9ns7&HAQQy<1(1k|~RwWY7W8iKqzlb+392_C*S<+Xigb{c7?= z%~l<)Lv9=IUO)uDAP`UZfG|@w-hesX*&ix4t<<`|VfKY7gz64Ev-p^+#N5CfsM zW_z@m?9NG;Ay72R#@IBtJ6*WFQALS6bib!qid(-dej_n z8x9OUAJst^0_8wTlvWUV}k$ufT^*5-jQY>{k@?ApFGGz>w&vKY6N!g7pi1c z!FS>b4m_zCK>^z8&y)G6!-f`(SOQ6Dsx56eK(ei-RnPiBpj?3x&vt&NeNxB-;t_~u zkKQZXFh7G@yINSNepY%7YPQt8_~xklw&%e5uNwEM6!OjQ6||FQ-lN=tx2qmSj3Xxc zJzW_5v$JU-16Ya1#u8_L5#8$>nBH5t2cBLQ@$AHl-}TI%{_;iem5Sq@&r>V_Sw8^! zLMl>|D&yO!UFDtU)t%a>h-_ifZr!C*Z@eJbvQamAgxE|1qaA#?2 zI)9xpYglmlnz-BqMRdOt&B=ve*&%u7dvN&59NnCXKT`7Y^)jrNumDGXKrV?Z&Syy77C~b{Z z>v3G=9b9*8`S|_p%HMov{jD^Q(f&)%m;P-!|1%QGPZ}M#A`j7+YhevhjwSB55S*V6md4u8L|KSDC2p-MU9WYd-LV(|WDlWv<{4M)(| zb}T)qw%QcGlWpy%!l0$9m&_f>lO4hO~-8_aC?f`JkAnD2hC7OCjyL)sQ~rA8TUv2%JKRkdmQAsCn6A3K)37iwO@Twu0w?0M|%GwZsb)(rn` zP#+WTnRW0Pqmt=kyt5M7ME{Xwtp^w(WcH7rsfhFNa2>ZFz~`;-ef)ryzkEEi7aAyL1m6?FngAkVHd*Kj4zq2 zp`yaoPW>#juJU!tD>=9Nh$I9iyAC}C2wC7(p|#4jB$hkw*iue*-}Qr&|IjRt*n3HJ$utvek=Ab*K8ILG438)=BZnLup0mGrzPP}iY9o$B z=xT1qlA{ReBsFvTOI{lcZD=NQne5tdeH!*#)fCB%DJd!OMt?pVKl|Mmo0RmtN>Zla zq3}t{{96yMlxl0Ktxrm)t2mh0AY&S8|G#dPda~foFVi^el$I4s39ShbdaU5{AB`P$ z%=@He5k&{XwyD_7|tO2_I9xTQ^<9Q9V7 zkX%9ySY?{8k5JWS-P_i@VdiBhaf-G?O4!5|FoO9*ovIQ<#%#WC`r* zV47=>yGOWi`a*Da^@oZQ^|&lU$a{%R91t&z=->sSm)-meVJ z*(h5*uRe~ChZug~iI2AtNVCo~HJ?5-VKJ&1#pQEb=xRa?eWLy&3Uz8kL*Y)cNfzq-Slj zpKCU}TrXaVx7+=G5sMgs8n}@+HeARPn&n_e4g}%i8_WxbLcXPisw&R~*|ApkMaLsN z309VE3`(oRnJ}#orj`0Hjn|36isAz=EE7Stcr@?SF~Mb~6SP81N+u^$r_+9DbtbMIy{eW^;aX)IU`UjA^=-#v4_ zroR&C)BK|xzbH7U*wY$ipaM(^Y`qw!@KWfrF&H>}bKokZAF!>gfj znvd?WWKKSo?_hgn!_4jSM5LwRa-WEbe%f_>yuZDfnG0c9Lu|&XZ$26E0A0!j2Ort! z{ZZ<|AlMGVE>|s16anz?21@?O2_SH_*}ikJ+WGFMcb>4w@y7EJc;IKhF*{XKJaT+Dmts4}Y_?eG!oa1x37cL_cNSoBYh2_gPG-nW+E3O_{hweZ3 z?{}RO5w1W~IA=7sN%@#h4)gPpsj?TpOen)q;(GiX4kgPTyv&UM#5&A#qvVHX#jLVZ zlXZk-=C911Md#@J_Y!Tc}?WDh;Pot7C&E)yI%M{B*%!`!xj@pnxxQMY`?x`%A|(_Q^jQm zxl)pSj40f`#Rj6k@(3iP85AE+9?C{RJrvR{=)Ov*KE+Au-BBPy+duer%And&Z<)bi zyM;`3!A{uWw8d_OCme2{1I_s`DrTv^PBW<_$|s(c)V1i~;V2iI!N|x=q{_$~!eA%d z2b?Xpa7JJ+8LQOq5Kv1~BEc;DQbtar^q@Fc<(;S9Ob83fxX^ZlSND8JuXH0Px4+Ek zcaP#B^{EZ(Fd{cxS4MnUk(FGIB78MQr@-Um;}0J`9NA#c7qixzq+1Ig7~QvLkB&=6 zL)G}}%U6DXB3{I9>54EV$!@s(0;wiP@@!yfW2|T95D`b2@>mtK`8J!7#JwtepelGh@ItUD_+>^E(dGAa^_C85 z%7xw8*qaMoP%(u4HFuRG@(E^tWhe#>>}fFLA3J?wYXJfz#oT4;%c!hnUJs2c9y94! zg_GT^+?T<*mLRbr7&u3?+u9Q&PetR*)Tz!%9I`mwq#}S0D7wKmRzt(2P?NKWJb=i>!#!VVo zlzYs}{lLqZht%}wdlSqR^bT(_AtV<6OfKUMsVc3{ROj2SXFsj(Z1-pS?>bH$p341T zPU&1KVZ<0QDG!EM|Re6zMiT_IL>ZeiAGMjzmS)7(C~<>IAIx% zLy6#XE4;WFE<4HDJ)1q&7z;R4x9s>sOjBr0E3Cr5N|_DT4v; zmoRfGVqT5s$s>|JSCIn)Mdoobft#7I_3QmbUm_*OIg`2bk_T8#aKp4dA+Gc>1RbXQ z3oD9<9BAB!C|p@+NJY*`k)w%ZIQw^onC~itr)U|$Aa!{0AL>Lsz$L7zshh>cA}L zT`Z2GzC!eDl~Lr_WY+r8P-H~O$Irpxv22~a zFfUURZb(-xC%ZM#gSeV>>X8wR#<#;6EJItYp}qwu-zM789cfFvHJFq9AmPW%5u1_} zfg*TBcyKh^bcXYeKCFRGnk#!kX~BM0+Lb%RK2Eia@m}_2etG`+#rkMBB9<7m?&v=9 zGU1b;u|Rt2*ihO*E1EpC@YzX|IDn1=9*iaL8`6Vw+fX5qB?rpHpyYJ5yTzZYV zk8iv4l4raA6Uni9&eikS;^K2DLcB!Tk%tUlTxgZmYUmWfYK&j34O^U*v~?@1^cxz( zNh_gcGe-+KR#o=pj`wjzH)lF5C023I9^ZU_NT-+tvqzyaeWgg{zUAtvSRA#(7A+&p zL2Egh>Q>51wdNER*>BTI_D5>JIv~V_g~=k$LUASqHTvzTBD%ZWdwwh!4h`}m@usGQ z2jv+n)&+p4t{fGK=P>xZpTX_EkY ze|N9@@mW*gxR)0^`Mzgvv4qV2^&46#t-s}T%b3&z>GJ`9lk?kd&z2I_mpcRR8_)Mg zOgr<0zE(j_7iQC9I3vv8rdcmFq||D${W-q;D9uyyRlm`rXDtVswFxBh*XqnXND2mK zeo92K4^+NXB??kylLb4t2H~yniivc|t&Umo&r8(pv=9K6ve(Pw5m{VZyx=(NO2fX< z+p8d)9nZ6wV_Qer@1Zee;SdALu+9uXL4)~_6gq@Th+Z#eiU=Y(+@}vPK#wRdUa=&* z(v(7~^egqI1Wo1!Hr&92ZScxyT#%?`&Icsqz&eL7{+QvAk|+#=0xFy>HwZ%o{9P-| z9Z-U2Pl&@|E;FXX@5uiT@662_vr z_#Rn#*)E)oXSVp$Eu5C;M0t!DREbET!Ffk&G6x_862KfQ0`C**<+pow6Wa@FRV z8uKie)6y%VF!Lq^q6Fo;hC}cHUw*EMO!28DXH1cm1yqmP%yc=n z>LI{hOeKGEt~+>2@OrdTQ6OAKT@AjwNtiw6xQ7%jCVNSg0!4&e6x(CkxhZ^|mF%pR zLOL&sh*uP9h!A)pNOFus?&8&&q#w+FadXq=a%T!CKr@DMSXJ~Zy;<0Fz2T@J&`ldb zhfT{5ecYk=T!hfERh)aI$H!huhx6}i?P87 zwu_0uoJS9D5!;{@e?4}LUe4Cea zU7=lbf>OyfU&81w;`kU}SaRZpjIUgB&UmaSf1}6&i7YzDC-v-;cz&TFfXxg zQuHs+I#QNdx8&RVHzWH=uSOKUs_!mM&*$~XYVS1x?=e1DSp1GMhI+Zuzz(6!!~uV)}Anik>)_Dw(!8XK_0|AoRqjULuIM1vV+sH6~5sn7RSU`Ldrz!b~PCuXFY?8pP89aM_!GrwBjX#D}wDn zStEc!$l>RFg9}9vK(9TOrK6u;tA1s$vr7@o;%z%edD`F2@h2J(vn$ zNywVFaES81DYwr;p-^(TCUdqnHZU0M6Lw#+ zefgxM+G}d~`1pB0?>Ggm0`;<`h3W0|Ug)f!pl2`71`r}f3l z4F~qwJd+yok=4?wBKSOLRl;m}ny5QtvBuAV8+0L%avI4o{j#MrFW?3Cw9f^dr3p9tLKWS;@y;n>kbKyV>GPdtHEMM3qY1=V z38Z%#q5Fj3hVpXmo-U~2k}06Qp7nfmhD744E|*4TZZ5j1fC|V--K*uYib56#2Oqz=ZS=T)5qgX7Z_mXp zR-i%IbT{t2ZMJe}4LrCSMjfHnCpzPG)=_J|_ftQWrqULfhhoJ4CMUd7+xb1-eJI$* zuT!-(^o~f%6CJn!j*DeR>9qsMjytgZvJ1o~tYpK#m@@~_I-2%sZ2`(xy+5(tWkQQp z;N$w`x^LiJo)M#d)pmT_RW`ipqsQj~k0*24tjbOg)17W2C;y0cxJ&p%oRms{wmZn?p7$!@GKPW5bU6lG?aNIYrshz1SUE$JS)X(0EA|ji zzspYDJO3SH8w8~g?0kN9x?7Jc30!r*1FhSVL1wSe~2ZNo|IoQ;=)KG0Eow7i7UTrTpcEn zM`>?;sX}HWnd7I|KS_+Tu&|sFS`CC~lvHQfbt;V^VP4|EQwlIGG8eT3z zb0t{w6tDs%$-Y9p)CH-&Ur~I{A);W?_9@`h{W@v zX(p}m!g$wTXtoLTxM92+bP$-LG6Gu2HYC&1)7PaqfZ`Avz%sMi2ffS}Lrg8a)ad zPx*7Bg@Bk&{{Hx!Fi}Ht5I-tr-K1Y6qt63Tr4e`nxS@*HU?eBEd`TUSEq=nm^e7xKd&V2>mfY zwNH`W#vn~+(VcB}r`%O0_${Gx@ov?Q`bbzpVu`Pjmbp?}#10J96HPBg7evHqbcp_O z_=A!niz3}woL<-Q_Lo11x8r!^Y~Zo0GuEL@LqA(3ZSlTWvD%wgq6lWl8vECXzw4~$0G`v|K!h7s|5vms9zQjohsf0ic~HU|T7XGP)${N1Rn z5$)~*O9jP+hI#SC)Qn+xk78W?H^`A}aoY29z!s^^Ed5-_^vM!rGeoNsYjVI(1(~=2 ziHuwS@A<=Q$lPZ7`8l0tr-tUwdoO5HzIy6^PL?OkaT?cdHr7Aq{l7ci_O;?(gP|#3 z46>ID15@v-?;YDN-y1=*Xu9*7t1`{5_FG%4(aJ}l+9`5P0!8vVd~vFTROx?$z{R*? zKzb}sF)<_h6xI4^dB6nPgZv%m8d$h@R|lV%8{6yr*24^2f4bfZ7rkJO^b`XaVx$;R zijD_@L>@t$YYo=aBx4cSObot!wz~ZF=x)<2!MSAiJ@q(+YY{-LUzXFjGwz^c$~@q8 zPGFXC608KdOW@EMT`4ZHf&gb{XLIx57^j-zVc~7N@gc{pW7Y&9RT7h2_gk&+Jkght@mG?=!4Ha@QYY-HKY?QJ%s%85Zv zN#t{OWZpI)1glK0yrc24|8$PAfAejO18vDB6DKDpUiY^K9lDOR&v;R{`9c4D2ri@Y zjH~`D5y#d<=f$N&4F;)OV5v}{tpBWt$jw_hQ_lq#{d$kU*-j$)9~FZC|1S#GIgAz= zMDKn<^_8oB&m0)L?Ehr8^Xk0raf|D=pGwu$#MWtHN*yh*CTAU5ddlp7M45ot zY(#RS$&iHuhq7*L?Z<1#^k4?DYh zOM^xWdv*cCg8ZP_%Pt006*EXM6}$|@@c%lKTeDJkjqPaixW z1zeeCc?M+3n^znkhR4QOMV@U()Tr5Z|@n@r2c343F+=A6xkG=Cf zCC$piRQXkD+tSF9ceV<04=g;jgEfgF|M)776iP36@5{zxH!t|^92?T|N1rO pSLhCMVN@m~D@#oTeRhwbiU>1I6ZftKzBvX`ReYlWmwOlT{{XIY1FQf5 literal 0 HcmV?d00001 From 02b1d22dec8aa17223fe1440a280520fe28a285a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 26 Dec 2023 10:28:07 +0900 Subject: [PATCH 135/276] fix(avoidance): fix condition to trim front shift line (#5949) Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/src/shift_line_generator.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index 01bfc375e9515..8ed56ce9aff4d 100644 --- a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -890,7 +890,7 @@ void ShiftLineGenerator::applySmallShiftFilter( continue; } - if (s.start_longitudinal < helper_->getMinimumPrepareDistance()) { + if (s.start_longitudinal + 1e-3 < helper_->getMinimumPrepareDistance()) { continue; } From c0c6e886aa98764aabe981978402bdb5fd8430e7 Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Tue, 26 Dec 2023 12:19:56 +0900 Subject: [PATCH 136/276] refactor(motion_utils): change directory name of tmp_conversion (#5908) * change .hpp name Signed-off-by: Zhe Shen * change .cpp name Signed-off-by: Zhe Shen * correct the #inlcude and #ifndef Signed-off-by: Zhe Shen * change the CMakeLists.txt Signed-off-by: Zhe Shen * correct the dependencies referring to tmp_conversion Signed-off-by: Zhe Shen * style(pre-commit): autofix * change all the tmp_conversion to conversion in all the autoware.universe Signed-off-by: Zhe Shen * style(pre-commit): autofix --------- Signed-off-by: Zhe Shen Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- common/motion_utils/CMakeLists.txt | 2 +- .../trajectory/{tmp_conversion.hpp => conversion.hpp} | 6 +++--- .../src/trajectory/{tmp_conversion.cpp => conversion.cpp} | 2 +- .../motion_utils/test/src/trajectory/test_interpolation.cpp | 2 +- common/motion_utils/test/src/trajectory/test_trajectory.cpp | 2 +- .../control_validator/include/control_validator/utils.hpp | 2 +- .../include/predicted_path_checker/collision_checker.hpp | 2 +- .../predicted_path_checker/predicted_path_checker_node.hpp | 2 +- .../pure_pursuit/pure_pursuit_lateral_controller.hpp | 2 +- .../motion_velocity_smoother_node.hpp | 2 +- planning/motion_velocity_smoother/src/resample.cpp | 2 +- .../analytical_jerk_constrained_smoother.cpp | 2 +- .../motion_velocity_smoother/src/smoother/smoother_base.cpp | 2 +- .../src/utils/trajectory_utils.cpp | 2 +- .../include/obstacle_cruise_planner/common_structs.hpp | 2 +- planning/obstacle_cruise_planner/src/node.cpp | 2 +- planning/obstacle_cruise_planner/src/planner_interface.cpp | 2 +- .../include/obstacle_stop_planner/node.hpp | 2 +- planning/obstacle_stop_planner/src/planner_utils.cpp | 2 +- planning/path_smoother/src/utils/trajectory_utils.cpp | 2 +- .../planning_topic_converter/src/path_to_trajectory.cpp | 2 +- .../path_sampler/src/utils/trajectory_utils.cpp | 2 +- .../src/static_centerline_optimizer_node.cpp | 2 +- .../src/successive_trajectory_optimizer_node.cpp | 2 +- 24 files changed, 26 insertions(+), 26 deletions(-) rename common/motion_utils/include/motion_utils/trajectory/{tmp_conversion.hpp => conversion.hpp} (92%) rename common/motion_utils/src/trajectory/{tmp_conversion.cpp => conversion.cpp} (97%) diff --git a/common/motion_utils/CMakeLists.txt b/common/motion_utils/CMakeLists.txt index 43c8158b2f98b..f42deaa7f8c41 100644 --- a/common/motion_utils/CMakeLists.txt +++ b/common/motion_utils/CMakeLists.txt @@ -14,7 +14,7 @@ ament_auto_add_library(motion_utils SHARED src/trajectory/trajectory.cpp src/trajectory/interpolation.cpp src/trajectory/path_with_lane_id.cpp - src/trajectory/tmp_conversion.cpp + src/trajectory/conversion.cpp src/vehicle/vehicle_state_checker.cpp ) diff --git a/common/motion_utils/include/motion_utils/trajectory/tmp_conversion.hpp b/common/motion_utils/include/motion_utils/trajectory/conversion.hpp similarity index 92% rename from common/motion_utils/include/motion_utils/trajectory/tmp_conversion.hpp rename to common/motion_utils/include/motion_utils/trajectory/conversion.hpp index 28d783aa4d293..804ae47ff0f4e 100644 --- a/common/motion_utils/include/motion_utils/trajectory/tmp_conversion.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/conversion.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOTION_UTILS__TRAJECTORY__TMP_CONVERSION_HPP_ -#define MOTION_UTILS__TRAJECTORY__TMP_CONVERSION_HPP_ +#ifndef MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_ +#define MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_ #include "autoware_auto_planning_msgs/msg/detail/trajectory__struct.hpp" #include "autoware_auto_planning_msgs/msg/detail/trajectory_point__struct.hpp" @@ -45,4 +45,4 @@ std::vector convertToTrajecto } // namespace motion_utils -#endif // MOTION_UTILS__TRAJECTORY__TMP_CONVERSION_HPP_ +#endif // MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_ diff --git a/common/motion_utils/src/trajectory/tmp_conversion.cpp b/common/motion_utils/src/trajectory/conversion.cpp similarity index 97% rename from common/motion_utils/src/trajectory/tmp_conversion.cpp rename to common/motion_utils/src/trajectory/conversion.cpp index 6f4a4039832bd..97a0bcd06e8cc 100644 --- a/common/motion_utils/src/trajectory/tmp_conversion.cpp +++ b/common/motion_utils/src/trajectory/conversion.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include diff --git a/common/motion_utils/test/src/trajectory/test_interpolation.cpp b/common/motion_utils/test/src/trajectory/test_interpolation.cpp index 80df1fabf562d..5794ed61e9e44 100644 --- a/common/motion_utils/test/src/trajectory/test_interpolation.cpp +++ b/common/motion_utils/test/src/trajectory/test_interpolation.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/interpolation.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "tier4_autoware_utils/geometry/boost_geometry.hpp" #include "tier4_autoware_utils/math/unit_conversion.hpp" diff --git a/common/motion_utils/test/src/trajectory/test_trajectory.cpp b/common/motion_utils/test/src/trajectory/test_trajectory.cpp index 6664e6154bdfd..eb6a06041e65d 100644 --- a/common/motion_utils/test/src/trajectory/test_trajectory.cpp +++ b/common/motion_utils/test/src/trajectory/test_trajectory.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "tier4_autoware_utils/geometry/boost_geometry.hpp" #include "tier4_autoware_utils/math/unit_conversion.hpp" diff --git a/control/control_validator/include/control_validator/utils.hpp b/control/control_validator/include/control_validator/utils.hpp index 39ec316dbe437..8033ac9442960 100644 --- a/control/control_validator/include/control_validator/utils.hpp +++ b/control/control_validator/include/control_validator/utils.hpp @@ -15,7 +15,7 @@ #ifndef CONTROL_VALIDATOR__UTILS_HPP_ #define CONTROL_VALIDATOR__UTILS_HPP_ -#include +#include #include #include diff --git a/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp b/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp index d21b11e5b68de..1d7791955b576 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp +++ b/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp @@ -15,8 +15,8 @@ #ifndef PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ #define PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ +#include #include -#include #include #include #include diff --git a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp index e3c3b5cccfb8f..3ce5728521141 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp +++ b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp @@ -18,7 +18,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/control/pure_pursuit/include/pure_pursuit/pure_pursuit_lateral_controller.hpp b/control/pure_pursuit/include/pure_pursuit/pure_pursuit_lateral_controller.hpp index daaebaacde8de..ca0d77140b195 100644 --- a/control/pure_pursuit/include/pure_pursuit/pure_pursuit_lateral_controller.hpp +++ b/control/pure_pursuit/include/pure_pursuit/pure_pursuit_lateral_controller.hpp @@ -38,7 +38,7 @@ #include "trajectory_follower_base/lateral_controller_base.hpp" #include -#include +#include #include #include "autoware_auto_control_msgs/msg/ackermann_lateral_command.hpp" diff --git a/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp b/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp index 7be91d67cb945..fc347cb11f5cd 100644 --- a/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp +++ b/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp @@ -15,7 +15,7 @@ #ifndef MOTION_VELOCITY_SMOOTHER__MOTION_VELOCITY_SMOOTHER_NODE_HPP_ #define MOTION_VELOCITY_SMOOTHER__MOTION_VELOCITY_SMOOTHER_NODE_HPP_ -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "motion_velocity_smoother/resample.hpp" #include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp" diff --git a/planning/motion_velocity_smoother/src/resample.cpp b/planning/motion_velocity_smoother/src/resample.cpp index 37f3ce953bd48..ae638f8e4db1a 100644 --- a/planning/motion_velocity_smoother/src/resample.cpp +++ b/planning/motion_velocity_smoother/src/resample.cpp @@ -15,7 +15,7 @@ #include "motion_velocity_smoother/resample.hpp" #include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "motion_velocity_smoother/trajectory_utils.hpp" diff --git a/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp b/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp index d1694d7420ca2..84d6331b3429d 100644 --- a/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp +++ b/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp @@ -15,7 +15,7 @@ #include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp" #include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_velocity_smoother/trajectory_utils.hpp" #include diff --git a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp index bb15feb32a06e..61cc4e9fb1fcc 100644 --- a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp @@ -15,7 +15,7 @@ #include "motion_velocity_smoother/smoother/smoother_base.hpp" #include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "motion_velocity_smoother/resample.hpp" #include "motion_velocity_smoother/trajectory_utils.hpp" diff --git a/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp b/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp index e86782c9cb0cf..b836cee1aeaa6 100644 --- a/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp +++ b/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp @@ -15,7 +15,7 @@ #include "obstacle_avoidance_planner/utils/trajectory_utils.hpp" #include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "obstacle_avoidance_planner/mpt_optimizer.hpp" #include "obstacle_avoidance_planner/utils/geometry_utils.hpp" diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp index 6c44c4744e96c..21cd980373df2 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp @@ -15,8 +15,8 @@ #ifndef OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_ #define OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_ +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/interpolation.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "obstacle_cruise_planner/type_alias.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index 31f011b3749b9..ccfd731416475 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -15,7 +15,7 @@ #include "obstacle_cruise_planner/node.hpp" #include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "object_recognition_utils/predicted_path_utils.hpp" #include "obstacle_cruise_planner/polygon_utils.hpp" #include "obstacle_cruise_planner/utils.hpp" diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index a7dac94e1c38a..f00ad01efb0d9 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -17,7 +17,7 @@ #include "motion_utils/distance/distance.hpp" #include "motion_utils/marker/marker_helper.hpp" #include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "signal_processing/lowpass_filter_1d.hpp" #include "tier4_autoware_utils/ros/marker_helper.hpp" diff --git a/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp b/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp index cc1ad6999b898..aea2afdb896f2 100644 --- a/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp +++ b/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp @@ -21,7 +21,7 @@ #include "tier4_autoware_utils/ros/logger_level_configure.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" -#include +#include #include #include #include diff --git a/planning/obstacle_stop_planner/src/planner_utils.cpp b/planning/obstacle_stop_planner/src/planner_utils.cpp index 369b1700aa5ca..31fb843c234d9 100644 --- a/planning/obstacle_stop_planner/src/planner_utils.cpp +++ b/planning/obstacle_stop_planner/src/planner_utils.cpp @@ -15,7 +15,7 @@ #include "obstacle_stop_planner/planner_utils.hpp" #include -#include +#include #include #include diff --git a/planning/path_smoother/src/utils/trajectory_utils.cpp b/planning/path_smoother/src/utils/trajectory_utils.cpp index d9d02a15628dd..872fc65a9d456 100644 --- a/planning/path_smoother/src/utils/trajectory_utils.cpp +++ b/planning/path_smoother/src/utils/trajectory_utils.cpp @@ -15,7 +15,7 @@ #include "path_smoother/utils/trajectory_utils.hpp" #include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "path_smoother/utils/geometry_utils.hpp" #include "autoware_auto_planning_msgs/msg/path_point.hpp" diff --git a/planning/planning_topic_converter/src/path_to_trajectory.cpp b/planning/planning_topic_converter/src/path_to_trajectory.cpp index 5362686617fc7..f5df79121029b 100644 --- a/planning/planning_topic_converter/src/path_to_trajectory.cpp +++ b/planning/planning_topic_converter/src/path_to_trajectory.cpp @@ -14,7 +14,7 @@ #include "planning_topic_converter/path_to_trajectory.hpp" -#include +#include #include namespace planning_topic_converter diff --git a/planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp b/planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp index db55e5f8557e4..76fa90c6baa4b 100644 --- a/planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp +++ b/planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp @@ -15,7 +15,7 @@ #include "path_sampler/utils/trajectory_utils.hpp" #include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "path_sampler/utils/geometry_utils.hpp" #include "tf2/utils.h" diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index e12fde7f85abc..0aeec7be0b55d 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -18,7 +18,7 @@ #include "lanelet2_extension/utility/query.hpp" #include "lanelet2_extension/utility/utilities.hpp" #include "map_loader/lanelet2_map_loader_node.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "static_centerline_optimizer/msg/points_with_lane_id.hpp" #include "static_centerline_optimizer/successive_trajectory_optimizer_node.hpp" #include "static_centerline_optimizer/type_alias.hpp" diff --git a/planning/static_centerline_optimizer/src/successive_trajectory_optimizer_node.cpp b/planning/static_centerline_optimizer/src/successive_trajectory_optimizer_node.cpp index ab147ab1f4f74..a8663abb2eab7 100644 --- a/planning/static_centerline_optimizer/src/successive_trajectory_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/successive_trajectory_optimizer_node.cpp @@ -15,7 +15,7 @@ #include "static_centerline_optimizer/successive_trajectory_optimizer_node.hpp" #include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/tmp_conversion.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "obstacle_avoidance_planner/utils/trajectory_utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" From 5051ae1bb7a84eba5be2fe43a3c035635459fcde Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Tue, 26 Dec 2023 07:04:09 +0100 Subject: [PATCH 137/276] fix(autoware_auto_geometry): move headers to a separate directory (#5941) * fix(autoware_auto_geometry): move headers to a separate directory Signed-off-by: Esteve Fernandez * style(pre-commit): autofix * fix: fix header name Signed-off-by: Esteve Fernandez * style(pre-commit): autofix * fix: fix headers for CMake Signed-off-by: Esteve Fernandez --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- common/autoware_auto_geometry/CMakeLists.txt | 6 +++--- common/autoware_auto_geometry/design/interval.md | 2 +- .../bounding_box/bounding_box_common.hpp | 10 +++++----- .../bounding_box/eigenbox_2d.hpp | 8 ++++---- .../bounding_box/lfit.hpp | 8 ++++---- .../bounding_box/rotating_calipers.hpp | 12 ++++++------ .../bounding_box_2d.hpp | 12 ++++++------ .../common_2d.hpp | 8 ++++---- .../common_3d.hpp | 8 ++++---- .../convex_hull.hpp | 9 +++++---- .../hull_pockets.hpp | 9 +++++---- .../intersection.hpp | 10 +++++----- .../interval.hpp | 6 +++--- .../lookup_table.hpp | 8 ++++---- .../spatial_hash.hpp | 11 ++++++----- .../spatial_hash_config.hpp | 10 +++++----- .../visibility_control.hpp | 6 +++--- common/autoware_auto_geometry/src/bounding_box.cpp | 9 +++++---- common/autoware_auto_geometry/src/spatial_hash.cpp | 2 +- .../test/include/test_bounding_box.hpp | 4 ++-- .../test/include/test_spatial_hash.hpp | 2 +- .../autoware_auto_geometry/test/src/lookup_table.cpp | 3 ++- common/autoware_auto_geometry/test/src/test_area.cpp | 2 +- .../test/src/test_common_2d.cpp | 2 +- .../test/src/test_convex_hull.cpp | 2 +- .../test/src/test_hull_pockets.cpp | 4 ++-- .../test/src/test_intersection.cpp | 4 ++-- .../test/src/test_interval.cpp | 2 +- 28 files changed, 92 insertions(+), 87 deletions(-) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/bounding_box/bounding_box_common.hpp (95%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/bounding_box/eigenbox_2d.hpp (96%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/bounding_box/lfit.hpp (97%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/bounding_box/rotating_calipers.hpp (96%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/bounding_box_2d.hpp (71%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/common_2d.hpp (99%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/common_3d.hpp (93%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/convex_hull.hpp (97%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/hull_pockets.hpp (95%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/intersection.hpp (98%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/interval.hpp (98%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/lookup_table.hpp (96%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/spatial_hash.hpp (98%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/spatial_hash_config.hpp (98%) rename common/autoware_auto_geometry/include/{geometry => autoware_auto_geometry}/visibility_control.hpp (90%) diff --git a/common/autoware_auto_geometry/CMakeLists.txt b/common/autoware_auto_geometry/CMakeLists.txt index 454e0e7ef044f..ee819b7cd797c 100644 --- a/common/autoware_auto_geometry/CMakeLists.txt +++ b/common/autoware_auto_geometry/CMakeLists.txt @@ -5,9 +5,9 @@ find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED - include/geometry/spatial_hash.hpp - include/geometry/intersection.hpp - include/geometry/spatial_hash_config.hpp + include/autoware_auto_geometry/spatial_hash.hpp + include/autoware_auto_geometry/intersection.hpp + include/autoware_auto_geometry/spatial_hash_config.hpp src/spatial_hash.cpp src/bounding_box.cpp ) diff --git a/common/autoware_auto_geometry/design/interval.md b/common/autoware_auto_geometry/design/interval.md index 26260ba8d8e67..4fe65ff8e0310 100644 --- a/common/autoware_auto_geometry/design/interval.md +++ b/common/autoware_auto_geometry/design/interval.md @@ -39,7 +39,7 @@ See 'Example Usage' below. ## Example Usage ```c++ -#include "geometry/interval.hpp" +#include "autoware_auto_geometry/interval.hpp" #include diff --git a/common/autoware_auto_geometry/include/geometry/bounding_box/bounding_box_common.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/bounding_box_common.hpp similarity index 95% rename from common/autoware_auto_geometry/include/geometry/bounding_box/bounding_box_common.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/bounding_box_common.hpp index d1dee63f73b56..0f3a68e14d442 100644 --- a/common/autoware_auto_geometry/include/geometry/bounding_box/bounding_box_common.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/bounding_box_common.hpp @@ -17,11 +17,11 @@ /// \file /// \brief Common functionality for bounding box computation algorithms -#ifndef GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_ -#define GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_ -#include -#include +#include "autoware_auto_geometry/common_2d.hpp" +#include "autoware_auto_geometry/visibility_control.hpp" #include #include @@ -185,4 +185,4 @@ std::vector GEOMETRY_PUBLIC get_transformed_corners } // namespace common } // namespace autoware -#endif // GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/bounding_box/eigenbox_2d.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/eigenbox_2d.hpp similarity index 96% rename from common/autoware_auto_geometry/include/geometry/bounding_box/eigenbox_2d.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/eigenbox_2d.hpp index f050628f32f25..e0f2e66e87ee5 100644 --- a/common/autoware_auto_geometry/include/geometry/bounding_box/eigenbox_2d.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/eigenbox_2d.hpp @@ -19,10 +19,10 @@ /// bounding box // cspell: ignore eigenbox, EIGENBOX -#ifndef GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_ -#define GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_ -#include +#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp" #include #include @@ -244,4 +244,4 @@ BoundingBox eigenbox_2d(const IT begin, const IT end) } // namespace common } // namespace autoware -#endif // GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/bounding_box/lfit.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/lfit.hpp similarity index 97% rename from common/autoware_auto_geometry/include/geometry/bounding_box/lfit.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/lfit.hpp index 9b8991a7c7132..07fd6c989cedc 100644 --- a/common/autoware_auto_geometry/include/geometry/bounding_box/lfit.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/lfit.hpp @@ -20,10 +20,10 @@ // cspell: ignore LFIT, lfit // LFIT means "L-Shape Fitting" -#ifndef GEOMETRY__BOUNDING_BOX__LFIT_HPP_ -#define GEOMETRY__BOUNDING_BOX__LFIT_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__LFIT_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__LFIT_HPP_ -#include +#include "autoware_auto_geometry/bounding_box/eigenbox_2d.hpp" #include #include @@ -278,4 +278,4 @@ BoundingBox lfit_bounding_box_2d(const IT begin, const IT end) } // namespace common } // namespace autoware -#endif // GEOMETRY__BOUNDING_BOX__LFIT_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__LFIT_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/bounding_box/rotating_calipers.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/rotating_calipers.hpp similarity index 96% rename from common/autoware_auto_geometry/include/geometry/bounding_box/rotating_calipers.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/rotating_calipers.hpp index 5bc05810bb1b0..fb75384eb07cb 100644 --- a/common/autoware_auto_geometry/include/geometry/bounding_box/rotating_calipers.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/rotating_calipers.hpp @@ -17,11 +17,11 @@ /// \file /// \brief This file implements the rotating calipers algorithm for minimum oriented bounding boxes -#ifndef GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_ -#define GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_ -#include -#include -#include +#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_ +#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp" +#include "autoware_auto_geometry/common_2d.hpp" +#include "autoware_auto_geometry/convex_hull.hpp" #include #include @@ -277,4 +277,4 @@ BoundingBox minimum_perimeter_bounding_box(std::list & list) } // namespace geometry } // namespace common } // namespace autoware -#endif // GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/bounding_box_2d.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box_2d.hpp similarity index 71% rename from common/autoware_auto_geometry/include/geometry/bounding_box_2d.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box_2d.hpp index d1d84122889c9..c4c52928ac19a 100644 --- a/common/autoware_auto_geometry/include/geometry/bounding_box_2d.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box_2d.hpp @@ -15,12 +15,12 @@ // Co-developed by Tier IV, Inc. and Apex.AI, Inc. /// \file /// \brief Main header for user-facing bounding box algorithms: functions and types -#ifndef GEOMETRY__BOUNDING_BOX_2D_HPP_ -#define GEOMETRY__BOUNDING_BOX_2D_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX_2D_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX_2D_HPP_ -#include -#include -#include +#include "autoware_auto_geometry/bounding_box/eigenbox_2d.hpp" +#include "autoware_auto_geometry/bounding_box/lfit.hpp" +#include "autoware_auto_geometry/bounding_box/rotating_calipers.hpp" namespace autoware { @@ -31,4 +31,4 @@ namespace geometry } // namespace geometry } // namespace common } // namespace autoware -#endif // GEOMETRY__BOUNDING_BOX_2D_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX_2D_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/common_2d.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/common_2d.hpp similarity index 99% rename from common/autoware_auto_geometry/include/geometry/common_2d.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/common_2d.hpp index fd045003521ea..da7121bf4e9b5 100644 --- a/common/autoware_auto_geometry/include/geometry/common_2d.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/common_2d.hpp @@ -16,10 +16,10 @@ /// \file /// \brief This file includes common functionality for 2D geometry, such as dot products -#ifndef GEOMETRY__COMMON_2D_HPP_ -#define GEOMETRY__COMMON_2D_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__COMMON_2D_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__COMMON_2D_HPP_ -#include "geometry/interval.hpp" +#include "autoware_auto_geometry/interval.hpp" #include @@ -584,4 +584,4 @@ bool is_point_inside_polygon_2d( } // namespace common } // namespace autoware -#endif // GEOMETRY__COMMON_2D_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__COMMON_2D_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/common_3d.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/common_3d.hpp similarity index 93% rename from common/autoware_auto_geometry/include/geometry/common_3d.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/common_3d.hpp index 4477b010e7eba..74cd210dec586 100644 --- a/common/autoware_auto_geometry/include/geometry/common_3d.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/common_3d.hpp @@ -16,10 +16,10 @@ /// \file /// \brief This file includes common functionality for 3D geometry, such as dot products -#ifndef GEOMETRY__COMMON_3D_HPP_ -#define GEOMETRY__COMMON_3D_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__COMMON_3D_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__COMMON_3D_HPP_ -#include +#include "autoware_auto_geometry/common_2d.hpp" namespace autoware { @@ -74,4 +74,4 @@ inline OUT distance_3d(const T1 & a, const T2 & b) } // namespace common } // namespace autoware -#endif // GEOMETRY__COMMON_3D_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__COMMON_3D_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/convex_hull.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/convex_hull.hpp similarity index 97% rename from common/autoware_auto_geometry/include/geometry/convex_hull.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/convex_hull.hpp index e690c4d07441b..e566e2e43ae3e 100644 --- a/common/autoware_auto_geometry/include/geometry/convex_hull.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/convex_hull.hpp @@ -18,11 +18,12 @@ /// \brief This file implements the monotone chain algorithm to compute 2D convex hulls on linked /// lists of points -#ifndef GEOMETRY__CONVEX_HULL_HPP_ -#define GEOMETRY__CONVEX_HULL_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__CONVEX_HULL_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__CONVEX_HULL_HPP_ + +#include "autoware_auto_geometry/common_2d.hpp" #include -#include // lint -e537 NOLINT pclint vs cpplint #include @@ -191,4 +192,4 @@ typename std::list::const_iterator convex_hull(std::list & list) } // namespace common } // namespace autoware -#endif // GEOMETRY__CONVEX_HULL_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__CONVEX_HULL_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/hull_pockets.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/hull_pockets.hpp similarity index 95% rename from common/autoware_auto_geometry/include/geometry/hull_pockets.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/hull_pockets.hpp index 6e8caa0df1e80..fd04c0266e065 100644 --- a/common/autoware_auto_geometry/include/geometry/hull_pockets.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/hull_pockets.hpp @@ -18,11 +18,12 @@ /// \brief This file implements an algorithm for getting a list of "pockets" in the convex /// hull of a non-convex simple polygon. -#ifndef GEOMETRY__HULL_POCKETS_HPP_ -#define GEOMETRY__HULL_POCKETS_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__HULL_POCKETS_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__HULL_POCKETS_HPP_ + +#include "autoware_auto_geometry/common_2d.hpp" #include -#include #include #include @@ -107,4 +108,4 @@ typename std::vector::value_typ } // namespace common } // namespace autoware -#endif // GEOMETRY__HULL_POCKETS_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__HULL_POCKETS_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/intersection.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/intersection.hpp similarity index 98% rename from common/autoware_auto_geometry/include/geometry/intersection.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/intersection.hpp index 87dc32b0190d0..08c70c3a5a6be 100644 --- a/common/autoware_auto_geometry/include/geometry/intersection.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/intersection.hpp @@ -14,11 +14,11 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#ifndef GEOMETRY__INTERSECTION_HPP_ -#define GEOMETRY__INTERSECTION_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__INTERSECTION_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__INTERSECTION_HPP_ -#include -#include +#include "autoware_auto_geometry/common_2d.hpp" +#include "autoware_auto_geometry/convex_hull.hpp" #include #include @@ -309,4 +309,4 @@ common::types::float32_t convex_intersection_over_union_2d( } // namespace common } // namespace autoware -#endif // GEOMETRY__INTERSECTION_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__INTERSECTION_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/interval.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/interval.hpp similarity index 98% rename from common/autoware_auto_geometry/include/geometry/interval.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/interval.hpp index 59c26f27cc454..17e2789ac0325 100644 --- a/common/autoware_auto_geometry/include/geometry/interval.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/interval.hpp @@ -18,8 +18,8 @@ // FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS // IN THE SOFTWARE. -#ifndef GEOMETRY__INTERVAL_HPP_ -#define GEOMETRY__INTERVAL_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_ #include "common/types.hpp" #include "helper_functions/float_comparisons.hpp" @@ -355,4 +355,4 @@ T Interval::clamp_to(const Interval & i, T val) } // namespace common } // namespace autoware -#endif // GEOMETRY__INTERVAL_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/lookup_table.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/lookup_table.hpp similarity index 96% rename from common/autoware_auto_geometry/include/geometry/lookup_table.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/lookup_table.hpp index e23a8c31b60f8..c689638aa2bd9 100644 --- a/common/autoware_auto_geometry/include/geometry/lookup_table.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/lookup_table.hpp @@ -17,11 +17,11 @@ /// \file /// \brief This file contains a 1D linear lookup table implementation -#ifndef GEOMETRY__LOOKUP_TABLE_HPP_ -#define GEOMETRY__LOOKUP_TABLE_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__LOOKUP_TABLE_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__LOOKUP_TABLE_HPP_ +#include "autoware_auto_geometry/interval.hpp" #include "common/types.hpp" -#include "geometry/interval.hpp" #include #include @@ -175,4 +175,4 @@ class LookupTable1D } // namespace common } // namespace autoware -#endif // GEOMETRY__LOOKUP_TABLE_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__LOOKUP_TABLE_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/spatial_hash.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash.hpp similarity index 98% rename from common/autoware_auto_geometry/include/geometry/spatial_hash.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash.hpp index 78626548e5c74..c160685fb0f8c 100644 --- a/common/autoware_auto_geometry/include/geometry/spatial_hash.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash.hpp @@ -17,12 +17,13 @@ /// \brief This file implements a spatial hash for efficient fixed-radius near neighbor queries in /// 2D -#ifndef GEOMETRY__SPATIAL_HASH_HPP_ -#define GEOMETRY__SPATIAL_HASH_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_HPP_ + +#include "autoware_auto_geometry/spatial_hash_config.hpp" +#include "autoware_auto_geometry/visibility_control.hpp" #include -#include -#include #include #include @@ -328,4 +329,4 @@ using SpatialHash3d = SpatialHash; } // namespace common } // namespace autoware -#endif // GEOMETRY__SPATIAL_HASH_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/spatial_hash_config.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash_config.hpp similarity index 98% rename from common/autoware_auto_geometry/include/geometry/spatial_hash_config.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash_config.hpp index e118ec24c7759..926b170f807c2 100644 --- a/common/autoware_auto_geometry/include/geometry/spatial_hash_config.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash_config.hpp @@ -17,14 +17,14 @@ /// \brief This file implements a spatial hash for efficient fixed-radius near neighbor queries in /// 2D -#ifndef GEOMETRY__SPATIAL_HASH_CONFIG_HPP_ -#define GEOMETRY__SPATIAL_HASH_CONFIG_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_CONFIG_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_CONFIG_HPP_ +#include "autoware_auto_geometry/common_2d.hpp" +#include "autoware_auto_geometry/visibility_control.hpp" #include "helper_functions/crtp.hpp" #include -#include -#include #include #include @@ -447,4 +447,4 @@ class GEOMETRY_PUBLIC Config3d : public Config } // namespace common } // namespace autoware -#endif // GEOMETRY__SPATIAL_HASH_CONFIG_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_CONFIG_HPP_ diff --git a/common/autoware_auto_geometry/include/geometry/visibility_control.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/visibility_control.hpp similarity index 90% rename from common/autoware_auto_geometry/include/geometry/visibility_control.hpp rename to common/autoware_auto_geometry/include/autoware_auto_geometry/visibility_control.hpp index 96efe9aa6e27b..8972246997997 100644 --- a/common/autoware_auto_geometry/include/geometry/visibility_control.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/visibility_control.hpp @@ -14,8 +14,8 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#ifndef GEOMETRY__VISIBILITY_CONTROL_HPP_ -#define GEOMETRY__VISIBILITY_CONTROL_HPP_ +#ifndef AUTOWARE_AUTO_GEOMETRY__VISIBILITY_CONTROL_HPP_ +#define AUTOWARE_AUTO_GEOMETRY__VISIBILITY_CONTROL_HPP_ //////////////////////////////////////////////////////////////////////////////// #if defined(__WIN32) @@ -38,4 +38,4 @@ #else // defined(__linux__) #error "Unsupported Build Configuration" #endif // defined(__WIN32) -#endif // GEOMETRY__VISIBILITY_CONTROL_HPP_ +#endif // AUTOWARE_AUTO_GEOMETRY__VISIBILITY_CONTROL_HPP_ diff --git a/common/autoware_auto_geometry/src/bounding_box.cpp b/common/autoware_auto_geometry/src/bounding_box.cpp index 225ea099e4e79..3a4ea96a151a2 100644 --- a/common/autoware_auto_geometry/src/bounding_box.cpp +++ b/common/autoware_auto_geometry/src/bounding_box.cpp @@ -14,13 +14,14 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. +#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp" +#include "autoware_auto_geometry/bounding_box/eigenbox_2d.hpp" + #include -#include -#include // cspell: ignore eigenbox -#include +#include "autoware_auto_geometry/bounding_box/lfit.hpp" // cspell: ignore lfit -#include +#include "autoware_auto_geometry/bounding_box/rotating_calipers.hpp" #include diff --git a/common/autoware_auto_geometry/src/spatial_hash.cpp b/common/autoware_auto_geometry/src/spatial_hash.cpp index 024cca48b8ee7..ffd91aaa08b3a 100644 --- a/common/autoware_auto_geometry/src/spatial_hash.cpp +++ b/common/autoware_auto_geometry/src/spatial_hash.cpp @@ -14,7 +14,7 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include +#include "autoware_auto_geometry/spatial_hash.hpp" #include // lint -e537 NOLINT repeated include file due to cpplint rule diff --git a/common/autoware_auto_geometry/test/include/test_bounding_box.hpp b/common/autoware_auto_geometry/test/include/test_bounding_box.hpp index 5e42622b19ce9..a179fbde5f151 100644 --- a/common/autoware_auto_geometry/test/include/test_bounding_box.hpp +++ b/common/autoware_auto_geometry/test/include/test_bounding_box.hpp @@ -17,9 +17,9 @@ #ifndef TEST_BOUNDING_BOX_HPP_ #define TEST_BOUNDING_BOX_HPP_ -#include "geometry/bounding_box/lfit.hpp" +#include "autoware_auto_geometry/bounding_box/lfit.hpp" // cspell: ignore lfit -#include "geometry/bounding_box/rotating_calipers.hpp" +#include "autoware_auto_geometry/bounding_box/rotating_calipers.hpp" #include diff --git a/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp b/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp index 50e946c416270..fc2d97c257b95 100644 --- a/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp +++ b/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp @@ -17,7 +17,7 @@ #ifndef TEST_SPATIAL_HASH_HPP_ #define TEST_SPATIAL_HASH_HPP_ -#include "geometry/spatial_hash.hpp" +#include "autoware_auto_geometry/spatial_hash.hpp" #include diff --git a/common/autoware_auto_geometry/test/src/lookup_table.cpp b/common/autoware_auto_geometry/test/src/lookup_table.cpp index e7533518d7f49..092f8a04f2540 100644 --- a/common/autoware_auto_geometry/test/src/lookup_table.cpp +++ b/common/autoware_auto_geometry/test/src/lookup_table.cpp @@ -14,8 +14,9 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. +#include "autoware_auto_geometry/lookup_table.hpp" + #include -#include #include diff --git a/common/autoware_auto_geometry/test/src/test_area.cpp b/common/autoware_auto_geometry/test/src/test_area.cpp index d722314dada83..bc9c28682ed44 100644 --- a/common/autoware_auto_geometry/test/src/test_area.cpp +++ b/common/autoware_auto_geometry/test/src/test_area.cpp @@ -14,7 +14,7 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include +#include "autoware_auto_geometry/common_2d.hpp" #include diff --git a/common/autoware_auto_geometry/test/src/test_common_2d.cpp b/common/autoware_auto_geometry/test/src/test_common_2d.cpp index 642e396bdce31..baf6967edd47e 100644 --- a/common/autoware_auto_geometry/test/src/test_common_2d.cpp +++ b/common/autoware_auto_geometry/test/src/test_common_2d.cpp @@ -14,7 +14,7 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include +#include "autoware_auto_geometry/common_2d.hpp" #include #include diff --git a/common/autoware_auto_geometry/test/src/test_convex_hull.cpp b/common/autoware_auto_geometry/test/src/test_convex_hull.cpp index 43e3a3ad08adf..8b9bbce36c428 100644 --- a/common/autoware_auto_geometry/test/src/test_convex_hull.cpp +++ b/common/autoware_auto_geometry/test/src/test_convex_hull.cpp @@ -14,7 +14,7 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include "geometry/convex_hull.hpp" +#include "autoware_auto_geometry/convex_hull.hpp" #include diff --git a/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp b/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp index 2b79d4ff0f22b..9477a83a488ed 100644 --- a/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp +++ b/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp @@ -14,8 +14,8 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include "geometry/convex_hull.hpp" -#include "geometry/hull_pockets.hpp" +#include "autoware_auto_geometry/convex_hull.hpp" +#include "autoware_auto_geometry/hull_pockets.hpp" #include diff --git a/common/autoware_auto_geometry/test/src/test_intersection.cpp b/common/autoware_auto_geometry/test/src/test_intersection.cpp index 69c54960d4fc5..1036c69573c49 100644 --- a/common/autoware_auto_geometry/test/src/test_intersection.cpp +++ b/common/autoware_auto_geometry/test/src/test_intersection.cpp @@ -14,8 +14,8 @@ // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include -#include +#include "autoware_auto_geometry/convex_hull.hpp" +#include "autoware_auto_geometry/intersection.hpp" #include diff --git a/common/autoware_auto_geometry/test/src/test_interval.cpp b/common/autoware_auto_geometry/test/src/test_interval.cpp index ba8d5742dadc5..266ab123f5203 100644 --- a/common/autoware_auto_geometry/test/src/test_interval.cpp +++ b/common/autoware_auto_geometry/test/src/test_interval.cpp @@ -18,7 +18,7 @@ // FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS // IN THE SOFTWARE. -#include "geometry/interval.hpp" +#include "autoware_auto_geometry/interval.hpp" #include From 007f958142c1c8cced7f29aa6a2b568ba926de06 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 26 Dec 2023 15:29:37 +0900 Subject: [PATCH 138/276] fix(ndt_scan_matcher): fixed oscillation in ndt_scan_matcher (#5956) Fixed oscillation in ndt_scan_matcher Signed-off-by: Shintaro Sakoda --- .../ndt_scan_matcher_core.hpp | 3 +- .../src/ndt_scan_matcher_core.cpp | 70 +++++++++---------- 2 files changed, 34 insertions(+), 39 deletions(-) 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 a78b717e3a785..6a5c61041f0da 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 @@ -125,6 +125,7 @@ class NDTScanMatcher : public rclcpp::Node const double score, const double score_threshold, const std::string & score_name); bool validate_converged_param( const double & transform_probability, const double & nearest_voxel_transformation_likelihood); + static int count_oscillation(const std::vector & result_pose_msg_array); std::array estimate_covariance( const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, @@ -195,8 +196,6 @@ class NDTScanMatcher : public rclcpp::Node double lidar_topic_timeout_sec_; double initial_pose_timeout_sec_; double initial_pose_distance_tolerance_m_; - float inversion_vector_threshold_; - float oscillation_threshold_; bool use_cov_estimation_; std::vector initial_pose_offset_model_; std::array output_pose_covariance_; 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 401ab4a108557..7f6fe605c42b0 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -64,42 +64,12 @@ Eigen::Matrix2d find_rotation_matrix_aligning_covariance_to_principal_axes( throw std::runtime_error("Eigen solver failed. Return output_pose_covariance value."); } -bool validate_local_optimal_solution_oscillation( - const std::vector & result_pose_msg_array, - const float oscillation_threshold, const float inversion_vector_threshold) -{ - bool prev_oscillation = false; - int oscillation_cnt = 0; - - for (size_t i = 2; i < result_pose_msg_array.size(); ++i) { - const Eigen::Vector3d current_pose = point_to_vector3d(result_pose_msg_array.at(i).position); - const Eigen::Vector3d prev_pose = point_to_vector3d(result_pose_msg_array.at(i - 1).position); - const Eigen::Vector3d prev_prev_pose = - point_to_vector3d(result_pose_msg_array.at(i - 2).position); - const auto current_vec = current_pose - prev_pose; - const auto prev_vec = (prev_pose - prev_prev_pose).normalized(); - const bool oscillation = prev_vec.dot(current_vec) < inversion_vector_threshold; - if (prev_oscillation && oscillation) { - if (static_cast(oscillation_cnt) > oscillation_threshold) { - return true; - } - ++oscillation_cnt; - } else { - oscillation_cnt = 0; - } - prev_oscillation = oscillation; - } - return false; -} - // cspell: ignore degrounded NDTScanMatcher::NDTScanMatcher() : Node("ndt_scan_matcher"), tf2_broadcaster_(*this), ndt_ptr_(new NormalDistributionsTransform), state_ptr_(new std::map), - inversion_vector_threshold_(-0.9), // Not necessary to extract to ndt_scan_matcher.param.yaml - oscillation_threshold_(10), // Not necessary to extract to ndt_scan_matcher.param.yaml output_pose_covariance_({}), regularization_enabled_(declare_parameter("regularization_enabled")), is_activated_(false) @@ -505,10 +475,11 @@ void NDTScanMatcher::callback_sensor_points( // perform several validations bool is_ok_iteration_num = validate_num_iteration(ndt_result.iteration_num, ndt_ptr_->getMaximumIterations()); + const int oscillation_num = count_oscillation(transformation_msg_array); bool is_local_optimal_solution_oscillation = false; if (!is_ok_iteration_num) { - is_local_optimal_solution_oscillation = validate_local_optimal_solution_oscillation( - transformation_msg_array, oscillation_threshold_, inversion_vector_threshold_); + constexpr int oscillation_threshold = 10; + is_local_optimal_solution_oscillation = (oscillation_num > oscillation_threshold); } bool is_ok_converged_param = validate_converged_param( ndt_result.transform_probability, ndt_result.nearest_voxel_transformation_likelihood); @@ -590,11 +561,9 @@ void NDTScanMatcher::callback_sensor_points( std::to_string(ndt_result.nearest_voxel_transformation_likelihood); (*state_ptr_)["iteration_num"] = std::to_string(ndt_result.iteration_num); (*state_ptr_)["skipping_publish_num"] = std::to_string(skipping_publish_num); - if (is_local_optimal_solution_oscillation) { - (*state_ptr_)["is_local_optimal_solution_oscillation"] = "1"; - } else { - (*state_ptr_)["is_local_optimal_solution_oscillation"] = "0"; - } + (*state_ptr_)["oscillation_count"] = std::to_string(oscillation_num); + (*state_ptr_)["is_local_optimal_solution_oscillation"] = + std::to_string(is_local_optimal_solution_oscillation); (*state_ptr_)["execution_time"] = std::to_string(exe_time); publish_diagnostic(); @@ -763,6 +732,33 @@ bool NDTScanMatcher::validate_converged_param( return is_ok_converged_param; } +int NDTScanMatcher::count_oscillation( + const std::vector & result_pose_msg_array) +{ + constexpr double inversion_vector_threshold = -0.9; + + int oscillation_cnt = 0; + int max_oscillation_cnt = 0; + + for (size_t i = 2; i < result_pose_msg_array.size(); ++i) { + const Eigen::Vector3d current_pose = point_to_vector3d(result_pose_msg_array.at(i).position); + const Eigen::Vector3d prev_pose = point_to_vector3d(result_pose_msg_array.at(i - 1).position); + const Eigen::Vector3d prev_prev_pose = + point_to_vector3d(result_pose_msg_array.at(i - 2).position); + const auto current_vec = (current_pose - prev_pose).normalized(); + const auto prev_vec = (prev_pose - prev_prev_pose).normalized(); + const double cosine_value = current_vec.dot(prev_vec); + const bool oscillation = cosine_value < inversion_vector_threshold; + if (oscillation) { + oscillation_cnt++; // count consecutive oscillation + } else { + oscillation_cnt = 0; // reset + } + max_oscillation_cnt = std::max(max_oscillation_cnt, oscillation_cnt); + } + return max_oscillation_cnt; +} + std::array NDTScanMatcher::estimate_covariance( const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, const rclcpp::Time & sensor_ros_time) From c0e1baff4fd8829d6630143302771f5e118edb42 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Tue, 26 Dec 2023 07:35:03 +0100 Subject: [PATCH 139/276] fix(tier4_planning_rviz_plugin): move headers to tier4_planning_rviz_plugin directory (#5927) * fix(tier4_planning_rviz_plugin): move headers to tier4_planning_rviz_plugin directory Signed-off-by: Esteve Fernandez * style(pre-commit): autofix --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- common/tier4_planning_rviz_plugin/CMakeLists.txt | 8 ++++---- .../mission_checkpoint/mission_checkpoint.hpp | 6 +++--- .../{ => tier4_planning_rviz_plugin}/path/display.hpp | 8 ++++---- .../path/display_base.hpp | 9 +++++---- .../pose_with_uuid_stamped/display.hpp | 6 +++--- .../include/{ => tier4_planning_rviz_plugin}/utils.hpp | 6 +++--- .../src/mission_checkpoint/mission_checkpoint.cpp | 2 +- common/tier4_planning_rviz_plugin/src/path/display.cpp | 3 ++- .../src/pose_with_uuid_stamped/display.cpp | 4 ++-- 9 files changed, 27 insertions(+), 25 deletions(-) rename common/tier4_planning_rviz_plugin/include/{ => tier4_planning_rviz_plugin}/mission_checkpoint/mission_checkpoint.hpp (93%) rename common/tier4_planning_rviz_plugin/include/{ => tier4_planning_rviz_plugin}/path/display.hpp (97%) rename common/tier4_planning_rviz_plugin/include/{ => tier4_planning_rviz_plugin}/path/display_base.hpp (99%) rename common/tier4_planning_rviz_plugin/include/{ => tier4_planning_rviz_plugin}/pose_with_uuid_stamped/display.hpp (92%) rename common/tier4_planning_rviz_plugin/include/{ => tier4_planning_rviz_plugin}/utils.hpp (93%) diff --git a/common/tier4_planning_rviz_plugin/CMakeLists.txt b/common/tier4_planning_rviz_plugin/CMakeLists.txt index 5c17af5df22d1..69b61ba506b32 100644 --- a/common/tier4_planning_rviz_plugin/CMakeLists.txt +++ b/common/tier4_planning_rviz_plugin/CMakeLists.txt @@ -18,13 +18,13 @@ include_directories( ament_auto_add_library(tier4_planning_rviz_plugin SHARED # path point - include/path/display_base.hpp - include/path/display.hpp + include/tier4_planning_rviz_plugin/path/display_base.hpp + include/tier4_planning_rviz_plugin/path/display.hpp src/path/display.cpp # footprint - include/pose_with_uuid_stamped/display.hpp + include/tier4_planning_rviz_plugin/pose_with_uuid_stamped/display.hpp src/pose_with_uuid_stamped/display.cpp - include/mission_checkpoint/mission_checkpoint.hpp + include/tier4_planning_rviz_plugin/mission_checkpoint/mission_checkpoint.hpp src/mission_checkpoint/mission_checkpoint.cpp src/tools/jsk_overlay_utils.cpp src/tools/max_velocity.cpp diff --git a/common/tier4_planning_rviz_plugin/include/mission_checkpoint/mission_checkpoint.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/mission_checkpoint/mission_checkpoint.hpp similarity index 93% rename from common/tier4_planning_rviz_plugin/include/mission_checkpoint/mission_checkpoint.hpp rename to common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/mission_checkpoint/mission_checkpoint.hpp index ea15788d789fe..964c418a3df1f 100644 --- a/common/tier4_planning_rviz_plugin/include/mission_checkpoint/mission_checkpoint.hpp +++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/mission_checkpoint/mission_checkpoint.hpp @@ -45,8 +45,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef MISSION_CHECKPOINT__MISSION_CHECKPOINT_HPP_ -#define MISSION_CHECKPOINT__MISSION_CHECKPOINT_HPP_ +#ifndef TIER4_PLANNING_RVIZ_PLUGIN__MISSION_CHECKPOINT__MISSION_CHECKPOINT_HPP_ +#define TIER4_PLANNING_RVIZ_PLUGIN__MISSION_CHECKPOINT__MISSION_CHECKPOINT_HPP_ #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829 #include @@ -88,4 +88,4 @@ private Q_SLOTS: } // namespace rviz_plugins -#endif // MISSION_CHECKPOINT__MISSION_CHECKPOINT_HPP_ +#endif // TIER4_PLANNING_RVIZ_PLUGIN__MISSION_CHECKPOINT__MISSION_CHECKPOINT_HPP_ diff --git a/common/tier4_planning_rviz_plugin/include/path/display.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp similarity index 97% rename from common/tier4_planning_rviz_plugin/include/path/display.hpp rename to common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp index 7d635f0cedcad..66b4a31f0993f 100644 --- a/common/tier4_planning_rviz_plugin/include/path/display.hpp +++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH__DISPLAY_HPP_ -#define PATH__DISPLAY_HPP_ +#ifndef TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_HPP_ +#define TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_HPP_ -#include +#include "tier4_planning_rviz_plugin/path/display_base.hpp" #include #include @@ -228,4 +228,4 @@ class AutowareTrajectoryDisplay }; } // namespace rviz_plugins -#endif // PATH__DISPLAY_HPP_ +#endif // TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_HPP_ diff --git a/common/tier4_planning_rviz_plugin/include/path/display_base.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp similarity index 99% rename from common/tier4_planning_rviz_plugin/include/path/display_base.hpp rename to common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp index 74c2a60df3f32..4a59006e3bb96 100644 --- a/common/tier4_planning_rviz_plugin/include/path/display_base.hpp +++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH__DISPLAY_BASE_HPP_ -#define PATH__DISPLAY_BASE_HPP_ +#ifndef TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_ +#define TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_ #include #include @@ -40,9 +40,10 @@ #include #define EIGEN_MPL2_ONLY +#include "tier4_planning_rviz_plugin/utils.hpp" + #include #include -#include namespace { @@ -654,4 +655,4 @@ class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay }; } // namespace rviz_plugins -#endif // PATH__DISPLAY_BASE_HPP_ +#endif // TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_ diff --git a/common/tier4_planning_rviz_plugin/include/pose_with_uuid_stamped/display.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/pose_with_uuid_stamped/display.hpp similarity index 92% rename from common/tier4_planning_rviz_plugin/include/pose_with_uuid_stamped/display.hpp rename to common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/pose_with_uuid_stamped/display.hpp index f1fe3c30cd457..285a6902ccc1a 100644 --- a/common/tier4_planning_rviz_plugin/include/pose_with_uuid_stamped/display.hpp +++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/pose_with_uuid_stamped/display.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_WITH_UUID_STAMPED__DISPLAY_HPP_ -#define POSE_WITH_UUID_STAMPED__DISPLAY_HPP_ +#ifndef TIER4_PLANNING_RVIZ_PLUGIN__POSE_WITH_UUID_STAMPED__DISPLAY_HPP_ +#define TIER4_PLANNING_RVIZ_PLUGIN__POSE_WITH_UUID_STAMPED__DISPLAY_HPP_ #include @@ -81,4 +81,4 @@ private Q_SLOTS: } // namespace rviz_plugins -#endif // POSE_WITH_UUID_STAMPED__DISPLAY_HPP_ +#endif // TIER4_PLANNING_RVIZ_PLUGIN__POSE_WITH_UUID_STAMPED__DISPLAY_HPP_ diff --git a/common/tier4_planning_rviz_plugin/include/utils.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp similarity index 93% rename from common/tier4_planning_rviz_plugin/include/utils.hpp rename to common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp index 76f9da0685908..94943a25f6a64 100644 --- a/common/tier4_planning_rviz_plugin/include/utils.hpp +++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef UTILS_HPP_ -#define UTILS_HPP_ +#ifndef TIER4_PLANNING_RVIZ_PLUGIN__UTILS_HPP_ +#define TIER4_PLANNING_RVIZ_PLUGIN__UTILS_HPP_ #include #include @@ -61,4 +61,4 @@ bool isDrivingForward(const T points_with_twist, size_t target_idx) } } // namespace rviz_plugins -#endif // UTILS_HPP_ +#endif // TIER4_PLANNING_RVIZ_PLUGIN__UTILS_HPP_ diff --git a/common/tier4_planning_rviz_plugin/src/mission_checkpoint/mission_checkpoint.cpp b/common/tier4_planning_rviz_plugin/src/mission_checkpoint/mission_checkpoint.cpp index 6be2cfc426870..2ba5a309baa5c 100644 --- a/common/tier4_planning_rviz_plugin/src/mission_checkpoint/mission_checkpoint.cpp +++ b/common/tier4_planning_rviz_plugin/src/mission_checkpoint/mission_checkpoint.cpp @@ -45,7 +45,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include +#include "tier4_planning_rviz_plugin/mission_checkpoint/mission_checkpoint.hpp" #ifdef ROS_DISTRO_GALACTIC #include diff --git a/common/tier4_planning_rviz_plugin/src/path/display.cpp b/common/tier4_planning_rviz_plugin/src/path/display.cpp index 5bda4cdafd7e3..916201669e9e3 100644 --- a/common/tier4_planning_rviz_plugin/src/path/display.cpp +++ b/common/tier4_planning_rviz_plugin/src/path/display.cpp @@ -12,7 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include "tier4_planning_rviz_plugin/path/display.hpp" + #include namespace rviz_plugins diff --git a/common/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp b/common/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp index 8df04e04b2963..b525608a65625 100644 --- a/common/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp +++ b/common/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "rviz_common/properties/tf_frame_property.hpp" +#include "tier4_planning_rviz_plugin/pose_with_uuid_stamped/display.hpp" -#include #include +#include #include #include #include From 0ced30d19cbdf33651a2b6644bad9775c55e2bbc Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Tue, 26 Dec 2023 07:37:12 +0100 Subject: [PATCH 140/276] fix(planning_test_utils): rename header directory to match project name (#5863) * fix(planning_test_utils): rename header directory to match project name Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * fix: fix include Signed-off-by: Esteve Fernandez * fix: fix includes in downstream packages Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * fix: fix includes Signed-off-by: Esteve Fernandez * fix: fix includes Signed-off-by: Esteve Fernandez * fix: fix includes Signed-off-by: Esteve Fernandez --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../test/test_behavior_path_planner_node_interface.cpp | 7 ++++--- .../test/test_behavior_path_planner_node_interface.cpp | 7 ++++--- .../test/test_behavior_path_planner_node_interface.cpp | 4 ++-- .../test/test_behavior_path_planner_node_interface.cpp | 4 ++-- .../test/test_behavior_path_planner_node_interface.cpp | 7 ++++--- .../test/test_behavior_path_planner_node_interface.cpp | 7 ++++--- .../test/src/test_node_interface.cpp | 7 ++++--- .../test/test_freespace_planner_node_interface.cpp | 7 ++++--- .../test/test_motion_velocity_smoother_node_interface.cpp | 7 ++++--- .../test_obstacle_avoidance_planner_node_interface.cpp | 7 ++++--- .../test/test_obstacle_cruise_planner_node_interface.cpp | 7 ++++--- .../test/test_obstacle_stop_planner_node_interface.cpp | 7 ++++--- .../test/test_obstacle_velocity_limiter_node_interface.cpp | 7 ++++--- .../test/test_path_smoother_node_interface.cpp | 7 ++++--- .../planning_interface_test_manager.hpp | 6 +++--- .../planning_interface_test_manager_utils.hpp | 6 +++--- .../src/planning_interface_test_manager.cpp | 4 ++-- .../test/src/test_planning_validator_node_interface.cpp | 7 ++++--- .../test/test_scenario_selector_node_interface.cpp | 7 ++++--- 19 files changed, 68 insertions(+), 54 deletions(-) rename planning/planning_test_utils/include/{planning_interface_test_manager => planning_test_utils}/planning_interface_test_manager.hpp (98%) rename planning/planning_test_utils/include/{planning_interface_test_manager => planning_test_utils}/planning_interface_test_manager_utils.hpp (98%) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 3041ae7e1112e..581aafa6c860c 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "behavior_path_planner/behavior_path_planner_node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 7b9a608aecec3..8cf85554e2b2c 100644 --- a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "behavior_path_planner/behavior_path_planner_node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index ff5be388704da..434988cc3ab08 100644 --- a/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -14,8 +14,8 @@ #include "ament_index_cpp/get_package_share_directory.hpp" #include "behavior_path_planner/behavior_path_planner_node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" +#include "planning_test_utils/planning_interface_test_manager.hpp" +#include "planning_test_utils/planning_interface_test_manager_utils.hpp" #include diff --git a/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 7a606b5d126ce..82f721411d5a4 100644 --- a/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -14,8 +14,8 @@ #include "ament_index_cpp/get_package_share_directory.hpp" #include "behavior_path_planner/behavior_path_planner_node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" +#include "planning_test_utils/planning_interface_test_manager.hpp" +#include "planning_test_utils/planning_interface_test_manager_utils.hpp" #include diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index f2c22f774fc77..28ee6d31e80dc 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "behavior_path_planner/behavior_path_planner_node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp index 94be083bdebcd..eb7d1afe27549 100644 --- a/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "behavior_path_planner/behavior_path_planner_node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp index 491df4c7a8766..239abbde27609 100644 --- a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp b/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp index 8c6336b2f45d6..013eb3c33cbad 100644 --- a/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp +++ b/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "freespace_planner/freespace_planner_node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp b/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp index 4c8eaac67cbb5..430f8b78ec88c 100644 --- a/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp +++ b/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "motion_velocity_smoother/motion_velocity_smoother_node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/obstacle_avoidance_planner/test/test_obstacle_avoidance_planner_node_interface.cpp b/planning/obstacle_avoidance_planner/test/test_obstacle_avoidance_planner_node_interface.cpp index 75b61f80622d1..9c567487e9cac 100644 --- a/planning/obstacle_avoidance_planner/test/test_obstacle_avoidance_planner_node_interface.cpp +++ b/planning/obstacle_avoidance_planner/test/test_obstacle_avoidance_planner_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "obstacle_avoidance_planner/node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp b/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp index 5be04ab801e14..d412286d77d53 100644 --- a/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp +++ b/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "obstacle_cruise_planner/node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp b/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp index 95afdd7f2ea3b..7f986bf848777 100644 --- a/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp +++ b/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "obstacle_stop_planner/node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp b/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp index c2ffaffc75287..a89042ef210d5 100644 --- a/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp +++ b/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/path_smoother/test/test_path_smoother_node_interface.cpp b/planning/path_smoother/test/test_path_smoother_node_interface.cpp index b18c49b0e88b0..3598e07f84fd6 100644 --- a/planning/path_smoother/test/test_path_smoother_node_interface.cpp +++ b/planning/path_smoother/test/test_path_smoother_node_interface.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" #include "path_smoother/elastic_band_smoother.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include +#include +#include #include diff --git a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp b/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager.hpp similarity index 98% rename from planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp rename to planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager.hpp index 556ef9a4a4afa..a63b0d02152f0 100644 --- a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp +++ b/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_HPP_ -#define PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_HPP_ +#ifndef PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_HPP_ +#define PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_HPP_ // since ASSERT_NO_THROW in gtest masks the exception message, redefine it. #define ASSERT_NO_THROW_WITH_ERROR_MSG(statement) \ @@ -266,4 +266,4 @@ class PlanningInterfaceTestManager } // namespace planning_test_utils -#endif // PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_HPP_ +#endif // PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_HPP_ diff --git a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp b/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp similarity index 98% rename from planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp rename to planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp index 0af375c9d9c8a..4d8d7be96b44b 100644 --- a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp +++ b/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ -#define PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ +#ifndef PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ +#define PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ #include "ament_index_cpp/get_package_share_directory.hpp" #include "rclcpp/rclcpp.hpp" @@ -569,4 +569,4 @@ PathWithLaneId loadPathWithLaneIdInYaml() } // namespace test_utils -#endif // PLANNING_INTERFACE_TEST_MANAGER__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ +#endif // PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ diff --git a/planning/planning_test_utils/src/planning_interface_test_manager.cpp b/planning/planning_test_utils/src/planning_interface_test_manager.cpp index 6489f32dc4cdf..a9d096bf00fd4 100644 --- a/planning/planning_test_utils/src/planning_interface_test_manager.cpp +++ b/planning/planning_test_utils/src/planning_interface_test_manager.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include +#include +#include namespace planning_test_utils { diff --git a/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp b/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp index 95619e749a9f9..606dc182504a2 100644 --- a/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp +++ b/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp @@ -12,11 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" #include "planning_validator/planning_validator.hpp" +#include +#include +#include + #include #include diff --git a/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp b/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp index d3d6939f49b83..7413be07ef904 100644 --- a/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp +++ b/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp @@ -12,11 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager.hpp" -#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" #include "scenario_selector/scenario_selector_node.hpp" +#include +#include +#include + #include #include From cdaadc7a23e2ff5e420ba393981ad24e1dc8bd0c Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Tue, 26 Dec 2023 09:20:00 +0100 Subject: [PATCH 141/276] fix(diagnostic_converter): move headers to a separate directory (#5943) * fix(diagnostic_converter): move headers to a separate directory Signed-off-by: Esteve Fernandez * style(pre-commit): autofix --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/{ => diagnostic_converter}/converter_node.hpp | 6 +++--- evaluator/diagnostic_converter/src/converter_node.cpp | 2 +- evaluator/diagnostic_converter/test/test_converter_node.cpp | 5 +++-- 3 files changed, 7 insertions(+), 6 deletions(-) rename evaluator/diagnostic_converter/include/{ => diagnostic_converter}/converter_node.hpp (93%) diff --git a/evaluator/diagnostic_converter/include/converter_node.hpp b/evaluator/diagnostic_converter/include/diagnostic_converter/converter_node.hpp similarity index 93% rename from evaluator/diagnostic_converter/include/converter_node.hpp rename to evaluator/diagnostic_converter/include/diagnostic_converter/converter_node.hpp index 53c762dac0ffe..59bb02ebf301f 100644 --- a/evaluator/diagnostic_converter/include/converter_node.hpp +++ b/evaluator/diagnostic_converter/include/diagnostic_converter/converter_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CONVERTER_NODE_HPP_ -#define CONVERTER_NODE_HPP_ +#ifndef DIAGNOSTIC_CONVERTER__CONVERTER_NODE_HPP_ +#define DIAGNOSTIC_CONVERTER__CONVERTER_NODE_HPP_ #include @@ -63,4 +63,4 @@ class DiagnosticConverter : public rclcpp::Node }; } // namespace diagnostic_converter -#endif // CONVERTER_NODE_HPP_ +#endif // DIAGNOSTIC_CONVERTER__CONVERTER_NODE_HPP_ diff --git a/evaluator/diagnostic_converter/src/converter_node.cpp b/evaluator/diagnostic_converter/src/converter_node.cpp index e61b19833d2fe..2a2574732694c 100644 --- a/evaluator/diagnostic_converter/src/converter_node.cpp +++ b/evaluator/diagnostic_converter/src/converter_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "converter_node.hpp" +#include "diagnostic_converter/converter_node.hpp" #include diff --git a/evaluator/diagnostic_converter/test/test_converter_node.cpp b/evaluator/diagnostic_converter/test/test_converter_node.cpp index 47f42d018ea71..167421f0777df 100644 --- a/evaluator/diagnostic_converter/test/test_converter_node.cpp +++ b/evaluator/diagnostic_converter/test/test_converter_node.cpp @@ -12,8 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "converter_node.hpp" -#include "gtest/gtest.h" +#include "diagnostic_converter/converter_node.hpp" #include @@ -21,6 +20,8 @@ #include "tier4_simulation_msgs/msg/user_defined_value.hpp" #include "tier4_simulation_msgs/msg/user_defined_value_type.hpp" +#include + #include #include #include From 316bb43e6240c27be29122bb09b06d0206ade3be Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 26 Dec 2023 17:28:48 +0900 Subject: [PATCH 142/276] fix(ndt_scan_matcher): fixed a lock scope in update_ndt (#5951) Fixed the lock scope in update_ndt Signed-off-by: Shintaro SAKODA --- .../src/map_update_module.cpp | 31 ++++++++++--------- 1 file changed, 16 insertions(+), 15 deletions(-) diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index b0baa3c6fb237..446f926a1d3f7 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -92,21 +92,30 @@ void MapUpdateModule::update_ndt( } const auto exe_start_time = std::chrono::system_clock::now(); - NormalDistributionsTransform backup_ndt = *ndt_ptr_; + const size_t add_size = maps_to_add.size(); + + // Perform heavy processing outside of the lock scope + std::vector>> points_pcl(add_size); + for (size_t i = 0; i < add_size; i++) { + points_pcl[i] = pcl::make_shared>(); + pcl::fromROSMsg(maps_to_add[i].pointcloud, *points_pcl[i]); + } + + (*ndt_ptr_mutex_).lock(); // Add pcd - for (const auto & map_to_add : maps_to_add) { - pcl::shared_ptr> map_points_ptr(new pcl::PointCloud); - pcl::fromROSMsg(map_to_add.pointcloud, *map_points_ptr); - backup_ndt.addTarget(map_points_ptr, map_to_add.cell_id); + for (size_t i = 0; i < add_size; i++) { + ndt_ptr_->addTarget(points_pcl[i], maps_to_add[i].cell_id); } // Remove pcd for (const std::string & map_id_to_remove : map_ids_to_remove) { - backup_ndt.removeTarget(map_id_to_remove); + ndt_ptr_->removeTarget(map_id_to_remove); } - backup_ndt.createVoxelKdtree(); + ndt_ptr_->createVoxelKdtree(); + + (*ndt_ptr_mutex_).unlock(); const auto exe_end_time = std::chrono::system_clock::now(); const auto duration_micro_sec = @@ -114,14 +123,6 @@ void MapUpdateModule::update_ndt( const auto exe_time = static_cast(duration_micro_sec) / 1000.0; RCLCPP_INFO(logger_, "Time duration for creating new ndt_ptr: %lf [ms]", exe_time); - // swap - (*ndt_ptr_mutex_).lock(); - // ToDo (kminoda): Here negligible NDT copy occurs during the new map loading phase, which should - // ideally be avoided. But I will leave this for now since I cannot come up with a solution other - // than using pointer of pointer. - *ndt_ptr_ = backup_ndt; - (*ndt_ptr_mutex_).unlock(); - publish_partial_pcd_map(); } From 33ca7c86c84daa6f992fabd4e6c5b2e03ab03366 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 26 Dec 2023 17:55:55 +0900 Subject: [PATCH 143/276] fix(avoidance): don't ignore objects on straight lane in intersection (#5939) * fix(avoidance): don't ignore objects on straight lane in intersection Signed-off-by: satoshi-ota * fix(avoidance): fix filtering flow Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/utils.cpp | 36 +++++++++---------- 1 file changed, 17 insertions(+), 19 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index a4399c41bc0ef..ed7063c9fecba 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -635,18 +635,7 @@ bool isSatisfiedWithVehicleCondition( return true; } - // always ignore all merging objects. - if (object.behavior == ObjectData::Behavior::MERGING) { - object.reason = "MergingToEgoLane"; - return false; - } - - // Object is on center line -> ignore. - if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) { - object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE; - return false; - } - + // check vehicle shift ratio lanelet::BasicPoint2d object_centroid(object.centroid.x(), object.centroid.y()); const auto on_ego_driving_lane = within(object_centroid, object.overhang_lanelet.polygon2d().basicPolygon()); @@ -659,17 +648,26 @@ bool isSatisfiedWithVehicleCondition( } } - if (!object.is_within_intersection) { - return true; + // Object is on center line -> ignore. + if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) { + object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE; + return false; } - std::string turn_direction = object.overhang_lanelet.attributeOr("turn_direction", "else"); - if (turn_direction == "straight") { - return true; + if (object.is_within_intersection) { + std::string turn_direction = object.overhang_lanelet.attributeOr("turn_direction", "else"); + if (turn_direction == "straight") { + return true; + } + + if (object.behavior == ObjectData::Behavior::NONE) { + object.reason = "ParallelToEgoLane"; + return false; + } } - if (object.behavior == ObjectData::Behavior::NONE) { - object.reason = "ParallelToEgoLane"; + if (object.behavior == ObjectData::Behavior::MERGING) { + object.reason = "MergingToEgoLane"; return false; } From e00eaa3db1ead590044bb4a15399136b481a4d86 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 26 Dec 2023 17:56:05 +0900 Subject: [PATCH 144/276] feat(avoidance): suppress unnatural turn signal (#5905) * refactor(avoidance): clean up Signed-off-by: satoshi-ota * fix(avoidance): suppress unnecessary turn signal Signed-off-by: satoshi-ota * refactor(avoidance): move utils Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/scene.hpp | 7 - .../behavior_path_avoidance_module/utils.hpp | 4 + .../src/scene.cpp | 123 +----------- .../src/utils.cpp | 189 ++++++++++++++++++ 4 files changed, 200 insertions(+), 123 deletions(-) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp index 91c115706e030..889d48c481b6f 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp @@ -325,13 +325,6 @@ class AvoidanceModule : public SceneModuleInterface // generate output data - /** - * @brief calculate turn signal infomation. - * @param avoidance path. - * @return turn signal command. - */ - TurnSignalInfo calcTurnSignalInfo(const ShiftedPath & path) const; - /** * @brief fill debug markers. */ diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp index 23a6ab5c52536..4508cbc3c18f6 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp @@ -174,6 +174,10 @@ double calcDistanceToAvoidStartLine( const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, const std::shared_ptr & planner_data, const std::shared_ptr & parameters); + +TurnSignalInfo calcTurnSignalInfo( + const ShiftedPath & path, const ShiftLine & shift_line, const double current_shift_length, + const AvoidancePlanningData & data, const std::shared_ptr & planner_data); } // namespace behavior_path_planner::utils::avoidance #endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__UTILS_HPP_ diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index b03b9189dfca5..31849c716971c 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -17,7 +17,6 @@ #include "behavior_path_avoidance_module/debug.hpp" #include "behavior_path_avoidance_module/utils.hpp" #include "behavior_path_planner_common/interface/scene_module_visitor.hpp" -#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" @@ -874,7 +873,7 @@ BehaviorModuleOutput AvoidanceModule::plan() if (success_spline_path_generation && success_linear_path_generation) { helper_->setPreviousLinearShiftPath(linear_shift_path); helper_->setPreviousSplineShiftPath(spline_shift_path); - helper_->setPreviousReferencePath(data.reference_path); + helper_->setPreviousReferencePath(path_shifter_.getReferencePath()); } else { spline_shift_path = helper_->getPreviousSplineShiftPath(); } @@ -887,9 +886,13 @@ BehaviorModuleOutput AvoidanceModule::plan() BehaviorModuleOutput output; // turn signal info - { + if (path_shifter_.getShiftLines().empty()) { + output.turn_signal_info = getPreviousModuleOutput().turn_signal_info; + } else { const auto original_signal = getPreviousModuleOutput().turn_signal_info; - const auto new_signal = calcTurnSignalInfo(spline_shift_path); + const auto new_signal = utils::avoidance::calcTurnSignalInfo( + linear_shift_path, path_shifter_.getShiftLines().front(), helper_->getEgoShift(), avoid_data_, + planner_data_); const auto current_seg_idx = planner_data_->findEgoSegmentIndex(spline_shift_path.path.points); output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal( spline_shift_path.path, getEgoPose(), current_seg_idx, original_signal, new_signal, @@ -1285,118 +1288,6 @@ void AvoidanceModule::updateRTCData() updateCandidateRTCStatus(output); } -TurnSignalInfo AvoidanceModule::calcTurnSignalInfo(const ShiftedPath & path) const -{ - const auto shift_lines = path_shifter_.getShiftLines(); - if (shift_lines.empty()) { - return {}; - } - - const auto front_shift_line = shift_lines.front(); - const size_t start_idx = front_shift_line.start_idx; - const size_t end_idx = front_shift_line.end_idx; - - const auto current_shift_length = helper_->getEgoShift(); - const double start_shift_length = path.shift_length.at(start_idx); - const double end_shift_length = path.shift_length.at(end_idx); - const double segment_shift_length = end_shift_length - start_shift_length; - - const double turn_signal_shift_length_threshold = - planner_data_->parameters.turn_signal_shift_length_threshold; - const double turn_signal_search_time = planner_data_->parameters.turn_signal_search_time; - const double turn_signal_minimum_search_distance = - planner_data_->parameters.turn_signal_minimum_search_distance; - - // If shift length is shorter than the threshold, it does not need to turn on blinkers - if (std::fabs(segment_shift_length) < turn_signal_shift_length_threshold) { - return {}; - } - - // If the vehicle does not shift anymore, we turn off the blinker - if (std::fabs(end_shift_length - current_shift_length) < 0.1) { - return {}; - } - - // compute blinker start idx and end idx - size_t blinker_start_idx = [&]() { - for (size_t idx = start_idx; idx <= end_idx; ++idx) { - const double current_shift_length = path.shift_length.at(idx); - if (current_shift_length > 0.1) { - return idx; - } - } - return start_idx; - }(); - size_t blinker_end_idx = end_idx; - - // prevent invalid access for out-of-range - blinker_start_idx = - std::min(std::max(std::size_t(0), blinker_start_idx), path.path.points.size() - 1); - blinker_end_idx = - std::min(std::max(blinker_start_idx, blinker_end_idx), path.path.points.size() - 1); - - const auto blinker_start_pose = path.path.points.at(blinker_start_idx).point.pose; - const auto blinker_end_pose = path.path.points.at(blinker_end_idx).point.pose; - - const double ego_vehicle_offset = - planner_data_->parameters.vehicle_info.max_longitudinal_offset_m; - const auto signal_prepare_distance = - std::max(getEgoSpeed() * turn_signal_search_time, turn_signal_minimum_search_distance); - const auto ego_front_to_shift_start = - calcSignedArcLength(path.path.points, getEgoPosition(), blinker_start_pose.position) - - ego_vehicle_offset; - - if (signal_prepare_distance < ego_front_to_shift_start) { - return {}; - } - - bool turn_signal_on_swerving = planner_data_->parameters.turn_signal_on_swerving; - - TurnSignalInfo turn_signal_info{}; - if (turn_signal_on_swerving) { - if (segment_shift_length > 0.0) { - turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; - } else { - turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; - } - } else { - const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_); - const auto local_vehicle_footprint = - createVehicleFootprint(planner_data_->parameters.vehicle_info); - boost::geometry::model::ring shifted_vehicle_footprint; - for (const auto & cl : current_lanes) { - // get left and right bounds of current lane - const auto lane_left_bound = cl.leftBound2d().basicLineString(); - const auto lane_right_bound = cl.rightBound2d().basicLineString(); - for (size_t i = start_idx; i < end_idx; ++i) { - // transform vehicle footprint onto path points - shifted_vehicle_footprint = transformVector( - local_vehicle_footprint, - tier4_autoware_utils::pose2transform(path.path.points.at(i).point.pose)); - if ( - boost::geometry::intersects(lane_left_bound, shifted_vehicle_footprint) || - boost::geometry::intersects(lane_right_bound, shifted_vehicle_footprint)) { - if (segment_shift_length > 0.0) { - turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; - } else { - turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; - } - } - } - } - } - if (ego_front_to_shift_start > 0.0) { - turn_signal_info.desired_start_point = planner_data_->self_odometry->pose.pose; - } else { - turn_signal_info.desired_start_point = blinker_start_pose; - } - turn_signal_info.desired_end_point = blinker_end_pose; - turn_signal_info.required_start_point = blinker_start_pose; - turn_signal_info.required_end_point = blinker_end_pose; - - return turn_signal_info; -} - void AvoidanceModule::updateInfoMarker(const AvoidancePlanningData & data) const { using marker_utils::avoidance_marker::createTargetObjectsMarkerArray; diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index ed7063c9fecba..493ca35f09a3b 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -16,6 +16,7 @@ #include "behavior_path_avoidance_module/data_structs.hpp" #include "behavior_path_avoidance_module/utils.hpp" +#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/traffic_light_utils.hpp" @@ -225,6 +226,98 @@ void pushUniqueVector(T & base_vector, const T & additional_vector) base_vector.insert(base_vector.end(), additional_vector.begin(), additional_vector.end()); } +bool existShiftSideLane( + const double start_shift_length, const double end_shift_length, const bool no_left_lanes, + const bool no_right_lanes) +{ + constexpr double THRESHOLD = 0.1; + const auto relative_shift_length = end_shift_length - start_shift_length; + + const auto avoid_shift = + std::abs(start_shift_length) < THRESHOLD && std::abs(end_shift_length) > THRESHOLD; + if (avoid_shift) { + // Left avoid. But there is no adjacent lane. No need blinker. + if (relative_shift_length > 0.0 && no_left_lanes) { + return false; + } + + // Right avoid. But there is no adjacent lane. No need blinker. + if (relative_shift_length < 0.0 && no_right_lanes) { + return false; + } + } + + const auto return_shift = + std::abs(start_shift_length) > THRESHOLD && std::abs(end_shift_length) < THRESHOLD; + if (return_shift) { + // Right return. But there is no adjacent lane. No need blinker. + if (relative_shift_length > 0.0 && no_right_lanes) { + return false; + } + + // Left return. But there is no adjacent lane. No need blinker. + if (relative_shift_length < 0.0 && no_left_lanes) { + return false; + } + } + + const auto left_middle_shift = start_shift_length > THRESHOLD && end_shift_length > THRESHOLD; + if (left_middle_shift) { + // Left avoid. But there is no adjacent lane. No need blinker. + if (relative_shift_length > 0.0 && no_left_lanes) { + return false; + } + + // Left return. But there is no adjacent lane. No need blinker. + if (relative_shift_length < 0.0 && no_left_lanes) { + return false; + } + } + + const auto right_middle_shift = start_shift_length < THRESHOLD && end_shift_length < THRESHOLD; + if (right_middle_shift) { + // Right avoid. But there is no adjacent lane. No need blinker. + if (relative_shift_length < 0.0 && no_right_lanes) { + return false; + } + + // Left avoid. But there is no adjacent lane. No need blinker. + if (relative_shift_length > 0.0 && no_right_lanes) { + return false; + } + } + + return true; +} + +bool straddleRoadBound( + const ShiftedPath & path, const ShiftLine & shift_line, const lanelet::ConstLanelets & lanes, + const vehicle_info_util::VehicleInfo & vehicle_info) +{ + using boost::geometry::intersects; + using tier4_autoware_utils::pose2transform; + using tier4_autoware_utils::transformVector; + + const auto footprint = vehicle_info.createFootprint(); + + for (const auto & lane : lanes) { + for (size_t i = shift_line.start_idx; i < shift_line.end_idx; ++i) { + const auto transform = pose2transform(path.path.points.at(i).point.pose); + const auto shifted_vehicle_footprint = transformVector(footprint, transform); + + if (intersects(lane.leftBound2d().basicLineString(), shifted_vehicle_footprint)) { + return true; + } + + if (intersects(lane.rightBound2d().basicLineString(), shifted_vehicle_footprint)) { + return true; + } + } + } + + return false; +} + } // namespace namespace filtering_utils @@ -2055,4 +2148,100 @@ double calcDistanceToReturnDeadLine( return distance_to_return_dead_line; } + +TurnSignalInfo calcTurnSignalInfo( + const ShiftedPath & path, const ShiftLine & shift_line, const double current_shift_length, + const AvoidancePlanningData & data, const std::shared_ptr & planner_data) +{ + constexpr double THRESHOLD = 0.1; + const auto & p = planner_data->parameters; + const auto & rh = planner_data->route_handler; + const auto & ego_pose = planner_data->self_odometry->pose.pose; + const auto & ego_speed = planner_data->self_odometry->twist.twist.linear.x; + + if (shift_line.start_idx + 1 > path.shift_length.size()) { + RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency."); + return {}; + } + + if (shift_line.start_idx + 1 > path.path.points.size()) { + RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency."); + return {}; + } + + if (shift_line.end_idx + 1 > path.shift_length.size()) { + RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency."); + return {}; + } + + if (shift_line.end_idx + 1 > path.path.points.size()) { + RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency."); + return {}; + } + + const auto start_shift_length = path.shift_length.at(shift_line.start_idx); + const auto end_shift_length = path.shift_length.at(shift_line.end_idx); + const auto relative_shift_length = end_shift_length - start_shift_length; + + // If shift length is shorter than the threshold, it does not need to turn on blinkers + if (std::fabs(relative_shift_length) < p.turn_signal_shift_length_threshold) { + return {}; + } + + // If the vehicle does not shift anymore, we turn off the blinker + if (std::fabs(path.shift_length.at(shift_line.end_idx) - current_shift_length) < THRESHOLD) { + return {}; + } + + const auto get_command = [](const auto & shift_length) { + return shift_length > 0.0 ? TurnIndicatorsCommand::ENABLE_LEFT + : TurnIndicatorsCommand::ENABLE_RIGHT; + }; + + const auto signal_prepare_distance = + std::max(ego_speed * p.turn_signal_search_time, p.turn_signal_minimum_search_distance); + const auto ego_front_to_shift_start = + calcSignedArcLength(path.path.points, ego_pose.position, shift_line.start_idx) - + p.vehicle_info.max_longitudinal_offset_m; + + if (signal_prepare_distance < ego_front_to_shift_start) { + return {}; + } + + const auto blinker_start_pose = path.path.points.at(shift_line.start_idx).point.pose; + const auto blinker_end_pose = path.path.points.at(shift_line.end_idx).point.pose; + const auto get_start_pose = [&](const auto & ego_to_shift_start) { + return ego_to_shift_start ? ego_pose : blinker_start_pose; + }; + + TurnSignalInfo turn_signal_info{}; + turn_signal_info.desired_start_point = get_start_pose(ego_front_to_shift_start); + turn_signal_info.desired_end_point = blinker_end_pose; + turn_signal_info.required_start_point = blinker_start_pose; + turn_signal_info.required_end_point = blinker_end_pose; + turn_signal_info.turn_signal.command = get_command(relative_shift_length); + + if (!p.turn_signal_on_swerving) { + return turn_signal_info; + } + + lanelet::ConstLanelet lanelet; + if (!rh->getClosestLaneletWithinRoute(shift_line.end, &lanelet)) { + return {}; + } + + const auto left_lanelets = rh->getAllLeftSharedLinestringLanelets(lanelet, true, true); + const auto right_lanelets = rh->getAllRightSharedLinestringLanelets(lanelet, true, true); + + if (!existShiftSideLane( + start_shift_length, end_shift_length, left_lanelets.empty(), right_lanelets.empty())) { + return {}; + } + + if (!straddleRoadBound(path, shift_line, data.current_lanelets, p.vehicle_info)) { + return {}; + } + + return turn_signal_info; +} } // namespace behavior_path_planner::utils::avoidance From 7bc3ee4770f754fcb879f2ad7e6fb84b7d18ca77 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 26 Dec 2023 18:01:20 +0900 Subject: [PATCH 145/276] refactor(lane_change): use new interface for state (#5950) * refactor(lane_change): use new interface for state Signed-off-by: Muhammad Zulfaqar Azmi * fix some state Signed-off-by: Muhammad Zulfaqar Azmi * fix scenario failed Signed-off-by: Zulfaqar Azmi * fix ablc not transitioning to success Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi --- .../src/scene.cpp | 5 +- .../interface.hpp | 15 +- .../scene.hpp | 2 +- .../utils/base_class.hpp | 2 +- .../src/interface.cpp | 233 ++++++++++-------- .../src/scene.cpp | 12 +- .../interface/scene_module_interface.hpp | 16 ++ 7 files changed, 166 insertions(+), 119 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index e245f1c44fe0e..7d36c06a3482e 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -54,6 +54,7 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const const auto & data = avoidance_data_; if (data.target_objects.empty()) { + RCLCPP_WARN(logger_, "no empty objects"); return false; } @@ -73,11 +74,13 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const std::accumulate(object_parameters.begin(), object_parameters.end(), 0UL, count_target_object); if (num_of_avoidance_targets < 1) { + RCLCPP_WARN(logger_, "no avoidance target"); return false; } const auto current_lanes = getCurrentLanes(); if (current_lanes.empty()) { + RCLCPP_WARN(logger_, "no empty lanes"); return false; } @@ -106,7 +109,7 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const const auto maximum_avoid_distance = avoidance_helper_->getMaxAvoidanceDistance(shift_length); - RCLCPP_DEBUG( + RCLCPP_WARN( logger_, "nearest_object.longitudinal %.3f, minimum_lane_change_length %.3f, maximum_avoid_distance " "%.3f", diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp index b9b44d3c96186..f1072b87755b0 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp @@ -69,11 +69,10 @@ class LaneChangeInterface : public SceneModuleInterface bool isRootLaneletToBeUpdated() const override { return current_state_ == ModuleStatus::SUCCESS; } - // TODO(someone): remove this, and use base class function - [[deprecated]] ModuleStatus updateState() override; - void updateData() override; + void postProcess() override; + BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; @@ -118,15 +117,13 @@ class LaneChangeInterface : public SceneModuleInterface std::unique_ptr module_type_; - bool canTransitSuccessState() override { return false; } - - bool canTransitFailureState() override { return false; } + PathSafetyStatus post_process_safety_status_; - bool canTransitIdleToRunningState() override { return false; } + bool canTransitSuccessState() override; - void resetPathIfAbort(); + bool canTransitFailureState() override; - void resetLaneChangeModule(); + bool canTransitIdleToRunningState() override; void setObjectDebugVisualization() const; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp index 50766621b2f44..9c3c371627a78 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp @@ -71,7 +71,7 @@ class NormalLaneChange : public LaneChangeBase PathSafetyStatus isApprovedPathSafe() const override; - bool isRequiredStop(const bool is_object_coming_from_rear) const override; + bool isRequiredStop(const bool is_object_coming_from_rear) override; bool isNearEndOfCurrentLanes( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp index aa3ee0dc4c98b..451899fbf27e6 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp @@ -90,7 +90,7 @@ class LaneChangeBase virtual bool isEgoOnPreparePhase() const = 0; - virtual bool isRequiredStop(const bool is_object_coming_from_rear) const = 0; + virtual bool isRequiredStop(const bool is_object_coming_from_rear) = 0; virtual PathSafetyStatus isApprovedPathSafe() const = 0; diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 00793532023b9..e5aa8e06ece4c 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -76,110 +76,6 @@ bool LaneChangeInterface::isExecutionReady() const return module_type_->isSafe(); } -ModuleStatus LaneChangeInterface::updateState() -{ - auto log_warn_throttled = [&](const std::string & message) -> void { - RCLCPP_WARN_STREAM_THROTTLE(getLogger(), *clock_, 5000, message); - }; - - if (module_type_->specialExpiredCheck()) { - log_warn_throttled("expired check."); - if (isWaitingApproval()) { - return ModuleStatus::SUCCESS; - } - } - - if (!isActivated() || isWaitingApproval()) { - log_warn_throttled("Is idling."); - return ModuleStatus::IDLE; - } - - if (!module_type_->isValidPath()) { - log_warn_throttled("Is invalid path."); - return ModuleStatus::SUCCESS; - } - - if (module_type_->isAbortState()) { - log_warn_throttled("Ego is in the process of aborting lane change."); - return module_type_->hasFinishedAbort() ? ModuleStatus::SUCCESS : ModuleStatus::RUNNING; - } - - if (module_type_->hasFinishedLaneChange()) { - log_warn_throttled("Completed lane change."); - return ModuleStatus::SUCCESS; - } - - if (module_type_->isEgoOnPreparePhase() && module_type_->isStoppedAtRedTrafficLight()) { - RCLCPP_WARN_STREAM_THROTTLE( - getLogger(), *clock_, 5000, "Ego stopped at traffic light. Canceling lane change"); - module_type_->toCancelState(); - return isWaitingApproval() ? ModuleStatus::RUNNING : ModuleStatus::SUCCESS; - } - - const auto [is_safe, is_object_coming_from_rear] = module_type_->isApprovedPathSafe(); - - setObjectDebugVisualization(); - if (is_safe) { - log_warn_throttled("Lane change path is safe."); - module_type_->toNormalState(); - return ModuleStatus::RUNNING; - } - - const auto change_state_if_stop_required = [&]() -> void { - if (module_type_->isRequiredStop(is_object_coming_from_rear)) { - module_type_->toStopState(); - } else { - module_type_->toNormalState(); - } - }; - - if (!module_type_->isCancelEnabled()) { - log_warn_throttled( - "Lane change path is unsafe but cancel was not enabled. Continue lane change."); - change_state_if_stop_required(); - return ModuleStatus::RUNNING; - } - - if (!module_type_->isAbleToReturnCurrentLane()) { - log_warn_throttled("Lane change path is unsafe but cannot return. Continue lane change."); - change_state_if_stop_required(); - return ModuleStatus::RUNNING; - } - - const auto threshold = module_type_->getLaneChangeParam().backward_length_buffer_for_end_of_lane; - const auto status = module_type_->getLaneChangeStatus(); - if (module_type_->isNearEndOfCurrentLanes(status.current_lanes, status.target_lanes, threshold)) { - log_warn_throttled("Lane change path is unsafe but near end of lane. Continue lane change."); - change_state_if_stop_required(); - return ModuleStatus::RUNNING; - } - - if (module_type_->isEgoOnPreparePhase() && module_type_->isAbleToReturnCurrentLane()) { - log_warn_throttled("Lane change path is unsafe. Cancel lane change."); - module_type_->toCancelState(); - return isWaitingApproval() ? ModuleStatus::RUNNING : ModuleStatus::SUCCESS; - } - - if (!module_type_->isAbortEnabled()) { - log_warn_throttled( - "Lane change path is unsafe but abort was not enabled. Continue lane change."); - change_state_if_stop_required(); - return ModuleStatus::RUNNING; - } - - const auto found_abort_path = module_type_->calcAbortPath(); - if (!found_abort_path) { - log_warn_throttled( - "Lane change path is unsafe but not found abort path. Continue lane change."); - change_state_if_stop_required(); - return ModuleStatus::RUNNING; - } - - log_warn_throttled("Lane change path is unsafe. Abort lane change."); - module_type_->toAbortState(); - return ModuleStatus::RUNNING; -} - void LaneChangeInterface::updateData() { module_type_->setPreviousModulePaths( @@ -188,6 +84,11 @@ void LaneChangeInterface::updateData() module_type_->resetStopPose(); } +void LaneChangeInterface::postProcess() +{ + post_process_safety_status_ = module_type_->isApprovedPathSafe(); +} + BehaviorModuleOutput LaneChangeInterface::plan() { resetPathCandidate(); @@ -286,6 +187,130 @@ void LaneChangeInterface::setData(const std::shared_ptr & dat module_type_->setData(data); } +bool LaneChangeInterface::canTransitSuccessState() +{ + auto log_debug_throttled = [&](std::string_view message) -> void { + RCLCPP_WARN(getLogger(), "%s", message.data()); + }; + + if (module_type_->specialExpiredCheck() && isWaitingApproval()) { + log_debug_throttled("Run specialExpiredCheck."); + if (isWaitingApproval()) { + return true; + } + } + + if (!module_type_->isValidPath()) { + log_debug_throttled("Has no valid path."); + return true; + } + + if (module_type_->isAbortState() && module_type_->hasFinishedAbort()) { + log_debug_throttled("Abort process has completed."); + return true; + } + + if (module_type_->hasFinishedLaneChange()) { + log_debug_throttled("Lane change process has completed."); + return true; + } + + log_debug_throttled("Lane changing process is ongoing"); + return false; +} + +bool LaneChangeInterface::canTransitFailureState() +{ + auto log_debug_throttled = [&](std::string_view message) -> void { + RCLCPP_WARN(getLogger(), "%s", message.data()); + }; + + log_debug_throttled(__func__); + + if (module_type_->isAbortState() && !module_type_->hasFinishedAbort()) { + log_debug_throttled("Abort process has on going."); + return false; + } + + if (isWaitingApproval()) { + log_debug_throttled("Can't transit to failure state. Module is WAITING_FOR_APPROVAL"); + return false; + } + + if (module_type_->isCancelEnabled() && module_type_->isEgoOnPreparePhase()) { + if (module_type_->isStoppedAtRedTrafficLight()) { + log_debug_throttled("Stopping at traffic light while in prepare phase. Cancel lane change"); + module_type_->toCancelState(); + return true; + } + + if (post_process_safety_status_.is_safe) { + log_debug_throttled("Can't transit to failure state. Ego is on prepare, and it's safe."); + return false; + } + + if (module_type_->isAbleToReturnCurrentLane()) { + log_debug_throttled("It's possible to return to current lane. Cancel lane change."); + return true; + } + } + + if (post_process_safety_status_.is_safe) { + log_debug_throttled("Can't transit to failure state. Ego is lane changing, and it's safe."); + return false; + } + + if (module_type_->isRequiredStop(post_process_safety_status_.is_object_coming_from_rear)) { + log_debug_throttled("Module require stopping"); + } + + if (!module_type_->isCancelEnabled()) { + log_debug_throttled( + "Lane change path is unsafe but cancel was not enabled. Continue lane change."); + return false; + } + + if (!module_type_->isAbortEnabled()) { + log_debug_throttled( + "Lane change path is unsafe but abort was not enabled. Continue lane change."); + return false; + } + + const auto found_abort_path = module_type_->calcAbortPath(); + if (!found_abort_path) { + log_debug_throttled( + "Lane change path is unsafe but abort path not found. Continue lane change."); + return false; + } + + log_debug_throttled("Lane change path is unsafe. Abort lane change."); + module_type_->toAbortState(); + return false; +} + +bool LaneChangeInterface::canTransitIdleToRunningState() +{ + setObjectDebugVisualization(); + + auto log_debug_throttled = [&](std::string_view message) -> void { + RCLCPP_WARN(getLogger(), "%s", message.data()); + }; + + log_debug_throttled(__func__); + + if (!isActivated() || isWaitingApproval()) { + if (module_type_->specialRequiredCheck()) { + return true; + } + log_debug_throttled("Module is idling."); + return false; + } + + log_debug_throttled("Can lane change safely. Executing lane change."); + module_type_->toNormalState(); + return true; +} + void LaneChangeInterface::setObjectDebugVisualization() const { debug_marker_.markers.clear(); diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index f0972d66416c8..c7ddd8fe63636 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -1526,11 +1526,17 @@ bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const return true; } -bool NormalLaneChange::isRequiredStop(const bool is_object_coming_from_rear) const +bool NormalLaneChange::isRequiredStop(const bool is_object_coming_from_rear) { const auto threshold = lane_change_parameters_->backward_length_buffer_for_end_of_lane; - return isNearEndOfCurrentLanes(status_.current_lanes, status_.target_lanes, threshold) && - isAbleToStopSafely() && is_object_coming_from_rear; + if ( + isNearEndOfCurrentLanes(status_.current_lanes, status_.target_lanes, threshold) && + isAbleToStopSafely() && is_object_coming_from_rear) { + current_lane_change_state_ = LaneChangeStates::Stop; + return true; + } + current_lane_change_state_ = LaneChangeStates::Normal; + return false; } bool NormalLaneChange::calcAbortPath() diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index c27c513832fa8..82002ead9a2d1 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -449,54 +449,70 @@ class SceneModuleInterface */ virtual ModuleStatus updateState() { + auto log_debug_throttled = [&](std::string_view message) -> void { + RCLCPP_WARN(getLogger(), "%s", message.data()); + }; if (current_state_ == ModuleStatus::IDLE) { if (canTransitIdleToRunningState()) { + log_debug_throttled("transiting from IDLE to RUNNING"); return ModuleStatus::RUNNING; } + log_debug_throttled("transiting from IDLE to IDLE"); return ModuleStatus::IDLE; } if (current_state_ == ModuleStatus::RUNNING) { if (canTransitSuccessState()) { + log_debug_throttled("transiting from RUNNING to SUCCESS"); return ModuleStatus::SUCCESS; } if (canTransitFailureState()) { + log_debug_throttled("transiting from RUNNING to FAILURE"); return ModuleStatus::FAILURE; } if (canTransitWaitingApprovalState()) { + log_debug_throttled("transiting from RUNNING to WAITING_APPROVAL"); return ModuleStatus::WAITING_APPROVAL; } + log_debug_throttled("transiting from RUNNING to RUNNING"); return ModuleStatus::RUNNING; } if (current_state_ == ModuleStatus::WAITING_APPROVAL) { if (canTransitSuccessState()) { + log_debug_throttled("transiting from WAITING_APPROVAL to SUCCESS"); return ModuleStatus::SUCCESS; } if (canTransitFailureState()) { + log_debug_throttled("transiting from WAITING_APPROVAL to FAILURE"); return ModuleStatus::FAILURE; } if (canTransitWaitingApprovalToRunningState()) { + log_debug_throttled("transiting from WAITING_APPROVAL to RUNNING"); return ModuleStatus::RUNNING; } + log_debug_throttled("transiting from WAITING_APPROVAL to WAITING APPROVAL"); return ModuleStatus::WAITING_APPROVAL; } if (current_state_ == ModuleStatus::SUCCESS) { + log_debug_throttled("already SUCCESS"); return ModuleStatus::SUCCESS; } if (current_state_ == ModuleStatus::FAILURE) { + log_debug_throttled("already FAILURE"); return ModuleStatus::FAILURE; } + log_debug_throttled("already IDLE"); return ModuleStatus::IDLE; } From 2b0094f97683e6ad880255ba61f1f7f3ca12e02a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 26 Dec 2023 19:55:43 +0900 Subject: [PATCH 146/276] refactor(behavior_path_planner): remove maximum drivable area visualization (#5963) Signed-off-by: Muhammad Zulfaqar Azmi --- .../config/behavior_path_planner.param.yaml | 2 - .../behavior_path_planner_node.hpp | 1 - .../src/behavior_path_planner_node.cpp | 12 --- .../marker_utils/utils.hpp | 2 - .../parameters.hpp | 3 - .../static_drivable_area.hpp | 3 - .../src/marker_utils/utils.cpp | 84 ------------------- .../static_drivable_area.cpp | 28 ------- 8 files changed, 135 deletions(-) diff --git a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml index b4d323de45cde..0c5dbc082c9b9 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -25,8 +25,6 @@ input_path_interval: 2.0 output_path_interval: 2.0 - visualize_maximum_drivable_area: true - lane_following: drivable_area_right_bound_offset: 0.0 drivable_area_left_bound_offset: 0.0 diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index c47dc70213d1a..5d40f2a8614ed 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -166,7 +166,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node const BehaviorModuleOutput & output); // debug - rclcpp::Publisher::SharedPtr debug_maximum_drivable_area_publisher_; rclcpp::Publisher::SharedPtr debug_avoidance_msg_array_publisher_; rclcpp::Publisher::SharedPtr debug_turn_signal_info_publisher_; diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 93747fc6e9aa3..9fd397bb8a8b1 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -73,11 +73,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod debug_avoidance_msg_array_publisher_ = create_publisher("~/debug/avoidance_debug_message_array", 1); - if (planner_data_->parameters.visualize_maximum_drivable_area) { - debug_maximum_drivable_area_publisher_ = - create_publisher("~/maximum_drivable_area", 1); - } - debug_turn_signal_info_publisher_ = create_publisher("~/debug/turn_signal_info", 1); bound_publisher_ = create_publisher("~/debug/bound", 1); @@ -264,7 +259,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() 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.visualize_maximum_drivable_area = declare_parameter("visualize_maximum_drivable_area"); p.ego_nearest_dist_threshold = declare_parameter("ego_nearest_dist_threshold"); p.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); @@ -447,12 +441,6 @@ void BehaviorPathPlannerNode::run() planner_data_->prev_route_id = planner_data_->route_handler->getRouteUuid(); - if (planner_data_->parameters.visualize_maximum_drivable_area) { - const auto maximum_drivable_area = marker_utils::createFurthestLineStringMarkerArray( - utils::getMaximumDrivableArea(planner_data_)); - debug_maximum_drivable_area_publisher_->publish(maximum_drivable_area); - } - lk_pd.unlock(); // release planner_data_ planner_manager_->print(); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp index cfaa8de9b2fb9..1ce3dd3736276 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp @@ -81,8 +81,6 @@ MarkerArray createLaneletsAreaMarkerArray( const std::vector & lanelets, std::string && ns, const float & r, const float & g, const float & b); -MarkerArray createFurthestLineStringMarkerArray(const lanelet::ConstLineStrings3d & linestrings); - MarkerArray createPolygonMarkerArray( const Polygon & polygon, std::string && ns, const int64_t & lane_id, const float & r, const float & g, const float & b, const float & w = 0.3); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp index acda01dfc603c..811c89f61c066 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp @@ -76,9 +76,6 @@ struct BehaviorPathPlannerParameters double right_over_hang; double base_link2front; double base_link2rear; - - // maximum drivable area visualization - bool visualize_maximum_drivable_area; }; #endif // BEHAVIOR_PATH_PLANNER_COMMON__PARAMETERS_HPP_ diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp index 284b4aad20a6a..9053da45708a0 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp @@ -47,9 +47,6 @@ void generateDrivableArea( PathWithLaneId & path, const double vehicle_length, const double offset, const bool is_driving_forward = true); -lanelet::ConstLineStrings3d getMaximumDrivableArea( - const std::shared_ptr & planner_data); - /** * @brief Expand the borders of the given lanelets * @param [in] drivable_lanes lanelets to expand diff --git a/planning/behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/behavior_path_planner_common/src/marker_utils/utils.cpp index ec182ae5b909a..9e20b9c3f8714 100644 --- a/planning/behavior_path_planner_common/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/marker_utils/utils.cpp @@ -236,90 +236,6 @@ MarkerArray createLaneletsAreaMarkerArray( return msg; } -MarkerArray createFurthestLineStringMarkerArray(const lanelet::ConstLineStrings3d & linestrings) -{ - if (linestrings.empty()) { - return MarkerArray(); - } - - Marker marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "shared_linestring_lanelets", 0L, Marker::LINE_STRIP, - createMarkerScale(0.3, 0.0, 0.0), createMarkerColor(0.996, 0.658, 0.466, 0.999)); - marker.pose.orientation = tier4_autoware_utils::createMarkerOrientation(0, 0, 0, 1.0); - - const auto reserve_size = linestrings.size() / 2; - lanelet::ConstLineStrings3d lefts; - lanelet::ConstLineStrings3d rights; - lefts.reserve(reserve_size); - rights.reserve(reserve_size); - - size_t total_marker_reserve_size{0}; - for (size_t idx = 1; idx < linestrings.size(); idx += 2) { - rights.emplace_back(linestrings.at(idx - 1)); - lefts.emplace_back(linestrings.at(idx)); - - for (const auto & ls : linestrings.at(idx - 1).basicLineString()) { - total_marker_reserve_size += ls.size(); - } - for (const auto & ls : linestrings.at(idx).basicLineString()) { - total_marker_reserve_size += ls.size(); - } - } - - if (!total_marker_reserve_size) { - marker.points.reserve(total_marker_reserve_size); - } - - const auto & first_ls = lefts.front().basicLineString(); - for (const auto & ls : first_ls) { - marker.points.push_back(createPoint(ls.x(), ls.y(), ls.z())); - } - - for (auto idx = lefts.cbegin() + 1; idx != lefts.cend(); ++idx) { - Point front = createPoint( - idx->basicLineString().front().x(), idx->basicLineString().front().y(), - idx->basicLineString().front().z()); - Point front_inverted = createPoint( - idx->invert().basicLineString().front().x(), idx->invert().basicLineString().front().y(), - idx->invert().basicLineString().front().z()); - - const auto & marker_back = marker.points.back(); - const bool isFrontNear = tier4_autoware_utils::calcDistance2d(marker_back, front) < - tier4_autoware_utils::calcDistance2d(marker_back, front_inverted); - const auto & left_ls = (isFrontNear) ? idx->basicLineString() : idx->invert().basicLineString(); - for (const auto & left_l : left_ls) { - marker.points.push_back(createPoint(left_l.x(), left_l.y(), left_l.z())); - } - } - - for (auto idx = rights.crbegin(); idx != rights.crend(); ++idx) { - Point front = createPoint( - idx->basicLineString().front().x(), idx->basicLineString().front().y(), - idx->basicLineString().front().z()); - Point front_inverted = createPoint( - idx->invert().basicLineString().front().x(), idx->invert().basicLineString().front().y(), - idx->invert().basicLineString().front().z()); - - const auto & marker_back = marker.points.back(); - const bool isFrontFurther = tier4_autoware_utils::calcDistance2d(marker_back, front) > - tier4_autoware_utils::calcDistance2d(marker_back, front_inverted); - const auto & right_ls = - (isFrontFurther) ? idx->basicLineString() : idx->invert().basicLineString(); - for (auto ls = right_ls.crbegin(); ls != right_ls.crend(); ++ls) { - marker.points.push_back(createPoint(ls->x(), ls->y(), ls->z())); - } - } - - if (!marker.points.empty()) { - marker.points.push_back(marker.points.front()); - } - - MarkerArray msg; - - msg.markers.push_back(marker); - return msg; -} - MarkerArray createPolygonMarkerArray( const Polygon & polygon, std::string && ns, const int64_t & lane_id, const float & r, const float & g, const float & b, const float & w) diff --git a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 1d33190692d1a..ec147a7bb2771 100644 --- a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -1017,34 +1017,6 @@ void generateDrivableArea( path.right_bound = modified_right_bound; } -// TODO(Azu) Some parts of is the same with generateCenterLinePath. Therefore it might be better if -// we can refactor some of the code for better readability -lanelet::ConstLineStrings3d getMaximumDrivableArea( - const std::shared_ptr & planner_data) -{ - const auto & p = planner_data->parameters; - const auto & route_handler = planner_data->route_handler; - const auto & ego_pose = planner_data->self_odometry->pose.pose; - - lanelet::ConstLanelet current_lane; - if (!route_handler->getClosestLaneletWithinRoute(ego_pose, ¤t_lane)) { - RCLCPP_ERROR( - rclcpp::get_logger("behavior_path_planner").get_child("utils"), - "failed to find closest lanelet within route!!!"); - return {}; - } - - const auto current_lanes = route_handler->getLaneletSequence( - current_lane, ego_pose, p.backward_path_length, p.forward_path_length); - lanelet::ConstLineStrings3d linestring_shared; - for (const auto & lane : current_lanes) { - lanelet::ConstLineStrings3d furthest_line = route_handler->getFurthestLinestring(lane); - linestring_shared.insert(linestring_shared.end(), furthest_line.begin(), furthest_line.end()); - } - - return linestring_shared; -} - std::vector expandLanelets( const std::vector & drivable_lanes, const double left_bound_offset, const double right_bound_offset, const std::vector & types_to_skip) From acfd5ce96236c9fdb3fcee0ec048dd929b68028a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 26 Dec 2023 21:42:26 +0900 Subject: [PATCH 147/276] docs(bpp): separate behavior path planner documents (#5961) * docs(bpp): separate avoidance document Signed-off-by: satoshi-ota * docs(bpp): separate ablc document Signed-off-by: satoshi-ota * docs(bpp): separate side shift document Signed-off-by: satoshi-ota * docs(bpp): separate goal planner document Signed-off-by: satoshi-ota * docs(bpp): separate start planner document Signed-off-by: satoshi-ota * docs(bpp): fix invalid link Signed-off-by: satoshi-ota * docs(bpp): move docs Signed-off-by: satoshi-ota * docs(bpp): remove unused images Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- planning/.pages | 18 +++--- .../README.md} | 8 +-- .../images}/avoidance_by_lane_change.svg | 0 .../images}/avoidance_by_lc_trigger_1.svg | 0 .../images}/avoidance_by_lc_trigger_2.svg | 0 .../README.md} | 52 +++++++++--------- .../images}/avoidance-debug-marker.png | Bin .../images}/avoidance_debug_message_array.png | Bin .../images}/avoidance_design.fig1.drawio.svg | 0 ...shift_point_and_its_constraints.drawio.png | Bin .../images}/dynamic_lateral_margin.svg | 0 .../images}/envelope_polygon.svg | 0 ...ape_multi_object_both_direction.drawio.svg | 0 ...hape_multi_object_one_direction.drawio.svg | 0 ...to_decide_path_shape_one_object.drawio.svg | 0 .../images}/intersection_problem.drawio.svg | 0 ...tacle_to_road_shoulder_distance.drawio.svg | 0 .../images}/parked-car-detection.svg | 0 .../images}/safety_check_flowchart.svg | 0 .../images}/safety_check_margin.svg | 0 .../images}/safety_check_step_1.svg | 0 .../images}/safety_check_step_2.svg | 0 .../shift_length_parameters.drawio.svg | 0 .../images}/shift_line_generation.svg | 0 .../images}/target_vehicle_selection.svg | 0 .../images}/todo.png | Bin .../images}/use_adjacent_lane.svg | 0 .../images}/use_hatched_road_markings.svg | 0 .../images}/use_intersection_areas.svg | 0 .../images}/use_opposite_lane.svg | 0 .../images}/yield_limitation.svg | 0 .../images}/yield_maneuver.svg | 0 .../images}/yield_maneuver_flowchart.svg | 0 .../README.md} | 14 ++--- .../images}/arc_backward_parking.drawio.svg | 0 .../images}/arc_forward_parking.drawio.svg | 0 .../images}/path_goal_refinement.drawio.svg | 0 ...ver_freespace_parking_flowchart.drawio.svg | 0 .../images}/shift_parking.drawio.svg | 0 .../README.md | 4 +- planning/behavior_path_planner/README.md | 30 +++++----- .../image/avoid_fig_multi_case.png | Bin 93144 -> 0 bytes .../image/avoid_fig_single_case.png | Bin 59688 -> 0 bytes .../image/drivable_area_plugin.png | Bin 156302 -> 0 bytes .../image/lane_change_fig1.png | Bin 40773 -> 0 bytes .../image/lane_change_fig2.png | Bin 74366 -> 0 bytes .../image/lane_change_fig3.png | Bin 37153 -> 0 bytes .../image/minimum_lane_change_distance.png | Bin 85266 -> 0 bytes .../image/path_shifter_old.png | Bin 91428 -> 0 bytes .../image/shift_length_computation.png | Bin 113434 -> 0 bytes .../image/side_shift_fig1.png | Bin 25998 -> 0 bytes ...avior_path_planner_drivable_area_design.md | 30 +++++----- ...ior_path_planner_path_generation_design.md | 4 +- .../behavior_path_planner_safety_check.md | 6 +- ...ehavior_path_planner_turn_signal_design.md | 34 ++++++------ ...ynamicDrivableArea-ExpDistances.drawio.svg | 0 .../DynamicDrivableArea-Expansion.drawio.svg | 0 ...micDrivableArea-Expansion_Input.drawio.svg | 0 .../DynamicDrivableArea-MaxWidth.drawio.svg | 0 .../DynamicDrivableArea-MinWidth.drawio.svg | 0 .../DynamicDrivableArea-Result.drawio.svg | 0 ...drivable_area_boundary_marker_example1.png | Bin ...drivable_area_boundary_marker_example2.png | Bin .../drivable_area/drivable_lines.drawio.svg | 0 .../drivable_area/dynamic_expansion_off.png | Bin .../drivable_area/dynamic_expansion_on.png | Bin .../drivable_area/expanded_lanes.drawio.svg | 0 ...arkings_drivable_area_expansion.drawio.svg | 0 .../drivable_area/sorted_lanes.drawio.svg | 0 .../extended_polygons.drawio.svg | 0 .../front_object.drawio.svg | 0 .../safety_check_flow.drawio.svg | 0 .../images/path_shifter}/path_shifter.png | Bin .../activation_distance.drawio.svg | 0 .../avoidance_and_turn.drawio.svg | 0 .../avoidance_and_turn2.drawio.svg | 0 .../avoidance_first_section.drawio.svg | 0 .../avoidance_second_section.drawio.svg | 0 .../continuous_turns.drawio.svg | 0 .../lane_change.drawio.svg | 0 .../lane_change_and_turn.drawio.svg | 0 .../left_right_turn.drawio.svg | 0 .../turn_signal_decider/pattern1.drawio.svg | 0 .../turn_signal_decider/pattern2.drawio.svg | 0 .../turn_signal_decider/pattern3.drawio.svg | 0 .../turn_signal_decider/pattern4.drawio.svg | 0 .../turn_signal_decider/pattern5.drawio.svg | 0 .../turn_signal_decider/pull_out.drawio.svg | 0 .../turn_signal_decider/pull_over.drawio.svg | 0 .../sections_definition.drawio.svg | 0 .../README.md} | 0 .../README.md} | 22 ++++---- .../images}/collision_check_range.drawio.svg | 0 .../images}/geometric_pull_out.drawio.svg | 0 .../images}/pull_out_after_back.drawio.svg | 0 .../pull_out_collision_check.drawio.svg | 0 .../images}/shift_pull_out.drawio.svg | 0 .../images}/start_from_road_lane.drawio.svg | 0 .../start_from_road_shoulder.drawio.svg | 0 .../images}/start_from_road_side.drawio.svg | 0 100 files changed, 111 insertions(+), 111 deletions(-) rename planning/{behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design.md => behavior_path_avoidance_by_lane_change_module/README.md} (86%) rename planning/{behavior_path_planner/image/avoidance_by_lane_change => behavior_path_avoidance_by_lane_change_module/images}/avoidance_by_lane_change.svg (100%) rename planning/{behavior_path_planner/image/avoidance_by_lane_change => behavior_path_avoidance_by_lane_change_module/images}/avoidance_by_lc_trigger_1.svg (100%) rename planning/{behavior_path_planner/image/avoidance_by_lane_change => behavior_path_avoidance_by_lane_change_module/images}/avoidance_by_lc_trigger_2.svg (100%) rename planning/{behavior_path_planner/docs/behavior_path_planner_avoidance_design.md => behavior_path_avoidance_module/README.md} (97%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/avoidance-debug-marker.png (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/avoidance_debug_message_array.png (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/avoidance_design.fig1.drawio.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/avoidance_module-shift_point_and_its_constraints.drawio.png (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/dynamic_lateral_margin.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/envelope_polygon.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/how_to_decide_path_shape_multi_object_both_direction.drawio.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/how_to_decide_path_shape_multi_object_one_direction.drawio.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/how_to_decide_path_shape_one_object.drawio.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/intersection_problem.drawio.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/obstacle_to_road_shoulder_distance.drawio.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/parked-car-detection.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/safety_check_flowchart.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/safety_check_margin.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/safety_check_step_1.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/safety_check_step_2.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_avoidance_module/images}/shift_length_parameters.drawio.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/shift_line_generation.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/target_vehicle_selection.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/todo.png (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/use_adjacent_lane.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/use_hatched_road_markings.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/use_intersection_areas.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/use_opposite_lane.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/yield_limitation.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/yield_maneuver.svg (100%) rename planning/{behavior_path_planner/image/avoidance => behavior_path_avoidance_module/images}/yield_maneuver_flowchart.svg (100%) rename planning/{behavior_path_planner/docs/behavior_path_planner_goal_planner_design.md => behavior_path_goal_planner_module/README.md} (97%) rename planning/{behavior_path_planner/image => behavior_path_goal_planner_module/images}/arc_backward_parking.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_goal_planner_module/images}/arc_forward_parking.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_goal_planner_module/images}/path_goal_refinement.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_goal_planner_module/images}/pull_over_freespace_parking_flowchart.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_goal_planner_module/images}/shift_parking.drawio.svg (100%) delete mode 100644 planning/behavior_path_planner/image/avoid_fig_multi_case.png delete mode 100644 planning/behavior_path_planner/image/avoid_fig_single_case.png delete mode 100644 planning/behavior_path_planner/image/drivable_area_plugin.png delete mode 100644 planning/behavior_path_planner/image/lane_change_fig1.png delete mode 100644 planning/behavior_path_planner/image/lane_change_fig2.png delete mode 100644 planning/behavior_path_planner/image/lane_change_fig3.png delete mode 100644 planning/behavior_path_planner/image/minimum_lane_change_distance.png delete mode 100644 planning/behavior_path_planner/image/path_shifter_old.png delete mode 100644 planning/behavior_path_planner/image/shift_length_computation.png delete mode 100644 planning/behavior_path_planner/image/side_shift_fig1.png rename planning/{behavior_path_planner => behavior_path_planner_common}/docs/behavior_path_planner_drivable_area_design.md (90%) rename planning/{behavior_path_planner => behavior_path_planner_common}/docs/behavior_path_planner_path_generation_design.md (97%) rename planning/{behavior_path_planner => behavior_path_planner_common}/docs/behavior_path_planner_safety_check.md (93%) rename planning/{behavior_path_planner => behavior_path_planner_common}/docs/behavior_path_planner_turn_signal_design.md (86%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/DynamicDrivableArea-ExpDistances.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/DynamicDrivableArea-Expansion.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/DynamicDrivableArea-Expansion_Input.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/DynamicDrivableArea-MaxWidth.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/DynamicDrivableArea-MinWidth.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/DynamicDrivableArea-Result.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/drivable_area_boundary_marker_example1.png (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/drivable_area_boundary_marker_example2.png (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/drivable_lines.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/dynamic_expansion_off.png (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/dynamic_expansion_on.png (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/expanded_lanes.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/hatched_road_markings_drivable_area_expansion.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/drivable_area/sorted_lanes.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/path_safety_checker/extended_polygons.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/path_safety_checker/front_object.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/path_safety_checker/safety_check_flow.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images/path_shifter}/path_shifter.png (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/activation_distance.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/avoidance_and_turn.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/avoidance_and_turn2.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/avoidance_first_section.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/avoidance_second_section.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/continuous_turns.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/lane_change.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/lane_change_and_turn.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/left_right_turn.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/pattern1.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/pattern2.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/pattern3.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/pattern4.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/pattern5.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/pull_out.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/pull_over.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_planner_common/images}/turn_signal_decider/sections_definition.drawio.svg (100%) rename planning/{behavior_path_planner/docs/behavior_path_planner_side_shift_design.md => behavior_path_side_shift_module/README.md} (100%) rename planning/{behavior_path_planner/docs/behavior_path_planner_start_planner_design.md => behavior_path_start_planner_module/README.md} (96%) rename planning/{behavior_path_planner/image/start_planner => behavior_path_start_planner_module/images}/collision_check_range.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_start_planner_module/images}/geometric_pull_out.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_start_planner_module/images}/pull_out_after_back.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_start_planner_module/images}/pull_out_collision_check.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_start_planner_module/images}/shift_pull_out.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_start_planner_module/images}/start_from_road_lane.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_start_planner_module/images}/start_from_road_shoulder.drawio.svg (100%) rename planning/{behavior_path_planner/image => behavior_path_start_planner_module/images}/start_from_road_side.drawio.svg (100%) diff --git a/planning/.pages b/planning/.pages index 6ae8abe240d9b..c41a1cc8c6603 100644 --- a/planning/.pages +++ b/planning/.pages @@ -5,18 +5,18 @@ nav: - 'Concept': - 'Planner Manager': planning/behavior_path_planner/docs/behavior_path_planner_manager_design - 'Scene Module Interface': planning/behavior_path_planner/docs/behavior_path_planner_interface_design - - 'Path Generation': planning/behavior_path_planner/docs/behavior_path_planner_path_generation_design - - 'Collision Assessment/Safety Check': planning/behavior_path_planner/docs/behavior_path_planner_safety_check - - 'Dynamic Drivable Area': planning/behavior_path_planner/docs/behavior_path_planner_drivable_area_design - - 'Turn Signal': planning/behavior_path_planner/docs/behavior_path_planner_turn_signal_design + - 'Path Generation': planning/behavior_path_planner_common/docs/behavior_path_planner_path_generation_design + - 'Collision Assessment/Safety Check': planning/behavior_path_planner_common/docs/behavior_path_planner_safety_check + - 'Dynamic Drivable Area': planning/behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design + - 'Turn Signal': planning/behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design - 'Scene Module': - - 'Avoidance': planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design - - 'Avoidance by Lane Change': planning/behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design + - 'Avoidance': planning/behavior_path_avoidance_module + - 'Avoidance by Lane Change': planning/behavior_path_avoidance_by_lane_change_module - 'Dynamic Avoidance': planning/behavior_path_planner/docs/behavior_path_planner_dynamic_avoidance_design - - 'Goal Planner': planning/behavior_path_planner/docs/behavior_path_planner_goal_planner_design + - 'Goal Planner': planning/behavior_path_goal_planner_module - 'Lane Change': planning/behavior_path_lane_change_module - - 'Side Shift': planning/behavior_path_planner/docs/behavior_path_planner_side_shift_design - - 'Start Planner': planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design + - 'Side Shift': planning/behavior_path_side_shift_module + - 'Start Planner': planning/behavior_path_start_planner_module - 'Behavior Velocity Planner': - 'About Behavior Velocity': planning/behavior_velocity_planner - 'Template for Custom Module': planning/behavior_velocity_template_module diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design.md b/planning/behavior_path_avoidance_by_lane_change_module/README.md similarity index 86% rename from planning/behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design.md rename to planning/behavior_path_avoidance_by_lane_change_module/README.md index 2c91cc43995ac..d91d7116ee056 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design.md +++ b/planning/behavior_path_avoidance_by_lane_change_module/README.md @@ -9,11 +9,11 @@ This module is designed as one of the obstacle avoidance features and generates - Exist lane changeable lanelet. - Exist avoidance target objects on ego driving lane. -![avoidance_by_lane_change](../image/avoidance_by_lane_change/avoidance_by_lane_change.svg) +![avoidance_by_lane_change](./images/avoidance_by_lane_change.svg) ## Inner-workings / Algorithms -Basically, this module is implemented by reusing the avoidance target filtering logic of the existing [Normal Avoidance Module](./behavior_path_planner_avoidance_design.md) and the path generation logic of the [Normal Lane Change Module](./behavior_path_planner_lane_change_design.md). On the other hand, the conditions under which the module is activated differ from those of a normal avoidance module. +Basically, this module is implemented by reusing the avoidance target filtering logic of the existing [Normal Avoidance Module](../behavior_path_avoidance_module/README.md) and the path generation logic of the [Normal Lane Change Module](../behavior_path_lane_change_module/README.md). On the other hand, the conditions under which the module is activated differ from those of a normal avoidance module. Check that the following conditions are satisfied after the filtering process for the avoidance target. @@ -21,7 +21,7 @@ Check that the following conditions are satisfied after the filtering process fo This module is launched when the number of avoidance target objects on **EGO DRIVING LANE** is greater than `execute_object_num`. If there are no avoidance targets in the ego driving lane or their number is less than the parameter, the obstacle is avoided by normal avoidance behavior (if the normal avoidance module is registered). -![trigger_1](../image/avoidance_by_lane_change/avoidance_by_lc_trigger_1.svg) +![trigger_1](./images/avoidance_by_lc_trigger_1.svg) ### Lane change end point condition @@ -29,7 +29,7 @@ Unlike the normal avoidance module, which specifies the shift line end point, th Although setting the parameter to `false` would increase the scene of avoidance by lane change, it is assumed that sufficient lateral margin may not be ensured in some cases because the vehicle passes by the side of obstacles during the lane change. -![trigger_2](../image/avoidance_by_lane_change/avoidance_by_lc_trigger_2.svg) +![trigger_2](./images/avoidance_by_lc_trigger_2.svg) ## Parameters diff --git a/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lane_change.svg b/planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lane_change.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lane_change.svg rename to planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lane_change.svg diff --git a/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_1.svg b/planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_1.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_1.svg rename to planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_1.svg diff --git a/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_2.svg b/planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_2.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_2.svg rename to planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_2.svg diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md b/planning/behavior_path_avoidance_module/README.md similarity index 97% rename from planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md rename to planning/behavior_path_avoidance_module/README.md index c4580bb1e82c3..20c0985f0f333 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md +++ b/planning/behavior_path_avoidance_module/README.md @@ -20,7 +20,7 @@ This module executes avoidance over lanes, and the decision requires the lane st The following figure shows a simple explanation of the logic for avoidance path generation. First, target objects are picked up, and shift requests are generated for each object. These shift requests are generated by taking into account the lateral jerk required for avoidance (red lines). Then these requests are merged and the shift points are created on the reference path (blue line). Filtering operations are performed on the shift points such as removing unnecessary shift points (yellow line), and finally a smooth avoidance path is generated by combining Clothoid-like curve primitives (green line). -![fig1](../image/avoidance/avoidance_design.fig1.drawio.svg) +![fig1](./images/avoidance_design.fig1.drawio.svg) ### Flowchart @@ -185,7 +185,7 @@ The avoidance target should be limited to stationary objects (you should not avo - This means that the vehicle is parked on the edge of the lane. This prevents the vehicle from avoiding a vehicle waiting at a traffic light in the middle of the lane. However, this is not an appropriate implementation for the purpose. Even if a vehicle is in the center of the lane, it should be avoided if it has its hazard lights on, and this is a point that should be improved in the future as the recognition performance improves. - Object is not behind ego(default: > -`2.0 m`) or too far(default: < `150.0 m`) and object is not behind the path goal. -![fig1](../image/avoidance/target_vehicle_selection.svg) +![fig1](./images/target_vehicle_selection.svg) ### Parked-car detection @@ -203,7 +203,7 @@ $$ The closer the object is to the shoulder, the larger the value of $ratio$ (theoretical max value is 1.0), and it compares the value and `object_check_shiftable_ratio` to determine whether the object is a parked-car. If the road has no road shoulders, it uses `object_check_min_road_shoulder_width` as a road shoulder width virtually. -![fig2](../image/avoidance/parked-car-detection.svg) +![fig2](./images/parked-car-detection.svg) ### Compensation for detection lost @@ -365,9 +365,9 @@ Therefore, in order to reduce the influence of the noise, avoidance module gener object_envelope_buffer: 0.3 # [m] ``` -![fig1](../image/avoidance/envelope_polygon.svg) +![fig1](./images/envelope_polygon.svg) -![fig1](../image/avoidance/shift_line_generation.svg) +![fig1](./images/shift_line_generation.svg) ### Computing Shift Length and Shift Points @@ -388,7 +388,7 @@ else The following figure illustrates these variables(This figure just shows the max value of lateral shift length). -![shift_point_and_its_constraints](../image/avoidance/avoidance_module-shift_point_and_its_constraints.drawio.png) +![shift_point_and_its_constraints](./images/avoidance_module-shift_point_and_its_constraints.drawio.png) ### Rationale of having safety buffer and safety margin @@ -399,7 +399,7 @@ To compute the shift length, additional parameters that can be tune are `lateral - It is recommended to set the value to more than half of the ego vehicle's width. - The `road_shoulder_safety_margin` will prevent the module from generating a path that might cause the vehicle to go too near the road shoulder or adjacent lane dividing line. -![shift_length_parameters](../image/shift_length_parameters.drawio.svg) +![shift_length_parameters](./images/shift_length_parameters.drawio.svg) ### Generating path only within lanelet boundaries @@ -410,7 +410,7 @@ The shift length is set as a constant value before the feature is implemented. S These elements are used to compute the distance from the object to the road's shoulder (`to_road_shoulder_distance`). The parameters `use_adjacent_lane` and `use_opposite_lane` allows further configuration of the to `to_road_shoulder_distance`. The following image illustrates the configuration. -![obstacle_to_road_shoulder_distance](../image/avoidance/obstacle_to_road_shoulder_distance.drawio.svg) +![obstacle_to_road_shoulder_distance](./images/obstacle_to_road_shoulder_distance.drawio.svg) If one of the following conditions is `false`, then the shift point will not be generated. @@ -565,7 +565,7 @@ To solve that, this module provides a parameter for the minimum avoidance speed, - If the ego vehicle speed is lower than "nominal" minimum speed, use the minimum speed in the calculation of the jerk. - If the ego vehicle speed is lower than "sharp" minimum speed and a nominal lateral jerk is not enough for avoidance (the case where the ego vehicle is stopped close to the obstacle), use the "sharp" minimum speed in the calculation of the jerk (it should be lower than "nominal" speed). -![fig1](../image/avoidance/how_to_decide_path_shape_one_object.drawio.svg) +![fig1](./images/how_to_decide_path_shape_one_object.drawio.svg) #### Multiple obstacle case (one direction) @@ -575,13 +575,13 @@ Generate shift points for multiple obstacles. All of them are merged to generate For the details of the shift point filtering, see [filtering for shift points](#filtering-for-shift-points). -![fig1](../image/avoidance/how_to_decide_path_shape_multi_object_one_direction.drawio.svg) +![fig1](./images/how_to_decide_path_shape_multi_object_one_direction.drawio.svg) #### Multiple obstacle case (both direction) Generate shift points for multiple obstacles. All of them are merged to generate new shift points. If there are areas where the desired shifts conflict in different directions, the sum of the maximum shift amounts of these areas is used as the final shift amount. The rest of the process is the same as in the case of one direction. -![fig1](../image/avoidance/how_to_decide_path_shape_multi_object_both_direction.drawio.svg) +![fig1](./images/how_to_decide_path_shape_multi_object_both_direction.drawio.svg) #### Filtering for shift points @@ -608,23 +608,23 @@ use_hatched_road_markings: false #### adjacent lane -![fig1](../image/avoidance/use_adjacent_lane.svg) +![fig1](./images/use_adjacent_lane.svg) #### opposite lane -![fig1](../image/avoidance/use_opposite_lane.svg) +![fig1](./images/use_opposite_lane.svg) #### intersection areas The intersection area is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md) -![fig1](../image/avoidance/use_intersection_areas.svg) +![fig1](./images/use_intersection_areas.svg) #### hatched road markings The hatched road marking is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md#hatched-road-markings-area) -![fig1](../image/avoidance/use_hatched_road_markings.svg) +![fig1](./images/use_hatched_road_markings.svg) ### Safety check @@ -647,11 +647,11 @@ safety_check_backward_distance: 50.0 # [m] safety_check_accel_for_rss: 2.5 # [m/ss] ``` -![fig1](../image/avoidance/safety_check_flowchart.svg) +![fig1](./images/safety_check_flowchart.svg) `safety_check_backward_distance` is the parameter related to the safety check area. The module checks a collision risk for all vehicle that is within shift side lane and between object `object_check_forward_distance` ahead and `safety_check_backward_distance` behind. -![fig1](../image/avoidance/safety_check_step_1.svg) +![fig1](./images/safety_check_step_1.svg) **NOTE**: Even if a part of an object polygon overlaps the detection area, if the center of gravity of the object does not exist on the lane, the vehicle is excluded from the safety check target. @@ -659,11 +659,11 @@ safety_check_accel_for_rss: 2.5 # [m/ss] Judge the risk of collision based on ego future position and object prediction path. The module calculates Ego's future position in the time horizon (`safety_check_time_horizon`), and use object's prediction path as object future position. -![fig1](../image/avoidance/safety_check_step_2.svg) +![fig1](./images/safety_check_step_2.svg) After calculating the future position of Ego and object, the module calculates the lateral/longitudinal deviation of Ego and the object. The module also calculates the lateral/longitudinal margin necessary to determine that it is safe to execute avoidance maneuver, and if both the lateral and longitudinal distances are less than the margins, it determines that there is a risk of a collision at that time. -![fig1](../image/avoidance/safety_check_margin.svg) +![fig1](./images/safety_check_margin.svg) The value of the longitudinal margin is calculated based on Responsibility-Sensitive Safety theory ([RSS](https://newsroom.intel.com/articles/rss-explained-five-rules-autonomous-vehicle-safety/#gs.ljzofv)). The `safety_check_idling_time` represents $T_{idle}$, and `safety_check_accel_for_rss` represents $a_{max}$. @@ -673,7 +673,7 @@ $$ The lateral margin is changeable based on ego longitudinal velocity. If the vehicle is driving at a high speed, the lateral margin should be larger, and if the vehicle is driving at a low speed, the value of the lateral margin should be set to a smaller value. Thus, the lateral margin for each vehicle speed is set as a parameter, and the module determines the lateral margin from the current vehicle speed as shown in the following figure. -![fig1](../image/avoidance/dynamic_lateral_margin.svg) +![fig1](./images/dynamic_lateral_margin.svg) ```yaml target_velocity_matrix: @@ -695,7 +695,7 @@ If an avoidance path can be generated and it is determined that avoidance maneuv yield_velocity: 2.78 # [m/s] ``` -![fig1](../image/avoidance/yield_maneuver.svg) +![fig1](./images/yield_maneuver.svg) **NOTE**: In yield maneuver, the vehicle decelerates target velocity under constraints. @@ -736,9 +736,9 @@ $$ SHIFT_{current} > L_{threshold} $$ -![fig1](../image/avoidance/yield_limitation.svg) +![fig1](./images/yield_limitation.svg) -![fig1](../image/avoidance/yield_maneuver_flowchart.svg) +![fig1](./images/yield_maneuver_flowchart.svg) --- @@ -935,7 +935,7 @@ namespace: `avoidance.constraints.longitudinal.` - **Planning on the intersection** - If it is known that the ego vehicle is going to stop in the middle of avoidance execution (for example, at a red traffic light), sometimes the avoidance should not be executed until the vehicle is ready to move. This is because it is impossible to predict how the environment will change during the stop.  This is especially important at intersections. -![fig1](../image/avoidance/intersection_problem.drawio.svg) +![fig1](./images/intersection_problem.drawio.svg) - **Safety Check** @@ -963,7 +963,7 @@ namespace: `avoidance.constraints.longitudinal.` Developers can see what is going on in each process by visualizing all the avoidance planning process outputs. The example includes target vehicles, shift points for each object, shift points after each filtering process, etc. -![fig1](../image/avoidance/avoidance-debug-marker.png) +![fig1](./images/avoidance-debug-marker.png) To enable the debug marker, execute `ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner avoidance.publish_debug_marker true` (no restart is needed) or simply set the `publish_debug_marker` to `true` in the `avoidance.param.yaml` for permanent effect (restart is needed). Then add the marker `/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance` in `rviz2`. @@ -971,7 +971,7 @@ To enable the debug marker, execute `ros2 param set /planning/scenario_planning/ If for some reason, no shift point is generated for your object, you can check for the failure reason via `ros2 topic echo`. -![avoidance_debug_message_array](../image/avoidance/avoidance_debug_message_array.png) +![avoidance_debug_message_array](./images/avoidance_debug_message_array.png) To print the debug message, just run the following diff --git a/planning/behavior_path_planner/image/avoidance/avoidance-debug-marker.png b/planning/behavior_path_avoidance_module/images/avoidance-debug-marker.png similarity index 100% rename from planning/behavior_path_planner/image/avoidance/avoidance-debug-marker.png rename to planning/behavior_path_avoidance_module/images/avoidance-debug-marker.png diff --git a/planning/behavior_path_planner/image/avoidance/avoidance_debug_message_array.png b/planning/behavior_path_avoidance_module/images/avoidance_debug_message_array.png similarity index 100% rename from planning/behavior_path_planner/image/avoidance/avoidance_debug_message_array.png rename to planning/behavior_path_avoidance_module/images/avoidance_debug_message_array.png diff --git a/planning/behavior_path_planner/image/avoidance/avoidance_design.fig1.drawio.svg b/planning/behavior_path_avoidance_module/images/avoidance_design.fig1.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/avoidance_design.fig1.drawio.svg rename to planning/behavior_path_avoidance_module/images/avoidance_design.fig1.drawio.svg diff --git a/planning/behavior_path_planner/image/avoidance/avoidance_module-shift_point_and_its_constraints.drawio.png b/planning/behavior_path_avoidance_module/images/avoidance_module-shift_point_and_its_constraints.drawio.png similarity index 100% rename from planning/behavior_path_planner/image/avoidance/avoidance_module-shift_point_and_its_constraints.drawio.png rename to planning/behavior_path_avoidance_module/images/avoidance_module-shift_point_and_its_constraints.drawio.png diff --git a/planning/behavior_path_planner/image/avoidance/dynamic_lateral_margin.svg b/planning/behavior_path_avoidance_module/images/dynamic_lateral_margin.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/dynamic_lateral_margin.svg rename to planning/behavior_path_avoidance_module/images/dynamic_lateral_margin.svg diff --git a/planning/behavior_path_planner/image/avoidance/envelope_polygon.svg b/planning/behavior_path_avoidance_module/images/envelope_polygon.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/envelope_polygon.svg rename to planning/behavior_path_avoidance_module/images/envelope_polygon.svg diff --git a/planning/behavior_path_planner/image/avoidance/how_to_decide_path_shape_multi_object_both_direction.drawio.svg b/planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_multi_object_both_direction.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/how_to_decide_path_shape_multi_object_both_direction.drawio.svg rename to planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_multi_object_both_direction.drawio.svg diff --git a/planning/behavior_path_planner/image/avoidance/how_to_decide_path_shape_multi_object_one_direction.drawio.svg b/planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_multi_object_one_direction.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/how_to_decide_path_shape_multi_object_one_direction.drawio.svg rename to planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_multi_object_one_direction.drawio.svg diff --git a/planning/behavior_path_planner/image/avoidance/how_to_decide_path_shape_one_object.drawio.svg b/planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_one_object.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/how_to_decide_path_shape_one_object.drawio.svg rename to planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_one_object.drawio.svg diff --git a/planning/behavior_path_planner/image/avoidance/intersection_problem.drawio.svg b/planning/behavior_path_avoidance_module/images/intersection_problem.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/intersection_problem.drawio.svg rename to planning/behavior_path_avoidance_module/images/intersection_problem.drawio.svg diff --git a/planning/behavior_path_planner/image/avoidance/obstacle_to_road_shoulder_distance.drawio.svg b/planning/behavior_path_avoidance_module/images/obstacle_to_road_shoulder_distance.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/obstacle_to_road_shoulder_distance.drawio.svg rename to planning/behavior_path_avoidance_module/images/obstacle_to_road_shoulder_distance.drawio.svg diff --git a/planning/behavior_path_planner/image/avoidance/parked-car-detection.svg b/planning/behavior_path_avoidance_module/images/parked-car-detection.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/parked-car-detection.svg rename to planning/behavior_path_avoidance_module/images/parked-car-detection.svg diff --git a/planning/behavior_path_planner/image/avoidance/safety_check_flowchart.svg b/planning/behavior_path_avoidance_module/images/safety_check_flowchart.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/safety_check_flowchart.svg rename to planning/behavior_path_avoidance_module/images/safety_check_flowchart.svg diff --git a/planning/behavior_path_planner/image/avoidance/safety_check_margin.svg b/planning/behavior_path_avoidance_module/images/safety_check_margin.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/safety_check_margin.svg rename to planning/behavior_path_avoidance_module/images/safety_check_margin.svg diff --git a/planning/behavior_path_planner/image/avoidance/safety_check_step_1.svg b/planning/behavior_path_avoidance_module/images/safety_check_step_1.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/safety_check_step_1.svg rename to planning/behavior_path_avoidance_module/images/safety_check_step_1.svg diff --git a/planning/behavior_path_planner/image/avoidance/safety_check_step_2.svg b/planning/behavior_path_avoidance_module/images/safety_check_step_2.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/safety_check_step_2.svg rename to planning/behavior_path_avoidance_module/images/safety_check_step_2.svg diff --git a/planning/behavior_path_planner/image/shift_length_parameters.drawio.svg b/planning/behavior_path_avoidance_module/images/shift_length_parameters.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/shift_length_parameters.drawio.svg rename to planning/behavior_path_avoidance_module/images/shift_length_parameters.drawio.svg diff --git a/planning/behavior_path_planner/image/avoidance/shift_line_generation.svg b/planning/behavior_path_avoidance_module/images/shift_line_generation.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/shift_line_generation.svg rename to planning/behavior_path_avoidance_module/images/shift_line_generation.svg diff --git a/planning/behavior_path_planner/image/avoidance/target_vehicle_selection.svg b/planning/behavior_path_avoidance_module/images/target_vehicle_selection.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/target_vehicle_selection.svg rename to planning/behavior_path_avoidance_module/images/target_vehicle_selection.svg diff --git a/planning/behavior_path_planner/image/avoidance/todo.png b/planning/behavior_path_avoidance_module/images/todo.png similarity index 100% rename from planning/behavior_path_planner/image/avoidance/todo.png rename to planning/behavior_path_avoidance_module/images/todo.png diff --git a/planning/behavior_path_planner/image/avoidance/use_adjacent_lane.svg b/planning/behavior_path_avoidance_module/images/use_adjacent_lane.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/use_adjacent_lane.svg rename to planning/behavior_path_avoidance_module/images/use_adjacent_lane.svg diff --git a/planning/behavior_path_planner/image/avoidance/use_hatched_road_markings.svg b/planning/behavior_path_avoidance_module/images/use_hatched_road_markings.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/use_hatched_road_markings.svg rename to planning/behavior_path_avoidance_module/images/use_hatched_road_markings.svg diff --git a/planning/behavior_path_planner/image/avoidance/use_intersection_areas.svg b/planning/behavior_path_avoidance_module/images/use_intersection_areas.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/use_intersection_areas.svg rename to planning/behavior_path_avoidance_module/images/use_intersection_areas.svg diff --git a/planning/behavior_path_planner/image/avoidance/use_opposite_lane.svg b/planning/behavior_path_avoidance_module/images/use_opposite_lane.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/use_opposite_lane.svg rename to planning/behavior_path_avoidance_module/images/use_opposite_lane.svg diff --git a/planning/behavior_path_planner/image/avoidance/yield_limitation.svg b/planning/behavior_path_avoidance_module/images/yield_limitation.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/yield_limitation.svg rename to planning/behavior_path_avoidance_module/images/yield_limitation.svg diff --git a/planning/behavior_path_planner/image/avoidance/yield_maneuver.svg b/planning/behavior_path_avoidance_module/images/yield_maneuver.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/yield_maneuver.svg rename to planning/behavior_path_avoidance_module/images/yield_maneuver.svg diff --git a/planning/behavior_path_planner/image/avoidance/yield_maneuver_flowchart.svg b/planning/behavior_path_avoidance_module/images/yield_maneuver_flowchart.svg similarity index 100% rename from planning/behavior_path_planner/image/avoidance/yield_maneuver_flowchart.svg rename to planning/behavior_path_avoidance_module/images/yield_maneuver_flowchart.svg diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_goal_planner_design.md b/planning/behavior_path_goal_planner_module/README.md similarity index 97% rename from planning/behavior_path_planner/docs/behavior_path_planner_goal_planner_design.md rename to planning/behavior_path_goal_planner_module/README.md index 888d5d9ff9826..f777e49e5fd78 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_goal_planner_design.md +++ b/planning/behavior_path_goal_planner_module/README.md @@ -91,7 +91,7 @@ Either one is activated when all conditions are met. If the target path contains a goal, modify the points of the path so that the path and the goal are connected smoothly. This process will change the shape of the path by the distance of `refine_goal_search_radius_range` from the goal. Note that this logic depends on the interpolation algorithm that will be executed in a later module (at the moment it uses spline interpolation), so it needs to be updated in the future. -![path_goal_refinement](../image/path_goal_refinement.drawio.svg) +![path_goal_refinement](./images/path_goal_refinement.drawio.svg) @@ -203,7 +203,7 @@ The lateral jerk is searched for among the predetermined minimum and maximum val 2. In the section between merge start and end, path is shifted by a method that is used to generate avoidance path (four segmental constant jerk polynomials) 3. Combine this path with center line of road lane -![shift_parking](../image/shift_parking.drawio.svg) +![shift_parking](./images/shift_parking.drawio.svg) [shift_parking video](https://user-images.githubusercontent.com/39142679/178034101-4dc61a33-bc49-41a0-a9a8-755cce53cbc6.mp4) @@ -234,7 +234,7 @@ See also [[1]](https://www.sciencedirect.com/science/article/pii/S14746670153474 Generate two forward arc paths. -![arc_forward_parking](../image/arc_forward_parking.drawio.svg) +![arc_forward_parking](./images/arc_forward_parking.drawio.svg) [arc_forward_parking video](https://user-images.githubusercontent.com/39142679/178034128-4754c401-8aff-4745-b69a-4a69ca29ce4b.mp4) @@ -251,7 +251,7 @@ Generate two forward arc paths. Generate two backward arc paths. -![arc_backward_parking](../image/arc_backward_parking.drawio.svg). +![arc_backward_parking](./images/arc_backward_parking.drawio.svg). [arc_backward_parking video](https://user-images.githubusercontent.com/39142679/178034280-4b6754fe-3981-4aee-b5e0-970f34563c6d.mp4) @@ -267,9 +267,9 @@ Generate two backward arc paths. ### freespace parking If the vehicle gets stuck with `lane_parking`, run `freespace_parking`. -To run this feature, you need to set `parking_lot` to the map, `activate_by_scenario` of [costmap_generator](../../costmap_generator/README.md) to `false` and `enable_freespace_parking` to `true` +To run this feature, you need to set `parking_lot` to the map, `activate_by_scenario` of [costmap_generator](../costmap_generator/README.md) to `false` and `enable_freespace_parking` to `true` -![pull_over_freespace_parking_flowchart](../image/pull_over_freespace_parking_flowchart.drawio.svg) +![pull_over_freespace_parking_flowchart](./images/pull_over_freespace_parking_flowchart.drawio.svg) Simultaneous execution with `avoidance_module` in the flowchart is under development. @@ -287,4 +287,4 @@ Simultaneous execution with `avoidance_module` in the flowchart is under develop | :----------------------- | :--- | :--- | :------------------------------------------------------------------------------------------------------------------- | :------------ | | enable_freespace_parking | [-] | bool | This flag enables freespace parking, which runs when the vehicle is stuck due to e.g. obstacles in the parking area. | true | -See [freespace_planner](../../freespace_planner/README.md) for other parameters. +See [freespace_planner](../freespace_planner/README.md) for other parameters. diff --git a/planning/behavior_path_planner/image/arc_backward_parking.drawio.svg b/planning/behavior_path_goal_planner_module/images/arc_backward_parking.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/arc_backward_parking.drawio.svg rename to planning/behavior_path_goal_planner_module/images/arc_backward_parking.drawio.svg diff --git a/planning/behavior_path_planner/image/arc_forward_parking.drawio.svg b/planning/behavior_path_goal_planner_module/images/arc_forward_parking.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/arc_forward_parking.drawio.svg rename to planning/behavior_path_goal_planner_module/images/arc_forward_parking.drawio.svg diff --git a/planning/behavior_path_planner/image/path_goal_refinement.drawio.svg b/planning/behavior_path_goal_planner_module/images/path_goal_refinement.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/path_goal_refinement.drawio.svg rename to planning/behavior_path_goal_planner_module/images/path_goal_refinement.drawio.svg diff --git a/planning/behavior_path_planner/image/pull_over_freespace_parking_flowchart.drawio.svg b/planning/behavior_path_goal_planner_module/images/pull_over_freespace_parking_flowchart.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/pull_over_freespace_parking_flowchart.drawio.svg rename to planning/behavior_path_goal_planner_module/images/pull_over_freespace_parking_flowchart.drawio.svg diff --git a/planning/behavior_path_planner/image/shift_parking.drawio.svg b/planning/behavior_path_goal_planner_module/images/shift_parking.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/shift_parking.drawio.svg rename to planning/behavior_path_goal_planner_module/images/shift_parking.drawio.svg diff --git a/planning/behavior_path_lane_change_module/README.md b/planning/behavior_path_lane_change_module/README.md index a1fa2068b9ab5..bffa5201f2882 100644 --- a/planning/behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -155,7 +155,7 @@ stop #### Candidate Path's Safety check -See [safety check utils explanation](../behavior_path_planner/docs/behavior_path_planner_safety_check.md) +See [safety check utils explanation](../behavior_path_planner_common/docs/behavior_path_planner_safety_check.md) #### Objects selection and classification @@ -163,7 +163,7 @@ First, we divide the target objects into obstacles in the target lane, obstacles ![object lanes](./images/lane_objects.drawio.svg) -Furthermore, to change lanes behind a vehicle waiting at a traffic light, we skip the safety check for the stopping vehicles near the traffic light. The explanation for parked car detection is written in [documentation for avoidance module](../behavior_path_planner/docs/behavior_path_planner_avoidance_design.md). +Furthermore, to change lanes behind a vehicle waiting at a traffic light, we skip the safety check for the stopping vehicles near the traffic light. The explanation for parked car detection is written in [documentation for avoidance module](../behavior_path_avoidance_module/README.md). ##### Collision check in prepare phase diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 40a23a09030de..6f462e17248f0 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -24,17 +24,17 @@ Essentially, the module has three primary responsibilities: Behavior Path Planner has following scene modules -| Name | Description | Details | -| :----------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------------------- | -| Lane Following | this module generates reference path from lanelet centerline. | LINK | -| Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](./docs/behavior_path_planner_avoidance_design.md) | -| Dynamic Avoidance | WIP | LINK | -| Avoidance By Lane Change | this module generates lane change path when there is objects that should be avoid. | [LINK](./docs/behavior_path_planner_avoidance_by_lane_change_design.md) | -| Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](./docs/behavior_path_planner_lane_change_design.md) | -| External Lane Change | WIP | LINK | -| Start Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](./docs/behavior_path_planner_goal_planner_design.md) | -| Goal Planner | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](./docs/behavior_path_planner_start_planner_design.md) | -| Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](./docs/behavior_path_planner_side_shift_design.md) | +| Name | Description | Details | +| :----------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :----------------------------------------------------------------- | +| Lane Following | this module generates reference path from lanelet centerline. | LINK | +| Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](../behavior_path_avoidance_module/README.md) | +| Dynamic Avoidance | WIP | LINK | +| Avoidance By Lane Change | this module generates lane change path when there is objects that should be avoid. | [LINK](../behavior_path_avoidance_by_lane_change_module/README.md) | +| Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](../behavior_path_lane_change_module/README.md) | +| External Lane Change | WIP | LINK | +| Start Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](../behavior_path_goal_planner_module/README.md) | +| Goal Planner | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](../behavior_path_start_planner_module/README.md) | +| Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](../behavior_path_side_shift_module/README.md) | !!! Note @@ -168,7 +168,7 @@ The shifted path generation logic enables the behavior path planner to dynamical !!! note - If you're a math lover, refer to [Path Generation Design](./docs/behavior_path_planner_path_generation_design.md) for the nitty-gritty. + If you're a math lover, refer to [Path Generation Design](../behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md) for the nitty-gritty. ## Collision Assessment / Safety check @@ -185,7 +185,7 @@ However, the module does have a limitation concerning the yaw angle of each poin !!! note - For further reading on the collision assessment method, please refer to [Safety check utils](./docs/behavior_path_planner_safety_check.md) + For further reading on the collision assessment method, please refer to [Safety check utils](../behavior_path_planner_common/docs/behavior_path_planner_safety_check.md) ## Generating Drivable Area @@ -208,7 +208,7 @@ Static drivable area expansion operates under assumptions about the correct arra !!! note - Further details can is provided in [Drivable Area Design](./docs/behavior_path_planner_drivable_area_design.md). + Further details can is provided in [Drivable Area Design](../behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design.md). ### Dynamic Drivable Area Logic @@ -228,7 +228,7 @@ The `TurnIndicatorsCommand` message structure has a command field that can take !!! note - For more in-depth information, refer to [Turn Signal Design](./docs/behavior_path_planner_turn_signal_design.md) document. + For more in-depth information, refer to [Turn Signal Design](../behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design.md) document. ## Rerouting diff --git a/planning/behavior_path_planner/image/avoid_fig_multi_case.png b/planning/behavior_path_planner/image/avoid_fig_multi_case.png deleted file mode 100644 index 014806fa7a4b6b0d678a71a13018cff0d8fa85f4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 93144 zcmd?RcRbhc8V3GpmuRCDA`K%{q?8d78b(%TNSPrsvt^W|WF$Leg=8c$N|I!6GD74UhfBgRbd3DaW!FxQe`pU;nD5 zftl6NvOHl5WhX^i;)J4I@IZ@0@B{0)qTk~}-M8O#8*Fvg;k_?*OrMIq`#z0y6U$TT z!-*L^FJGw%#wx~JHz-DJ6H7ZyrOtN#$)}WSt1E-uw{?BEf3$Ucbh@By_E5yuk3xsE z%8Ls0vXiF;9e;WbSmg{2b?Y6ZF4%wvTlf;CJ<^c6wyZYS$$@4oujqdDj5Jvbl}ClT@@=_J*7cgUhTlKjRp|`Y*Vmt# z87?0!6=>Uc;DG#XV#XR zcm3z@j-vh#cQ>nLS@kN#(NZWiXaDZa4Tg@n=^>Ts=Vy0IySlo{oHEA7!QSUVSL4$Ld0ZwvwVWsQohH7y{}~;v&A+*9P_f0&(%igam-q2&N@e=#YNKB* z%h}o4dv7Id*45QbGif}yU-hM^SGD)e?vF6 z^6lHVBUnPtJ$ocAEG+t(Unl!>YsT+B?QbwP(3thjZ9B(cp8cp%=~MpGJUJsi$AyGO zKWvsYXi77bk(RFPt4;6=2}xW@!(i~~AxmFdUf$r5gxdJdk^tiZH=561zW922dSXBL zuKkcoH*0InXme+Fj&)s2Z}j_n;Zp&#&xH5(je=e3YK)k>W^c&I$N>Zadj^)L#Hqn(z8>e=Pz6cWQ(&MYVE5}4hyyKi}Q5WqEO^44^S^8xLn7ZH*eSv z9#n`q7gE)l<6ye}XMLi&ZENoD-@mb+N)i%xb}%yT4hdQE=+UEy04;mz;qG#k1m#3N z%dRtnjj2U8U$cjD6IQIH+sDc(c0T4@t)92gbNshA@Jgt>kx{&9-aX6Qu_oibru2kX zmwBg?r%o9oeC>Oq14b%OG4~el4Xc@%9Inl@(98M#al4F+Ojgeo^-S}Kt}lU+8K%uf zRZ-Ge^K;Yb*M~2k4L%}|1)vw=W??x|HIytEYd0TcmK&Egn_4bh{ebZp*+-$tACIru z*wo$Mb|}rXIm0uwzlhnT=CQ1B+^t(n$v@ivE~KYrVoI`Yb5a?~84oqh!-5OVO>_v_ z{R&5b@>zVBSh0LLiJ_^!gk&~pv%J|1Y+m@~(x<&Gwr#by*9%Vsg#klrG+z9L+Zw7w z_1FGv(a)d9>lHnqTEAY!(eW)3bFYeuinM}_O~%;ImW1h_+2wSr745#?-D@(xWAo<7 zO|cdo9~lI$1|K$UiuzXIe%fbHeVXx@jUqC0H%aTt zKbUR-y?c3|a!@}pCopXh!dUlQW)t;6WnN2gz z4hRUiToxSHl5LxSt)YL*jC2G9q?V>lZCjRo3|_C+IbKQ%U9;O6Ews*SHTb4Iz5OZ^8VuJ=|o9`47??`WThN;W^bX$4$=+#U=&yXW!D z%*>A;KQ67^R+e+_#EEw+M5@<|%!L2>^Jkc8V0^H7{MO*ZG9?WSlkB~Dg#`uTK307- zaWc)>HiJfMx3Lx1*Q)@+Yu?>n#bXybGvml8?5OHAJ?3}&ws>?cUC1%pI(lu#2xgZV zc_I6ein5SnwNcWW)j#bF36V`P|MtEu5#^yqcoCr0Sa^73eM~IZ{>Wl%(RxmfjvP5Q=0}>P8+fUkGkkrw?ALm$Iz2w5f{o*%^Bl~v98YK; z9MtShkBp4`a(VcAb5!auGdCM2=V_lG-QBkD#$7yLzkdDd)vHVCYNlb`VpMC_?hbKT zkD658Twh);3vkJ5KPnr1gr(OcJAQ5Y3!kXRdu5x(^!=7nDD~_A)_l>#Uj^$$qE znA_MWCu`-T8P#$$-@8p<#$~o&n`ip#a5!=I4hYSrBh4o#CN#`lB~B*Nd7c#bYF=RG$Pwo}JC#AZptDh=qfWy6MF zK}E|bH<~)X8*?s@rr0Hjq>=Y)d17C_d|4HKS=y-aRkYgctBE9mw;wi!vXq8$r;`SSTd$Su|6EpC5f=}*b*LKjF{zs>nDhFS;Ikz4lTk+yTDx0+4$NOHO|Gcz+2FzT&}w*UF2 z+X}>iLqI^~bO1Nv-b2v#=S)zM$ncj#_H&cn{I)+eoF+R1kcf}LN3g(Y;3KntN_etn z$C~-Ce$5wv8P{8%q<1@^*XG`rMvTCg%wqQVlwayz5`;6kyZB#ogDD zI~&y}g_!=bQdIOkY|;=;uVr@vb@V*mh?bc-`NIc^vrqYoZG>H1Tn5|nwEOE49|K(k zZ3a{ekFB9l2JZf)$#Qy%FLpjGE4v6uP{C;XHR8nWmF#?cBe#l11{%)~y&Zmlm?Pj6 z-4D#tC_g@YUwG!1IIb<7o105misb#R5h(A*?{2NI@AOkiyZG)FN67r^`waXt_ztzy z%U+kiJYfN>wm44@lI+sZ)N~nE#R}$3b_F%P)VWO_Ki#+<3v~X^@89yId+lTYXlbH}Q3A72z{)EW6{= z(iCsryvcCf?j@c~r@6eXO*{2UdEF{z$8eA-!W%%Ls&OyQ+Tr%w>-%a|v}=QpT3SsH zzTOOZA$L0PzGb~M&;!3O*|KGeK~F_Q)_AJ}zx{}TL%{i%`^+L*d(Q<|R7Ia2)P&ZG zefOktfi%a~l2UYmi;iZ;k&4#nnxngS@4kj&W4jHE(rr<$)CeMOWTd1jjt#wyB`#27U|v8jt!i#=Xk=e(|NMPmgx-Oif)o^Mv;V*e-C^Ckm|U)1`y# z+}vduvM9ez8K#^90s`P0r+rY_62ZrcOH0p!z9jdZT0)swf9S8mNiRcwjnt`|71!1( zp|Xb$eq%{`FqAj1h5zNMr5i=dM@lwk?`Zeo2hb6o-jr^9rTMV_=PlqOhI2EMK;QFt zqfo~`(kJa8B&|);xana*4C;|3E0oa zr)c)}w`8~R6=VTF9{EC|a_N%; z;-x_X0q*YZDD)#>G)h??LxmiyK!)P+uH?H73}W}lhQ4_J{(ZuqZO>)HlE8h)>It;k zMbhzTaXl_pGz_y;-)q|V>Lk|x)Po(Bb&2Zw2Lr7NXapLXZW3XEzdv-P%-8BL?-N1m zcrkJD&c43*8#gF4+YU;sTF;ag(#A^-GE9=@(B&@=larG_K43I{tgeJ7?*+=F%(Uib>m}iWDbN0@;P7?FuK$Ue8tIJ$Juv|1rb3>BY>fis4M4Q8 z!vSo_E$N~MjMbZEk4MyNyJ&)JRr#`?AE`Rc(~Go{yS6G zJPWT?>b);0NWW6fgoKfso144m<)s7;k1ei!ZKmzD?U1Cm@Kh`qB3A(~*)pS!k6ust z41EaSh>nTr?+nmZ4&c@tnH_KAJaR-8yYS$_gQho@G3SDhL`T)Cq6HPa%)G$|>`?e^{4kAj0W4BMbH7`(O%WVDo1MM`=d3=R&ykBBVbrPf10 zxv}X%`}>UriMZsl6i-09(%|*L!fPI0dJ7rjH|Ee2;Z6;l@4)siEYP|Cq;$d4!=@b4 zPY>w1K`$6Lx5k~{J3DCR@;D|Y#xy83H5Db)#GxftewTC=o}K&DsiNVG?yfEwAIQOU zor0CtsDD-I&1r^_K0cfDFJD%EGlwT5szfDO>zet*{HY7At*w1{HNSF)1*YV~cQK!W z;@|AdZ&V}2C}>roqV1$)NL1AY2+554y|SS-V7$cCD6XtbsXDrndMk+aHK*ZH0l%`! z*Jf=p$(%n8&z*a~W{4u|69u)9UF8g|{<*Z&FE7u*LNTCNtAZ?~8&t9i zjWy`?fxhF7U2 zREM_HuXn5L+i$K)yHxDMDLkK$oEu;Kc(3t~Pmk zwx^ZmM>*VNii(PWMuX3WRLm_b-n37{HK^B~pQ>N06{)LV+{wYt{^sJ@S|?3P=8k{< zTm2GQSy>beDL{-*tx+vOAn2oh=w+eg&dN>#2|^)K2uK8VDJ5`%*1C{ zC4mB5L&B%`c#$`AJ-|BNvDNaVq@+yM^%E%3Z&!^R{hq_>IxW``fT(m72CK z(eK}j|fuA^r zwqGsWu|Ch?NVM4ZCpM+%xp$R?B;b*oyCgIQ`Y;27NtI#;G=%mNXgA2kpOe*xG zPXMomE>VIR2fd^-RAnBr57hlHe@*^8Nwy0V2$WdUZ&>rR%CNA;*?=jBnsj3oezVq@ zr!~td0k{83k{d=~7ti4F8GL*1Drnht9|(1(giXT|D^1FFO|rI#L%=g4-1{0*B6CV& zEx1P<(#+a~aRb^dTN*Nm>j+!qrI5_>8*LwW|7Lpp2}8p;?0ZaR=8?|sZsYtLO9=UD zG|7E#t(vI3&5Z?B#@Jr7W(T=XhnK*BrW>2#a963ypa!VsH7hIM+v0=sOoOh@-rQEn zOim+}#!8zg8vaf50tXiMmj4Xc3si7aLxXC_5eqS}j!L-1By7+2zf?J4*bag%V7MW9px8s9lesVz1WQcgvWKD=q(AgOcjd4B<3m{{! zGBab5Q4EJJ-+urNWSBQU(=F0h741npsc+vRUcThb`SpG+RC9pU+>ku{V&V%*L+~m< z(y?h~T31Eayo9-lZA#S2Q3Dm0^Q7DV1Mdt6uqS7{HG9BeIVJDoy}vvviPf|4S>!2i zBPh$ypFYVUwD>N4+JF?$999EO3WrxE4-2|FMpgx|o_w7qHV_nrTBW2ADde&%Y}T{;2KFU04!O0+2g1y) z?^C2_0EhN*?);p?bvwHrROG6#xskm{QX+%>VC<7i1!y~8Al5br&2=prXrbCe<;Nq* z9!-rkoAEFxXc^I*J9mY7$+@7zXTN>>riMbKp`k%Ytk9oNyNG88J;2j1yd?k4A`oQC z0BARD-kg5%-BJ);;;0hCT~zdjX5SioKUUrP$ES_NMHChmh83N0dVlN%4&{|>d-gOf zjYU7k2)zrnJm*>c6*Mr;ic7_UxiIIto()#H1+7wqXE{TpFT;MHoSZ{_ApNjTu2e%2v69PX*+D5@85Mv;Bjzs zXUx7*)=)j+H7AJ(XAqW2^;q{_p?6Igm#J(lZ+vALQ8L0{(Ger)CF>ql5XF>f46GSUy^>cMQzuq2Wd{8jjcf7 zC{&LUUTXM|qt6o6Zp0Hl%}#RQ>hUoc3gd zm5ShVUFCw>%(+5UF8|>SrQ`RL?T(lo48(q3d)Glz@Y3lptViMiD59A}8b}Kk3tDqm zvwHUs`lXcg`TPaMA|Kr zRv?apzrT${;Csn`vjD9r$PU=ZBiA`;VDrYpOEJV-6JvR5Y%l=~M2&1&f<|{|9feZs zx=210<#Ba?t_#mV6&Fg0kbN55Wz*@8mS-zd^iHi%tziD8gG%--;AJFSKoPprM~VAjGU%ODH_GD&6#-7iVXB_zoWs_* z^bx2mhmerwnl)>np)#+A2|KY#1ITL8HRBlUK$XOs_d*?T?Aw=lk%m^M)2!Adj-MiG zop3>9a-puvokq*W00a?rf_Nc(a00=iYBL|65NythKIP2>%R+A-Us4v6kUc4+)$kM1 zkvoi%<^YaS10v2Ut@i5DU7yE~cZZmEj#kTxz`Z*M$rTV57WVv1;4}2^;#}tErpjIB zB8fjiun2~cm2_e*clT64Jkt3oyd{`Z(O@?{Z@NRP^X5i*to!Q-mit7JC5P>q1%sRq zU<$lAfx1{9=`9?OmM+p+(MM5BE9pw;bxGnRqg^~&NUz-kW1=3Nv>Jp6X&Ah8yLX}# zb-4mi#&blwQ^6SFCfU!nungSiVcjUdP>q?3>z5OCVJUn5*RW5QywKJ!-+&C7=ZHpM3D#?3IO9H{TJ`!e>}A8zO6WV>=-IKy7{%q+S(u? z3K|;0Fkxz8ssJ^<2^bTWgH931lKp8^{mO?d;$_X<3+r+DAomvc1=4+E?dS6HdT6QV zussw*Lqo|=UCkcM7+zUZCy|^x6;E25v9bGFT;^y0{Q3n96!ogkaj*pqMqjeHHJT!t zC_h|h`PXe02YEHX90Kvofo-&mjENo|9%>s8N?lRmx3jnB5Eh<$=JX8|oSS}euq7b; zWc@&Ku+p!H7^06T5|` zCO3Kx5#sLgfU5MQ(GB7eOA!5wc5b`C7J7PPSQ%<>?NU%#`R#sPRA2k7DHiwwW>nbfB?9-es3-}Cv4P6>u4|R#r#aDrznlswp%jSN zhXc4~RaPwC zts6d?p#4ZJ9hYi&S{fhx18I4Ad6=ayZ4Fht;E4TvJA4i(dT0y0^#3TJxgy;ZGVijM zj!O;}!BzCR$aD%aGz~x2f_@4M{6^gW?~iRw)ThWY$YTZaXL2CmJF`#wd1G)*v}Yuq8e$HAiOHjhQT6V z9J+>$-hcA%MrS5%bBp-$JdI;~u=)fg%$JkAO zA2Q#1|FL80#5%yk)SwOQ#U!LgdjGe@TjpiEwAZ_GlXZvN6;2mFEyBNGH=Az+V?p;c z5CXLZ#e@6|lD7WjC%FjSeIq1T{QP!%7V0j<;(p87nIFpuw&WirZ86H=Gzx&pn^*Agn8Ahuy@&>FdRPw=&xL?1_ zk>AbPeAzvXsWBLoK|`!u4l2;Rago^8`@xUE%bYW=d+{hCApx|7cH>4Cuy==m%K|{P z^I$^0VPXH5pYnnaf+sZY{Oory@C<{nVM)U1AVq#ek-oR|RUAn;06f94w2ylk4D_Fk!OMcz6M7N5gcy;cx)u z3IaVIgnl7n1H2X+cQLRch=WgvF}&p(FgZ9-pG^)Uh!|o}l*n?R{98|r7&-)ChQnyh z-<=f=QQCO$Lt!C1I+k!E16Hovu@5e-LxA!w%;!kLMNvj~p7dPctvUo?gN&B^`$^!) zLQW!bFI>3L*P4^=^&o@_etv$9+0>L+zs1$IKKEZ;%qZfl5h7@< zfUYH^5m^P516!sLd>}m>;t>{_`#3qP9fopZNJ9`+8C@`n5#ztx>!OsPcJ>nIA0&ye zb5i*J=3DyvH{ua_b5q8&w6u-cY~gCiGN(Vqdr6CtkPbvS_Mj=7ixR8!@5$US$%YO* zne2G>j1?nFC*X=b#4JM2=>#SFkscP9BfHtydLYa2B(aBK(L!%m<;~BUk?8<369)T> zb=4}Sz$N*e?Ph05G>e8@OjiSCdOqIfqD_V!R8^mlxJ1>%GWDlnkrUO@t9q+r$aD+w zq{-7pMMd>M4Jf0v^D}SWxy7d0bfJ5Afg;zxXptES74Z6EI0+60=|;1#u-v~N-#$0xHV#tcPN{(@GdeJLIBTWG*bfu3gD9t^Nx(oVa-3G zar?hGpcYaAvj_s17uUkRRZfle6AnXW4zRUXCJs?FR?O@t)2|4^okOG?%(A&(66)-Zse-t+dZ|Ln(!S*rgUbKRf&l0Xa4 zf}MivS^MndS}^&>>=#BlTiqb%@C%Y3A_#3+h4bhAz`9?&;DVh?rnW$ENGB4ipO%3k zKIm$e^v|C^)4s*sM7brTlkteTC}|yLT6FyA=+Iku`2*Wvt7oq!n?iAxMUf{~1;!5J z!3)TU7xVnYDF`;?MK>9VczXQ$D?lb6W+q6R20hSLea)16yzg{VJ{hHRpduL>8o~fq z#xw^y957)xqyfbl+O$xZuA2!1?s#y_sz32Hfbft;rWj0?G>?;s5qTJe(c-7|16ADwG>^~ zjH@m2tC;LWk;X5szB~jH1`FO0GK0*WO#JSs&9XKYTS2T7bd(PMg@`}0i=w2-|I+R zO=x~*7_+5{Ky!jwT?Z+m{48pJmsAzuOvXr|rF|bij)XKKlc{&8Z7N`Kkufl|(&Z6m z=x-Q*5GdeW>Uxh(3T_EjC&P~lo(Z8lC>&Aq+KKHyey{J-$Q)vd$P>yUh62jLv3gdT3N$L2nOXIY1?Ej37 zWw=t+ZuGUYvm=9{C=X-|l2q_DoA>;>GRA;LRpr+=mZYD@$;KvuMox4o14Z%BVo~$b zOHn05Ph?U!E-sGPx1?DC)3qr(tzQjDGCJ8EW(*^PBszqfN}_l~xn>-?#1QJfp`lmT z(m_{Z`gcEAxcc3T2Lpd}b?r%QG+9eaoZ0W+ubo|~iZ~?Tg)y@l*m7y8JENHILASTo z*)(`ITW|7D=hV;aA>tb2v4Opq*;pbPa%yopS^j^FK#ZpVQ0_f=K-AfwW|K7!n(ruR z@%|ANwEG{HF*Z38LuNV>(*gRIE`8EXk-}PGH%c;O-ZeKj*DWp9BJzfg4s%_OWU32< zfYl&#B|{5 z{pqAs-b06==mBk%l$HGfU4hl+w1j7(J&AG~5EK*?YWIB&Dt+ywhzdn+^Y8Q9N$JbK z`hO!NY|Au^J?>qnq7@H9YMAPX;l=SyXt+#ySi*z zglG7JNk|qd>-84qc<~g94%dz}FH!)iN$m(o7_`OL3fQ-IpS%40BWHyA#6LhT!}1ek~E?d_F0 zdzKKooRYXhD1jqrF(ibCi$XJJ4Q4b?WG|x(c>EPA=B58^4Nxfr7N6sUx%JPl7f@lw zxCgU-_3M-p=Q~kR3T0hJ<{n~&O(`^?{cj@*6s)+Y=oF@?YTzhi(VvHhhxglezAse# zVkmX`^y5O^6x*ZLVq~fabKf8<7!5gz(Mf-dlH`;uz0uFGs1%>VCs4$+9O>grGYDG6 zVzhJ5`t|FNsVEC5rHRI?#>wI8BO_KQkqz%%;XZvfO8<;w2gf)G~mzUG;KqwGk%oehiGw6-Yw(9z_P1;X=Cn5sFQOy|&5#QCv zl?)wfKv?k3z3uOA6D|$5eP%jJ8}5`mQV_+n7P8@%8wW6)3=$|Os_h2nf%MbBj2@xy zH5(R}#Yp9U8o-O5GEA(`0I$~QS_aw#S`N3v0lvP3n@CGbXV9*NLG%wtFR!KLxV3_w zJ|KZ^CBRz)Tnt~B5qyGNVcENvNg%ky^S=D`fwMa*pM4I(XjXB zk{b+n=DQbYj3N=VL~M~cAIy)Suq-wq8zHk3b^XLnt|h}F04Yd-%iFm%HgX&}dbAjK zAf;|)G1wsb$+gNcNMlR}`UM3gAUer_r;-+_8u^o{}fFNDJt|*WfhN-deHN_vzDktboyCcMJOY5jXY9u{zW@ay9tCynNG}d;;IhO+`4uf5Cz&6aIK zcI?>kV_@J#c=%3q8a@NZn3$MsE+m@AUCsQq5)DqAvJl6pR)JE;GI{zZrI$elI6#(N zCJLBWGdR2d-!!KR63=KPZyCj0=%3-E1cv|;h4lL{Wl1;=I0VO$BMk^#sYUkyA^!p* zgLvp*PVifjl-BnL@f+_!^9lux$hwG#2x?d1Qzz9?==hpVXf&SaY$cFG4oAV25t{0W zBq=sIyqvp3qH{KNUY=;GD?l&NZck2A89Ut z_*%-Z?TaC*;tHGc%aNJP(tC&wU9_gtxYRTdsJjcxn!>J^IM+G|pEP;v8tk$9s zgV;hNR0;G0)5U|D=e)k7>S7)dRD0jvz3xgh^p64pVu;)Y&q9^1!zdG`6bu&v@pjk< zd3TD+7Z4wPeZyj(-NZk`WJ?xTelhn8OsF`Xe47}7@L6a{nr~e z+M=zkjUF`FaOmAJ?wF6T=m~MhaXH~d{3c`{=-!-z zT|uUcW@cxJRnxv{k=iApJTCAUfF)_HqAy8~Q-LlH!bBT`a}*DQ2BUPbhgfd2@tZcG z-J^w;#(8^t!Tq<&@@P|WWx?xT`F z)|{48*#HzD&N4|U&;=u>wc&l2)77khwV#0fl>isr+NcwjCr=rY3D*G1ZZ(abE8?YQ zJbF!n^j@L($(;8s8A`0{zia#a4;8VnAfsuuZ!E6>!U?1fp@Wav7g(w8j*gCfUj<&5 zGg5_wg~?X@5&-vu{zFA|h z_fmcGd#x`X+WW(*;ONlzr8}i4As?>Z_%R%(%fJ1{nsLi2{1 zzigI8$4aAgwY-=^yb5t!qI^{~G>%uDxIHvIQRFgn$`Ll{Rz}9cu=&X_Jw#PoH7o10 zy;gSjL^qL_suZnOi`3xOyMBEe2yUz*hq)%bOq{c<^I(Sw|4f7Z!uiYBEe}O6|Hat5!uz%#VaJ_g+mWB z!y@yCIQ*!bI|Q7UT~aN3)r>WA>}lsmWasbL=R6RZP8BJ@B-}Q!jT;%w zXZD|yAYZa))71(``|E#W+^!vyJ7R}}P9A4+?>MrRnc3a6**$5^Po3~|x9;n)_5E1b ziB2AuyEw{4{o8H_CXOW&l?#$*o07kcyUdSY==-t8%ggH>-&tRo-TR`$(}jIK33Yyl zdU8KHdbe+hzC>iD`1NDVDja@dxGk3QV^NXL1?9Y$kuTsV?PhabW)I7|e;>;mK4ypW zE{&q09z7c_R*3$6)RS?F?=g_$0gTqu(OD9wNQIgG9SD~lMK?Q+cu25PGpu~55Kqfj z;~M7C^luixi2uj%^{=^3+c9Z&)UmB-X685vd^bIkT8>{Ss?_Of zG{(lpt8Yb`6&qA2broFVy6yXNW-6P zdF#uEH+V@-3q{A24If7e&n$DEEYa3AGNN*sigEe;%2-0eef9kNzd`8KIW7G2>zmso z9g*LldPkgRj#Twp<;6&POS8LrdC`!O_)nKppM-=IVqnL8aL|+l57szuwmGl#kWW~} zmoL<3swITOuACp)^}KO|y`f>RoWOE31(|PcbAxTa;Lg0a*fGk>M8`UA(0-v^gGcLQDGqB#p19krTEDSUzA*ge0wj%j^=D-|jB_Vx<=nG7{s7s-w&^Z_ zD^&DwP$3R(dm{z!dwXNHvNgY_XP-&)$BBs}&tqcb_iZ6pk5J_rbI4j%1+#BQ(TO)2 z$cov}bwYZjnl!dQzaFjeo`3&->Da

Ib0A_1M#S$Iq7jkshcvABn0q-0F4{=Dm1hOoVd6x1ssDA&dUH{lOwG zsMSR-_Z2y6hYSJ9=igthknoOGU+>ymaso0RUkOKkqB9wTL|Am#V62{^!qBJBoS>zO2tc>=*C?AT};v!c_va?%4*> z`A|U@sfqYmeJi}}e3L-#P>1$hr#89n&d0^=?jkcRQN9hWtv|ITB5+=XWsdlmXwo9gDuc4hr7DF9o(ozRfX9%-QBtAt|)uqD-qd!Oy0XT z-OabwtTE#E4;R#Z>csH$nA$qQM1Byb-&mUbai_N!=ta(b?_aX9a%29#6gg>mQ*rgX zKRm0X-e`P0#q4wk6Z8lh5>rPkyQoc?oqJT-_4`wVsXe1+ePp6{MoVx9=v}n@z*n-D z(VvMCaVRobEGw6&{2P;$-@#A4N3!n#9EJaZBaiCO&h|Lel0qKmn+Yn(?|G?b`jY23 zFz4hd#rCJ6=zGWfkEU`X5o*uUksgIO#e`EuCtL>lM+Ke#JPz9#P@;p)!0<}n=2>nQ z)@Qf>QJcz*iV3y9&~a<0&zo3rXTyY__9Shvkc0o)+fMo6-+E+Xs(GoGAvHt0M;!!Z zzhDKh5vmt1;N0Rn+q`MbF%uS6LEXhP-N<+V@QjJ$0+cW6=qycbu!&#Q-xZ@j(>MnCwNpaE3PavI7qU=LOryRK z9Y(T=cA@T`^gQ1&N-N68FgRZGfU7xUqnBiaFB0!kh4}|QTmBs%+$v<)Ns6i@X`I-w zoK!`NfrbN8#hrUtpGCUmP2MH(>+xW9`7n+|-#}@M)JpEas@vg6??!K6OZqMzKbaG& zZ;D0a|B*g*Ce^C$gvrX>oE$IP*6XXlfZC?&UYo-ZfAYMMB(6O3e;#!y5UQ$b6B+eW zUwBk}X-bIS2!tq6m`1ICS$g{!ZP|l? zcYHV18ja=;7@!zHdvMp))$s}n-owz7XJ~nu@_ow&a!vM5H%>!hz68SB%Pbih=bb5{nad#@S$T2aQ)oTs3ib_vdTD1 zhZ}&)3eS$5H%R>5pEuXPb=$UYmVO={nUR01P|rTFQV=@)z2SbNs*6WIoxRyxY?!Dn z^4MR0)S4T6;wrWzso%zTs7g)G$%zq13z-l#I8)>H=FQQ=F3)e~zx0fq|4*Q@DEu*P z5C0q9u3|S&6l_G&sCB+FX=Z8&tJF>LKohfQUqDHw`M0IyoI^uK3wCw@-8%8 z3G@rX03cBPwel~zZWm)-qGk+4d_O*0*CFE3H!9eAy_?a*)Rg328$KSVaVF5i!)DtT z72bugW_`A6PvDvNd}o0-nMutO6^C=MEAEF zCt3`(3TeE#w&KKwcIeWNAY3am-frHwag<)0aUq>NJXT6Lgsogj z1JwlDu8L22RmY&Nu5O28^>WGezZ1=z)}mp#HItEELW1we1l5U!Sd!q|35I2SN*tqX{QO4^E_?7#4OW7B9z@~7udOhfVow_MB{>y|4M)oD1JJSrmFikrZpH#o zE^b{3reg8?`$=fMn`?bE>IrA&V<;TY9T)o0@f&#pjHmp|M~P)@foH^I?rLxs3DYc# zRgaa6Q$%Pz!szq2rIghyYRnHhE;>5y0MA?Y+A~6vZPPn}+}|``%FFfewuzbd;GZLMY_Sgd-m|c_UtN`kQn(iaqr&_iB|RUfz+m`N|2x{d-TdSMhuml&NESy z3Y82}N`_sET|JwY_0ekVKCY+s?pDVUYD7uTr+>mkf=?9J;Gz>xR|8vzc3RbSX5w~~ z`kJU~Z@zNe^ew#%o}+e5<|*@YL)J%9kfX0}xk|9UDn1G(19^fyjKjT)Q zR(Wz){jNu=5m?&}ZrCWV;%NQ1NU}2U-j!JT-0&F?eE9f6hS1#6+WoMpgt_zD8%_P2 zPdlA;Q???z5|%5Z_KwMK@sd0sEc^hpRQXM;d*IWjx{YjDj9!D>XN!wL!wcqkW{-TL z@}rW@4c@2Ld zwe~n`^oN?7EnFq`lBv5uJlsw!tJHfM82AoHUGri{Nb#9J9WBeQ9erM~pUJxeg*_j3 zcV5i3Scnv5k((GA5NGDI;=HNI;b$|bxX(|9@?P#8FZF5`JP~;T*oJ^QJ&3qnyLO#= zw!Eqy51fL!o}Qk*YHZ0yv5N)IGwH~w_^Eps?^yey zk(U|>fjg0Z4;IhYb!AzY$ol4t=>rIF!JYq#-bR{mC?&Q{ zYkpii3UYGff#puRhU`IQgY~q41exfnBsp*%3D%ofQgROf4WzC9ny8oooLPgq5{*;r zYuqvgHxK&1vjY~x`Vaqkeo-8cTMB8es-`B!;de{_!ZO;!R_NRK$s}B`JfuOXprVcP zg)GB$@^RGX0NfiKpu&`hWaB}QMjBV5Pk2tis5HE|B_J*L#+;QQ# z2|bk9?`Z!!C7x>KO04E`i6T}@VlGu_3svbRsnW}(aIgGiP;`@&<_v6X#_|U$jtmeg ziUU?Lu(GnJ4)QSK6=>a9~=y}AV{{N(v$4Si40+Ool8w6}JOM#wePzI>w)Cu-cn;j)|p ztSBfbARgSOPpdzE{0Q$sJ=*r^F-8M(w#U-I<>e<{_W!}0TL(-e6n=%U%aS7((fn*X zzw;Risf2f&S|W=1m;(bTj?0RyHRnRCB>1;aXN1w5oxXDI+9o`mfLW`AV93?c{SDPl08YS6Nx@FF~^Y{aX3;*DqdjNWc-t{1RV&LkK?!47{m- zfzfk*@SPYS-A~l$r!s;RJ}U3o%}~WE zS~QQttb&K8g^ETPV$!dUs`N;%uC%U~na%{h5a9(R-XNAgJ{vl|8|vuTf6H~e+`fyj zAw#>ZXQ!|umoH!D<>ycD|AP-aA-*v_psha>v2y0@S!*s;GdPI)`qACDM&TZz;2ryz zn3SaJa-!mY^yJw?GJ?Y!3EGc&4OZWvg4uwn)Y3wt*E%EgKS=9GGv!v6mL_79H17~gbP zqNo$DdBMkzlI0hP#6mgi_=8Wu+7(bT>X?hOQd!1F$+?gS4Q^Y;UC|%VZV|lYwsZ9_ zd}`9@4tg(13miv&kPmz3YnJs|Kbh$MOe;Yzz?AKM45JaDhNeURtFaqKy1KWbeZlG? z7Ne{(_n|@tLuCe!YUQ^YuGb*wI?Xoan|Mb?VS#BtO5I%hyXEsY>hlNZNWFz zS!!TA?VYf%gKuuEzvDUI@-YN+L*46^vFq0tIu!7lL$QYHc$+qB76Ekt_@mSg;F704 zRRm9CT-E-8XHmz@Bs>B4O;2OOHVFCPlh-afIAjxM04kuGJEUi7N&^$&9q^m@-=Rw! zJXV~z;pa!|h@+*@qVI4vrmRp3w8;~$gf0fj@Uwzd4W;f2urqdYctE3?@7wg;vhum; z+vVdJ;1!kbbbEiqxZAj4)7%&yR#vGls{BsyRw*R|$!lQ~w^UO^W@IOf>LhRU*H#vhvHU zEUIV_H_2&HV=wfopyG+_foF)}RuHDP^SiKg&xCbfb3@*K8RgHAVNl=gdZ{K~N@FL} zk~=-)Ul1=lQ@PgSj2I*X$ijOxKfh&hV@KT#_?m`#D>p;-LPxA!yO#J&NGoLaU)!BL zn$t%xj-J(Px0s7?{;KZZqg%N;bo=n{s$lQR<&WXo+Fuh}{XzFYFv!T?{i{#bK7}R- zAOzKdWw(F|^A+6wu-0iX0mfq_?+aOJv3dRCQ_NXs+XU8^-_aGW{0l@ zN#(rvlU~0YejEDwtT9bB-?*v9@PPsTr26B23af9m$K5|vTDIF`FXQ;j?k5|b8A~U} z@L!b+t(NV0GZ}7y1v`ta?D@1&Ow=%ZGW6ONp`7ucF9n|;GVHRrxF_G~G(hMoxAV>-f-QCh9Ae{mN(j5wdNP|cS zN_;>5&-bz}EEa2+S@+&^Pwc(VIf5XS|JH`{mYNka|%JX`{!K` zvC$rYrh-sRwe#XtZ@hNZ!o@=nkc8vL4GX_`1Pz2B>UAbGabP?FEh6J_i$~sf$MzDS zygU(pa@)YSMeYc7z2MB8xB)U5t(wKogb5oSKQPD@_noYdnK?k!0iAbADG0DKAY*K@ z-T*WU;I1&9BEtr-o)@O=ko7iSvtE$;fe?R133`O0L2UqXcC*aQzBe>rmciRSf3s1b zd_@P)#y+X;_{Rs1jfP|8VQI4~5ioCN;369m1D)hLR}W7)!EaDPn|W)D=mgN=nM~BecNNLg?rs zLRsMrE6)y$Xd$yVB=ETK(x2NNqf>FEWu8fndW54U;?Pk%rbGBt{Te@g6ErNTvy{HL z`1$C)?(2{>7#-^RPxzY81a%ah&SZ2psS-(Y4GlM$+EF+vu!BXsTW2^|ztNL-mXdzx zT)Q6^-q;B-42S6ES4*TME0ieW4<{xR3Vws2Gl{xLIn8EuIBpfE+h;@p5V321$w0rV{Bsc+C_qXY4g za?js<*&U?LPcN}@ZMY?gll$S(Q84}0byPFvxe9K-AYT&>GPqU9lq9FGd zFFYf2My2bVn!gaW`LJ3bCBuM!AUx%52L9b_I??ByY{`+RQ|lVSC@enStEcy8yE&X3 zNVEfj0o(@4QF}?PhUMb4LsU$*^l_Qds~m+FnMb##hgTaMgyP-;MJ9j`Q)8T?`PTPJjF8(q+AIeSM8k z7!J}}vx#evpoulgsx`O+M=mymONS^gFW;GQ;y)ua&j&Dh;Sv5^-#_H`M#La!jS4M$ zCj&DPH*j8;2WkmYV1v}{P9yGl^%4}|#+PeX?On;0&YE?(#86(S+UI8^vSZ;Ad;Xo16A?y-sQ}U=ICh>u%GW3zo63xAR7UxaBFYFvb8#&;tTWc z7|?C;A0cKvBY7D^%7=+u&VL8_l`gqR^w}WnB(`6F_>-NIRS!#(R$Ed7x?f|lC9UT7 zlBg(DlGWDGC72+OwEjuF;Qwg>+I(mt*4kd~yE(nZ4Oo8W7wASC5lRS$d4eF_Z-AVJ zJeZFFJx+pB`)h2?V1iZ%3`8$dvzADNt`ND8eYYzgbfjpzU(orSdG6nZtP-cR1Q-7P z-l50xoDLI1I#hBv8JlD>It* z29beDXgoaGU-~n`>DS_<5VRhfyzud`x+NVJ#KK}pGNi^c2nCekbBPE{7EuKzkUjJe zuKJ-ImlOJpjRcqxg&&vNnm%OV6pKs~I);?u&cKRFg5i3UP-!7sf>W2TUHQNDB;g!$ zR0uw}WW1OYvCnF?V?d0s6zKgXkgso4wgi(5tffVwEiUr%?0Wb{*>NxMaWksX3!vo2 z9id!Bk?)Kx;Ce9>OYv;^l$En5U62C)=ni;IO)mRxoo9)Fk{HM9zAfU(Q$y4A&`c953+z{Qfrd@7{G2q?%RlfAP`Ohv;klgn|gZ_fZ*Bt z5707c2?h<*mV^$V8%j5O8^z?kfSO360bjVo0cI)p4Nbb~b< z@p$1M%8YZ{#-YMY6GqYfmxs1U$GYNll5655ricT{9As6U!8XKa6|$f38?j&>lf!m& zp)QcoC@KbPd8fc8T=)!!mctfhI?EhnOoT=?xOKuLcrGls30y7)&3e`#pO0_rv354ocBa#L9_+G%z6&V~(vuW7h{hiO zE&yxmXZpfJSVWX&;>;HzFl0{L?1ERm9{hD}Ana=Zu zu(t&7XF>zlBN!yTb6-03Cm84c8PCmh~LB3Gwu`|IN8Qk!l4}$iH0% z`4nWEnnE}Wa_F(XB)u*wr(juV+IQP1Oc`VubZ0{NS{pNtS^*V)C7TqyZh!6s0}Ti-n;w>cMQ4-ldmuNwOAcp_ZEX{VMrWj&Xw{NoG|pu(ChS~xezjP z^1&F$9QqLQkn5G>iWtV%_J0&2GR9q;*HJQ)IJ3LID;oLIc`$FJLUnl}_caLxiB)Tf z+Ri79VA*s?>ozL@{+v!&A_tEgAQQY-L4TI$wDm2+Ght1D(fIP?0PQJ&z`2A@UnhC z;4>S&1c!*|tg`(nBAjIJnVa)0I``UZt3ToVLnvSOS0PZwqz1(HzFlkob(tPxse0Yf zlPk!?x_Hn>OqM=8Qa&F$D4K&DUZQ+b0vXE!A$lZ!i-AMXYfpuD*h5jSY9HiETeOe3 zQ$!f6_#jR1ABXGBNnN@$$VV@FAQKd}LDb1Nrx>i=ZazS}WM^??ht|hqFuM8dT3ZEYjX^s-(SEai=0j14=~VwwzGEy}x^%ot?lRiYcK;lbT5 z0fBKQLWVL+nOkw)BHD;mLsS$WLHTcs{2fvVoptuoCNjHr{`6n3>!5sZh?8ap--aT# zNCPDXv!G);9?ZgHW#lpjraBnql54nDD~0G?R>}&6vM|n=GfIiG7_F3^ve)h*I1}mB zY|LoR4Ib^`fBs~9WLTGv31el)x=|j&fpE^a-T%7CsY$9~v6(=3G9oE3k*WV-)r7}) z<4T0;`2C)x&h30Nrk~4&!HQ{Q9+`@ZqMk&V(J4eK^GrvK*fo_GtrGfXGAR8QK^ulFlB}@JAlC5LdATFIuUvQX8$2ol z7)|polf8h+T`m9+Z17Jo1bQC~7hw;tp{53E{1OC908L&61RFq&Ifz$1fu59_?D3GX zB<%ZN@;@Kdy5ESros7jQN1|nH!7f6e8El+k>zc0{_+=jW7jo|uShsZp_}-pc3Y;(Or;*EGo#dD1mQG{cN{UW0>*gM-jDc^+yhCQHkJl}}$9!N>Ls z3~Fn5YwUb#hjntg9hpN;GKaV%NoT^ASJ2Lr$m@-x8MA#(-Hu)0zp@Q1^nwKl>vTbq z_q6>6Dsp$xxPCj*_#_&bJNGsHB7#JweX%MZ#8a?+1waNdU)nkXlxRVl(Mth)vdDG7 z8p9l00c_jM9!mR+Tox2)bu%qgfm7hMrB*;)iBPJWc@wlcnD0W->v(N~J2U<|@0dDc zAMM~8v$!r3;zQgV2}ft^gw~a=riexr5x3M8D9RU!@wLP~qbC#*6JwGZZUzqiRWUi= zv^iq^=Crj#DW(pKAu?_gBZtg0{3cvaXTyq!(5NJM?aw1>1R@0C@?UifH!7uW`B6_~ z{=qeuLmvN>!lz+x-J;i%NLINyEENJ-whhVc-*W`*S;3n`3b%bU zh3-ma5r;yIJ8(y=T^aZ1;)<^xM?5W<{h&UL*rR?Sq3aWjP|(T{XBom1so~0c_r{me zxiseW)L%D_7pG4b7Noy`kn_!l+xX#6y|ldiBxI`zi$ON-F&_mO<#JJ&m_5LRw9Yxr zpOK@QLu!e!f;wD>mWd-!CypYVezDz&y8X#R+g$jDASuI6v(_LjOh(#f&_rGjB}q9Uvi1Mf$2(dliW#9yLxnlPU zh9ZTgcnc=&r)8lXhiUb+d@Agf4zs!~G&ixxhKz|yfASC3*z$8)8`DeY--BuB-|?s? z9-v&00QfOL8^jeelAk%?imko}m+RZNP1}>M4=evY+C;AyLE55gy0sLAm!YbSZro89 zN@uF+nm1eDbt0Mcon~kbdhCpfn@Ha7W=BY$Erf|i3d?}hH_$~&7V()bD-^-Al;a_y z7wpM6A#rL}>IM@!NjAOM3iw_RsWYX8avW3mkV?no_rjCIzM;*nINTPAu@EKTX+jXw z=DOZ*wu?=s$QTzbmKg^UNsh}4&3(}x{6^3j-0g};2m6K%P=u@*T--T%9=ol{y=b?? ztjGv@Jnmr`m6un~khn5y>Nc7>!3^zyz+MQ|Mwr5Hd(zrh;* z0Y*$7iQjkNOVhr<7v)-S!cF@M#aiVn#PR|K@KFd^uugL4vt@sOlYO_;W#er6FI zG=I2(h%fZKN$aj~S)MD8Z?;yuY(bsCwr(hDOgTCeg&g)69gM5Y4?D36J<$$THY+|2 zFkEBVx!xvjF^J~+GP2g|>>R4uwKoTaZgk7fI-7sRgwGKSTE3gzN5hLk?woBg=KI-2 zpveOLy3tXzp2PK#zt>fun;1W)?EBJTWjp!KK|W;5eK6AOPYZ60VgE)}WU3CgX^$TI z1Rs(s{jruvm*9+3*rQT?mytjfx48g?V)UPnG*IUsj*ZVTj1eNM6OWGY@+hmfhmHD^ zHkLrF_-7B4P)|YObyP)gtAxJ?)ekLelhps4^%Lkl*Q$ z$3VU9DQ#>nDpcO39GySImtQmE+D7I}c8=-<7VG#gN9w+&SE0@Z&YHIqh4!IaG7J^qPI?%Co_gzt69AvNScW$L zX%ll!AlD4^eW}QTwP1=P?Djptwl;ISy~))ogri^cm@XP97y>YXug2M!oN4LqjwfJN z2ONJ%SW9CgWctEbq`C_U?SCizwgFdm!8Zi*!wFuU;~l{{A{a$+%J~=9=MZi{n#34R zxL;E^GE;rHa3Ay9ja!ss!G;W8tE(wj(&*qD1!K&fP zA9xGvt{9K!;Wl1xrlez6;h7WVxbi$2TlHL9^r5FKD+d(Ct?;@KOVSx>>Hdfecx{1P zC&9ix*y#=8*P-Y(Gwc#~4!Xf!(m8q7Mz}T zU$fS6V;wbD3!`H*4pHOHzosMswq5*;w&1+nZ-u;U<%Fav*?!;s5YJp4Q5~XoQ!y!w zkwUp6hBulM8pGOY82zB>4e0-DQANTa#QLHX5+4Mc z&IhSv@xS$MT!)~q=SY0>l&?mK#@C+6-+GqR2#-vpc)}x`EXvxb`YO&x&r{A7FsX|X}V;# z&I%v9(J}C0`YkfFoh1}!yn0C}HI%BU4Tq14`|W_bVCvq&9|xP^xIb#wxbdr-f&3>} zzmH4SH@LfOz@XHu3bl6Re%Gq4uiplv**OY<48Ruj=o&z)y&JUa=&tjCniu7}NZ_-> zE=iRIZ$vGbl2atZ6}O>pn2Dw53hvK-ZhdM;nqTQFl5#3C{-eceV2qW6Q_@LdQFFO( z|4JNv9WhEr;EN(atpqBWAt4zBsZ?X7Xc0=*VbJWu~bJbe}lf{%m z`huIGMJw!<7+x%#Kfic}87 z1yqbFj;-W?2&Nph1jXY2beMmY9k2u;5quVk{TQMw4Txl90ku0&s(t}JCWUQMwbR%4 z*2~K)Ujk>w!yEDc1svNe^k0NIkI5AA{SZIBA&sT*yN!S~oC*ZIV4>kU9_dS@CiPwx zm^K?gSo3*l@&1eU2Wp*~Zaw-4O|morW-w{Z;*GEO3@=k?r;ftcDtf`Rqq}BeH%IKe z*l2lK}Y&Q)X)T>Shv|c%2wTsi1hsCfa`6AH%qW!c}NJr4hXs4hiTYGON%dyDUYkUDgMRhniYAPgh z$eL-?tm^;??vi+~M2s9_LZT6DI0Q~oN>bYCvDmtgxXxFZ9S(+B;<79g7mEI@@}~l> z9}{M-)R1LGq&&Z|95{$q6B;lWw{(5qMnn0@L%yxxS$3I{f}2q?#7PeG!NLMmD$wWy z>JexZIF2lOAB)2q$ZJX{InU4uz^d?x6i_-nbA4wor-%SgEIKV$T%8nux_QFIfD6mQjY6m! zhveA8LPwUugS+Zc&;ei3-wQ&?4co zSkzR8j+%d2hA=p<54u@BIz|5Nl`cL${pbE~-~#>!JNf+3KVMZkL{Rw=xo`bVmoJQ% z8h&`+PWEW)n{gk^!Xa} z`6_=LGM*S)S(L;S^jk0L+hWnS`Ss5@yWiKMcX|Zyp2}9ZqL#Nw@L_YG4ZK#i{c%ILNhXsMF5Ts2AKM6|GT{koAOqp6fry{^g;aM=~gSsO-HBqajOtgt}X$ zrzdY_whZwJ$PoG#;ArJavp+^)A42SI6f5TcV9q^cSQ!G>>)24 z9ip?$pbmQ2nfOBjGDKT>CF4_w!GU`)tgZy7?oK>EyDzat8n^w|-MvJMEhL*1vMZ&C zMu*fw3=6@!uYiL>ZD}h(+a8&4ETX0=v6d>a`@|sX!%n`t{NVNXBbGsWcKD<}{Hv}AhY(7_M;t-(vAz#=x=4`WS_}%R zD|RCqT;vGLv$KIh{yNC>0_9vgR-|VYkRsgPmKgc7_z)zlzyeg^jeLAW)6eAtTXLec z8nxEJR#Xt$G}K&G`*}-9GS%A?>R+2LpX}Ic3tFtDN@OxHcs(NkpURjNv;Y0cgKfV1 z8J(6i7lFPpDjr1`N{94AoEgizVODUkkq#S5zfVke-jZX4!6#F|b>a|3_P6R2d7_dN zv^GA3*F+3ovTJR+osSCs^E~573HjGx_`tiW|j2&ws_*`~34>=JM5#*?HA|1nJ zGefRnzxgQ@-B%y_HNGVVJ4(6sEjY?o86lRb2gN6J@iq!v-C~&U1NtXA{=3+`?~Aq6 zGn)9j7uQ<1Of-snU*J)_d@{*LW3fOY22oT?(OJth>ayVzsVl;>Qh6(evXE+niyz1y z+OmnYt2P1tc4Uw(T`J7iIMzZU@x^s?pQ?|gq@S*1K8OZw@@<1|mNpaxlhhcpEl+(J zT95DKSE&|j4<56m!U4-de)n%ODbyOym?}!*lP>9@Xe7N8UwFZnsG~wqCN4u2lBr(J-J%M2%~V;hhp?dMgLRS$XzK?nb2ESHookB7trzz$YTE2 zw}l)P6`JvLrvb@{3K>hoQX$+0J)YsyqxIRha0;=be`jy%|MhxjaEvwg98EHHQ3#-| zx_vH=6fZ6-#$u41V?Zd^%xamz=6#-Dj41};EvJJ1E9IR*zbZ~HA zv!#Z2pwMv%j{Jx_k?)d~0m4#)dS~g73HH&ijG>e= zUFPy}FFEU0ZoLY2%uFx>*YN#Y*`h<}o6$i-wK`L$6-Ky~P|&H5nGdTS)a0ozoe5|b zi1~M4I3FxaVxu6#O=)Na`QH?n+YqS2;%P7M4sh9C1@+s$B`;F{%2So$P zJB;bdwRh|@=1~6m=9HabmkQ@MQk$3;%U`55>a%ttey8NEhQpldx!!jS<`rz7cdOdy z)@SNf>FZ|KR|=Wf0LT`Sv?HX4X>m-?flq{+g6NX~mndUv zv)v|AtTzagLCJUOqO!Kxtz18;-ZLprW&fCTO3IpkY17@}+|u^yGnw@d;d=bjaTKil zg2iNchOu`FQl#vwk|R|5HN>8G;psN<@#{J~yu4)rp^L-9`mM7$j-~u!!Nc>v;WbJZ zwe+fqV0xozF5H`7nI#Mg^hTY>%@aTT3q%tcOD)kiBzdiQbExz6TebDrrm09aHZIQn<_N)$Zs7_Xl#(*_+B-c4%$D4XkJvMrjxVA$Ec*-szY9r z;7}`EF?*oJ82nQNf>FYvjhnaflRNgAkrR`;M(mxKH1=)|ERR@zzc6cpmol9cw9E`5dP|Wi0VDlkT=BY%6ecZ_K`7Q&KrZ zc6vEKe^`ejc_lc%I8cY;?REtA3tG0}PWx6SRPpJgP;|)Dh2m}O?&dCs8sc42=aX%H?FZ6)M4#vHX+~sASh$>CSxQA^V%@m_T=MTfAzQAWtCA^ZP?Xy~Ww;>hx;iZ2o%%CI|;uC2mnk zNzX_iFP~hSE`O0w@bP=cW^(J{ZLgj2_gI{Wsd7q}!e5s+UMx``o{u*R~^hH`aZG%BDF zXOyz=94}JaFNIeHmcHYY#!8(k`WD%uJkpi4Fk4VRouMPF=C`U*DQ_v;@;IA7EFzAf z?~ATuo~Ln7y=R3p!Ur~B9-;IE17rmv&8b^wN|BewEyB|!AaVxZ@4vP9BD9#N*+Y%N z8sR0=9Q5Ii_&v;h5krP5$JL=Td%iq9-QQTyI$`37?|&Aa6C{1`!pq zOWooZ(@L>_ohg(?PPV2R&0+DLVaQ|IAtp@oZ+ulnBa9EDDeT6`N|)q+cXy)i%zIEq zRl$)M??>iP7cO1iv@ndJQKcWny^RjgQkSh^taZs&l`q#;0>)xVI@0%;aiVXCN~>L! z25tlJ<`z`X3?ZRAey#tR@o&|#wE5H{#q2cpor=HDW2ao{#!1Jn6Z2p5dzYEdGM0Xe zZPoCgEVY?SJ#W4bn{m?N`Cggkt>03oYg69Q)^L!WvE8PmC5kGHIc=#hM7G9}Eq6hk zvG8qE3eRZF81!8#nXuDmM^Mh|unE3TR{3e0*DCyl!m#U^pmr<%N6aJ!0x}{BxpX^a zw&e-7>9q7;1TyvbLcW=%9`C9b4~v55#s-md^&I% za{q;=J;QRxscEAb>F8Cl2EF`*`xao(UKfeE7xPA!MjVgDDRZRI$3GtjNQcmF>L+s zgq)uFSG*^&3t~)F+VwQzKhl{qLcx+xq2KXy^bS}HY%E`z_@G=jvw2ycto+g-GvWQ^ z2YCkT>0Rgh#R0=t9nMlF3I?a6y{-DK`jukS!x%SOq#sq91rEFYpZU3dirZTQHv`jrqrCQtQic>?jqWlJry~v7KVi>8y+@7bPxUJ*L2{KM%|G7 zP;Rss=RHZhllaxkcf}U2Kj+Co?Taq693TcfXqvg?Cf9PVYQ8s7G=Je*_=63zuENQi zsw&ZuuaC$6jDkMBIl)Jj;p&6E*(ytt`_fYOJAvQnlZjAIhg}~&S^erM_Vov2gtkowLnD#k|haEhYHPn}QHrk5y=u2a`} ziO?&IaPuUmsrY*DRxVDgTaTaA)&ANs4f4Ew*->00%Sm@+D91z|6rZQ)Q8p97Z2IwL zXY2)rnKWswYslR4!cSH;mjZIrjMFl`tml<89F=?~+O7icokc`Gu{GhTsjD9Xovd!d zvJNg{PCOQ zuGs03KSM&Y`?u$#Gs;rX-RKk=L+`tro>_G7meZpdFVX1!sGg7`nlnF>qKEB1_l=vN z`-j!rku1NLU)MsaDkNG~ph{fsgI0k-x$Q`r-7K8eHt`=SiL`1mxuc$DbK~rElC63;*V14RC}$ST!ntfIK9n7yUimqWu(KFmP;);Dz311>a-4+3 zFn2NuRbTg;e17{6I!Ho-`Cba(7-dSpdZBWIMnsMT{3ubb9E?vs&A~p(kWt|6yLV{( zxoVSOeL1F#e*yFK1!!OaEwT=|h!B$O!e5Il0(>TUi^rd9$?37YdGakYkswFZQV5~N zydx}`Eo99j@Xr*&HM%t|Y!+DXdmm@@{(a@I7XLF% z{hFk!P7hZp-@KBg`S;LG&oag?%KgM!O)1hboI2sJk|EH=Q?f~48CLYayiq+5r)Uax zS}((miO+;c5z#T0uMt9b>6H2=lZ;yE2iF?k&|uIFHY5EVXws61-1< zGc{mlfSgttn3O&0?zL*0Id*a5i2-?$HiN})kTq`_qCOd<10JVIqMr+D+y-!vs4#E1c4s%fL-UMIX>O*fGLLJ}^_vy3kf?`kA6X3hznm>QMuu;EMO%f_Y5AuE>+%JX6SN z8UA3^M{xGpkTjtiSMw6(8I3&&78f>=oMq4}R}Uo?%hJfNSn78h(C^ie*2JwIv3+P{ zqdKL#M~{I)$`aH{jx9;L+?fmeiqfgJ8Ybff9;~Gi_Gw-)(?6G8RBsi94Kc1(KDZ!# z)!#T|OBSO>CDVA1gFH37eRi-gYBQ%~*2Ld1D=nRP;=-C4<0WTn-mo&as2C8bJm7x; zuVKE$x;&nLEp)U(@HR%h*;AT!R^@7iG3)~|1N`EI_u|AAVGUdb=5q^)p2qgw)&)!faY9k+w13t&F7y6<*|?~%hWlwM>BtR&IK)3 zFTVL`$ywlpheUqt?1s-XR`M1I5)NxC?6%Lwyv=q$6bKNBsimci+s?5OX?F(cNaw25 z&%G1!Q}mZF2<)EvY|Q_Y{@(4C$uxDI-j9zvzdoIp%_P!H=e>@L`S7)8=CStC;YI2K z`zxN3e3QAq54;zL-s@{d1w|eZ_8QlU8hwEW8PD(5 zBFjrbKH>!iaCu>czjjH2CyDJf+NaR+8R=x}^C=>5!T*f>_Cy*5z6SJ97&)PIk%8L) zI>2tI5Fz%(na5az;XZA3`fdC-`^>B7=nyBcY9~~WJ~O308}o8O*F;10C3-EzYhAb0 zW+?^zioO_^f4BX=kxm9Okg-C#S5phGf`Yh3zu`4;DOjGr4LvzSO~Tp{kk?`%W4G?U zF=YOhpQL1H_MxVldgYf2k@2Ob<17c+jJ$a2tv|U$Xby5EvX=+Q#4h$X(wHU?bamW*<6S9tE-9OK~qrGn$1+JcqM z**6kK27w{^&BgJV?}lIx8?n41dPQ!{%yz4dC$`JB^93QN)g|V^w&oK4y>;}XcHVLw z^|`)2Uc<6w5fkv!0XANuNtL>p*tc!XhZSAnyqm<*F_C{hGe-1h%ej{67nkc7dk=b# zj6B{yN5sLPldVYCvJ2Y|zm>cVG6w}g{n68`#}+mCP;vGe^S^#s zjg9P<-x-qoF`~?#Ezt_Pr917Wx!9%`PJ_)FneyzVLoYB^X8f)&EEe6U9GXcFNM6n9 zl%~!Mtfs-UE1`|4DOn1dyNd6whE4cB-@mDTC|N}bZ>Tf#=^Bofb??VTy4M^?%~W=3 z*{af3gm!1?Rwd0P2Nb=>{&FzxLi9C6=2{NRP(5Jo`aD8gNyFvUVN}93jmrVFr!vzl zLv$w(&Z(|8{Z6xbGE!KS0H?{dHPG?ndQJ|^3(B<6w5s{Ffaar5b28y=>|KK0eVd(q zc_Fz%LZ-er1q#ltwDEzia{XS_{CVq}>Z))Bie^hrY?Hs!h3={LE0b>Zb*}1ff&@|* zutXFttJyCCLaIyO7f4jp$lG6GtP8L4ld+8%Z${bJq@9+fpO*0(i=E@Z0B{Cu_;#cF zCy(bj@tw1ZXJiMRZd~hU@*41Wa8y?_o1P)pr}UI*e@(*=ksdSGerGPtD#72raUsSS zsD!N7fY55JrXhY?#^3-JPaJv)1E2}y&R~9g<0-hE>eakZ_f?gv1tqV9=}qO^!!qF( zp~1NA+X8e?Bv4n6w|anp!|dYy(tR?b8@(?u%yRot5>lfqOlQ_QR=sw3*jKZx>#Pov0B&xZl$->2&_0 z^YYE#bkF%hqGXSVl-t>>vzKR)eoq^cjTWfETfrZPGa z;d{^ghiZ1pN@v;Z&`DvKZS1vR-k>z9R(*P=DfP?bpXi>B34Dv61s5nCs*Rv*mxFYA zv8`;E(ycv0F+vpT`z*6@2=5rrq&&DbZN|E2-l$%uklct2WXo!mJx!d>S66sih48eo z@k8OgDp;#&C4dmh&+H`=XqfNu4{Se1|SY*WPiJR&7l zrIn_<@4YgM1N)5!v@t{VmImGTTmM&XjpB%(1A<-m8ebl0j7SqsA|NQh0h8t+C9vnIraK$|0&JkcK6kvNIwg zYO^bZHl}pBXP+haJXL*(_`rrJ-{y1}?W5Vb5nr)UGR&r~_ESfw>a$X_PY6Og_1IT#%-oJT&qe44HfRve6z zmV(W1>bo9BV2{8&m};M{$Pi^l9qLVcDJ{pO{X@2Sgw5lb98-#SZLKv*VYIrRv?gvx za?mo3sX+Ti+%~P{?0K<@MQ9x7tV*RWXVnG^j(Ie5P{DZ> zFKNz+=KKdUBe`%h65h$S-rG{6MU!Mo&sf7@2t9uZVb<7+r%o#>4S=~ zB{!Z%1k-Je`U1x|er=X_r`Nu`D~c(}=N|XBgmDOAsYpnBj!DiOU4`X4y)dk@qVntm zGFZD>Pk@ukI=l7@+vyc^bRh$b;2S}zuYB#bsiy#Ys5Y;x0YCE{oL*=gF=9p+UhXmn zw|e`CuuNrAbb35fh-FyrtIdnZOUR8fpngzt_~b|D%)hXRr0(r&_@2)%1bI zX%XeoeushB`}@`Vp%-}lY;$VfJHG_x$YjDlTNV&5y_fz_G^a|*L3ku*YqAQeWQ#}u z@*Ad`Dv(ba_gK{|UMrU!bZ9Er1*-{`(_cwOQ)rhu5eX^Dc@PF6xo8(xHYUZ?5`)*_RgMaci_O9qM5|pLn-X0phQ!Jcnn5%j2Oeo!=wJp zRfz%1M_5tclC+8hQJWBp_;*)+K|#Q`uuVG*t8{U?p{G>6CI$YIVi$;tCH8B}9J1@XBi&8eT(QX>)K3YSyG9w!hA zhYL9i^DX}-l8mJ`Se4XFR&~}_A$A6F=(2ujj0;PGBN>(cSAJf)6Fwm=s9Uc?1^GF|DnZiR|3>7Fq2XQydBEdS2wvC$vl zj{QbDrtxoYa~rR}v-QrNsjen z(q&%4dUM>Ja!duAcxxw@hK8DIGZ%({;PlrQ?~`v|WBcoWmO~b<10|8(PPQeI+8YI| znB|%&svFy5THPiVjbB{jOSp7B>wEU=kDHMmY!jQ>iIqms2-k#?Ub@ps)X%O+E(v+0 z(7V&pjS1Js=Ta`v?R?G>@-n zip@E)dP6T+@O13bci|-&u@(eE5l7L)DX7 zor!&U9;Os}EFV%zd*Zqy&Y*=uO|9KB&d%H2Q5w(K@FQ{mVVaA5x{E!(zn`}D23xU~W2Jt56*#n9X9&m) z!*e#B93S5K`_mVUzvh^j{LnuP67Lr zgtoMD+IYTYti`O%9JA7Z^~I)_rP*yY`qO&TI7G7b(*Cg}ngX%DoE)|c? zcd{Nt-$rI5#!a{RGLXF-8Rsviq+m&zO_`FvwU`&rCzbtspVo&lhBz_0GK1PH}PPvkO`sRG_%^MU2Tr#R^kpK_j8rm=8dX?v2 zYC}Ry%47$XE0!Brwdai5T_h^G&3l9?%nM%C=OVhSVif z-fBI2@NIHO{m!C2ewFTnK=fg*BB=76bY)Ywp1^Q+iD6gXXRQu>{SN&ll}mghYkm=) zn(SG!#c_U6%_6HI)R->7`0n4lCz^_`?*33B%P5u00O{|{*k|GkaW(~nY`Xop^2hn1 z7ij%#V0Wj5*)P+oG=4VQ9m;+j>B%;FZ+Hc&O_uoD!OvPO8UW)*NFqVPQh)P(os@o* z+e4M*wdH6S_j!HPaNMH`GM&nZ;mdHiDdT{R=C8Q&Db{Zv?iJ$dO;*ykI7Eyd{koV( z4aowVlWfkv-|H*JQTtj}yse?F*YVMG`oJ#sw{}sZrXZes+@I=eV{1)rz1wc5*>glj z47e}a`pGcDsA3y>xe9s-FJuw&+W5hNpYI5c5(-=WLOz{e>*^N}upJoNrpT|BrMWpI zM_i2>^6ndT1#kKo837Q4PbYiU%ikCP`snxrjT4BCiaQb%ho?tu+!>m;8O<9U09S<^ z#gX{28BCDZz^b(CSOhaEe3T$dsDOn%O3>P{a;R+#5|?Ihx{sVvQh9BiKtu9T#+cNq zyIpVY_EP`j99rB3hUs(HDzBgajNIDnuQ&^b-L|cxlJ(dda}Jmmu;)G0D(mPk0@J&T#BE@4ZNk=QGKoLd3b6?SxO< zf+Nka5ZAowtu9e7JNHePc#h8lfh>s=kUc#PH86)3;cBZ=MRo?rUSttmf0R|cnP{%x z5C*+Nz!db=q8@{SbyZt^A5aNr4-;7I*YbgkGIV0NCO)%hvDFrNL}PX>5MGD!JHT zK;%uYcUt}VIquWBBsjCzD7Tg<*Oe%@KAX0GiQ7NE!;ArOwy3vm@#dR5;l$xfX3k`91FVKePpfkRVhljYPTHpzpBainIaTGc=|?|H#y zj10bkU4A^182(Ahfj)vp!Uu6tcsRy6BsN~=C>ttIt@-2x`7%!gIu;##Y z{nVrmCgyow*eAn7^!1C4ND(o19gWOC^H7Dh#uZwC_YnegLY)e>X$km#rsTM54A?p? zmzIh(C~OPvNc~@Sn_Zs>`%CTJdUU|*LD-*3WEylB>)SG66Q_iDJYARA|5kSOzZ`4z z0A=r5=bIV^2XPSzR4O}p`voQ6C{sGOhi4LVmtZr+R3uwpaqVTf!^;=IWVSYTe|nJD z!LYxjioFGJ_W!nHo2MNI>95|_wo&h+;AHzRDjZd(Z*N(O3rhSz5BsqE*IlJ<)YwBi zfvwN@|1tO9@m#;}`#An+X`yM9q^%^Q?2!tE?2v2`WoKlM1}aKOGD<1Q$c&IxLb8&* zLiVUg$n1Mu==r{V-k;y+|KH+lcUYe=Dlhino;8JMm1 z^vJaAE#|cpzRmL@Gx0CYgyV+Z#iws;*(E)&*C{ln4B_$83z26=PY+c6*dC|Ybt={^ zDmIBO*7~gE*9_LqVU~lGc8QoPGTly&>)AIm6_V1B_`D*s$6B_2*0lbQ`^<$>qysiP zJspU0C>GDrB2ci;3uVxI|0~#LA|gxWzPHZjKhK)1%Mz%$$B^PN##UXijio`0 zGlom^UhiRoUAqWDTXMQ>XvZ#(rV=FYF<5{Mfr=wbPM+1_3fACpK-Z z&)~ZhxR2*)c~iV}z;a5)%Z1DQ@Evb^uyVcsu3D8ds;bP@+^VXzwtrv6vI+0xV>Eqb zv_0Hktoxvitu) zc2k1o%j7*S>f26~nYyi_>pVfc;r56AH1TZqXS?WEp+d>%>-&j~bM*%LyuJ4suiT<| z99d8k6S`T!#xd7${a7AZpy(7h?Rl>PV%?ks)}g{H^B= zsow6TUz?+Nl_C7MYll$Vn1Zuw`-&8={BK$k`p*aIW7ou9{Z-!^l(X+3zjX5+3e(M? zjmJ+s{`qLQ3Vhr9KwW-;eFB#SOFqR`xi=@yivM{*p%g60n^E6l%CKHGA-OJvx^?)* zaK{b3_p9kbr0SBd`_-vS%0K@o5wKfwpOBmO-;Bayjbb*Qr(IH_iL8SOP5$jR-v56wz(D*8m5!_=--}r;Pl#dPe(=Rmdj6)7P#UKHRo^S;9}Y z4%V&}(d(c{?7;n}907XHI!qBY6 z_tdK|N)RDqy#fJfbdCRLJ!s&Y@b-t$-oO&#NpK;@`4~dsyRl={?*;?EnCkw%fw;sv zXwYc|r;|mT@3SBPuO}{G)$T!#Gu*pzwYKy3G;BM;M{U*o3ecy|yn2BXkiNHM2IAN_4AY7QEi=8=kg%|71-DZW9j1apV%zvG&53M+i&~YrdJ;4OO{^#6G$ZLGCn)h(%`>(+W)7m z7#+b39j_T2(+{SY5qyYG9gYwC-{w-!j1`V&_c}H&>ZVsNyl5|ukE3xU`h$gGl3Z9s zdU9*89djNZQhL)|o1py`=JK$dTv$sYdy33x(hJdv78{~+h2osf+^^tN#2P%~$83GH z{?S3NBh96ax5%5las@^SkWRg@q*UWz0&%*tu^O)) zSY&q7Lkl=)!Q9xy7v8^is>;vpIqPGG6P_oITRK&Tp_5_Z6+A91t}Gecv*~-fMb4O- zoUH7}%YQZzLsU0+2%^P*^;DgHSDhkj@}(BXAdRKNvc)I7z4(Mj#KaOYJqoA@*tcBv zW(&Ig&!Y0B7u}oPcE_#_qSHgEp{V$m^S8yz?mL3MMSQ}SF1|=qquBry7tUf?Xxq0& zolh26`~ubD7Ya1uR*jqVC3+r*Q}k+aM7C4=)s>ri8l}yba9k(Oto?$;XIntSk2Vt8g^L(3E??FE9~R@0y7$ zhuN5}Ul`1%ePd2jUxIU=tHniWT4YM%yub_mBvd6)E!ZsMZ4wHmI@YPtjiuhgUAz|VlJOE^1$J$&6D0WF75j5k~93NfWpFfa>Sn6?kE94uXt$x z*o~I+9}Fy^UKmi$MceUt@&B-$Y^lX-tTBB>H1xi=<>}(o*3VE+dTA>pIv;r`|9$B; zf(KEPKfb;XN>OUWXA&4dQCrZ?_E^htd)N1`IhtqAoM}ok4W3uLBxr&}AiWg}mY&fL zA+6t^#n+WgxVFMCAdoMP+M4;)jAC{CoaxwDqPupjiE5%l;lbCY^&AUJdTto=0M zI{Q0XOm&z4XU(=LweHc$1tZp5vBmTi^OX(cnd;s=JLP8r(YLJr7Yi$zEL9J>MIBo5 zl?tX;f#kpBlkd2wu1Wr%-aGRqLjFk!=U;F{qsetVy8#3%2M4^%6sSGb2G;HuT*_*hAIExdeWMY7v*BOI*DBJHua7UxXKzO{j<~%2 zh^DRI_P%`d*{)o#a*cy+6G5{3DyR5SVlb#Hm3u|%zJDY{GN>>)oy!&;NU5k zj-zY;X>%EVMnR+#8ySD>*AaaL8KkBqybg-9DRrVx8#kdnEL>;v~GO{FO(aK#o;9fXMG@ zuuOgSwuJ&wa~vhN2DeR%9fLp>$m(nZaGG}c^(=~zBPxYM=ixqVqzleo&{b&8Ci0f!rTMbckafJXwEyN3A zIbAx|P6dihZbBkCKhS&nKl<+`+P-+PF=DF3!l0uymi{J34*yO3I$2?l4JL1Y=4z6& zaL1mmbCpVT{ccJ`S!baR7-f+?a*}ibkxfGt<6;c3i1rx*@%64xrHV}-Iau34w7?};;?5*vtVoWA=OqiN0-lyZE%y6G!Xmp@5ChGLMpqrDsQ_;Gr_ZPQmk;nNn) zgJVOdb*Gfy5}BY2P>PBRGKBEZ*S*D$zjwM1YPO{W42eO-B4T{{bd++s3R|O5s$j+t zx-8=H#mwHvdy6q>iD`JPUaeC1*?RYL(&Mpl2`T!Fw0E6xFz2g1(*O?6CEx#!u>7r( zNg)QbGMK>AWHit)xy-uHRsKy57-GTiIWxca9-R=x8-2~0zTY+q-DCXu@6%Rwi-N`3B&usS$!`)I?g>^b4KBu>8n{Ra{hxQZnJ~BEZb7u|GGIho4;wS zbm=*A+F}}R_KQpkyyu&h!BNTw!b-b`YHDf%3^+5pHck(m&2t(aTX}SNiK*`vk%Y85 zs^fZz8Q<1Sht_8o;YPC)ZI*i*iN2_ChoID+jpGw;KPTiTMF=uDc&m=Y4FsMGKJZ)WS>jUQfUNDdHcv#rjy_DK9qU zcn3MmoXPC)VgjOHscYGoBB|Vxdnx&lX8J`Vqn>Qj%+9;QT>`~_v;PqNz<0Ck;|caT zgRkFip?^D8r>XE#3Fitl9k3kjd*&w-@O9XWpFMLX*sVWUg(FzO@vW`UE66U8B zY!6b4OOLeolEqj{cUJ52r)G=RELCjbuOk=d%$&jO1w7x>#7dHott>2J9nP9Ft|ULo zg7QPKNWx&2(?Cr0@9&oGngLXYGJj-r-rf7R+#F9$Fa#k%I`8um{Pu5bBGS|%Cd-U} zdvdxQR}h42}ZKkNq~b2TCDCkWYUKFhD{(%64+dZ`D) z^q=U%5CrTR^h}oslIgxt%Fy;Vv+l5cuN$Y#C zX`}zfApN!5*zIw4oyf3<+xL1mxi_s>!oWGWO$NK4%Y*lfZToYlO`y|iu=TC|AbI^U z_!`AKC&iUE(+p_o{QULP6mRd+GB-PIht%=WI5)#wm~+W#9qTWH!G9+R*wWfR59^M# zu^t^+?b@}QrOI-)&a!_~#2?bf+MSgEk=D7B5z{Tb^3Khk#|t8+YNF*ERwT85`WulW zyv{F0=&#t^;}XM^N<-b%t9RU3zWiFs&GmfJ@6`?z-afyfMorT+O6=n4%Lh1A;xlTZ zOwvwJmK+Eh^6@Y`ao^Q@|Gl6+H|}{J8l0JH4?9p0xqPX3`)F2zRsQ+lU$m8z=hxI}5xhvMSqgH&Kbic&6= zG9Gmi*tAbpuQkgq_|;AIHx|s8q-fXaaiT2DW7e=fwXqC}N0SK0uC*hN;S*0qBs#J{ z_u|gmx6>CQ<|WcHzuvz{HsWrW6vJ6Od-m<~f~J^|Z*Wl1Y*#Wb%~MfP(f)?yP8!|3 z1Z`7xUb;;hut(mlK2Ol0z)zHYux|rF1rf=lrGyfYmmT%m+k&)kG z8>GvPK0i55j^p>;a-=7qST^LaXKXB6Pg#gTqWY2ss1>N@-G$VEbK(0*`EY@E(Ab0M zR+4+q332gDU$ZAw6Zhi4`d!wqYM#w&k#zmNfB$~_&!0cJuKXF+$7Po3wY|yfksk>y zwn|v(@%F7S6vW5hPMQ*N$7}*#(&z42y-Kbzn@)8aGw~jQkosKLqpA8x34JUY=IheKyTCJ}WB}3-mG)lO=x#-7o7OewmUI5dGNcwxkbzt&=txVE?$M5=6b` z=EuMNUvq?^P(q{{u>@}6VBCjYU51aH1`bdl4QunIx_b4hRrzLosfHyRjmkp{!Cnnd zO!NX_=wWNj@4Jx2enL0EKE_omiKp`!o|I z6Aa(qSe=bHBi5uosR7~faGe|{?n__xob+XUm+d&pDCQmqpT)-7^W zbG&-;H3(1q^3k1H`mE~XljGMt{*F056u7(#Q@T%BI1GWzAhi*IVlE$Q7$Ll-^s85| z9ye-(o}@93mQQnHb_b$ZMNMsp`6sfRMA>EL8$+HR)KNr0SmkF*h$|~^BpR)|Px|VO zd@Gy*oY~9G?N79rSy&?C9M?kSTSCG_PLp+B5po7XKcf*Us;b;LmmM?F|M}^%BSvLU z^b5S=HPUVa!_x$od;rWcE8|1%N~n{fo-`~;Jxk$4#<8X8*)NcmKxcb(Qx~_Z30#v zj-x$F+S=tfqdxHu?+tHnq_k~ZMrDi`_fzN2ZMl5;G8wrvR#9rIWq2urmW<1Imh0{a zvg+*g$UKW8n84Zn{vG8ZTM!5dy|kfnH`CN@OOIodR)VGnwCmBI`Ysj`B+jy z&hsxUE%kx6VN>JI`C~n#n5*if=WlDRt)iy(tI0Hx8?Osvzie+GeI{BydukvK3~yay z$NX$dF)Kwb$`8%oCn3~{hrGe!=cDSG|MlyQH1k(q_&?UQi++tPJ+k;-EG)jozt-a2 zJFnR!;Q@x|-affdMHLm>MnQ~TfgTr^<=1SDh`iX?+pw&T!9kxlZ}`E#WY$jUmb!(F$3}^eJCFK77&G_91yvDKf=XVi3YB;v2?ChCSei5S1e9Ne) z^J{B^h}n;H76(3lEPvv}iAQ@h-oJnUkk5Q8(QSlqb#BkU=iwFo2HTUnFb5CW20(h(?Br4_R z=K3=6-|a39u1?g=JH6dBwUJTKdJobUR`{b2hC&kxe#fs$ zdbU#Bi(3D~%?%_+Q-4)wdNg`|zH08W&Cga>`Z)Ag4S2RrBKIER%GGCaKY#w*yLT@?VDIUn$~OE=T@wR zXsu$0=~UHJ?FU?8G#Y^c3Rup z8zbbHHKwe%{w{x$g2<8?%e608Z`wE0=Ukm^a0+fmp)J>yxd`A~hl0ZfIGu-j%EP1; za4t&m_Egp_lxx?nWk8htT#Dgp2zF6DfjCYJNFOthu+Bd+SFT&P4sp-1!;|4hHV~!Ql#|7&;OVmY#Z|L+!JfO)Rh5+9!9n%6 zzU6=S?%ntZ)LV{NwI5?UcrXORLPRQ7uG`*)oIkT~TVmdvkhnK(6oOP)D6h|fGcVe^ zyCv}klNjbDfBtm(Z9xpD5F$?c&+JLOVeY&}gGW`4Z9yYcC)}M0XJaz`~*ccLut4WxnCz%fI`S<{-TL%g=r0I*?!Wvs3GIptV6o&6tlEeJ zOPt!PZ*Z{G+XU_bQcO<*hf_X=v`EbF% z`8U_`x4DR4x^w``DWc#Ha=X*2s&tSE+Q-JW#sgrI+|k<+C)OK-rlDr!^1xD?cEIRd zs*R;XIO)JzjFv{_8Bogu_iW(IjgE?{N;5rcR1tnFIGBL~ZNwX%p4=BcZT6yNc9Kg> zRE<;1$jpR9REO0&F+{rEr|xRi3Z|x{IE>Yvz0{T~iWkir%7*V>x_;|cCmasDb0-B_ zv!Bz=HR0R^1qI8(1*>%qjm(Tz9&w$r1Y;5Md2(?K$z?vtvybyiEKShLGSwz`GY7E^BN1de(I_8K9WcvGah? zzgewZdjiaa9b+3dg>!RrkM9w`vt${SfC%sdFATRE@81gvuJH(rzSG2ya%6%f<>fg; zQzY`M=QyQ_mQeKg!Y^`F0LQPe0p%=K6USPtBqpPQ< zhifJARagkca{?kF+XUXoRZlV$n-(dA3v^gjy#0~2)&q)dbpyPupIlsAR?*O0cz10D z33V8@GfGMwLrEl3bkRRw@bxX}V1TIFlgu}U54tMa)Xz?ua9G#B>{sG)`C|pG#%*q2 z-KNdkwNm>_53sSFuX(BTp|DUtO=DzuIKQ>^5pMO>Rimzm2V^hy_69r!( zCe+s2%ItyDO?@86Npm?kIW-l}%+4~WUySV^T)%#OyOmk_AJ3l(ii+zgK+9);SzD|H z_%{4_Z)XeAc^8Clf`TEiSrIPSIrMqqnV-E1oc~9IOGhSX|tDDo&X^m_)+;g#c^a{A+A%#gmMT2DhhMD_WV|V-ERo44EpXrUgVt zvoZ@`iLY&fp|b1dhNG|=kOvZwwvuR1o;`bZx-(RGmNVN&jFU4_%~a=3)al^E4#RqG zNPF)E1bkax?-$ef=^`+Z?Ou$P zLDB7uhK3CIJ0RwamyK^oypS^QXNn^KXh}Com(8+z`{>H|rpuseyg!`45(ieZepruX z+S1wzV|)j$L}X%WFcHbZPc0CM0UJGhVwWMJOP)OGB|aum9v&XP%{vnsf3wNKE5qZm zGLklS%HTzPK_%RL{(KJ*n{}Zyl?R`B)A~)D3II}BfKI=6ZrQShT|LR;>avwh&b&3A zrRLZ7_TIR0gUhy0acbhHU!$237GPNzzu)iQzvJdy$P?eJQCvVZ7MkWwua|IG?3e*f zx7`DGfrt6<`cidYb+n)Onezg{6bFQf1}sg;+8O{guJ-aJt9_gQ


MZJ&@| zy8YsXB3G(q+fj0BD6B3~M}B|>K=Mm5ry;PHr<9a7U?2>?eV9)gXvIKKrB#CL+_Nw6 z7MPKS;yJ_#Yfyn%c7sKDy7!=0#E~A1{Qga1&}2!2sR2M21?afG-_dgK*RNk^P~9Xs zgT%>`zfc>Em3}=xF020qI6KgzddceQ$>%)_9Dt-lxDBXqH^R%!^eebW!e#lgh;6qr zvl0PD#-mFBsv*jClXU~kLPEUncG0O6)3;e!hhg%eJeS@lx{Vz~WH|=^7&xL>mD zO!>?j^xCe(CXn@myjbJ)MWyK8oZ5%wM#$xh@9h-7hzxJAKJjee#Tb5!>UiLtzQMrA z$X$pJ$fGDvQc^YooFwTN4B6l|j94pxV-C*FNNTpHq^5qCZr1FdUBAJ9s$B1FQjzAo z)8YGtqQwKmH(HjXvQknvQw#j#hQX*+XFJ-=f$pz!jQa2j0+8ij_Xr6HJcI#ZT3Twz zq#}lK3q9GV&|M2jkuCs7Vk+-QxAj&Kkg$`ze8Q&ZjSpnhAnKC%Yat*zYr_!^N zg2MNmqFzYbB7X!Ll6@=^0#Bl>sA#3sdD&m{R=JT)AG1v=*Va3-54qkwHl%zkEnU_= zQp^(V{&!COmD+TJF4`naAxh>j8^m#~Y2uw{Pc3X=LfLWh1|SMS_bNYJD4wfVzQ+X)vkogTuvlIC6;Z1-Fq>>^i7k2gb3YTSC4L(P$$Pe|-^3^wIWZm41)C3ivGSJ!4as1>-Dk}@kd}yfo<96SAdQR%;?YK@wa~|lO z_HtH62A4_AetHfqDL_8F(~iT312*hFsr7nA^QWML(o$0SNb5X2C~#diRew!UlHLNu zkGuvJ8W|bsfYs%0?JS1*%X}El>@n}uQtxaN4EUKleHX=254Z&ZtqlLLdN?Y_zNg*} z@FtF^Y&~L@&rz-3(^Ov{3<XaehE&2568?x+dvv5|0$6dM8Kc2mQeV_PFbhlgw zrsQ%MZf9|IWpSV3)^!{i|K8RN%}USP!t zpxwyGc(dH7vsdh|AOP%ngmBybFP=j~W+a`DmVZR@61>)OOl7i3EgSAFeDqKIvR%7( zhah2dpDfi)QfJSe`Bh3G91Sp6b*7E+(W$=O&SQEQ9BDbZD4_Jsn>SnGsT5UJ3(+l5 z#%$m64xEG|U}hsi1{0sz=eFa!c8z(;&Bt~L3+LL}+VnKj`ldN3{5Av4nKOwxy*BSG zx|0saAtcPRA*|de)$V&!Ej=CG1@~+)Q<|u-nBz)T4mw-Mom@KAXgm?jZm5-8kVCi9e>>aPPg&p*TK(CHz3-WgOf;lB;xo*|A&E}sL_!S z*>nWk(xO?AIK@;A`xG7zaUBKO!=&d7yE5ksD_2ue(qCpqdIVf6?jJZ~=3!oVn{GTA z`%7D>8i3JEnA=d#HCkq-ATn~JAR98GO_XLhq)x6mV4?;sZEf?s>DHe^5MH(5^N=6(PR;LZ$4YQ{h^ zSMWOiGGx*V6SR4OAskp~{s_m@k`E&_RhDi4`)7VfWyoZv8m|K(8L$2J0n%(CVG)0y zJ*=#wU`MKA&airqV2nO}`ZSb7ZSwnP8_Tm1_u%8oXU=@@6>LMp)HlU)MMcGYl0nMK z0-AbaCYsy<9TYBH*lSuBpJ^73O|(mQaC2AbW7hsU9@6>Vtu5z*oZrfU%usuav+djn zvW?d!wYP%~o)s#y1Xp$Z_;FeT{BScpeUm{G5;ahM8Ch9Py*ws0H-G)ICQ7Q)S$CND z_d%yrzZDjSjGI&Atb~MxPORAcNwym{yv@iEh*vuZcMPLJAUlCX3Pf~4W#zi-@7jmf zOM2MIJ!*6QDGDERQbS`ak*79FRXTTWwUts}XHpWEcQNm+n`?_jMMQ?0moEW*yp-$m zH;H}n;SMG02veL)#ugSF6r`}Ua9SO~qA&Oo_T{eCwJ8@wytXds%*n}N-md#cqh0IB zVCY14j|*Io*cNAL>DAk}Z$G;kK(HnIKMH6i;t4gg&}J4E7PSPe5|Xy!ivZ<&kOeR> zFc^F9e-D9FB>dC`UNi#CX1x#hfOf9v;5Dwm{=7MsjD z1I`mFC(n@G-`_v&ZeGIH1YJ27hFk{TUgSQ!KYsiO)_#^=@mO^FStS!S)p-Mh@3TA{ zhG`m!Cg6iJNB%vWzYqAHU(mcXNYgl%e0~Kc`Nfkb9vJpG#MsRk5h+>OGD-UpaPrz! zBTJSnp}_g;+Pc7zBP*kf4|qYPQwXbMP{1^u5y;afqu?)mSlZG0C@oVLijtC2e&(7R zFe69WBLO*$pcK7rU3KS^{eoHQA*8-A#RMBrf^y2aMKs}SB+E_HQT3XwPry8h< zF#{uio3rP(7AL~)pXq5~U*@AO4+U*{C}P^&Kt}7r-}?M@LHM)F*woh67J-nHYSnRK z&6+jadN=@u5xSK$G@Kgk;CEN%17mJ0%7e}(%blMx+NLhUc}M9O_L+mKa767&9mwa^ z`8Cwk1fjBPW!yvPoOXawV7RmKN8@%-X#Os`%j9`<^eEbKlR>m;ygImRSH&|;#Rad{ zmEwDHw|188&K)~E@Q}mca!E`fIe&{yrKIy4pO*bd9SNsHxOjBdAYr^hn9LEBE4lUG zFDG=o7xfnF#!fUm$-zYsang~A3D%uEuL5Wi8asq*Z+NF}<~}LVH+2M&=u6pC|G0 zz8^kFfJ7|xW^wxn5*8whyr)DLYYfcGjNo%+1PSmc2RJ#Sfs;u-?M1_sg4jbm zf$Y9bz-qyw#mMv>!HPRT)YSo~meeqSioY3)O@|a1X94)T%#PKQxa7;oeJv&BFap*V z?(@rmoo4)s`UeL~kwMJ=0I?Fz7o{cw@4uk3AQVHJ_25stR^kl=E^dn!0i&{q?~pfg zveU2q-jrrg8>4 z#S@ha*K5`yK_G|-EoRnuH{g5>cDH@rG&3+a@%u3E{6>B7fHiAn7AW$Mbj>-={5Cyh z@4%HCXQ? zks>?=s*Q+S7&a$y(FM-D>vlO9Zqx}k($N)0%>8Bs`mJ5AE@0iY3eL+29uz=|3d0o4 zp*=h{R@)21lj!1mvViM1WS)mtANraT2G(H%Bcl`&Rjv@(3fj}*Wx#&OyWx`Fp+-Z1 z5Kswnt4=WKRWHXqNPK;Bc+rBpZaX?S=p7Dez?+`ByX`5w1fadP6upS3=&d_<3i0Lu zRfwhs4j$ai#kC%CZ?4dXhB4?bj*`?XuydEYK5js>zfWA;L1;>Wof8yh&s>do_yxHS z?=9p5$VB#6k$K#;EA9N@5b!C+I3AWDYDDjA*RR`cI7eChB6G|Y)p^%ra)^WDE}V%q z4&tY0S3h?7a&oG8K$t8FQ7H37qo9OR5%C_mQv(NY-@cvHXjVb1Fz}R+(ag-+#=S=v zsi~Rx;wvibpMeW`CEwZJq@E=sTwcxsAc(1=Z zMo7xfPnKw=o9W{Ohx@_7!g#3?iBqRY_dx*oKJcvY(ic$q?CS1Daq0We@bkw6jsGdP zbn6`AqO78&H3Dp|pzVA?9N5Xb+iumGr1^nozX>Pa$Z|?jl32P%x>>*PdP#{cq5ld8 zF%ek#{f()tU}_BJW+uTog~J_EQ(aFL4-At+vO)4cwYVUZ2aeeE$lmtxk(QSS=_;dX zQ9?($Q64cbrQoqUv1aV7Il{_MN=mLUO3jq7=rseQ3j8GO`${+O>(iyrkZ&Qw>!3Qd z55=sog(87OS1gdFE7sG!2M>w>sxkjISEQ^r{rdfz@CqWs`O73EC6f`Ch@U|nGv?(> zt1Ax53R)R#gN(IvV^75Q$t z{!XtQQ9=ZL9Eh$YTO$|}MRLi}zbNBZ0XKuU93CHkVNiS*j=Df!-p%bOTJbCqOp3r+ zwzumMngFr>yG=!#5XMIiR`ToDF9)!W$OB~`35}&_vT93H1N?Nsqx7I%4kHTOD-NeN z(dI4&)+)^nIwsG5{ImMA<&~9wr1**Th5Ses>;@|SSg;l+I5;>6p8dGnkMJT08>IFE z2No`9Q`FcYEoyl9QS93QV-|qR>_ac&E9YY0t-QAhKZt_NNZa4JU{a;( zEcQdD`wM z-2EOYU}Z)YlwaX9ilwY1MBLBY1;n$`Uph5&Sr5q%Rkr%L}3)N z-H*q7hFWs4?}Us2yxKNVr~A6I17}6B6KAOTjUV{RRO@aTG`IU}wOc5++kVBwsR}p5Jdx^!g>Gc6p8$5`qw|U|P zK$i%bAt^i-Ee}a@_j{-@5Mdd%Y>>#;SDzS>ld@DV-($&Zv&H~0T)$9LLRi{@HB}v1pyRJDNp7&|Um_*fl0wS%?|{(i^8pMi*c%&Lo#kN2{jT{l3<76ciBNQThC-Q4lf&jc@y$h7;wfm_JL4uh#f zu#W@h)iq3N4IU_nYCJOjbbnr`n%00IYsBckeaWXEus^-rS@fZ($a;L}+_VDTo_p(^ zc&*GY`fi|1m;w6r~F?I7gQSvpYQ#nYM4gTW<91<;%Xw9R=4iaKw*2*lRrUjy2;LSQq`+ncs=+qR+M zjGm=#=7DOctr;V4L87`0pnMn=B?^xKhW4R6}KSpqq4ftn;mUtix2 zuU4~1+XUneFziryyy>^wzP{Og4e;m`oE8MdD7gyJF z*$&)z$LB9!-bAzZMg|7^szM3>!6+n1C>$;20$6lD^9@NW>cF#s#S3}Xd{@V0cCCq> zgG)!-9Wp&yY?scG)SpW?wNUxoxkkxRGrq8b@IQYXXt#?Hd`;?!s5=<^8SX$txoS69 z2R74QmAh^q!fK}Dfkgmdw+nRGA{h_8r%Ny@q$3RG>vmb^hVHAHo11f)><%Vm`}_AN zNdAPKDW2Y7(Z%mK=K}yEe(8fbquwskaMTU=Iw*9MjqUc#j0@(o@BSDkD>`d1yVISB z&d8Kxq@-32=doRjkB|4cTV7UX`*2w=+e-9SNl8iRkv0#sj-Ze}g6&3!5zOLlC#Q3x z!Khri?azES$MXu}@c>g$Z$$( zoO>xFLjlUMXH2|Q=HhnYSb6JMuOF~?U|3iwD(Tzqq9RQS+7M&Nu}gO|FAF(R+%ZB5 z1VgL+(FUc@7dH9LhjUvGN?A#$(Ia6$0V1gpTa~V_T$g)s?Mo1zOYTKPxR;D^j_GLk z$r!-C!~VtZ=M`Y9tMlC5K}Hh?pNX@m2nPs8z458Es3JJR;$m+?!og9?oIXu55oE=& zcl`%nz!ozyGKRmL=EOrFuIqhyE{z_5_4M>bnB>MJ{bfk-UQdXUMkb(e+o1-3z?l)W z4je%+)^Qn;)JQXtM1V`o8Q+TBKp(wRkc9_0h?$O-N6{ zyk>Px;rX$|AV2XQZM~3xcBIh9B2Uqk1j${B6EC#cs7GZ(%r~;(U0rHMwf75w&@RAr}ppP z-wx9wy;4unLqM(oW_UV0SjXuW={`c%LyAqr=>xcuTF0`Lw96}IGqupHNV-9QVxn~O z+-9(Ah|rx2{ZTF@V{-d80SB=1^9Pe|U{Wy+4!7SsZ`$R0XJ}#<@~C8Bm|;{$tudOU zO0kiJC9x=1`CxZsW=X9@&ijA|2_3fIA*Ka^#wV3_2_O}o(s{%yFU0Ek#vcpDZt z&CA7Rq5&u?;TUbQzDTdCIv@>f~|U%?SU05 zR!qqfV`*8w*exlM5JrNX#UY-9X8(EtS_IN9+bXcX@dHwCv}f2}QCC&~2OEIoo6G=K zKWdEYP#Hxg(+*5KG(4X*X>wrTmxZoKPGiCRs?IKMInN^GAng8G?(4zVI$H*(8Wdj|ff@qm&8aSB{ z3KS35iZ~_zSfm6*l%Q?jdQ@RhfJINjBj!kq(?@g3e~cw)|XRJeH$E%Gb9~(AMO4%xV3O0j05#V zpk_p1J&>N2ot@nkb?dbNr2h|^L4jDW|KNW!qYsP2m=iV(z~FPrh0}=bw#At>s}Z%~ z%fTAFKt%*d@!sRdWTJt#;B?5lJo@ilRG{J=5)wjiFZdv&inmB4EC|q)0>uKB9p$2H zSR6^t6BfvyFGrS@$%4JSY-4lg{5f=SL@nZ-7DcoaWA@1$!<$@0%mvrm)O2#-eqtgg z;5D<=_yMtcVE=xy=f=U&v0vUM z<_sSEn+wL1xGOZzRe?L(%5(8a-k_v}#qmY1;N}@JvDkVy{jrDr{ngx-z82y+WBlXVk=#H8# zC?y0027)iu|C;Sc!dAGz2%g6TsgG)LvkT1hQ>=F@aY1F@U zQ;Jz}F$g8Zfrljo1;D8k-kXBzlTIPr7Bcv7QRfG^qYYvnCTrd#tOC$dK-vy2U*;xb zwtM$=aC<0pNGIy#^fe^!23Ju*n_7V;i_YF&@51wdel)V-0{&psfh93cG7h(DcB=AX z&_jQ}(w=wl31MKyNfi@)PVgV(sgVb_BjGApdm8*JiGirPVkefkqT=U6Z!Rdfq6O~p%wpy{397K@i5Un0s`s`CnN`? z%*@!q;&r2TL7J{!D(yymfH|XUc{lHM!oMx9TUSiN@y@y}Sh<110-76DJ}&Pl@J5x4fE;!92N5mTig0bP?r8BWsjP$)-%{L2 zyFF($z~}nSn{O1JfBO9S4S=2X;5RQ`>^l@h9UGI4KIdK#2Lwx^$p|Kko+U-kJ5tP8 zoPbeoASjk$sjR1?vpa2GylqCjOc)|Bc2E2U0q$>s9&3j2i(eM_7QNb5!=tvIV_4=9RhMg z*h3$*LaScC`SI1ih#Yf-FO2kuS@(V336g&`4NXq$@~h}D1G+ObHYQzPuwo2py=QCK z4Lk>48TJfoy$D~07pkBg%mPR!X*CE?8?=92`O$INzv|qM^1GKVAirs3l3vL#u^9*+1Fgf_Pc8N26=&%h=-*U3H6FKW^59AOlK4C(bl;8y3-7SB}(1U--i# zM*@N4K%AoE;k!d6EXMOAFxLRTu2@6G7 zHukn@1zsbp;r}!j5gr6f&>BpQu{WzSXPQN8C~j^8HXDRG78(dugnGJvFieO{2j~by z1iO?wcN@*nF}~fW@I7*NwB7(q$I|W!%2FJ4MsR$Qo!!#d(Xt*m83_`)>A6Tgd;0Y5 zy?Z^;kQ|Dof!sV*d~?iMQoTbnJ2G6->jykEAJWer|3`Hn!9)Q#)?d2b0^jsG^%i4i0@7J-34 z=YYcku2Zk8;|ePhO-M-s`INnh2&fF_H%8GM#3^maynwrafsjMk1O6Zm_~FBcn&~4+ zH7u|;QhCN;+@?GD@Te1tJmiK`oO_hY-R$JI<0^SMgJ-a75*V1 z(s(t%|J1V~Tkf26rbBUy3F+}p*ex;$gi0w}TOLwr<=~*z)oo*%n=qAAEx=~;LWDZB zA*!Stmw3Ltihuk3c*QUvtq^ee!`0Z>IG;RVjmmG8_t83-+9-=a4d_n_zO`{@�?^ zL?4<0>Lyru6|_nNnW2a7Rs21`&JOA}3J+j5=+UL)onKXjX=RgSK#y6G`1R4$OTr4#` z*BM5$7D5x|B?TA|P7HO7C+X4tVJH?n0qHJFW?*OS)&V>-imY&Kq~ih=Ops z)J7F!wDvhnc$!`c=#L~s`8qKuUxCa|XQe|cg<2e4V2N$Xz;gKXh3;k&bF;HW2t$S3 zW)etzvNq9866}D*MOAqW33@boaBh+s9H*4%vwty*iL`D2!2#nT?Ky?w#qjX3)fM$! zSJ3+n$O+hh0wN0do?pHwqlNFq_uMWZh}dlbYXE}L3_!BxD_7E8*X|Jr{u~>lh9nVQ z9zB7H=P`SR4sDeH}(pBHtX^^N)X8q5f8poyiU_#L`?gPdoAR?lY zwBa2#MA<1#zJ8J$0LmCiJ^`FD#=p(A<`K_85QYgQ(lQj`NPN0_^(rm};JRTYIw(b8 zs2Du8c=dNcwIqW8^=-1zl}Ru!nqX5DYEmq(ssySC*bUszIhP7kOh`x=m+^$XVw~Xk z_@D180#8bRNJCLs`8{qzn(3OGr@i)mBymVttUv6|Jo2qM2;YbdG!PIGq!Y~hv!`a} z0p!x$dijJISI7PoxPxyfMd1m2Fn88c?DvC$$esy6lJB=X!JaG=P&tU_*Qz;-Y*pAU z?2u342^8O8d}b(?_x1HLH5qr!#Cjpe1LE+Eh-jnH)WvQ)g|-h1+~HT!=KvE#*#-wL z9amR>IGz_A7EpCjC9qFZ5gc(&B59{aJVvt_e3!XpU3gd+Hcc!8^_F7)GJ+hCEWA8%U7quRe z{bLsSfB$S4joS(&APw|jc`!SgmN^{5{4(FXIf*QDM9zyBFXm+4WPKBXrq3Vf z6h!8UArH*3TKoKnamBsBK!cw#_uw88VcRoSD9h=3hJN?MYR24;3EkSfZCe>SJp|$E zKzH@h$nk{h))Mdwma*^=epFD$u))9SzqRoSyJr9bq)(qFM^X^?1wcVwdT?f672M1P z)Xy+5sC=-%P~!~?Xw*=IIJkA2=oy zV|4(I2KgKOIie@Oiz|WsH7po+t*7t@XrT*d_JSFHl=}`lZ!k+|O2@`$GAh`i5rB#+ zS_zM1>}naOsN&+|p94hzxfpvZTY|m^UGyF~5+TzOEILWwBv>Udo5tSurx9dnYu6y) z;SC6t49F;mEpd*Hj-){STa_!U92vPFkLmcYU+*vSe6_yix%M18Js|tXii&+=Vr>UX zyg=9knpPr|A{L@QZQQGP2frAaWkHXq*6#l%F*Sb38h-7|$I43kD~$7TFfFtvnqL_y zD1p9+gk%FMY47Unv=KMRXniDPcN>}qh-iaDiUV}$dqU6kaXbjB5<3ye(c()|5g^%c zW}O^TMX+o_r-U5VJVH5K6u3B9Oh0_*`12ETY1a}He@eR2;jt|ypTCd7%VQD*-DU(p zsqWdaquopQL?gCv(pYZ#qM=01i?4M{uUxlzRhRXF25{$q&$E{`a~%xK|* z4gLr1m7h!9V)Ku>6B(wW5hInzFyr-6mhzxPs?H-^zRP$-lDM}w z1*uO8hxBk#gnVw+ZvOVWQ+BW^1 z-pH&8`DpU#Q`~f-9mKoC*Z>`l0pJ!B^TXK$v|ca7^$iV|r<)g~u#33OFuG&&uVRb} z7at#0bGl!5&$xHPRyK#n-pVmIfP_8QMk%j8HmK!^1-X&!dG#emuXn{c(riKRi;AdH z8rg+}gdhU`nTH1F%&6<=6oJhoyg4+pC04G#PBjlyKt`g+KT4%N#}2@H*B_AXKr(8vn=Jt&hItrwu|JWlso*Z`?T$qD~HW?>=M$0 z;x)l4RsLLnvgRkyE!=^Ev*Gj>A)bJeJva)?%R%IBNXV8MklQa+*nszrDJWDXf2Foe zP`;-esgro>mEW&P5g0v>@D4Ng=YvAuMjTGRyeGTQuTaY~=Yf3m(^!+uUteE;afwjr zN!i)Hr~J0-J2*T%zHCF)k^<1aUO<*+C4n3fl@vCB^-l$6cuuQsL3su__&A{&3SXFjUpn7P`$~I#&Igj>Bk3 z^MqS3D=*hKGNNK;W)>L?g0z{E)!dBZhtA6_xvoqgP{otgMFPYlUEBPcc6h474i3aB zf9xIIzj@6)<@DFbQqXZKu{1<>U#waZyU)}2tdX&77*e*NH86|w$&5Vaf8PXB7v!Ua zpPYh|vK!A))6nSa>FKrkf$6+b^lxOS<*Kc^Kha?eI~6(s$slrpNqHd09qD&@v$uq| z{s~5Q9L2a_WmWSIbMvc)j8vLCm?{0XTTM+(KXzO9egAIWe3|DgZ?@Ce8oWxp38sC= zACs_!ale1{>Jnc+zfR=k`8740v$C@8$wXxwkoJ}zz1Ihj{|)&N&W;lRL-M-OO;P$l zhocV9*>{(>0qQ?ce5%EOwK-96!HD^yM|wer}$z^jq_%^y`$l47sk z?Au}R`Pe-6I8}ja#mLO0O<84S=j3QFF1wAo;Npb-hMYH6Qm-$Z!~DKO>Bi4G(-%Dm zkvPC1-;*ZyXMvq|jR|jjVxob$IZdM(pUKtDRBLWW=JS+4kiji!n$y>{xJEvS+)2H) zNiceeo+@nXc;UYh3|C<8D-zqh(77U(U$%ikkm z5c7=z;*v`>uWW5b?%bN?Sy(7ZSTS5iLi4WQ&AtpF#>A8J<9&0y0ay$BYiYlf- zpw)Go?DpUK{B*HT5iR?|M2jCZ^Kzwr)$-v|%?(A2aQ4M5)h{u`*N zsfVdeglbNnI;G#tCtLjig%hjJA{v!ARkC9!i9PNR(`1?k4dQaa`}a##R3&wFSx{QI z_4TXH%h;@+#o`esg&q}QXO4eqcazSc{By*Ut<%+?Z3e>waL3w_n8)6vx#ZnHu-BJb&-5ZS;@9GSYdcIz8Cy#ssU_LGy6C_9%| zM2J;-bgaU+6;aR!SHodq6clu0=gXLwcm#60n>_Z}x`SQ+xF4`U;!q(p2Kwp0e z_TC$-E@R%(ajy?a4%{iDAB$KKcq<=p0&c(L>U%3Ap5bb#sewBSxHqILn4Ahrc*N*+ zwW><#x$*%u-t`;Ow*2#Vzm#J(b7*CFU@_q6o$U|h4oBu3781IRNj5Muqb@BiMQaun zF+Z88U(#$2+lt>|(X=~m2N_GFT|Y5n`uUyB=N=x)aaHlNXBklShN$Y;G8^O@#WeqJ zLQmdSK;Y)sm>v9Tav>G7V7Yi?9Cm&nnIt~n^MrmSziw(HJ4_vZGVASI!QhUEtFC*Q z@vW^KZE_W$T>CnMWc)Z=(1~Pq!@{i_l)|_!&NnPZ8oc9?la-g>wcW21br1D(=LET! zE=V}<-L?^Xyf0h~^+H>72jF-EKGi=bl1_<^L=9GGoSg)Jm6psSjjhT4+*>M zt?8f_7pyEajA%nIE;#9}@g?U%?T}X#<@)vy91}?J?hTP8bg|}3Xqb15AaQkz$;mgQ z(VidvxY-vVV<208HU0hq5QX{%1{P^>W0sq7*QZa|=;~CU)G?vz=x~41DHr2AGw+ny zh%m8SR6?_)xP;(ab>R>5EIK5>lGCK8rx)lJfu$#+kBZv=zeUwOK0Zcc7DTQ8iAeY2 zpWun>S0{Mo@Sn%U%>xUD&WOK${ThArzkUB6@Hf%=-Vg$@=aVii-K7p@1&M@j#CxBE zfsdqv)eyed0fW`#rke0qfmMwe*~I!+DmvkGncw6SyjNaZ8wHzg0R+baM7h(Eihu7C zk&v{b9Kd11g3p6O5r#?2%&ZJnGpF(5b`;71S{s2Ikz^LWhiAx>ES?BGIN2#K{oUI$ zcXg$JgR>#Uz?NefPW`_r`wcr6IxDpb5KT4tULLpKZ*_P>zL6gvA1}#Bk*=Db#Z3TE zB=1$Rt(X!;G`8?P`8uPB1u?v}Iz1ig_cpFFw_$BR=KK$F5(1XbI5#BW~D)!Ixqod*p|8Gkd{vB&W$9mUemHvu?psIaMema3ulx(vV}q1FHRtj<98dd@uN5GMeXy$x;Ph`@Ivf*{BE6IyKyeIEHw3vg#km_?ES z-Uj8>pyJhXW*r^Q7M^FXVzX6b`+eIkfPwj`VYeW8I`GO`#3jAyi%NKnmH+-F>g*X;IgL3m6^M{1Af@RD!ZP zo-EKrJO&dxcPevp7r1z-+Pfpb%jpV{k^5Wx7md6en?U_!iS1fI!vMgAfBy=PjE)BW zv3H!9`ee5mdOz}I={kC2pgjxvjDUZwahz@koa8aBpsPb&s7)Y;53#`cHwGbiikKXh zv|iNWatkcSju%5rPUBvSC=w|MCUXL>_{vqE2lDdr;8%l7*Egi7AP~vH;!5c;x3Red z?!R=M2|20`*0ybGiUHDt5s>DbgK8EHo$BdG_beSA>e|xS($X7n9L*qQ08XBH72bZ6 zkri+?Mvw8%CPLMh6e*^wdR74nIo~6wL zfK>nW@TR=a(+G1jFdn?TyimG`0VoH2&XfP$H81~NU={~1s;D0i~&G& zx+{Glgsy0qM~g}QX1kzyhngESig+g}B_a|5(JV_!j|q8!BHLxI&mRecxtKNf})owe?xMp(1G^;j?(l2-oGH`sC(qW%X`Hr_%g zlc!ZEPcQth%lYqog3Z8_-)cYbhY%806XpUw1?FI*T%9wt<$S%R)AaPSX%@^GTD-io zZhArYAX6$%B>9fGc%lmXT>T9IJfRVmoc5VeS5kyJ`z{Tm8C-P}7Q!8S$4nUz9~C7f z`9I@O^%O#joJzHnloZVyDU<#xTP1MDfuaZ{!vuy=Q7UtJX_W*#k_N=Lkbi+*0UtmA zAcxkP+slFH%ZKRhqG;DOdvP|qlW=jEfHu#76cBU2zP{{thxqUH#>;q!wkUCkH|TJs z01HBvhB0ywx}h%Hrzt2@J^0TGXB>l=N*S?%C>c^8aRem;jEw1m+l z%sqS0O#sODZPC#1a5(&L*37=Glb!zaYg7aqQrK*^X8kgMGazh@#6&mDIt$CrW-Tr) z{Rto*4Q$~g3`|b?7Tg~}Ly8P3{}_nx=RvJe3qtR5Qo45HCHPhFP_V!7SwA*61A5Q( z&jB!g`bQ0)b$feW9x4!8+5q+#jl#e!_xf(;{u3#~?t&SN_Gu!yH+fO=UjI67hk$_` z$s|g%ME6MYF03d?UyEy|okV62kZ)n)D zw#EalD({u1VIc%z5ky^3cGLl1ZvII3uMks0*A8q`h-cd?ianUwHeN1enXd~ho&5mr zV@O!DXgDV!I?DRuKS=w4lO`68uAt!|5K4;K8c`x;(EDk^-)k$+q)Z+^7*-EVF53$g zh5{Om<}C;!wtP6tbGZB6{SCRneKK@;uZwpG)yPFiGQ!sQhH5L}H*Nj|>3t6eQ*nSGkfm~%)b`u|eFefW7^sJl zCuAleWh5w$B@Tk#+!_)TBQtZ?+#HLWu~XeC>?sHo$Ew#BVX1*08rzpZ#|>&~Y7J7P zaN)wr`ue2D5#&4oUo|e!v0?+%f~`5}TDM+b>w9oRS5ME==)<}=8qtBjclCx-f_Aba zBOXR6D(wA}ld+47R#Pp3%x~3kfv%fmG89h*>H1Oz!P7dR07_E@2D?je#1j_jYFbu(mmHewa($;sqx6Q zm=FavbgT;`As_+P7b<2hF6iw7|LsmGNa^nEE0k&Tpu=2u0XqPvF2>-0LDyG`p{T6f z6`ytjq$Rk>23#tzdUs|H;LLzOF~*7kW{q)lao77gKmXPQ={X?OI{{@+D<1*-^kj4y z=$?*)GlzNIT1T#!oZnujTHQ6JLPVBb?xpJ%@J*xcz<9xVQZCVz&(>&#oD?{T&dyG= z$^GD?N7)aq(!|Q*lb=cTExH01Ik>j;W8?8&etO+ z!8AMa@a)6L=LMHBR8xr-U<$>j`YnC+@L`9|E%vwSaK0SqFOK|}l2xrndxwEh?5RLG z)Gxc%8F!E&zC0GZg9`fkq!J>4ttLnG6Ok!uQsoV;Iwa#~EVHKcY}A_<+0X%O41k7V z7Qmz*&!Ev9B*-qO@7z~@*ksa$?&EmaoPh4yQ82phd){;{44Aa>a@F_V#;^s~>wyHV zFWowpyrfk7J0W1de3Fj7VZ2Q5U78YJZJ0)P`hf8$? z+-j*~6;-YQPu0N=ap3a{oPT3ZAH3A}Xd4EG8p0(Aonu7qGj>HsC{i-&{R4cnG`Qz> z`=q;|W*@lH=Rl?{OggoE2G(Vq{~~I~pBX5PZ3)t^kCS%AfP21)y8n+CVe?Vuy8o_q zWrZ8=DiFAJD?B5EiT&l>|1r#|@8QY)G>VvWI&P%jmxufg0S+t{d}#;D;m!MKc*41V zgIqD+{p;#Ozux~PCnI@~qLl+t*yM9+*soIh1OM`%f8)c*YWp4xxNG9w^K#gOZ=+XLK4xX)uk`LVMy1@Kbq1_Y-#=)r88Kb^*0k}VO?g26qK;6L4n9ppY8mnUjlU$3g zbt}s(z(D{dfF2OU`EY6>uyQCaDcO0tnCNPJ8Ev(J?_mjR1)?H*-KT*RG&mFg!OH<( z==F(?M7NiE>CyHWpa=r|1ejHg65UC^Fog|rT;Oa`913900A74Xb9^v1APOSob4ahj zGXMxeo88j&p8)3IBo#jaj(TZKBHozcjOmfSRDdk5BV4`~iPc%jw4D**rsNE=HC zqe|CvAV`8U>$eHN@qf5^AQGroDqLLL?ZX{QNHjbayaKQ(E{+&NEFdCCl=3aPeh+2# zEd!I6_li$GGn|Z;k#R9`1?#@*rP+gAY2Y>iZ0H*qeL6lC2Pfj`DSE@SnW(2?!oL;> zAjGx~KP=et5rr0}90J)c>JGO>%V zKiMV~X7V57MgH1qgO(voKIh)hCkWKgR2uN)z~^6mq4JTqPl^x=r*9X?Yd}`n8Zshj ziXv&BAq2e6k5MqoW+&;UWaQ-WE4%2^Y6?V}|@Jq5*U3~q_o=a4B& zhm8(-AbXKmxoooZxTgC07ziqGiQTTlRxkUfE96pAkCQDe*dmEK}EwllEiosm7c$n@KZH^@Xrsc6ph*utKM#l?X11{-WbfOBjrpQ)83^p07@XMyNKk1fTRoz& zp9E%G2{@gnPoMsvfjw@`h4$I;H{~g#=vxgwf3p4jsplPrTJO)}M;JY3gK(7pimb1% zgT;rr{Q6jsfC-E$0w@4#=-Q$3VaP#BE9VS)?dJyfYjrz3qeBh4GXg^a^gTp8pMU?p z4(_Yes4fJiGQxd}+po9=B|}g|)gFV><-!sc#Y02X5oD7J69nHikm=ki33<8(K;sI^ zy4!LMJ2w$B3e1G8?Svh%S-y4#NYC7<^LH@$otN*oyGm75X+N6SV}-Gc{Ah|_m( z6(`?&Y{%K0IqDqHADVrvG3+UAdDpR_WpYc+IlcGfWF(g|M28wSrrGWIPyj;OJk$so z2`1$xlSp&gfhVT43If(y3!KTSpyGO^$^juL_>`A+VPvp{ zYQTZPHmN7hzao1^_Lbp)Y4cQvq0=jf992lgnN5lSvI1Wt_?8F`sv#>pnld^|q#W@o zh@T^m%Gp1-o=}^ibuYO7L+hRnfr()o(?7XKwCw5d9ZCY9nMDT`)tr(imU0XMjMnw z0I;&AOjxM}^8_>u%ubyV3Cf}68DSob!J8iqvb73X zGW(P_5(vUEA$+?;tv;jx>jCsPBsgKGvb``<<6&c)cm}(4MPt|RQXih*H4UWdD~4b> zoi>9<9ck}At%t-IDQ4-9YV2xzl@b<+`-Slr=epu@H{+_1l3~i-L?{NcGU(^vb4<}X z&3wH~!1AgysA>+CCy=w@s^irkMkp*Yn_I?(9hM_JQiLzEfnoS6E85_pJ$c4JnSv?r z)GyM6+eG5nexF_$47phJj1r9yWFzFT!Y1$~Ldse+d*zRr^2&0471r(<$rljt%qV2=Tr1EAD zJwvlGzrG1=t_o?ZO4tmG{9YSYc+{_hOQN9g18y+q9eCTGy+qvqQPsuL606!EP8RCl z013e11WpOei*H%nMtnTU>F=k~p*E>rhuf@7PfvYUk2GH%y zfQQH#ConW*2_Gh~mjsc}NietsMxJK=`LA%RbCFr@^^dw*A9V*mY9U_7^1N2N`HPpL zRABCifE_!J$QG9cdk**MH@v4Txb&E9CNf0x<9plG2nxA1vUW$my(MDDD`$q(OjNaG zTJ6CkrUcj*FXM`Y)0<|eObY7!DG{uK1MVF{tTlnteC=zOSaW3LH|yovo@i9$%gLn{ zj1mSR+b`2)EDL$*Y-d@QckZ>vMD!-gw>xPwvm;pNB5y|i&7CCOl-u@_7ty(mPp%`5 z{UH9iqv)xcCibh(;`Y658l4^b39&-cB)CFSKX1-S){CQ=heFt@pl5LS)71MfLeMJw zQ7%cD7XJYz4h>LX+cs}q{0-p)BZp=_fvE?K$vnLYyhRrLNC#vY~C;?ne9RA!J^q&v9Nq;|II$_$;Dmz<0+4?Fv>Co=tw zFSdN+ihSEP!uZeWQ+k%x2{CkrS*#9mvv0eN*;WoG@%Z7xB@QyjaV%CT?j;V1i0lGc zvIQy(zDo~QoEb?A^bCqvsjxJD%vl!xcFwifEq6Gg>wfZ)ETDdI$G$mWA>b$|5!bdf z=Cq=<()}`4>@B|;!_SMX%vd(e?@2!90w=Oj z<_)qnf|k9dZig071#zSu76tC zxk_0Jl=plWxI&VuR9?+OLJ0%i9qZxNpAnJvkJ^-OL?S;Tt_~MyYtW_bPz*ZRFDXCm zjhvb*TZ(gDbvTNVl??jZ#6pBWOLUic``sL|*23q2eu^)V%sP1ZQPx6D<@YsnjN~2?uW4903hT&Y^;la-&NtUtV*FWSwry~z}X{To(Y zruS)`O#IVc^N?~B1d-7hsZdE$CyeUA21r@I^?a}B&~;3)^N+c;IwY{HFCgy;Q-axQ zcpn!ZpEbvugotiM>@Md^(9nFg*vXxUWL#n$Fyy87n?;A2H&SBH!}t>0d2n=efYS#a z>k>7%72!BTF>qzhJ1trYZY)Pq8typfhjML!-+c5-#|jQP8OFAek7TZ3Yh$%vMl=>+ zV#o|VIT#T=pO5ged}hQQ7Z|}TT3S}HO<2aFU3v3?Y$&p@pNL*=APb+FM}m7Wcwt1d z6a&fj;v-RkPw~yik1#b@g|T$i!`CrhvyvrT)6ikD;Zd0+u&56zE(qs6Udb1L6VvZ*_=w zicpoPhzR6+(E1Nel`d8AGmzYZ>V%L;((1{?70^b();uVEeMp6hAc$XpAWI<|-dC(P z2q$Ah>OyM3s#H#_>NZU*W7G*CwZEl@JSkBm46}G6-2?%5isnyJT6B?_@pi4Skd z#Nl8?2dDSFPB2LnC4NAYbF(YUWu)aVopGec7$U_{;8cH@HIMY_K-|men}4me^&@1S z%E`8CCr0z?>mO{F%{rLX_O+XyUyoLAtaf{(6C!zFZQ8sOoP$8JWyL7XW77#;!rp!$ zy340SsGEajnpwSbbO~$Xwd|K(^NvX`&1LROT`vn7WLGqhcZ+{XQt>cp>&S>xs9wkV zl12Q``J+$2!BEeqo%m0cM=$IeU87((_+br;o{)8n$gNNGuJP&59BK9A?+wts8t9;CtwbTUA?Of z6d^rXy8h9@*YFNym&=?ONhq$kE^OY{DJcL?rLFIG=t7E|S;7mQ(gH=r9PnO%22UoG ztO3SCh@rtjMAP2=Vacow<-q>(D@cG0SzJmnL73p-m#n6M7xRjOo|?KPkRpu8&Wc)# zpfw7s8S79gEXQg8khBP*QxB59C?}>H3>nwT6jJaE2Lc4N%+^hsUIjhDO`DVp=kfdd z6#M=G^2;Y3B6mnbQoX5fO|!?@UO(LW?mkx;fOYe1L8Ok?ojKf3K!E>?3Y8JF=*=I6 z79S3nobH60ssbW0GHtif=BMJ3(%og!{c}Sk<_66Oqk2n0t^rSb8Fi?#QURF((V%BG zzRc*Yf_e-cwbldn?nSm!pIqaxE%`4zd32%M?kcP`N;voCF-3S)vV@VW>@4gCOP2P& zl=c21o$YB1=Zn5L7ejqo0&(PiqBUW|S|p|kKLiF>+XivGFlouj{Rse%uWW2gdmKT| zWTn{)%<)>Pd*T=<$~?lqP;UsNI#AwCo&(Q4AP5y zW#ZiFCoFs=E+)*`{h@mY>WHZOHO41=Rbmf`%<>q=X_*a=V~c>yh&r%Nlcy^H-4?xH}Wh`@|+v#PIScCUW-%3qShd`ZjXFV z-|t50^G!)_;*&;7d@u<$qYDnNH))G+Vte-*-P9l4EESngAxG56pr8ncJEvMGDbWGH z=S$h+1UW(6K0rH!lMFN^I4-Wr(OjG|Zc7Kel;e~No1KX_KMEj`X1+G}=Ponq#+836 z$E!63--aQP0}LTews;^GgzyIw05EVZpn&GKhjjR90qX!nOTz@E>ui~QHQ0pJ27E|u z4Jw?}_id;RhiBA89cF}(%oeACe9k~{#hW2#yO~e6<3a1Lp zo->PHTzEQyMs3cmB|4adxM?-ZHCHsh{Rj0*+;`;+?9KOnwvG~6P{P7t@L~S%1ao(eEakz_W2(lI_ZY~@Y&Oq`Pru& z5|7$bI+*MirVZ54>7{|0N(XufLLfea%p$NAX9Z+gZ*#cC0?#D?)j7^K$3adEO_#*- zH>24e^4QNas~#v_wBFUCd`$3T9nhktLJSjAQ<&FYeg)zPM6xIu$Q@h8qTwBFJlFO@ zV~E}nEdyyH+nX0G(>z($WC80ExZ_6EENLRy9Y+W@F*Ot6jo&@aV;@_*U!U!d+>Ls2 z2cMOt!$Xd5lsH}uA16^NK)UHU^JYUqeb8THe8or&%cw^*_YXP~tEfH+w+d5P#~m=m zu;r}b&5|O?0uHi5QVC^L@LOV1if)}QZ24=iNr}YBCeGEFkSTbP0A zXH?!zPs|wdvSz?nk+JUAX%)24un_s7Phc6!`F($VMZExCVguRj!Xcpq34CvEmS4es zM=!j+Je#)@c;13THHDq`FhYPXIMI#u6JDdYeE>yH+l=Z%L^i_KQlOgodjMI`-|a&y zl8eQbqr<+IwbtF_``;um&L=5@6|N^dJCpjBVE^==;sfT=vNBSTt^$7z1-PKHnH&;2 zRaR2UVI4s0xtPzl@gNL`yeDk^*Jah!I7!RiAO!)*;XwbsbA|#f4|fdakg)lrhg!ZI z#DnOAk;8df#s*8l%R%jVnOK{VW2`vAipB1BSSS^{!AX7hlF*bS*I1V0_PTdLxiHaH z+JR zAC3GQBHJ}sB_-@I?ZF}g4sr0+v_LJt^DwBQ4Y+_V`(Ck{dG z)**Zk)KF;6D~NE=npa`|&jMLx28N`p{N4hN`YQ6ZYVLKl$ zn~SdN)LzgvV~EEF||q0MTTaC+e_dEg$?3M zU?Zvro~U33NY<7na66OP5+%we=IE#Yvo)WdiEE)Ksy&W1Jk;ARPPwj~I$ezNxW?mn z4QKTx8-`NxgpDo0Wq)yGcMGhizRp?ZYc8@#UN58G4m=ISJWF@6|5fzH+j9PKq=Ir| z%;V>Luh5+BL|esmP&3a1tB00h0C54FT2*6PDgF?*CtU94E^Z2Qvy&}g#SYUzX>%RkqsD1nvN^=Wbgi^yD}INcU>a4h_ky`P z)Yfn08S5*h;gDBxNR0d)Z)t1Z{I`Z75C+L{2lX#(uPfG?TuypTU_6~Bde0IIL`iov z3u?FR_Ij@n3_AJ5drZz z{1q_5of)Ck)wf`eqIHYV2bRBoU|^@sTpp+)XR~MdTCz7%LXk)i&%msqmFys$fKLQN z-k_%f)ENf2B3u-g3XsQ_HgAF9-)Tq3l3|M>t*&2#!a|&P8B#B0(^`)gJ8292zFzPo zsDC@N)NM|^B|hxv+{r}3R3x0VZ8n4Sbb%SWdD?kiKV23_(M$b~<9kt3Bnb~u$jF1Z z?g(dHgDP>dG_xBp-O zdtT!-+xhDkkc@7^mGcf|4>|;Zf-W01jJPFQBcr85jdD<~WCc|XXsw_gNsSkM1K$L? zIAldeU%yN~!PER>NBd7za`zfKB5lXi$nA%ZbEmbg4}>~(+K-i!-jP>zAhH=@H50k< zOoF-R_T|!b*-ygwJFHJ7!|gtel-`xTHdYpR;oe4vGgxFE@L6{F#mDDOlh)0`_MqUQ zQe8Atc{aABdMrzLU8VI|$PrZxiJ}gMVq{Pd@^Cw!PTTo#hJ^YGYhBOc{D+RV8H-)< z7?NyjXDZ^F3_TaC#xTdBX$~rJiI^QW2|ikj(l1#^#V=WLZ!mG>Vpe8z21e8lWj|5| z+}}xFdB(?%ilnKy_9d|-Tk+6ak*8!m?Ho5`0iE=~BGTuY#ORsvEaHn9ZPnKNpYa=R9PYoZKD@L4+O_7xq@j-Q@Ie658vp(9E$xU0Y|%#|m_;0_dsZRdw=OMdC3 z|B@BLLEAVz5!yX@>gjg$fT7CXj}#vxn>z?8FV|+l5gjP_erLS;a=*n4Uf3->wP%VQ zCK?hrG1@GC7{hw3ei({8vMlp>Z3>4+CCr4Tt;k0jlGHIpGJD$A8MvQyvb^bpAB3(U z)7q4-l3gP7&M}jVd7YSZTLP}xgRD_a&1H0L^5$$y0%U2>JQ=@9qxF^gVjDUTZTva% z6Ry1?qgDV)5{NQ->J`{96m9%B%u=5SvmZmZg<9`jPT-6o2^{%Yux{fR9X8MZ<4Hbh z#Vx2u#;1Oe@gb4Qi)<;T2Dfq1@%S{vQFwRnIvohiZz7@Cv75Mmd-(EEuw%zS+nIOGZ)(iJG$JV*+Ra z>;=UXAZgTuG*I7iu16{&hX4=2%OhPX?y$i1`t#Ri6>#hGPtXxUibP0A=ny*nfmjS( z83h7uA*feko4ESV`5Y_YV9Cxh+MRD0Hrw9yP1KS*cBd_*T-g%H+8Dle5;tiwv5f}Z zQH+E4)G=0vHQY}-3-Ic=WS=APiJ+yjg-8|^ecDOd(=xS2`5TngQnn-3;Z(SUa@g6j zZk83Ak^}hMjZ27}o$@U#HtVmi{KsQYLx_1FM)s3&J{;$y$*n zS@vyN{Oktts(RFh;Pj<)1sy8$YK1WoWa0EHwq*I^N_F6(4ll8yQ3m9c;oQIrvSa_G zQ7DPsNDNu7MC@pm8C#aqqTM4zM3RzmkPL^(SYmYuJ!ZqhPV5e{kTf(!wc#{QF+0WEjS zV(QmB_7*d6Z{Ag7p{c~Ug}bWFqD@K0llNEJ`L&`~>%GuCjvSQAz_)mAFEZII7AwoU zxz&mIBP!g9DrO6X(VOLF-^Cc2GJdwjdKYx9ZB^eWe%-%DXR$~74S6Z|No(<20VJ+P zH7!vW{*ykne2zrxOPsI^R&vo2aL_C{zf0%k>iVY=pteMA9%?^8G8(bGVf4ahz8wdO zQ)F}uO`YI&?0JyTfTwH^0QnwdJHf^%6>7JGOu!imOh83o2KAI(w_ICtVh z?|5$h^UqnV3?Yyu28BTf-(%y z?t64ig0P{fV}pjxw!xKAz>)_MY%v_UJc1ziEhAAJEW(V5v9qN4CduGIgt(<=5%4*9 zePR22go<+S+7sQVAQM=Cb*)|`2IcE8sGfA0=dHP;=>V#>zm z3;1n^3Sd@{Yv1y6cXRh-Z4pMy8skW5`m%`Y8%>87H3U_kxKlldmW$HA6`{|ETS?<* zuTA_$M~E(CnnLNYI0_D)j~>h!$R-L#J*8~Wn#(&8n4pD$e{nYU>~aT9>7CM^MORQz z_LjZu0Q2s3>uo7UIdvfu62zI^(7c+A4M1G-t#;v zK2c8b=i?NTd(_;c?0L-1UVaJpB>KYpf3Ebc^zXY82nX$jBqYZX_^pu1-Lbz)hd{(U zY4;@1=RMv&5VKZ!L*O&Sqn%$j{DPwD#_W+gF+#yt`O#n5#%s!=?a=|?i+%$ffE zFXoD*cyw{7?UpN-5G=a0M2v7+iY(fS;i{XT{S3rN?ObG(b&yD;J{)aD&}j$=3su2C1m7}_LidT)lBZ=)1+Tn$e`yj$p3s%cI*=K7emel}A?iRg zB=liqlSu5KEDKf;Ex9nD<*QJg#!&zq%Bq{sr1(GOE5pVemvwYJ(ZaWF=!d&yz?fq* zfkK9DOPN9o=u!9ivoYkqrKhvEen)?{m_%MdKy4!8>tokZ_xCoAMNbexAOr=W^lt-r zcOPYoi=e%71ub#_4K-A`f(|(tdK?t6J^oMzv950d@B`JxbxS#S3T1VI_Hs!3QoJtw z#V>KZ4zVflWx}?9CE<0S!+Q9c$|c3{exh$>wFTl7J7Y7FDo8fqd^L2MZnj<-V^|^* z=DhWLeAGA1A@l?NAFF7$ThTt(BJ}HtSj9dB&)n-R$bRxeL&d@AN>+mpnZ&DmV^;J# zS_~co5s!qjy}F;^lj|x91hD{N!TnZ!vo`wdA>_H@)0U*IKFFAHt-94)sr&_X4NJaX z8S4P(`C!*W@>;hDV9`o?gmw|KzJzbE0R$+Z1-q8k&Om(*iX5;SrDbrhM-4;a(1&DUVlX-0IwQE)1xq zaNCzD(B2KLBS(nzrAmk8wVonlQ?DNQtxH?-Y6xG&x6C8G)}b1DMtBAFqQXUj$!}KP zi6?pumu%~$M%}EMZ|eYq*j>D%$99H@;fLh>ouPBtkFRQ~w%!=;XY?0xv(}bIKRKIi zW&$I{8N|3NzfT~~{~Q|KKJ1stRC;!j2kI6m1cWgvoSG1fD!e#*`}!1HiW#mI>sM7&)~O`flZlR3+Eub| zw%s1vavl?2OCR&G;XnM-^|Vpv`(U0G_HPUh3vO??hRkMRg&0v?v1i&;1? zw{f%!mFBSw1>l@+kV4h%>L3TY>K6L5PbOM-2%uGhQlJdJH0sWp{|Rg}$k2eCx}ziC zKjX@P2R3D(7$_5Bs#rw;sZz}FFk$~Z%wK;6OX^00hdt?@zwQKWS=1UTN}y^M9{FDa z4zGDxMs@Gwh#&&L9k=f#+1Lq6_O6=jxBe_^&PH3Bc0`^At3Ronjb2aTb^w7&S$wUd zd9{UX_jS~F7nTW9bNcu8%Ih+UxsI(oh9A4*$Z~eLbYo@rLbq9qgESWB9p;tXv>~&F z_IM2>xA~G)z2GKjRFAT=X9il6G6$z<-CVyJIKf5_;$cLbid6Mz$l!fwA z*6YdXS{-8@jUY;IYb%Z6Hq>VvCTOF=z}HLi;#Mv;?|c9SKQYwCCCp5v}198b_W6yDk7an%&^ z6aVue@fYd65g#WSj%ddGyGqkxN++7JJm140* z1bK#KVYKE8iM%FNn!!7=;91?cFn6@i6BD1c#l6d8)IStjVJk}2RsR=fm!AdugT{9^ za^>BFNfc7`Qos?$w>P|GH;cc;;OjP9^M2%xwQE;4d3mk?uXdMO932%Bt5P!U<0V1XEx?wOar8XZ)%ROH*!)impr0S(_q$g?Is;gg{ zUp`dpR7jDqn2-X#T*+Kq){c)bonjNy$0ja&24X{Z@pQr& zUc_?#wBx#Gz_RC$4UfIiz_ZcguMYwSiK3f5w=zgbNpGd!Pea}9e8Z`K3JvS4Dl2n^ z@A2<)OmRaApIw9u^8r9F*qgRu49yEom_ccguyo1h&mTKnul!1d@$9DZ7R`+UHC1oYa>Ldv`Fx%^m306Q505A2=Z}*nuN^r>O(+~sU&qi8n}oKv$yVbA^hKW+ zK_Y1*l146!XuTuTkC;;}?^NRq=&|BAojo|UL@*=sSBH_Yc0F%un5)icet!8vTQt}7 z?Mm#86i%^65A_D=`{J-C_KSKZQ529?AnOOBYWajmA3 z2)zi>B;sdR6bbY;@h5pv&H*^X$qRaJj4dc&>hPGs;V@p@5iuWjwBbb9@0 zoeJ-)@mx!?8kW!cgCW+-CL_jctzQcp0qVc+Oz_twdGIyaI<<8VqL~Y&S zW&R-EtYd-A&|e}ZRrPOheu*U|jj1*lL|o%Fnk6N?EJh?Aws!D=Ojqu0ti$kMT;F^} zYpa}EM@IMP1}q~=S=piQ+C$%~E-~jJ|71&ViVl;W4G8*0`AIs9Ya9ioS$TTatP%&L zHZ@5`$Y5=~1;OIHb3tzIRp=J+)wgWkdF z(I=;uN;}P{bgZ6l#BHU%Zp3t;Mayf+zvLjzUzFMKT*vu7r;5Qhg<5sq%-cyS6)r6H z2oYhYzFSUxd#+nn)vPM%Hp*w3rlA8e@H%rb)x1)ILt16re)1d0(qk|V!f(~tOGsI6 zb$%?sX?!Ym_V-~pSygp4hg}I+!_I~Bi49Z|`=gVZEr{j*!v21nHIK=Mydu^2Q}PH% zYdRv_MlP&Y95!o&^J)n1qI>}l-Mg~-lg5p0t1az%mgN-X^2|tf!Q;Uaed)@i-TcQd zpZTA9a(x-o=X6|W+rO}0EBe?*8~!;d$Frv=<@4D4_I8{y?zi2v23#1+?J7f?+VJYz z8c8OVUAy0~7U#Q`aIzNP0ItrKx}^Fo=^rhsnLqwawNR&<5z&!NLPDbbIzMl*jRdw4 zY;n5{ZG@5OjIX5kpFEpnly$7gTlH7(SEDCe{EoC9y}owu;SAml8BHpmqd)meyGI7C zzOO-^z5*3A6OcMQz(8F7*R8q!`F`!X!O5GI5?lg$%4=R9I=+21mU)_05}zDrS=hKq z_(MtLKGpcH>2csKk8anpxhAUOysSCGYpU+vZQuTQ$HgV%mDT#Qzl}|Mh%x1*)Ls9! z!twpG=WB-)18=payAPT)A50e;8fW~as#D>7V>QX)gwNu<0j!}RbTAm5pU=+Q%gUa1 zG+ipi5L1SZX$w30Gbc+I%jx$&yzOxIW2pjB#&smKbF)dKS2m#Y5s_7QzE>I2fu+;a z#(O7cu``lzn9(pq-0o`f4EKx2Ycat!w&_$HN#)0%E49WY3TCBR@;AQFxf>{nsOJ3< z*A*=OqvMMt{Gz7xu#AnLI;K#4s<1)d`-rbI%6UO6=dM?&i$6et)oipEi8%)^7uj%g!ISt!aLB z%Vodo&Xd1lY3i#maEF@X_(7Sgf0dOLTW%~Z1IgS5-;z}0gn#uEZQg#dF%H>+)tn9#!u=9zk7BUT>v-n)m4Gdw8YPnA{Nc z&Hdh(>oKDHbV5^f9VxU?@Y4O&Qekn~6X{}Ha&6f;<44$pv03P>3gD-dMm@y$Aqe>H zPeZZO!+RedO8OmYK*RH@yFSVh9rJ~glN+e#H|a!C6J9l$8HxJ{Po34d6>95|_b4-z1SsW{L z3r|%Io^!vVgB2@dAw|+s}Hp45Xw(k)&b9;3ETv%<7bR`Tn=dOLV#w^V6zH3Q(^;cz)jO;pzFd z7X}+dkA`UZ>!`d&ZY%cbD@w;>bakUMcInY~2tKO>?(Jx|9K@a1F;!=BDw#HerL9sT{~<;g}LOyYCxM7ecF~ zU0ip|e=Q{$vr7zbZ4yfN8WendbMVpHU90-;pYNk3sn69Zg?|hap^k+vNA^|i&Z}$s z-3w(yTxR1gu%_lQ2>&5{;^A^d6ywtl8QV1qMXS8p=gF_W8XP)L)DffV{7!vBV%8l1 zngHuL>MW+suzQmb=3kWX0u$GH_4&<-dt4QrMQL>7d3?Q7lgvcS9IoSpO=3P-hN1c| z{CBf{x^HeN#2E0|c%0E7XpRW=a3l<$*qo+tnUi# zo9#3hoTR@^ekd8p+Gulfm3Lf$Q*8R!;C)-@_$m%5Vw=v&2>D#is_Eq}YkcgKpj%Xr zzRML}9;8F8%+IQaTAVRPKd{M?9$TgLaQ@heDitq~$*)8oao?=?Did%lcd_Ht<>SRW{Lwc+UaG~F zOLt<^M%Y`2xjHb8hCJk@Tw&8jDXRX(_h$<7Cb(zA()Vxi`x(oU-Cb0#;L}OQdr#MI zw4vhu#G0JfwX4Pdg&~g z6Jj(z_MOo$;Rnl3fy*q4Qd-(dJD1GKO`E;jd5crgpS>w{i>JPS z;nu!PrCxBOZ0bY(csEMXu<)~`?b*%I&CBhDlljRSR*QcMCrix|lh~KX8pvVwYL(EI z=#nR{Y~Y{D7gX-TnJEO>uQb(IwF$eP+}u8R_NIViTqW>awCt~GKwyFFhkSlPN}qCk z3U-HsVpNUi-=CFTT2ngxM`5%*;akU1XOt(~A_>nXVu_RZsX~T4nK&jkGq#>bbbMPM zE|RbF-*6o(gJ|f7hKn6SRNyJJZeMb650;PFF_SIPkTI)*}exojLqgb#qo9WUPL+XEA-O z<-8X(i`+VAa~5;-51#(Q?q9b`csAU(wKn6CW8$;_EaF(&4$miI(fvDKI7@GAmJL(Y zbY;xdqQR8CRPXA7=I2*+YZy(r57ti}ZTaCB#nOMcj=&4-wk(-J8GMx9SgzDJBmpC3 zEIH*+NS!(B7eN+s{%4`^{m@%>uDAMstf)oaHI_ftTY3_vm2EURY3b=TEyZ;4sHFKE zDcAl5X(i;pJQ-OpJ+7s-Kl3}>*t~MT_>tesDv9nfZ0{qUC;_FJ!?ng4l-L!^U%!tr zpA;=nf{SKN5f2-O;-GfGI~s*|9(8qmFnNf(*u;p^D8sX?NW;4Q zr}-f_38b|7ydG2KjC5yT@Rm^Czr>r6SYyuorW2vhDviwO>g4?zR9)Q#(OUZW+~?EQW&KMW^D)u(6nRC&5Ty;Ep< z@ili!)J1sjc!-(VR@`$~dqtP0&L~E!YiZmiOXLiORZcWJ)ncx`1BO1gGqc2{1E?PB*pP*o z7C!nYsF^6&cuqIU#LHdln!l*wPf4$LvYak=^P#YcyMW8_;;vjx4V(MJ+%GC4$hYI$ zB5k4nPkY}P)l?I;8w3@xfC5sa2~q?p(mP7;J)svxO6bxFRf+{gItWsfP6|jbh9*iC zkP=YPfC55@bOHhb-$dVg|KC6N*EeexE5MwybN0;a+56egnW4Q6R%ZRNzSl9L%b~0| zWtJKDE0U2qFH zv-!eWwZ|W%fdXf9c)+A~{ZmmQX>KlJAMn65*61%g2cE|DHv<|0R z{I~=dcn;^+j!abc4lc{P!H9m-m0Ws1#jZZJqP1N2j9W-U zsIv=M&vAU!E$SCZ<#3^mui3=cEPLV&Vns;p)$s7fgIQv10q^za=(e5C=SM_NPr}UM zL0OIF{>p(_#3J4nzFkWBVWaYzh{=yj@K~#6XLEOaj*!vT@_4_L&mgoo-UXArDQPhx zh`ek9GobzswQw7!0Gk6q!Y@7*lO#I3;`v1G)^9bWS{3eKK}=9<4$ntQc~mI*$Yflk zad)|gen@YwK~^{Nue#4om$V)8qOv5aOtg^+F~vfRbM6~&ZT{d-+)OIEN;i>T!Uf~p5xRdhp%D+w5$!7RN48oQ-c!}Dq_6)noO&2 z)^x)dDNWD!l?;bYCp@(z+<+?hpg@!& zLA#+uVpM=2gP=bTb{~ zBeeq31H{b&E^Ecv{u6udA#V^-sJYH}Km6!#P*u@k8T#En*FIrnsrn3)V8h1jc&{u^ z!1R*5KeV*d6Lw(eu<4Wrc^IY%d3n7@zS+{>@6OT8A>1bFXv`>s>9&c&Nc&OV^nT;a z8fvCe^~vZ-Xa6eT4RCF-8noIcw&runwX!L&JKKLjn-j48;jla={|vqiTFp+&z6=`W ztOCxZjkyS=$Q##nozwDn8s6^D1{J>TvJ7sdSHfnvmANu%Y2LqiR2u+`r(0=uS;;QVs{lV;R@@KnUXGWj%yFuw=5ZUOnq|w- zsSv*|H8MX=ED|>jn}YdFneh`rpg5ivgzJ+}=+~CEwDNHdXH@?5{0!)ZHCD2{UchIL ztwqRAx^WOU1fVHN_eS&Ft7jH)o)6zF$=4y`4wefG$@@=I-xg~3_63}3^zIf=&#k2TB;cH8W_TcmAd?av!>&#;$zh1T~Ti zVoSxOU~r1w;1uz8T#AXj9xg8ccV&0{<@R{NHg0HY@LWD$oFfN$%!|+sh(RjTC8hT< zkLwu?)#`%Lz0!&m$L?w;KXHg0-T4 zV=9%gdF3+=Qv?>TKum*t_R;(?q9UuvG~PqlRY{biKiAgq7|V0izW1i&TJ*pS=rr917_S8dzifcY* z82HBvU?L6i*MC>L)J8;v-y>CHT=_+t?<;h~5r{67CN zzV-xH1&vUu?5IyvghkY!y!@lNnP=MrM)}JJ!9Dw}Rr3h3ZC$slIDf|&li(>RKxphM z9b|k4rB?J&G>=#H(}vV*SM|qs%#}AcCq&h#iKyE+i0@F0s#!c~c>?9~c0=JtfPZ{_sPUJVH7( z;m@sxdS1?cgtnjU!YP+}iH$Fv4^%B#W^F~Eqmw$in3jXOMhw-Nbga~STM(1#h3Fsjb$vj*$kS> z)+VM};B3D^7bkR;tA?B>EC@_Y5f$zGeJaF9G&T24zYVG5Vi2PhCz8U^$GfghhhwhI zg#s`(oi4-TJCklGr$ATcis{rTj9~a|w;=Qh_}1 z!Z&k<4_1G3QDa2@RMo|&&i~nrSN?oc_lG5)VWu#$KRf1SpE^`3wy;6p!}!rTTx6I- z$ysRlk7D}U@1{9EL|_d@mx<+(T72Gw(+<`91;>9T5y{FUQCmtyqBGV^Mbv6U_Udg{Nk3Hw4U(dW|M>^N7EuC_+bpOpA{fH=NlF3i^ z?jBYi`g#;ho#a0ykaFJ8{`Tt^f}iinjmwAhb&KD3T_CZk(8x>r^CIK8C94K=UiGr> z(OqY@nHj3W=I_gWwY@4E&z<(fn#P;2S+yao3~4Fgiu?7jxXgVhX1T`-?gTyl1Kaf= z1^aHgM&&pk6o0t!oU1SA)qDBC!Pm;nh9psCvHhb*DW~8e2h!FZj3!ex*@t2)22!g@ zphD{soKL>jy}}0x$wJpI8z9Ij^5F3?UrF<@smgbcK72iGMCAQ?PUVnbL;}0_Svy;` zZA26bjB*~1fQ>Lbi2l=MCw~8k+>(hh1BX+${Q3s*mJ|e#LTEKW2?_s95$|+_}v&AbhZ7y9Pa)*Oi6q;+;Cm+ON}ZlAN7TB_v~! z;0Y$0c$?LZLcb!bG+Lo5*F95SQ65qH7zX5yrh)S<|3@vlMHjR@*CGR7{?Wco;%?h8 zH66ZVY@A%h$&(5fJo8c4*J;@_;RD@jOId1tpzM856=D#K*q*f94l{g0Vl9s6xNtUN zE2v^7l7XA@S@Wp*lo^VwBziQs3vQ zr$xtIh;X`aCAE&;-T`SGpvGKstJZGMv12Z?gi_C{-uSTcfl`E10gh?Cz+;h@15?v9 zt;2@A^XtUFK-`RKrnELPhB>8_f1!0kPCDlZ#(ubQN{9)~N6%lP#^RCTR$AxeoCdJc zYb+<%?x|gMDm8${-Gp_%rwJs*pB=F-iJ>LoUwoRU9VDK4?cRD1jfFjrJ9j%}qee4< zr_5e)?DTYeTj(Sa6&$mAA=i3i<2`jqdtE|i5N%L>*qdoj{|V^#t_gLmSf0ewPQVw) zXz&!|WL7*sTgZ6-byuDm`zo6>z;*_IJzBlz{CiuMq~?DKN86MS_zvTQfb_+^Mf0B` zs31&zOW1B@;bSX)0JA;-Fe`vdfxyJo3%rZ1F7cCS>YR^>_WCqR_+W&%Zh)A9WWi!i zv!#e-_Uu9{>Xdp_97XqM_ySeO+wzp}KIftmD z4?q#?a5vpQT%w@#M)qp4K7R-*;??QYVs1eY@7Or8pMOqfDC7^l?0=*&U4q+{hsgSL zQUUMFN+vCH4i4bPsIQX~BblePD81OduIH82c=Lu(@2D>b_%edT0mxOkD{{1(K-EyV zQLyt9KolV|r+~M+t9q}*UXWy3WD`O7{(P))?X;Xjc|iQV;&)dDBaE#?Tp?&E1@rYM zt=vS$>jLgBR1B#@zs0HrVwG>kAyzcYR;yyHM2qa}Xj3QqSkBeYK9{+l3KL?O2WHRi zlLLOVzhA&k@kOz_!1fV3UGA4|$#~+~!vU@Mqo+R1f!3+!(iv<}#;$!1DqL5+njU_B zFxpLrrj(%iUh%CfslRYx61z0#_)9dE;hsJmP0QUx&oa1?AB#S zyW86bX}eL%H2d@Am{AMp+1(cUh_w``ij*}+G~*EVIMqr{<)~Jo$J_twhGYDMc1P*d zRs*Qs?d2DQg1X^~%tSX74TolI%4X2e8#pBEZvK#z(ITRGw`Pj2*n0x>qeayCq@$v7 z@K-3x4N6%?ob5!sJ8jzr^7f>Ih`~jFxy2!DUVY{(3W)FAx&m52+l>1Oug zH9LH&74PlCqH&S)=Y!qb4BY3F9&GlYz26n zTlK9($7N&&vUzAm2}pOHB*j$+C6 zAFokBzOn(_&^LC$`ID>GZIc(oJClSf!7lrqS}?f24dZM?W;(x(h#WDURKpj-OxvBa z%`aF~bA~fF5Lzbbq6}$r{FfjXUB#A5Q&mW;n0sYu2L2XXy?#B-c_Fqj;l$zk{b~-y zkXH_1Tj~C-aIb^q=p|a^-?wy9u|zvyc}>aune#4*+pVS zyhBQoBs27Ilqu#6YcT559mVn!k9B;wvzkhO+%Y+XK$!Y(bUj)OE|7T{mX;4D4ygya zF2;O5v#YerZ%HzPR#x;d(qVdf+O@$bp->yVW>lI(RyiG6r-JMmZYAgpd8S?fJElV*c-^Q`i>T4b zh;Lcu^>)BhBdWjfh_9t+ofj8a!)DGPl@~Sh$_eTpl z4L+6UKKc^)<~aeVEnG8g=P5xDST>0ZqF}x@MfEE>DdjR1Q=+6&rTW?i`LXAtp)G96 z>`0jY=3Q#i`GCbCb~1y-*-9FE9vp>ZTsC$G54Nh)1SAh2N&yFA|Gc0;;sU0AHVwNc=aS=rqu1L&Se}&@m>S*_UPEDN_EK^3 z=#Nq5qSLn+-ygVvN69nP3eDF;3bL-^TlJ*CsOkSy6$tBf_t zcnfkR1YLEtW4v`kkV`+plx_t_VN1oimquCcu@d_B3bY7SrxN3D>uNg0k}Q*me`qR0YS`Hbxc@$FQYzBF!iqqJ!NvcxTtnMK@E9D?#W2g>y=T$+rd?@@dF%2&MZldjkuB!miLICr-U zu9zW@@DjMHbHDl=`(+9Z(`yN~#l2byw%3RlZl*rjqR%}wLxP(o{v1rC(avhRA0gV+ z4TqM=)lF;5(=Sut__drK>n}lnZpLH|H}8DTB9nUnp+Prwz9#r2Bw9}cXb1wqK0FVD z=L-&wHMTh9&zGH|*TDX1dyLAyB;p5vuD#FT{SD@^+{ud?^y+Lge0k@Dax~;>ZC`mb zyj*z49=$usO_k@~vf+e|zlcYlWSIE!Q*qOT-WcueA@bJE%I+%9m0#l6@-%&H+{{cz}It?Y^5XlA*p|r7JatXZKkeoKVQNSBuzke z1u3Fn1J(WQ#-e{iMAVzeQ#G1NBi(B=^YN8$w@w3ch`NFG8M}URQutQx(@%G$K;p`Q zt*TCz!#GzqCUoJ}9F8Y*81bxDmGOx??QD%O-X|e0J^-QzfDq0<>!;m^r?XmxAe9gR zr2;6MCPB5h{8@VXS|z*I?uOiL2!!URj{0qL_<%cC1LpE>E2%%twssYLhF{l4nxcc7 zEjh&#jxyG;_BdPLGzgavxr`~f)@RdxIk%}7bCTcS)n+D+pZ>|^-KRbL z>7b{FTfS8u{Z2ZzRI|fVoKZR2NFsf4EwG!~qO|;LcEAc{X%)C!Ww+9{aY)0+>Veid zl$x;QNz7TZ5M>fnmPwZ7FeHDGNyfjc3IzLF{YlVr)nqoj^a)>ox)jBG?qW+ShJ&d| zTmKBfm!CQ@;UMOEn4#)^+>tIL8Ds3R7 z1%(v`+a*?6$(v0KN)n7DR}(V=C7ciShvfTo@gbo^Mt$Qq59H_|(TVr0N>vWN7k~ta z!%iin>BPT|oK+glZ^Y#{)`PtgJ-0S<8W(c{_;Yqjp}#*30K7BfzST)u>0TC#c-n{S zWIgzRjwFl4`@{Y&5LQ}<`mY=ek{-j7AZ{lZAh(Xxw{~oYCSJ#$$2q?{4VvbH2#0)$ zw*b!=6)(V%U| z!GB-b*E>~wWVN$0h&J=P8cPNa`{<}i4gkRMO-O{LS1Z88qKSaz11^F1zP`)k5h6Rj z?)%x(zxz7TWw3+nbRN#mIZ1GO8q;C2K%+|Wf5W3gfhk@)w(l0G`{=2k3sS_7$k{t$ z6DG&nfIhEbdShC|YDxs$*H-GkZ!Of>k5pIzb$O^(VQ>eXCe>A{Wm8nTdFP_M*cNCx z>j%6-a;dDF`yQKRF)<*?YW}**&7&Bd)u-Vt=Q$P9hm;2@>xln1V<5IdFxa7v1E{+N z_^fMkM9_m^@Q@*H1R3HERd9eQy+Hg_W7hYi;Sv@_!&sO=Z>>f;!g%oW$~Z2fiU%+LhWEN zJJ`eKMxmk_nrqer>vt~dqrGjYE_pCsvTpFAK{i}*dU2IvR&yOM6t^5f+p+N9M3|*{ zY=;hEMJcRAuC82upgtmKevMcrejR!(ezVy9OL|YUD)t;NK*<@af8&{JcOoRr3NMJE zJpu6s&jG1SAOs*4hcikE&TBM(!Ev&>eG_k-IAbvLNBOUh()_;SnO<|byl9~+U<0J2 zCAB7$8?$6>R{MC5o!AhjV{9T zmSWw#Ec`q?^s+H5P3I=27mkBPzZ4cybS(V!cEJErniRAK1YrLNeb?M@^LW}J5z&H% zL959)29$6COi1`S?SOr2q>0^#Z3Fo|5|srg&3{5Pb?zx?m#|4%x3DjIe=ns`@?x%|e!0G{lhgMwZn zA;i0Fcf27oIcKiM4dBV<{crJA8j=6Mzj!|TXF|#U`QOj~6!gD(_ERXQ4m>XoXFG5-VH^B)BO diff --git a/planning/behavior_path_planner/image/avoid_fig_single_case.png b/planning/behavior_path_planner/image/avoid_fig_single_case.png deleted file mode 100644 index 7b50a286dca99aad8a912709a2ca0323f3d57920..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 59688 zcmeFZby$>J_%@1Sf`Wl`DBUG7G=g+@hje$R3P=qgEg{{x=>`=U8luUEZAM@MJJqbZU3 z&HIx2HQH&1Zif2BC@E3oMQo{;h_$t~?>`@icwAP_PqxO!nh)5g?OGo$7wMv)*d5$! zzX1lQPpDC87Fp7KY$2gYk3AGgCRS-Z$zeTRuM&#QFv!`w{qVNmS9&#fmpDe90y~&j zU*F;1g@|>5^92E{2Y0HBI-kfSu!z_=gSsW zR>Ncwycr~?zwRFY=4?sGUh4~k-k9HX*}}qNu;pyB#r$An{CMWDId^byP(h%yv~&y= zlQ+%xwB1)(MkdUpFWFsmximk2z*OL5+);IF+XXq{Jk$3O<%^pb3ak>E;VWQ935iKbvEt;=aF@E{EjyzqwvHx>belANTJ&bm z4{GG@At>_e>osRje{=4e`W~1<5uH7oo(=QRIRx`fJzb>o*zM&so~*{ES5NErJ>Mx2Fs1R$t8#*#HOdGkIxTVN})?xjus8*oiFJX z)YWNR{K35V$W@Y=DSSBXnuVCJzY@fpWAk;G;GI! z;&|NW+MEeZdFROM@}gTlhYg9`&ILZlL#b=cC!0gvOf5yJ=X<%ijU}6#Hs0Hzdc#__ zP1zql+?n>hI4dYB8g^|t(cwFsa?Iu3{E;rqZTIUflsPJ@swoaFt3$b#n^ScjOR;LA zVUEG=3&#k~=JYzp<+XQriGMKEOl1^n)vRgF9>>91sQBVpL}!mjYbxKg-qGO zx$yKps7O@-8Pfc>jj13rldNKEqRMiAf#gD6P1`np0hkl>?kO2pAK+cqMM79@5$nqcc@WWNjCKo{k*&I6!+hF z)82>E31`(-CP}IT0xrHV5l2L2`sXC6m>>itS%UEHe&p@L4UikDT zvP`0${Tq5R%cP%kN|)5_voj;S-Y(>%CrFv-b5aiL$wQ zKL1gtoMaTGOkx(M*Durw5D}VE%hnGM*N{jRL&Hpv%H$HEI83SlT`3-GG*CFG_-roD z&oXu64_Pfo=^=&$RF=r^U7w{)eX(Ea%jbCB7K%eh9I@U>m3p~IbS1U({=1E*JKfL% z?A7&qGdflXMg8vkTzGu!QLNXZt9Lq&Gcq=oD@Nk2Jf`Q{)OO$LNb$VfT+`tLjS7=6G^e5EBu?9z z`~5?+v%X#H$J1LrxrvF1(#(w6qA5i>4XOelgtG41$Ic!7{Q^t;=BwVKqi;ZlGU@VK zv;?5zNJh&}5Q0WO!UQK9WOqq0>kaOb6fj^daX| z+Qm`o1=kxM6cm`F(`AVk3|~PaW65JsKpkdF{mJEAvG*ar5y`17H8;D8L=ieW`0H0tg&dM?xPURzxAP+-Z z8k&@2&v_li&BMcPh=3o~?nF!V|-FQ53eH>IxML_x_7v?GLSgu~nQdXM>F zDsqW29akL_PYsQPwY9aq`B0`c$JCQ#uzDbboW}LF{oiwBl9ZK{GC_L!4j;TGwO6gW zc=41{8ums(fo9|}acG-t-Ou0t_n$fekghGo>y4%h2a1Ln5R;l(`u_cUC1Okz zlyhd2%eDOiTZV;0bkMYoAgDh(n0$G|dP0VCI?E1L1XX3Uz*Z`_GMCPr-CzGmYOx67 z5kM%`w?RNJC6f|(iK8o>Presy_V>XCxB{5X`cb~8kJ@1dol?o&ONsbB|21f z^_lZNeE6Us@DgD*S#6zJ-E_QG7?nj=+PIU|AHUf_!nLd;*(4@#I)}MGD8(cp*{gHt z#yipIzMFTZ>$NQcxLW6uFRcaiN*O>g#{0Yg1)Mp&akq~r;V~sZF-ZL5*^4thXD6o> zK!vsEdvX_h{)Uj+QBhW288=NG=}CAg7N*1Xl;rqF;NIzO|0OAa;Ff?&s}{j`@X4lb z3Hxj(zGc|4pD%a4wB_92?%aw&uUWgF|D>oHNZl1s+y}w3R2p|-~MNJvJhY$(Qw-G#yZ; z(Cl9XC!78JYj#e~^+++|$o7Q+Fq+vz$7E@sbs!X7W>&rPdW<+Zn{gMG_qx{XVAYuJ z$=!&Sxeo+RZO_!q77$^VGzRIXYU{#+0?C?Lp9T>0xSmhZl}4=jJ39{EXX|=nay~mx z&o)d2qQTpMnd}8HdCkT28*9X!AJ|@~LV^RN`QEUSTz*=bV7#7B-T7+jxdh;(-i-!_ zB}qV6tE;)GqnJK_P-A0aR=^|&x?<^GqQCQ*f13IO1R|@Q*i#zh+Yc~8DG;D9=H)$} z3`Y+kP<7mg6og>}U(WveSYcis_2d$q0Py9Hv%}faQg5WCsq+F*C&``=^@AEph=Ufe zSEzR;$vI_*`t>gtc4!;9ginh=cP#kh0*fkG1V9bLleR6zsCO~Urt6)75I^oQ<&Q>2 zA!2iKDEZFzhN7IlH9DZ6eDwCe1op?w^YxZm5|8p>=Z@zvIqz7Xlkbrf-^oS= zEfdpN)8R}Zm*ek_^(8t$PHq<~SCQ7PJU%|Iv|kWCJE&<^a3(-(h)Y!-i)Q9Ey>Cr6!g#ItSOU`W_&XN} z`hq>sm}rum{A`bjkB>(Vf+xU)ui{oq{hIVKP%@BERv~{fkSlOz&Y)AT91svN&IpnP zE(}+JggT0m4jcZ+0djKxPb=p7udjYkIdMMQze=C%8z^t>L#|5XN0l;l>E7O6%?6iZ z5FKSTwOj(*#z=h-*<`hUFDAoFJhnOAF!J+fo;-C{VQI6b>$G#cq@-lI4nF7um#>OG zibkY3d8KJTaj`~)C{&(+nsV;vJ2V3ed^x&B6hr|uI21-$yZ!LsUU5gZleE&7M6f!V#{3eOxJRV@Z>5d#B5{Z1DhMCB6`6ISuSmvOjv9pCr%I%Q1FQ2!p1H?C= z*u9-@ro!@a#fJ|cCcZQcZ`8HD!~oZIjO}!tU0p5Dj`uyb+i+As(E-A?H&sB7Kb2_` zS_{JKk^r;y@bugVUAiUE=3V{$V#Gr>2ewX>8;7R2&EKyp zDV(%vkdcaKRC)F4)#WTYt^uF?GE)3CNK(xfpQfnJtj*d5jA^%pFj_{&J{Ra+Gp|jg zzF;%90_0@P`dlE1D!^zj=WG#xltOlP_T~Hjx^+Fi3P8-mQ&UA%mSY7iEqdK?3`4~= zGm^}p0b2M>GeFc0c%#!(4Ylm+-K;GK|gH@W$are(yMH2v;~bX5QhT*2E(JH zIiUJNG658xtM}x)&g>bS|3Ds;7MlO)zXPojv5K17)%65|uCan3Y*zpsoocCWF#ut2 z5~m!UYSE9y&gcpV@?Xra$vgS+n6vZBj~5W+ZClQ&P5M(n8hMP2j+$JKZ|L8pwMO6) zaXGvW3kw6SVLTwj9MGN0eCAe(Gd6DE1vB}NXEFd!rlw{+J&<@12ztmPP$^V3A1%@- zw{F(GiSo8AK#mDQ-`k-lXaSWr)7;jx%{oxKUZ7IQ=6PWC9#j}+%I*7*d5QAp?lts4 zvj&+U`1ts2rhSC&O*5B>`qO;9XfsN-wxz_rr}ow}jT#~%A_c&ZIX&84+C92V@h>O; z&Lg|InIAHN0In1Pv#S=Vr-Rm}YwPeTeicGjL;*pnFi>^hSVv>LU504UZ_Nhi35fdXk{5K!xtK4%^j(Gt_ZgwU*a z%11*(yBZzWH9d9&iDphTdp8jK{Cy)r`gj^N4fQ}vt7vN{Lo|xgM{`wv-;&c{hvox2 z!g8!c#n-n5>QR7UpzBTuuwRs2U2A~W({`E#%pMEw~-{S8I#ge&@~|FvUw1hj#0xW|=_% z=zW0adHJ@2s#i?#1qN)uD$q4Riocv*3UnMbkR`OVynGepqALizwWod(oCjt=z+nZ# zT@TtD$UB9S?CpyybTaq7&QySs5L4jvpNxS#n+7BYRFrSuzI{bL8Q1HuAWo01feYW>4`B-%n^91_NB%oP znJKRj`UUst73nnrJx~DrVTkmA(=^VZw+%2Si<6oR;Zy&?>gML?@%}n+ak2^uXfIK0 z+E0lKzz!4k@&GauLHy=~@U~$&Vt9ibbgI(*m7S zdqvXlS95miAUMY@7bgNh+sS>^mj`VKEj@jY|AJ3TY5)-vDd;0?8@E4jb8~~XCD(oT zcYa2O5Ri;SL`2+PfB%{BKGfOY+cN`w6fHG%hf602?84O^Bs1ax2FBW9%S97pat8># z0K{YgnudaslDOHeeiwHbBq>3!z5$9Ku%nJGiW-mKNlob=ng`+kzvIxh43V*+L+qJrle)5br?GK*Erz z`ELf~v;!ufR{^FVbMt^EG;a7~KR-Wcucrz$R-o*ym3K3e;kE<;ED*u$1c4q0_&WX* zC{T21r0etcmeT`2DZjc}6@X--#x@m{XvTJXM!O|&wYqngsfJ7D;o$)_E#2kxIv%Up zV27l~MFJK8R7`6irX_F$0d67L@w+D>v$3)9khibe8ZvIcn=7#<3Zot_RIa1d}2#0s+t<^$B!VN#l;B_lhtHH|k_t zNrJ@#Qd16yqUAaRz{ykJbD>^B|3Ofj0SHAD`77qjbUgLWoAYf z+S35;ocxz$w=05sH5*!t`y?aH&DptJ(hkG5qt z70LP*J){o^05D8u1a*RR*TVJ>cAv)%I%)t}&{W050&}DjG60ak{BjoQIR8Bh&|JDZ zUR|uuOxRjk)97bt^Q!v!xj9{e%llU4lN1;BV4KUtuc-Nht^%;%E2-}u08P2R6# z=;prr3_$9a@^u~Z#s~EZ^4`u)4huo9LR&e;#uQ&UK;GkCT^41l^~;yHkjQKDJOuhf z8F~)5s#Q`cFfdRIZ=_CuA7H;Fp!E%8AwyyWgs{?W+dw9fEf{K+^&iYd6F^T&e)sk3 zD`{3JMgTKk9Ii0FT4auWKAWFL4C$IY8O(m`?(KSU@pUfnEp( z3(N`>IOf&!z$0&yubU9?dk5G5mmXf|b-B?Y^U|cJ!{t60yrCp$1u;nYi%LpLtm5CJ z(=#ze^!KB@-6eezyaI@JoDmh$+S+!+5rLS8;0306pw>0GZuPm~b=(AT|8g`qJuL$Z zPe!Oe1Am6T{*TN~?8Wc5!43!@;v^(1co8B7WB@n=K|g8y9Gx`sUTW$Mlw}d}C!H?$ zAr((X_ty>(rJV`z;lL(+h0dMww-CGiI@K=%X3pi;|MnEe71W^T{GT6qG4waq7-zhJ z^O1#ek^;OEZh5)NUvTv`;;bg)SVY4Yj2Z}&O%b?tB}wkH0ETv(+cdxzMZrY{fA3$8 zUatpaJ_bgFE0X0R`aF(NR%B{yre?i1@wKLA?bK z1uq2&rG2dw?tvO2`20DblHk|nIv9PKz_1r5Ck2n5o}OC819&nsUP&B7|Ndnqu=xd= z6X2gM*4tD|eRKaPPCg6_RVm5ys>dMoCPXr^$iUbI#2po z#+*lHXG{I=Vgkl9oBtksX>7yft_kcLI7a~x8<%JmjXvH&<}0%bJV$R3%Q zVFXl=n1~MuwX6Dw)2s-bt~fh8gLd-6iTMhmqMiUVCDwfb#B%vD=w^~{8)nVCGVj)k z%jg=TXuIG0d1IvbNY#YE_mp${P%KW174+B|h`=H>r!m;|0eOWc3_6$_o2jt2+29T@s z1-7*B0gUDs-Q|_O7d}9|(Gp@5g02IoF0?y-;CtuftepOwul{Ei>Ne0gAWWb!gr0{V z28JRDcn_Qq5~}V7OM?sTttJP|F-^wB9%sZ`f~|l1l!3kbB`($NBetg#1ZWnbV%kf$ zMSYkqnut*BeB7FJfsmrbeNX_V3WOx2kibT7J6@H;HVXo5S%7LuOB~T{PxuT6r!Xf+ z6qrbg5)u;CQsCV>?gK!|cG+i(3!$~cGwy3`XT{j@IfO+Tbw-MryoT9mMNz25N#xXs z$5Bj1@k(}NE(TR-k@-|8wiNAcwNBDY?WmU+O)V47B@4-N!BV~MB@g3Nte)($paq5i4;o4yNCt9@RfiYu^C@T%{ zF4e|Hi`=3J8QN7%2W<&NY~&)Y=L$PVl>HKZXQW*CHat(j`=QB7dZ%{btRdE3eHZ3W zv}4&?daw*1iOZsZCp_L zzN&%!fv)cErQPias2~OaV@ptx)-;SqQSPUT-uKLuAhBt`>SNOC@HQ)v1yO}|s&;l( zL{yo#@GJKaV~J|K$KjLJ^xb5WtUFrv?#2Ee{MORHxW1O(DAUo1(jIpRGhHzi)$Qhz z(C6beic@@1G3KyXlTj}AVIht}{DxHY1w-Q~s_2YKA# zBHHeJk7-tE6Zck;CA_z1!V4RJkZGi(<13zMsjea3ndVLMKMOjEv16dn) zvLYm>331Wd7Z6NhKApG;=|6aP?}XRe(EMVj#emWFa~9A#D64D~koR{O?#`~?&~My6 z@=Ao+XMlaKC0IBx;K29%_TNwU+rwCZa*zksH&D>D5vE>@GjBBF=)0o;$@uvANhV}BS-$v5xxMnkL4~vSiYK8Z^NSr=Zu?HO0!!w!cuefh_5IHBrq&y0 z_xsIRms#V)N+hf~5gqLK7;_YOW3h$9Cu!-090)uQx6^f|@oI`xByInC9;rb7M7h6- zw7A9bEwya-I?kJSQ5@b`PXgu!TRv@VZR3o~aNz!cLv%m~LgyEN(KXHpmC*%Y)_)`; zRFj0o8A#*{%+q4Ufe;YQrA?ghS!^AysSm3P-Qcp}P9yHp61&}%Ut(I9zvAIm6ikL^ z=|+OrDRH;u;Ky*pP@y`z#*{)UX@0%y|q75Ujl-Nt8E`#a(9AKD)0)Pv?9_NyCX3yZv_r2UC(oEY6sm zt95#_TCJR~)li3Z+>6^yz=mF$8_r4A>hw_OBIrykTxH;gk|Z~_>j=A9WhqsB4F+YOgwh{f+DLso-|Y31rRoREUSC3Ns_TeOQtX_h&>Mqgwk)&k(WSlQm zzvHiYxe&b^eqsH=Pv6{Zrkanfi~P(>H=Dc9dYo9RWF5ox9|D?ZF_-}Zl6Oz@)27!k zJJ!oYwL>D;bLyLwA{{NHgY5%d?1q-{od0)&I3sVATY#1 zj?l5RlE?AaAQl=jy`Rz_d_!!u78)kSQofdxyT`DJO0;KsH;EFV>LQUL>pK>!J6%DH zG!l8t`kf|IXeiI62-^pK{YnG+!x*k$YMKkle!=G-FC7}@a8P|0)Ol%$Hmdf2D@dIP z6FWb+GeYo?I?65X|=j)?8YkvEUjxlgG09k#VQqKzG?`UVXh7!0$7po}9#iw29DmuT_zHG(Ln&v;(?_4g!3U2Ty zb{0fM^*jDkgw|V2PTiuGkUX|5gIp%E5Ip=D$6LKv#$GucWu1K}h1^A?*XmBSK8b!*l+w?P(A6}cn0xCf(^*(}I8 z?WcNg@jUz35Ina_9?eQg-+j=zbIV9utGr2=Xn%Df+!u3WV6rIs_TumFhQ0P%$RDLy zjZvI(w?%Fc@nQcMX!@M!Dj^iF0;9e6=p!l$V-e5-eSLijzMCs6m-gKkcd&B~7cR@H ztQpE=@bvR&c$sJSEsDMc?v)Tp5=SMMnKAn~norS}IMJTZ;Dv z1=$gdN!#?x)LlW|IUXm!=trFQR4_OIiLBv&ClRI*K@~P}LP)eCSx`(>@>N{=v-f=> zqy+6Sj*!{IB3g~%1AH%F!AZ8Tal#aPj$HKUM`*=a_EkilZUr7+8q z8Xj}ZUN)R7vE)wMbx1?#I6U)oEc@9jm3WWE-DF&U5)!kPc=4%`cO|cBW2zgw&^?@v zvI7!XI#ap&B~Z81|L{!nZ6*$XOPl*NFp!cJegMW!qC}6aqGhXiS2&#eIEuA1PdbOr z%Z)7rgv-8JuIia??6bSz@TSTq5Ic#x+@up{C3>wd zh{&b;U9kI|u!Qj6$}8UGDXRC)nwZxCt8d%?)<4MLEM?eop<+} z#6y2W3oe81>IfQvex{Z&GyUfU&5c6r$Y7u{RNtf&za5LRmeQS!@-?gM3gXp`lAU`;V|DX+ErYN*Q>YBv#BKGOK5@!XJJ&O3tIt#ztX}V~_%>ge;=JbpB>bfuxm6+^v|@_}s21Ehe%% z`57J2b$1N2!VOQd)7$-QkPTY_0q=9bVb zJsEIru0)>tHRRH~-34bGaK)aKIPHB>E3G*iA;4S1t>Kld5}{Iz5WAf%tn+=)PTi(Q z{;q?^V{tj!d-0J2L5%hqtg>rn(HKTzF5#HBD^+tc-C=*&5wS^d%je02+@Dua!F}7^QOjEqeT=u4b=fjo&-)e7<4nrt0SEs~E_0*SJ%hGT&^BC4D6x#p_H-o2F* zaVJ*6K2cU6lvilhd)DSNqU@%kv!?JP6>T4NW>|YKatAf8Bvmc%Af;B{$BY1g;v<^c(Am7dkw->LiH@1q`KlXPf^-j$y1P znk&TOB)D4!#qZzpf2oK%%yXCVXiGA5abbOu%)d<@7Ws@i3c1}GMK`9NNe~zI600lco4sN3 z@WzIddCR$6&vZlbXntyvla>}JOy|BnFx=HD}&z?Hq0qZG;bpf zy3T)Uwb`HUK=Ct{kT<>^S0Kq(K)X#Xpx?b!wRo6y^Yjq^_CguMi1Ob`Bb&&Bnm~3t zdX_0Zo8q)&g+byPU(c z4P(T)K|@|*i4|Oj)~+oQT}?P96R={#s-ng%czEjr)0c81@;U^u&0RIxjW`0C{bB;K za283;gCLB9p8KqNdBy2AE{4(tbdwTY)z)>wM4Jd_^2sO`GHfDtN@t|v?=s`@e7jkh zuJwI0O_{nlZ)QCe3fFAt_h>g$lS?U+oF^ z4-X3)8czIEv&D+Cc)D|?6G%(rOMz2?0;~D!e;@udybKG!(mAc2Y%Ht3R)#bgEz?@A zpioPAdSWz49$4_PXi_?z_Rs#fJ1y-6*So*U-?@44BZcxQoFE!)@u@_#X5*mvc2?v< zPIaK6Xww@t;C@7^D+a$-Y(lk1@_9)QoR=uCSb4^58W0n?Bq=lC<89DZl{%Mmt*&|x zs%R!qtFIQX%KNVTerqoV$BAU}h)c~MM3o)x6A|9# zogl)>5TO@G#XS7jhLw!H=#uC8ucgpNj0LbMlm@q?f6pz<)q&x^9O%s@>% zky!m)T{~kPA%%!V(&1`)?d;uD>n>-VD~Vm*Bi{BG9*ZBh$TmQx2j(M3^Hx0F;{KAj z>A;aHqD?5cz^m~7$M((aK(n6?fmTITqy&Cdk!g`tmQ9tjHA$?> zh_jQ5$+Cv~$6DLh{wMtRP;Mpk5J-INxd;?ReS~rogZU}BkKO51Yg@EAY%|Aoq}LSD zzx8Y5m0GARBYm^`pO5zZ%t^^c3jOBDkct-yg!36U7?!t>4*9n}6FR=p`DXvZ|55i# z;)pumi}TYx-IhR{LKSjC9HD#AFHc^Na3z}Z!z=dI2dbo`ktMAIdkqHKO?c6Xs)X8J(zt}UMV^LW3lZul zU=1K$R$Uq*yoQLQ@O~#HB_;E?hAXe(o%=iz3i8JGWKq>fcG+!JZ%g}18#;oWtL>0C zeOjx6&Gwyk#(sL-`S%GY3j)7je+_Lb+wGGVlN|GXRlWx=zCVppn-L;>9IgI1A4|Zi zLcEFZw{8=sp8QTH*FTTjiu!q$cNT{{+!sO#!}@SJSJR|D%ui$*f8q5GZEnx#e{*#e zW=zrQLwC%^s#9k5}z(l!2O3FmKCq!!NIoT@PUmc(u#C}pC8_}9BukF6y)jXBr#!aGq{`RS> zY>@}9P!JV)seb^BRLJtv$EDbZsbB5B5eKgrl7FoYrHbjc)aJ#ZFXq3M#_6J6_fn|t z-ZD;H_3T-?pyyt@VaYTB>QOe5>kn2t9eOn?D=}rG_u{RBv+jW5rVEs7H<8@5I6{|c)~}G~4lz9T8&Ev7W>a?fuwa}z>53ZkVF+&l z&8l+Y;EmeIapMY~kABM#-R8_cj!Bvugf&B-nfiE5b&*fP9oR~q!S>TBRbp^3#Z;^e z44$?+`oM&^M40d2LwpTy9VQpCh?=OgP8Q-?t-zT#X4MLEWb@dW%?H@G;=p@w$Eac) z2gd#4`z!3Dfxa(1>?T<7Pgzu*+rvQ;7D9_6g~SCQ6@=&QD3pbQ_%xP-l3zI8Sol#k z9zL#Xw$lk)w&Te7#M0=>7-}1bqsq06D@%Wv_@eKfPl!DcH3veJtjJNS0aKEuoTe>U z^5byt3O^(Mw@MELSEyn?41J8jf7Wq`Q#yw7ez)_JD4u`{Y%5-!QzwsY*qz(kKYvWp z4wQOkg+!YYM7Wv5mVPs-r~2c#^W5AcYR`Rjyiq&ca?hSEOOdAUGf$1-Bs~gAM0-rP z@y^lb)M2#uZ##`hA!7Q}$|4(qXLR?0qp(N9%<13fJmNFoA?At`*L{O#f9ty{OE}i5 z;7bgmFkQGK_8Hq54x=osN=QPsvxRL0X1(9XbN#nN#7vE3rvc&!tJWI|8}}NQrURwZ zU`@Xlj&96-Zh-zuC`c!Tdj|1H< zy}5Dw-i_S|HUWuPcsP5)s}EDp;|VbwjqYl&o;^rV5H(3hx4-9>(q3lRuCApuS>_ER z+yUp81}&;!&TClh5hSzr&5CIK(eX?|gdS*jR*_#CQdhU`eZj#=!2)yAWjk6|3?h3D zC(L{_8v4P05f{D?cqkzNuXsxlO;@I?ZKL-G=3rG#RSSFV9_Uyd&w2-W+drD6xY;W)m=ZkyarJ8WJoSEP=n&P!nel_0ve6WSpQSXNhW}6B zQT5{h{xhMAce^o4S$9|6?NUg7NB{7`&!D6GTKDMgyV1nw_lSSm6u05N#Qgd)p$AQr z%3u9XE@7+H6Bo>K)Z_8<)4$9wzndRvDc*bW{p)jR!32$nqB|7na1rSg;W<^bauSxp zw9)Na2H9v|U`|t(BEJk`G&YO&&N5;|6R=vhKM`m>Cdgjm^R~EM7n76B?u74gLd7Xp z=<58gg?T9D_%8OruzD_Tgg3(PrhOjEJFl$$fT*$1{_iyH%$!D_2sYh)JYpy(`!_$? zr>rk^9LCjjlspo;x6OLr@1t(B7}Hp0>iSUkA?{)niZ&>Bum_;-&EE@RcwI*Jl)4@@ zsfX9+12g+GTn^f9%u=ez%#n!Pv++Q;-#LnVR3QRW5r4lHc25vS& zK>P)bd~cg;-~w7PVaiU~!h`4=M#RZ~sNz;1U2t-Bh^{`)+`DJNQ?srfy|qN+gof21 z67rcez~;tNrb8t*u+HD#aNMV4qm$9h#x8aU^+}go2`nUzgNCgQ4NqJ=2iFrHkuKv= zkotzD&+CpZPxI;U%aC*)xEj`9#t6qp+`<(try4`e?-cvqV#relgo>qkV<4~$W;b7e z^OIMf3lQM&izWaA_1ilNCEfi`;kAB$41I&u4Oe5hog|5D96g))hWg3hxYvlME2Rz7 zKK9?~`v}M)UO0C+UB_mKp50tUla&C(?0Y0Rw61R*F_MKXab-5x{C(=%V8QK+gEyAP z;!i4nB^y5B;`YO}svP#-qFRo!i2g}QwAGF67Gk06$DyxSYZjDvP)7N3Q;pq^y>50? z2+OVMYZjoNZy>fJ`VYQf8m? zr0G};F;<>?qZduAb&EXEMV0ra1BUx)kDEi~; z!q(vIfu!DQ{-XTUZ(L%yqI+W9zUd!#o~_^Z`<4z54AXuR)UcXFM0dY^+Urh5>l?B^ z)`_q#fMYj}-U5wHk_Lg%Yd$h+h3in=K-FHOCNLpzGF<1F>NtgtVw{C zK*P7kXfOQTG{Te&HJ7lFib=98_gl#>{`e#+0d%W#NWlDIv@wVqqxGxrlZoZ{rL@vx zMEPW%bw3R;6!XRP3wuTKu0$7yYH2|#$C=fWkiH^S%z!Rms*;TIO;sDAv# z*6X0m9FREu`*q&jtIUT~{7b3{7KM^^8aY21GnOu*9$^|64|CnyrbpzngjpD#^L0E_ zt}xTGI6u}%ogiU~2SOa29OF|zZwYFMfS?Z+$Xlz>up5=hy+FyJo(HAkL7=c= zK18K@`yc&bKPbQYn-q7dI!k@CgWera9LD%Pa{ev3w0F+wPJ+{3Z*JrT<>R(pqBg+5j^z#>z!SeNXR zxH_XQzdhm5s*_ojrV}?2bQ9lLLH91InOER7~;p%|TL(1xK^nS@Qm`7g~c z{W{?X)1nGD1h>MpgHu5SHq-TO;BMwRySbYwR7`r`yD4_a5=SVtVj1wO?lcM6jtD;i z*%6L)Su_w_fsUJa=vIo-kGHTUJu zu2~i$g!g5+CYCtDH2sR#0JEa!E@9pPBQt2ZM8!YM>yxjNjS}RX&&J2f-9;5TK4m%b zro5HlL;k{ebi1qZlZ^}df(B%wdA^*Pr}jdv0$N;N0}4pU-EM?$C8sily?&)=B9sS zH&Wz3n!m!}!co@yB?0FTWtlIXI*Tq~(j44Lr`oD#ZVW|#@CzShXCim+ z{MzK!7BhhnVc9JHGpjj_s3_?n}+(c(EM#lbL7H<=~+41I28&(qvJYu3qk7 zURv?3p!q*6h>yJ{&@8eQgLjwv9glX5ZDtxJ8m51P`%tv&og@lWzrVwFf4pDCtyRUa zX6gJPVXh#M9Aa;p`|Y5kNDd1sCWB88jm1m1j+wC`=vXrDud ziX)KjAGDA0EG>!OJmIRYx8M2wp{g?ptKxh+R;4fxsqdx9M_lk25sl*{M0lskD?+!q zeII>npe$!1uN(}vT7zsXo*T`+)-6S>PMb2myR5A2E4ZVf8{C-Mr>5uK22P*3ffMj< z;6o!ijaVVsj8aKkY-I9R(@(XoYHbd}_xuZ}Hs{%ez+BusG|#r#VqPV@{Yt&)LN>2% z?k@LGlEzCevfm8D_H!3pc;Qd)&Q?45d(nQ%io?topWbRbZ<(0c_E$x-rjI0kqd2fo z`rIETUsPsQY+F{~dwwdI3XQMlVJ5u9plx@xBEblRw;O_g zGvofS;&4qat)l!aThZJsn=bzg+%M{NezdIJkDi1ir&4Q%yW;a0IPF84K0@;Qs8U9*_RRzeW9Rb=013x z_wj+3eZNqyV6mT1&QBl5)I)BOv$2Zf`5i?yFB>RjQGRY z*czNQQw383TAF@AU~z<_6n_~C*In$mbw^&Gj9HG;&kN=c5h+9s05AGn7)hjaw2?A;UaR4=sme}p;2 z;IfL{pxt2i(D+%bDuu>Wg>L3BWBSyai^T|-`1|K+>h!GmVL=PHHSO=IG6!6KR$y4{#Y?Wvpfe(u52OlZI13pz`*8Xr)XU6Bm8v1Y0T!T=ZSHP0KS27y#)xPFu zn=;S80$4O)rS3twf##L@hfk)EBpM@!Z$OTxLhTh+``!s^QDH`W?LDJkbfclflIF=_ z3UYW8BoDBy#2Kw&HO*7Gvg>IA)s=Tx`jF>!GTqIG5>awJ^?kVlRPnc-cERtL>omsn z;N#3wJ5CJbahNF+cpVm7W0++5NjadW)u#5?jIRjrzisx_Zuz~YJ{bK z)A)kKhWL@f2#w^hKT0B!<4eu8DX+tOWqb6oP&pFbY|+C)6`B5;Yu=DdkC8OlY;&o9 zl$U6-GlcVw79qDUv7|*!!So=&E#bRv&+lW(r1d0}zfV&wnz}R%!z`L4T|Vk;-)nml zBblwPr|1;`$);(VgXSl7g+V#tUteKPMvC|g?ms(~?tGd^tCVXPT1c9F zA>d{0K38j-7K3?j5DzguGkDNY8m0RTp88d5{(Um=X`Z$tJ;brXzappw;{9**@jJ8k zJyk%j7^o65|9tDIea!1Qi)yz5L+mI^cFGQ`Co*KndEoS%eyvWzQ6Z+O%u zZv&YFxA*9oe(GB1InRiqyQp9jxBSjMo93l+n_uOq5i4HT5-Yfq&U4XNDIbe~fZ!9A zSF1V=dke&n;A0>lhTJWP1%v}JNnZ-zNr%Sze2~Hq8uFK|1hIFDEkb|9w^%}DDgN`N z1C$cdv34VcQNGi%9+^eCAfdNMF`jQiNNY2_K8S~vw;0c9$rZ1dtateLJg$|iq49?+ z3Gh?Yd5b$t;(3O8G|dhfT$5h>97kt+$T(qmV`x10MpWwRe7{Tcr*Yl6!*HZ@Xj^W4 z4Muw_zj2zNJN3g?{5ek5VjtrpaL`{6GwhI7kJkLuoV^KjFldOT=#?NHEO~40MbX$3 zsd(93E^s?a%G}?L!-*oLM%6;T{d3coef>bURcS7P8?-FK2iK39x)`vWPe)SmZa&w{Dz^ z5BimoDvM&e-0KRX4BP^9y6e|yDM`dncwFpcs;dW1o#d18fP(Qo7ya;VaoYJ;?T6mI zAK&7y(P^pfJvsi;iIwd&x7h&2{aS5iN}Rg6Sv+}Nj&+rYE4vcD&$e;Dx#a8MvKFuS z)%7X`iIKLITHUC4)84!`J-Ic&Zg$3Lg+Vk?GPWyC@|BFHfAa@tDG!m`<$Zm`EQSL; z%NLEZ6-E_#hAEr0WNF}y@%U%7rV|ZUxOY~hAxU_W*N?Uw(AInCI2G=!yYa$15#`I` z@k|5}8%rJVgN$thp_*V-TYpVJ@qE6$I)=D1Qy zu$I+rm75t|H<5BVM4ow+glQ|pXx__YQInm7%U-`BVABjJG~si{ROCzR8gn0uQ-=Q#ghQ1-pgGrbqBN zMk%IO!5Dyz+3eO5-4RU*_6S;(Z@5$nT&S!=&-C2KS7+S^Ntb=Z z=EiIZbc#;!TDqADI?aCW55CFqXN@=AUCP(a?(_Ll?Pr)vHAhc#T&rJ}YjXA<-P&}% z`npKa+hcViFR6G=Ay7z^#)zQ$Xuh?qP{X@J>)Bp+H-g@Dao4Rso0ERZK^M&ANE}6B z@zR&&$^*e4i&|mbrM7cd45eqsbLLfUcHPr)m-TALOCpg|O8Zj#YHp&MFwbJ^-zI->&;R}BsK{ua601^sOJ#T2lkfa&(#1;ThO3e$P#(dTWSO@+=n7%o%|bB)&FO`?s>-SxD@*GRQXeG8e``WQx3s#Lv1 zXFEEU_S;Q}fa7^l~-2Je}pvg2#c_>e?arnA~jfv}KyjBm-YDm<= zQmsaCZ9+Q#@iBJ0zGZ;xJd z6Jd}1q?q1RzSyfC@#x&=+}zcH;5+#7LFAEQW+N4+01U!(kx>AH1BDizVoBv>y9+1i zo)=cYD}O3Ab7!U|H&;$`*=&%`secqpDQBg?QmI>u=)QMT2 z>(f5q4_o1LkfRrpYLvR8X|<;8BYE;;`i-jv=gA_8jX#n9ny7E6xNWUg8`wCYpQC8k zyaubjJDcRlKU?V~J$h|8{sj{cx1cCdQWYbO1ZTEkmT+Fr;Q7!kjcDG?hp|f6Icfr~ zj@95Yw!L(Cm?%ZQ=G!UK@5) zO_ht{qwm)6BWr2KPEQoAEO8Z9{z-MCz@v5?2@FqIsIFCG5aj(cc*sgCQ~@jD0vY6C zltDhGN~}4yAar*`lX^tA{G5`TXZ6pQ*Gb>423+aO*1gDbCT7rwR_>K|8);J&?s5C$ z@2=%Bm6b}7PH_?JM7VaHJ{H9?&ndq2nqyd?Ej#k)ViWt<=tr;cN3AuF)ExKGkEu!E z)cB_J5}i>;#3zW-Fq?0Po*1eN$9VN$#8mH z@z(yfcB!=Yig|UHi5bnkP)-fc$Bc-r3GQNCJ9tqNA6`-0*`i2Vx*D88#F>p9yKo6y@FHMe6o7z92=J5Pi?(h`Wq^zbO^ed(ngHw}Xr z_@Zca%$jFsiHWnhKU??ZgOA%VjcU@HWymiz*v(z!ab}B#-_@3S?9^m{%j*-p-+xdN zxma;t4BJ>XwG0(4O-j07?v=&^QC~gf*3!9=lZ)P?n!QUCRiTZgvCK=~T&d{awciel zO|#c}lM?>gpqX|zcKRDbw0B8+8b+BuB5#d6Jp0MLNbkUw-m3Nm*NP#QMen4zU3lM+mB^3&aP>Ws zCVEGWKURam5|=V$sOBC~b%o^9OHUrF)x02SpDNd))M7nt(rU~e$oZon)P%^)C?a;UmGQnwxO-*7na?XGJlU29KRU(ocf;?JYxFb{N|D z26r{f8ixCtephBsHosggup&uPUYe)mND$k3vn)N@!AaYE)@=D4SAX-!lO^qC&%Y^S zwA*Nyh${?FuqUe?O_c*$ql#>&mCOX*<+Ug4PxWrQ2_>M>l~71n7>Jtk&MqCf{av$@ z?~>b7o1iGiI7*I&KdgVm$Iep0_G}64)ejIScD zQe+1a5=Ps-kXy9mSu3v6)RNN}nJvcH+Tt5(f93v2VW<%iDWd)4s@J4+%}ZDw))E2+ zAEv$Sm%dmP2~@#D8?#Rp4jJ z#@o0qibn+&vju)rFVtVH(0-hA|E|-Z$*GRHXkyTAn#A_q)&8^P=Fl4ok7_19(d@+a z)lWZ&e0iHDH5IZY@t!7TuRp?R`qE3XREeddn;q3>N|!XLrM1K6D|i-_FHoMUTr2gG z3OA*$kG7W>`BC_5v^jiWSa-R#7LUh)V$7;mT}7l3bFTR@2Nyog+J%o+0><1t5r&>z z3NK_h`_ld-$r^AO52fWi$)Q(*;g}m&>QatL3VfD$|Jw zy`OG)hnu6Ya{Z=xb{5HlvJW=Ve0w^`Uky*s*~c)z8ecG zp@HL+Hab8|is;w8ULGs5b(4+na97C^NNR~ynrgdiK0Ud)rL;(om%j0lzW0{~JoE|0BkBTL*UL0GGf@sY~p~phjA0=ns83u{S+$0@c7uvR|vMTldKGt#)4YQ&q`R z)+5>sJgLX{g43O{hxPc}d@6tM$8w5bvUcfynKmW7BHqD-vi>JGgFaLVk5kLuAyE=G zF>NeooAM@+|Kn=z>LU`PgXMKt#k$M;Zm^Q@Q`_O&W!vj~6}lr!V5pmELBD*3Z0_Z^ z%8D)%+wA5tJL#W~D@V^4Y}!rX+cI@|xaP!tF9{(3axAYVHV!w<@fUbtgX-X zZ@qZy!gBgjHp^*pj&wVBN+@$Lw%!hID2P5Wif?N+q88t$w?)h9*b^x`mVL-5y3zlP zI`^KT=jXgy)nc{@Z*O-YvA4t~Oo`R6+CIMOdeA-5A7N>}T>I81((Xd|ngK(<3 zY}@eb&lOwlmLwW>}Y=-i)0NU4@5==0ia(0bvT&5bOw zi#9j>$#huvR_QU z93@y-{W1MsV6D63cIR!%?k}t#8m=#wXiC-xWeRTCka{(5Rvn3FIPP^=I$u0j8ef^yLuhPa4q`)hq&I#_Lri}`!#r>>wz2OR$-D8u~`1* za<*z6`^SY56I*L#0-5>!dZAZFf^H6r>)w!fku}ylS+L&qL|3(I{m+Nt#ko$Sg8q{F z6wf3pY<1>^OK&v~2?ehVH2YLn;2$0Gj9t_J$l2}wt^(g)DE-2C$+Q>Pi5Mq`UBhWqUZHm0$H8e`j)hfyM9?+FF4ag70V-S z8Jt85tI3$l?Oq#yq+LlVP7vnsxY;*I8X0w*w#iWbGgYDqYf$#U;EZwJy$Z#m&txrq zd>Tpi)3s;JhIQuk66@A6kwLay)U|3sd5_SxcYAM72emdFKbYer6Ne>e`x! z5zNS65_HRD`6#RPdY13w+-MWqS1BreMvMMR!Pj~HyHAbNaI-vZ&SCraC zDkkf(CHo(jhmIE%{upBOgd4QaxElIus=aA-Y3XJAdN`g0&#h8~Z+Sz^lA8b;^_ITm zTX`)pwufKN)_5b$Qbv#8L_F+3LP$C}9UE>@$C~%q*G=&4P6FQ0`6)le2V+>QA4|7D z@fW;t+M`vC!{+CBXGIIh%@12%M&8p7ZHcSVx|%ArX*S8coHDu5iO}R>_<=gtGf3&n zloujin{TYQOP^dU4w5=bdQ^q+V{y221m^oKxvy>)iMfRBU*r#W4$NQ4wQ=o|xNmtV z>;5y$#O0fU`9;qLv#zzIx`g%c|9-Vg(wvzzal_`qq2`IWSLrQHabL@+@e}PLmY?Bz zz2<&Saj4jogKuywnSY)wR?%S1yQo*hplEb^F8<8@l213*dAE6tT5vD%|W z*W8cK|LDx^V7{raRu0GZE0*s!~Vw)*B~t%)iv{)3PU?cbP%UZhqrboqJmuwdAfRqk{s$?MoPD z%y}A?dN_p8L-2?w&E^@ZLe!zw1K}DSmsY=}SU<~%463x8m8yH#A!i%$RwAO@;~L>d z__XzjTxwtPa(ratIvYZW5ez!aMD?!qXUe&`IL$1M{UW;9 zUx`C1;d*Oe2(O!K?j#Y#U~hJe;`BztY~&edMjllfH_3Z-bBbxYmS&30^c+|F_0{vF z@c5jYsls|o8Eox{?quj+`SXM#h;gjsP^R2*nKOr`sKP`uzMYE;^RZSW8x6W)>B@?i zW#y%OT;JJDa;fSl@$ZhWUtVUteex@U+|sq?*yARVJVm=}{;RyEZ{otwvMJ!Q<$X#X zCn@!3PlG2uv!N@WiY3uBL6`j<+ zmb)8$*QRVvatlN3;`sbw?fi=@-&E|K92)~tS5)8_c?2o$4X0Zd>9j6YdX4YE+ zT50au@=@n@79dRZ!|K03H#HIFC@X)KqW110j(^m9-bT)daVtvt4D(Gv90T`294qNrl+O3zWgs zbhmR~M2czsnNJM~8*C=xoBi=B5?3dk!TBgV`Ny_P_x;XZQq+2XCTm`5^b+Nth@Taa z7jc{&Sn=yVcHSOTXHiHKKWQ>WoxX6IwBWT_f>=V0W2p9TqueR`K8>Xv=RcW+GJA!0 zWNAh!jU{F;rF7~EULQ(}NnaU43+0O{dg|hDPIMN>g`fCznM&|8F~u1PF&6QwToYeC zBudXq@tvV zOL5MZNRtNXbsAP|>3@;-t8AZ%yMD4plM#yH(AFI0Rs7Sj z_lgG0*R3!S$?H#)ph~lOdcuQjQ-5Ii#pv#F9RK$^vPvBoiUPgb z1|G(vlZOk-rrNdz1G^lJ?rrb*Eky@Y?`<)vJW}y^KN&a;JZfg+5fl0VM`>hO?E%A4 zyzWV3pYHovTRDwd(!R1D!}9wK56e2=5s0}dHYQMPO~Ux*mNJBaWp&@2MrOcpIPS&n z{5g+G6q6+NT4+|}IC*bWWHY|vo8WbQ!F7F2#b<(tX?k1OZEJ6XyQH2g)loKa;Yf<& zd2u>sF$!5~Z_N@#Wk| zEQl03Br4@BJgXGnwG8X+9D;u5n4mt%oB&52@nuTE&bqO^aP(Ats@*kv*L~YAxR)}K zK+~L$0jUO@f?fy9&YP%HO63l+Y}5xK1)YZNEaGOH6R&UzE9szNsBz|YqwYmL(%hJ= zbLz4avNZGBr^Jqrao0)i(OVRj%`lcSe_AL%+zBuGb=IAq5Z~V54ZphfV1du^zqI7+ z|Mqzou{XR)-wJpl%I^plwP|5;E9DG4#Zs0RT!LKAZ5ax5*10f6MqB9YY6N!i zC2Skj2kkyTMNdiJi^pNWJkB4Mvq`LnWnPNp6pHdg(BjCW-8S?H&a7|0w#yJBpP%Wt z#qLiinb{dQpTquc_5~0OBZ)~tKQwWt<=c*4Jyd{i%CuYhXg-j1ZGJFm?UnD0s(h_# zKx%OLC*XH6-Eh94*3<%{&`>)y9yyeCVH<9!999`KnH{?4Gbl{3M)HzhP-4HkjVP&_ zhBWpZJ-q=_VM49F-%Zx@EqiLwRm03vyI<Ogz(!V3N1XO^TZAT^$3ju%bz)MHBH2CtbSZ&{{9{( zbHv}_uIOYm2h(osqh(6bgiH>vQP zc}PDTub|gdz9h(?08Isk8Po22Y_6xLy1zP)xZ}d_Ohbu>Yh&f_N&0EVU{V!)}+mOOweAj zmstH<-{zaJ8-~FtU+>6-Up5_#aQ;6H3;WyAv9!av;SdD|aisQebaqU!tU+rtRvx^S zkB@a{o!+bMv(ej$oY=DTcCa#djiP-=^h4jC;?2D`GWMLO#xGTh`J0*%yRzIldQssa zYDBfV0yt!UOQMu)LMO%+Zc&!;ocac}SU@@?`G7UVHSoz0jz&f)PQg zM26l3-IoUT-UF2+jeC6wYadCW4IzH(H(k!&vzu#{hMj!&vBfRWF(j$`fhw;)D4gQ0 z#2u;qb=Um&3|nHcHCWRz8#b{aZnoi}J9#=E`o4M^fM1(>#&3AdHz>n?^VseY;b4#C=k7WO- zFO}3ppoDuR!>WUKmJFO=D)si~hnxE0e<+_5I}Seu8rYk9NAP{!o^tPp)L`5zUC%Tk zExIi2FH;pS^zXY3t4jwiwjwr3BIuK9=F-fONqnN&lTCR9rR?T%4C*&jI4=^dyz-XE z)|3V(VuuyKavNr0_Y7ONz6xOJF_#>bA8&0I7$!aS?_1G(jT1HcqCsl^r+YjRI6%Iz zraoYNc117GZ{f{1JAybCofla&L|NzRV}pLwTZiW1?%sM)evyhuGRwqc6w6=|6AI z`6hXhKRdIq+jG;NTNHwgl4JIhtKwf_Pk0_v!| zva*??LAo6WvcyY!p!V`O_PYI-5uMW~C$hD)NqiVih9%tgdbhZ3ytsagS+MloDKSAm zx)5O{Z?a9Ri@q|UKhAJ%w@`*2J*xIlH-Mbz#L;-150>V8q95qXwgX^lU^owm1-0zu zHy<=zA2Ir7|0i>k4#6+pVu^$E0rz@3*x4`8iF2b`h5Nz1toQFloUye2@7+aBQK9Rs-}1mxXfBAZKCn@E~~Js5ss5w#n%Q^%kc4_qNTt-WP9L zLPtw~5$<>Gc$nGkmOE#N)5Lr@#*ORLa_oP85u=>UsW)&bE$7Nb10ma)+9DYq6Nq9+OsRGspwiE-PBz|v%>mNmgzTVp%rTNN{b7eHr2nBpJ;!kUkL?Mi5WB^JdgnDuN7=EWH%I?s-7!<^4-j|GV@JXPf}P;%Br0wVLn-)+o^bcB{SGc5sD(qSwB8 zLpGjB`-k8c0dn*H=#8cQi}Jc(gHAcc^nm(tR+EvVs38u-_^w6UEu8|jo-r5*3%w*N zsdD>Uf%^N=U*O6khZOY~!*G+tBIA_l%s}OBFS>-o7xSfQi)Xi#mDWvG^YYO{M~BH&qCe z$AzZq${wf(DEn2a`-8?unj8lHTMh_?z>rl?$C5dLMK#t!DSw!?`ukfn)@jg?7~fxL`mI~Hl3%rdS|x??j6VbZP6Ne}Pbk!-xN}EncXtVRSpJ3zWb+eqSYx&)7sj)w7lHjm9B*D z0Y=FG23;qD81#O50&~A$QMy1Svh$PZ)g0YUk5pL67la3E!)~V4 z>5-I_1lN~QR!&1Io-hKvFH6Ji!i5W$h>3OQB@f{|ym|1z$!2g@fByVAefDfHTAd$1 zWMpJCF^ccKykzX`IAv*YaAFSh18`;XEsI-b}$F@70~Qh zp6!KqD;;N;^N{iuC8bvA?()X#$c_$kIRv(+ui3wPnffq33{+57%fVGXy9dh!wdru8; zz*b2}NXAA+;*c^U9UUFk#sME6pN);J7G@B^1yAGRrgbkL@s5Obg1H-)NlEEI&%)OC zi1Ph*rr^-fWO#XphJ{5Qd|2WxNFu%hEt;9`%xL!4e?&UrT<7Z^oTKBl47dda1=Q^9 zif`V$0m+(3nE#6;Fy;n}slSU~usA#f$OZzCEO%prGd9Py*GEe_8~)J6o8S^&$HXhROKf zWqiQd!Ss4|%h}|G1!I`jq&HM-typSTfP^2SxNPAViAF_5{r#52zi-J|bPB;41Lvk{ zj|~QaEf_0K{!&wuij6G{9kc(q7>h;*Ty$Df}#eb~d(9H&HrC?DUy4(x8}NYHIow)O*p0?-Cnq8|Z%WqV4e8AKe4X^_`W2 zgNBJo2EaBr$94!gIUsq^7q=9RKMn+ayRi!)KmYACw472J}V5Ef5)2A`u zy`A_EgpgXOSXo(X+S{c~OiVySMM_F403t~eh{Zy@N`Zq@*U%tiZ2Y-I09-zHf2b}v z#AH@>_B-HJsHv$BR*Zm7Ir)hv0fZ7!AyH9TUs5jQZ+{*?@V7caU@PEO$L8lV9~kse zQBn$EU$35GSS;V#{=24n{FoKLs>+@4$6>dwcItQ%fo;hC?Bh0@L}| z<=#CAp$`Mph?rC5Mn*?-KwU|xvkszGXNm1=i@Cne{hLudxS4NPAhf{8E|ZX?!Op#W z`I4HRUL2G_kSHM2i*Gn+=kl8l_S%?KTRuJQSr#u?k0NL@3keHb)ZfiZemy^A3hFWY z9{0|{;9=uKu4*;lpkRkjpFAl6Tgq%UA(9SXhB?eFASs3HE+OI86<4)+6EN?~e?=T{ zeqNv@@Pvu%XoX-VJqB_N*P#CnI5rT>LUZ)NlQP4W14`>chopt-VB00!U`t@=aUA;i ze>t&#=gq>(Pk}61BD#5-gK+zh%h=RZNfb}(_pBs0 zGBTpLbqkFC8O$9r{9mA#w5jZzvw9Nj*Gbs?{k3&LimKN2Hkj z+mpT&83}SXF(C&g)$&b7KK=2NC)5lK5}=6N4(SNOGsr}fDGru{NdmwYoL5;mth{`D z!QfS9XZ80#a_rwnjA8I1Ktz9EUte`~brcfDCnoyfg`*OzoW*q86EQKd{eAg|v2nT& zl{1V1I)vB>fC&7KAh@6Za&$dBzMzAsOnBho^L?H{h~C&pftfETGXUc)Jz58oz5mVy zK(08mbW=zvS6>pKL1(5akF~9BKiXDerhj(D2PheyBV96w5#+p3)}UJEFw>KD6X8W= zoWF4zr<)q??AI?fjG~~3NCzwkC;=pZ;yDcuk1EW(mH`~KpIn^9`}c){nbcqi_tbx# zMO|&Jq@iI39PCf<&NB@&GZY6vMeCn;Jo}@!R{>IvB`g+6Y@rwhZQuML7bOL7kdcuQ zbbKfQj-asXH2BX;9x*XC_H%P{1No?QgdQj<^}fG7hD0_10~|z#Xt>V9_=7m|?QD&D z78OJukQ9)7{MZ?32Y?zY(sx5xxH*aohQZwiXt{r#=l?wH5i=7LNgbVJWMo&bBDw6D zk4B}f@UjtF1qi!vW$B#5I6CJ4_T@X<{}vYCzC8?ba~S)rRbp1-7;x-rDDoz={5vlf ze0+S64;K>h0Pv2qPf$$k{qho}QAogc(6s(8%F2k39qbd2 zkAASk4{whB{CS<8o*tC`_(70Qceu3Vz{$q69)yIL^Z!@;bA#XbcGma6Rq{76coECe zEG{l87F(G>)&~B9hK)@DkjW}3A&!&cfjkw?t(_!Y3T|$d@87=z@@qq)P7tV(5EVpW z34Z?LaJZbV9zHlL$-ib(gOTfk7dAQ&8UkdE{WGWpDPu@cQPI9fNj=zfCo>|~8}jn< zPaZ!8acpsPD=4ynM+K!6Boun($`v6Ikp%FP#?KED4IDyEa1(QL>CVnanT>|_aU8lO z8?5gC4O4!49BjLjFyJ`kTOmbBt*Lnm>a}}qZHdA;I<4eLk1i!8Wu`U$1bUMH7;ru< zSd+iMKiWme8v$j@fI9_M3_Va80S74o013DJ^IATb)`2)FpyvZm0$+Ih?wu^?LZzkA zB7rT)Y(R!Q5MKBZfVdL#=m4SN$X9~3fRNw^a4d20@xkEA;7pZ#sDgv6WTH7b6EHah6mjrs=#Khw4fN2DdlUUTD;NJazY8msl9na{fU*$V zrG%cL=Ri;oCt3P`^TLo53PbXZjA`}&2;g+E{V(2k{}Ts7qBtE_AqGMUW-;3%38^F! z)&y6GF4qB5>tJ{t~=J-L%2=I57OQ-~7 zom!^blg39z+H^8DgqU+Dj}j9`4dX13p@jji0D|_&$OsZqL8uWTxvZez`_0uk45XLH zttDTEc;Kes&lrTl`7B~*gbaX# zLNFI8ENeA}_uAfy=|a&Q?7_pwM-C{H@%edrlrLxDd^1Fd{nxKpplfI#_SV+cB8&kZ zBs6-e{`b2m6e@Qf0`T>xB^k(2ub8SoQGU|}6P;Zf(fR7z4(Q<2mX(&a;50i{}S zIe4KCa=DHv-Y+0Mfye_e7?f%{>|o_V;a~>TaaKvsCSQc#LRnR=;b1C&1Pr)g$b2Lq zG67(ICW#l*`sEodvT;QIoIf861_6lv6|^At6__OzTF#}ete7J#Any&HQ(_*8|DL`2 zK&RaGEW7ELJ47gRFl_$I?$M1*q7XwsG=mpztsM>wa!R0uCj#UNAnO32i;Q~wW?|_; zGCdozr5ufFylXrT1FOY;4qKn;${A)kDI{Kl!h`wtx(WOT<+AN1PjuhlLx3Dp1WzTY ztV{xOJ;Zkj2?>ESsjIFQfT;*b_7Y)Okc;9)vfCh-nhK?&8d!7$N;B@GO}EJcVh9!^ z1?JHsDhKXdMnU1#nTk`~d-0$uQMS8@L2Gx7%SHxl5d9`>e@CH(9H0rxVa20@A=2^a7~)X5s88djw~uA&hGT{a1)6x?2l^ z?M%(R(N5dSN#fDD>9?PQ)Fik_q`dfqpI;?!XH0w5os8Z5DWzBh$drs*M_;_qe1?hC zRV`xKOhQ2+1*E0G(TVWvuE&Ff>s`o-AxnsIFval>_?wXg1q8%>{>)$xZ=#}5RJu7s zgQz_KM~Eyia(6k3<5Y+MNU|*9%z2({(oubFBMvwQkY@oNl%v1j-wzwFyYfnv3O56< z7GCSgfXq2EFSkje81d-O^1UE znE<$j{& zlXLsc6@O39GxN!ZaFic_D}9*0u(l=-vM~<{BUCQ)wgm+2r%&C1fg*13JpI@2xBe=3LyBjh#4etz$2qLKDEz7| z;S|kxV?HEE1A&0PP#oJVh;0_b?nS}V0>du_z!ONu7{G^x*9dTkV`fq>tEvtk&wdIl zkv)p29jAe`M2sI$+DHczN)1VfrT_4uI~g}+7eB=FSR5=UkQu>AN!pRkgXaLw>4Bp3 zCTJNq*>1Uz-iK#_2m~QZ5V4XA3oYQTe%lSzza(-63LjfEydwq@Dt$$-Gm*SGWUok@ zZc^r<@=U>^8_)J5005cG1#dP(04E|y3O+*KJOXkiV2>`7kaXGA}M%^zb z(bm=mKCGs`9;1@^U4@gAlkORzX=$f8xDjA&y&-x4i$DPn#Kz8E$KZ85uWtw#OgW4! z{Ew8B6p=i-x~WJU6D8r`1t&WMm8ov6t*q!XHJ@Ullfz&mCbwK11mwC;fL@^r;8Wl^ zK6rY1!YQF!Ka5nroR$%2=qS8@L=u)BK-dog_Yly0gZRP&r7G{>@(F5;E4941IW^X^JX4;iNnM{Y5S<5 zvhoQaILLtFfd&Fsr*H#_a428heR3ASg!YLzh$mg>%htnfVMCJ|-K8NrF0i*@AX_H4r)FA{Ze|dK;zx9f1EC8fC4<5+DPV2TM zyoaQG?m0Qa5gFHzaSq9xh=XJpMOG=PHnyFy&Kw$VNekx2Uak?y>d$7-CFVvbRF6W; zgy5P2U}OKhfQTzx2E+izA{8`3o1~kODY?=Xl}o^O-b&+n_js_$zE+QDI@9Ep3cgMP+3Q zXi}S6S{j2=HVofe$myi+$Lnb5k-5RSW`f5IOp zez(7Q3H-ff>HxLF--!>@LgB9utGI@UNNJ4}kCgA3xsm z&FdP6oU57+ykNUZI_`lgnZSiee-g=Bqsmcl2)&10vVRIN1oDKr-w>*)I5~^Onor^U zBlKLCfF7b|W9uE#7&upGJ{{+OQy>*2m9aKMMf0UfAjRBrnT$oJ)WZ@2?HBGLGla7J(ka{&k)LQ z;fUg%m_WHUVyGbTOEd9-0S6!@Erw78l=d!Py=wbpvP>DyjX39`^C$7>jHxM|g8Y0c zC}V(wZUY;{w(#NCLK-+UGz3g@2ZYg#b#MXFu!;+#iUWYJJstdix_+jH~^ceST|H+f?5m$`Y<*HOOd$+g}2R7 zvOOwQRn>x`A`F-s+=Mr7d2-fpZ_XW%AF=u6LWqzL@|6AkN|EdqZIsb=`gE%nvQp5B?0}VGwp%xb3|+Z( zgZ=}cB$NfhVL(X&;L?tt-`_D?ExZ8Am=7-5sk*yF2zN6DqUdc9;()$xpb4*Jzy*&D zR53sLNszehNR_1#Y_ne*OaifUov|83ibL5U3&B8TqERBNvBKx?ZcnC=&s2zi@b1XG|EyaEG+YRb#`0#<5n z`s(z2R)eglWpBHA?`Z%kg99`M0&*r*%f#GV2Iv5gf>%4Ekq7As+Qb^a8#d#?^0x#L z`hzkzsm;_400@8L%!H-jcKN-C)IOS2xS!vg-`h2U^y2wv*O$;BfGA#4yM;%h5v;A2 zL;3lvaF9mheyxKRIjXzE1N4Ewn+LIZ+&ktA63Lxloj794*pekM%oYW1EkpwAqW$sQbWwZ=93wkSM zz|~Ntdv=rPgQn6WN6Q=!q$UhA&NP&uz9-V&0Wh0F5M)vi&3~8Zg9E0v7cy29Dg?iD zVppKeu*!@Mz!4m{PMA$VZ&QLJq56ys#7rPeAJGo~G-S6difW+1R<|yWR=*7Y1oSb5 zAUhn6W4?nqdLM4Rf&)X$s99sZwz0c4-5iosB_} z<(!nd`pA=Jg`J3^=}#X4>PiIpE-amv^ zAr1`On~X;VQXS&^T3%3P(5Go@)&{+JR7Un8VT;4(UVn&crBLHo0pFwWPLhvXD$zE%lE)JMQsRBz9}BFuc)d*;1-2%1pc9(Hq)ye-3j9J zO+|YUnc%~Tz(4$0ZNd?RY`AFV_sO$obJB5n;C=3$gwbkWR65F?R7UC8#fxU0lZTxO ztLpv|ZN&MoT@lM~ydigOfmX8{DHC-XQ1Y`Ig!(J=ZGebpXRdBxU&Z^2SePi&J+tw< zFQ-ZB`Kf@9AC)w=z^l?1kZ&rQPqjP>0PbsqxF32KAl_%4Azg#ZznW@^%_W`Jm6Vi( z%1WNgb|)sMxp)_@2^~qOijs@?A|OrJwTJ6Flf=ouZ6sB>B}8%CD{|Sae8vXLuN6e^ z9IgUHv$9Z*Ps72n<D(LjY4aC*#uPEjQQ z%@#V2Pl_5PAZpvMvpf$m2C zm&treLa@xVc4{Vlz!~?C8-c z2nRu)p28(j2(H+`C|)Qk#R!mEKL$q%-Agg|`T+yo7LTF@lzf(y^BMT$Rnk*9861$& z1OM7pwu_~=^#w}#L!uF+V74_7?b#lc_ zalU!`1_K|70RV9iF*&9d7O2M!>g6Q@x+_595?ciod(2_A;IC+R{v-ooP1|M-_wz=hg#uyrGogkEK+D6-d$w@=0gHFEsH)bJfNvi zMNfXNp^SHi!}&?M#pcQ@!GL#1j3kcCT;*}ZF-DE9iLhdlFpfb{C}sQPRC~vtQBP$On}3tY8(v|XdMGCRMFQw z=F5PF#phgbLXCw$0|3peT%S*P>y!LfLEPyjp*B!yr&k7KD;bJSfU zqj`2V0YG&SsDXxIvR|sD1iX|IxEzrVe6gza|{-AEp;X`C4*EM+ZAcb1zWcCY{x#P#r=r z9Tl1&ArlU8#l3=>8c+;H*oB|J%G#G%R2tkov`iL*-=q_$9**;W^zJw{*exUltuVJX z!zNc3HFlwl4csRcq)On?3MRIW;&jmc3->r&d)v#V#>Oqu;#{&Cw$PCQY&9ihW-iXo zI*`n>LkE)eyaps_LSkYeplO3RB=DKwR9h@<0h3ukTe4t4TU#6KB^WiO;2m1p4uibG zPtd3WOcvmHA!PR8|MaWrp%V<&8{$^F$q?jJ(C_C>%sfO(M)a>2V5ZnCF)8VHv*T{| zEkv{f#TBqCjlWz+lc~ItH4SCP+ajSc4m+EjJwpJ41>0cO4V~32pkh>CIYDOELf|DF z0PG^SwHo$Gr+W_~l^{@2&26a_(Z;V~U&h^V5I&>&^4!l?^C~9QDv3UinWCM5` zQEo8t>QBU0D5Rs{xYGdrH%4(OLEl&)q-Ri?N&>_n7=Th!w5I_pL$>oNpu~*Ik=E7) z5T;O*5fT^Q9Py+#2M?zE!}*lWY*ux~#^#XqGcgQ1Y^5V% za%d9n?%7={+j|ba4fRtzdlq^NHRVCWw!HTa^q2nE+|9rix-&bVC)%5oOA(5S$o@N^ zaZ#`h+=%8GFJWQfVBi>FEVc?z&;bbmc2l9P8}*FAW?%QLGzEFQFE52RHaCR=pe_u) z<;HYgi!J2D@)prWujjjvuN<^nZk*}Oo;C*y6;uZ z9bs^yAnX?FWbTZ_Kx1Qil_d{P8L=t{JA0p8X>@@o`&!l_aNoDCu^RupAP?cz=z!N` zVsOJJ3rP^RG?K?a9i?&r*JaLb_EqE0R4sd`ZiPera0VCgHY}9{(XvxlEt_XbkXSJ`gxM6&7-kw z!?52+MFW!Nc~A-|rHPVMC_^)nM3X|JG?|qKrAd)AP${92(kRlTkfcQE#TywbGL+f( zyL$Jx*ZRKot+n^xdu{8j^|tUl&wbz5b)Lt09LITHh+G>)u?{of`L249VA0L9|F0@z z#gr?U+K)fp5~bs_)hEIX0g4c5lvV zFA8^Xe0^M*LMvhQwiJ=Yz&Tf03@m{d-KNTCeZAsa8rJ2+la~YF6H)!w=j84zkQXEj zCY=4cb@^={w=|TOL1iFGkeBY8qDrl4@t z>cKp$r=ZP+Xp9kojgO9rOs}J3eKW4g_*}@9_%FPJ=q|W%2G!M;s{FcJm_^XNz9&zK0f$?_9-IwZZe(YG17rL*+us*kK?T;M^ zjpwNG?_h#lI(Ss`Z#R*%GX?3mf1vAZcAKCTSwSDzS$$(ikl-!YN`LQhWqu-CksZcE z^VpiGPbhf81gCrB+5r&uE z3oIoEO|VG6!qWNo>0VcA#qm(S+L%3O9UUmR;_Ju5@2W3}(Z|$>6ZPtU58$cOlQaRu zUVG5!rHbjJy!ui1_U-q(cD$xhd?NqHi}7=WCjd4h$RqXEif3h;FMgg{0jIiQ)7y6G zmEw*Q$H6gKRr;|b)YQtNZv5EN68~u6_?n7&Gq;AhSL|viBAC1Vd@xI(O&}gtdHY8{ z1dlpk#}}uxv1>W(IbrW}E~VArt$dK9KWPUraK@@JZ}^xa{C_lFhNS(|XX zd|_IMhKkCoo?908Bb>V2ELaa~^Qcfa6Naz0`s1rh;o)i%CNRG6NZ$#@VTOk%uWhWi zsq{N^NN4SDXjw;GAq^?EEn7ZSw~>@7#H#5HuzIxpIxq^(dl&+Jdis3%0h2#`?01UY zGp)7$?eSr#B0whN;~^fumw>NOddt~mLRq1>RyLwKdHCaQPWS%()djdRFmQmM72^7j zxMH^{t#7BbUPEUQ%szsfsPm!91x10U_v5J?SX{wX!PsLpR-#a|TeIf#8q5EKN?}{+ zbc^8s^}vYn9t~R!X3a`L8>OQPPa=hVBg~qcnqID@J8ewV?hECBX)3P28`U^?SSf0} zxN#qVP`qABQqq-|ZzHz;YZWMVC6Ymm)pgPPL6+a(aWymT#*f~UHl9T$f?udX)KX3Obwr+GGMkL)F6bHnfiC$*bDqVqr<`-Zx@ zQ<#w;I>x=hgmnfv?8YY^&p1`p*W>5B|8jT38Ev?vMaSzw>!(R#;SQ&ZcrjC>HJA;^ z+OwVUTNI(Tyorg?yba7*V`_S+o(kxF>g(5I!EX-l$H+Ou@ZNO})p5xPSWVT?e0KwW zy6|DnMD-$g%2a+WnAVClkhY&_V$1P#aBx@yADR06xxO=O;Tj4%ZO^8i@40{9X&rGm z9qs~0;f!mSS0QGvfgP*=OSwmH-oAZePVBn190~Gc4IVo>Tdi(WjxY~<0#>>=lX7=H z`x5W*NE_no{mST51g!l(vQr)x^%!Y!>Ub&zz!{Ky5o_iRA;I=tEdBhStg+6O(%s{xKDv`~LCznZFNehjt%(i545jca-o!j8q^ebr%II7Q}L7R*$@Ipb9~>!TVZsN28YuK97MCViR2Y&A>eNCWEot>8JJ<-m2TCf+lS69f8-oL!!Uo) z@nY>Y$Z}pe7y%M!t$z5T+mYPG!Sr)5Pjk#;vlelKZbK^I-G%L{+aWv#hJH zKY-PFdd|Mi1Jopiyqc1dCg93EVa|rdD~fHr29=|Bu=`BJ2ZCz6_|Cr2wzVN>VeW_W z<0T27FzFgx%}f?E%C|0x*dy9Y$4;6QMBSWF65d5|!I0klN2m>DRd$uc;IA}qKzUmY z(OOmc?@Yz|xBK6sL94jnuu+z*CSF9vV0`L|Lx5GZ=<*Jf*gIC&3kwTgthLqL%}>vYOCqe3~9jvzs={0xO`t+UN;QLs60SpeWI#snR?isnL(cvS;7E zgTBA=?^EJZ)0<3~1$92J|9}C0a!1N5IyOu!5q+eR*+gL9fb|SH`S81k+>xWOJCfOk zhWpBP5_ydWDk>t5{Hm^A^euSGjvK;6_F%+8-_>i@97NU;B9GCyZE|-v<&BoCuCMwQ zOgT8X`KkDl0!<3aTr#q?b^fdjEFg83jIy|?%tW46J z0e%_$y&=f=-v@-dUgzeHfT3Iz_$E2|IDFo0;B~srtac#FQ^7W1A@Wob%i3Ts2XT9z1X`V^y#mao8BvMZ0ig9psaVkJVO0kTc z3%LlKYAJrg0 zcY#l*=do?tN@mZSH*3a>Hr$hT5KYSS2q6A}fqS8cq$JqPe!)7P$L+JTs_;P7O&sTA z#*KSML-xV%;}$Gw1XR^O559?zaT*HBN-+wlmjt2a!gQF8}5IkV>Lp|ff$KCKO|2)XRREt0O>I`1Ry z9o14w6PcXk?&HbcqITal?@mn23_huRk^1?%vA%wOZ6zYbM7e|aUa}_t{rYt`xah2| zM_POWhH!!Yem5E!$Bs=vG1BV=G34!A|DXI%zxW28l zPH+ABrBAQX)_RVPWzH^nU7GLJ!G?=*8?43nlJH{()E3`3L_4KB5kcdjs=mHiJDH>d z$+LZA9`W`qfNJoul`B>(SUuoHq-FHQcLhC~Hg5!?M1@`Q7@eJT{P*L* z*cQ#x+jv(=J&uS@uQ>A)4%9fS{gzG$#z%Snf=gtk-I{BRDh;LrD#D}L}zVsJeY#BJ|eW?e-SO}8y)^E+D z%*I9}y?@^gRAyK#(|q<=>k3EL7jI-;rSon}7hnAEse@>AiAO%TWS{c0Fyl`th7Sow z!r)|EZ&v(@FZZ1y7T+9*-84X3S64T;M62f{nFf~>%V{+=E=X{8V>Xp0JW+ogXa2e6 z%;cn#zjHSwTk7~_+#TtaBh$IR{pQZPjo-&f=Dkg<-kH}0z^K?`Z=%yh%@6e4ae3Y7 zbC`)N?v(#Ts-27s7nypg3h)$_fCzk;oDjxt@I7!Kk%;ZYfEc1s#H)f=tzP#}Mekqy z_`AX#HHT2yBcD<}?r1iyya>P1n~^9_Nu^^~KJUP}Yy;@Q(5D;Wp!EYU#xt~Q-yZbR z7H$6-WSV$Ib(^@l;Lp|{o@IMqDX_e^aoJfdr>7;;boCC}Tw+mUjL2ua$SF;`PPhhk z!#;fF7L9+k^uZRpy2i#;fJccp32n%bAyOzxi>peC5%CsW2c%I4K%Q!hFq=fPRBOt!6!1s;9zB`_xAcx$f8o7e z5{hD3k2%wNQXlP2Tgv_%o>i;f-2Pyw*i%^}9o0i#+`ePt)tSb%`6b#B7~=htcG^_* z!)m0YmZxsBwXJVU&Zp0xFS5T&=rzK>T}f%Ok_O=3Xv&H6{QYh_W~z}_m$QSSYQE~$ zl`UQiZ<%xc3u0s74{002%Rg@C`jtKMd~_U1D>Lc|O{BqQxx`qED+WBqv2<5IfByVD z56&`Xbw^AatM8;v%5(Q&cdw`8-@KUIZJgP@`J-M#4+b-Yhl|CF$FK7DZ*gkXyBNEa zg_$$WPU4zAcKrBmva|Vov2!N9?FhmFxekMKP0bG~gWn;{1yLmivPGmw^TPcEcu5?mKgz+yaX# zsd;TfkZ~j}-Qv>QFECvq73l9Tg=fIrYUN5L`cte5$8zA6Tz=`m(0W*s8`(Y9?Nv2; z6l&nmcx`b{k4Xm9SP}_a)BN(LFZZKgZQ%^U>GWVG&T9Z&cQ{{CKAZ*K_po7XFFOm1 zp5l~PpSbV{%V;Ic^U==5bH5~b*&5B8GiPs5P%ji|-YNbzEqlI)51R+hGd6z8t=bHA z)iu+kMhCYTNlYh(UQo%t3crC0ijmH`X{(XhY%r|_B((VQyi;SONKh}3)AGN6KSX)53bln)y7*g8 z^s4rRz5S$Aj2(7t=;&-6tv+w7d&B7Lu|YhC3K>@^mv6HGF0>@JRHYY>7h zaj2HHlGo|%wOe;Gp}=FNK40JZEk4pMP?0!)jeHIlGK2Xa|MHfM3830;PqMeqi=XP< z`aM{iYrwG~5srmUQ^Tnt=oa4-5ut)PLyk}P?CDUV}>>K}M$Gi#bz3RP_F5bU?|4DLkCs4HgKM!#;MqFsOCS=5-M(a~CC682T zrylE4wOSlzS6BUZ+Jfs=6S&C|T0IR;UR`*(6B{R;XClUCi9JPTj;3BZ6&!qlJt=8% z{)ekFUea7rQE^lN7|avBwKfmttl9(h)x|@H4Qt0M)nScEXPOb$_N34=_4EW;?wA1; zz!>7GrKM&5?YFu<49~+?BP|j8Nc3RTJis$Bo3(Ro$?eLzU#qz2gn+QwHQ&MQZJnK+ zP0vh}C#b(lOM3}wUa@J@QQGth$b(v(zQ`iz$j@ZwP=L60jcpz@Z?9bs1QM{ z11UP`3Ga;Vb(kk1Uag0knI5#(yX`>wL;bb8(karRbLW>h5}k_E20(711!PTn_{PL& zYKr?G^&cs(Unk-x*%MP+Q)NHfyCg(#bSw421fOj~*qCx>i z;F|S=u2_hD&YbD@`}-#!WH{)=wv+@(M4?K~(+Jj)LGrSHA1*Hjm+83Ib%B0Jf@MPYO}PCih;pwo`YaNvulWnI<&Fyhux%%czNAP+u6bE<*vWT)TDzwq$?oJW_*2>9FuO z+c5*aBKr32Zf@ZXPd$$$OvV_8)6 znBj;@!b&jt++5(wCAi4rG_CWfHP>g~no-^i0ecC5^4HQ*RTiTtJUVvjbUd>AjJW^l z1>hE{xR4u%F*0HO`t_HL1J$;aeNY9X`SW3YAqq>jPR4ZPuRm*+pYQBYU18)i6wJTU zytl9M%GjkBvAJghq|6-1;#E9!KMu*!nli?Rz1B=n(t8lIOBFkG^SskQJU#|BU zJ;)TB!rqF_1K3X*0IiFejxR9FBYP_`>Yyv$_20jLbD^UY2I|bO!mhkbGJ9{Q9-?fP zNph>q-z9n^SQalZKB`$#;eP7g(Y z7LU|mN>3%Fy}8|}K%~77(K!9gXK1NAPi3yUZW{>pdn-W89vl<7#o!koIsU3$I#?>ZqU)!~yZWwC75{ zJxa7Ub#lHI`G@LSAu7!;a+QB@uqvLeAT{$SUyG}O45l%{bZZ)_%gv%9_VqOl)-=f6 zv?#|s`#~?oC3p-4gAyAXoBipN5gfZ6l0?+6v9%9}{RK|)hiC7~)9kw7!9u{^ha1cK zp%Ht&n^T_?SRCJNLH*PEBkW6G-&bA!z>>7rZ}%5Y9~p4fcp9+Hz{Y zD=v7wd1;S}Ta-qOXb%8*%9=YC5YX=2-2FV96<~P#j7zWmHrfQM{V%`eUkZUEuI2C7 z#Vz}J^S>|m_az@Z%h&q9|D_l>MehIMo6Yk09ae1EaG1_%rRu|d#))fS)ayv60pwqO zD*g-aOVe>_XH1NpP0ZeF7?y}_J-M(>!-tW%VVuQMf+xanV{%>*rFyz!tg>2leqvj> zfjYf;CH$Nt7kq-v?#v?C%>iKS;&d!G%+d=e>HStT0q2*Nc06q8!*e)o{S(rMd)1D# zdLh$s!RBQmP2%5`DN7C{SbbB*g9ffB%)@ z&Z8&?-i|^pGyV43dDizgCtj)&#qjLe9f-OsR;}_O7p&y|B$uC^ z2HWHtF<2D8*$^ZLz+{6--3Y+yw_TYi=R}HAUwZeNX}M|yXPl! z%De$TQ5Rk=o8>UorK%kQtRW%I#CqbCDgE%6J}0q@%3I`2_?c6ax2fSUdR&|lk8Ab< ze@b#6PvNs(y0qhawj!1POK_%X=icv9%8_JMfAt#Ybq}x003_SJK0eR_X+5Y46#Mo)NL#ujzsX4CTEh;Cfsw+*M1UMN zYSi`YIBrx=$rhGS*Q`aXQE?8G@q7If7!eF4v+3wQZb2gIGiCew;E#s7#oxXi!1gJUETg9a zYXB*J^dW35|M(-gVbMZBNFb0ag;;Hef4hy|K%Je-7k)xM=^*)prCH4b<5wF!aVWI) z=bao4D_CGk?yDKRFP$hh{zxzd4?a}qb@q;{PMc!4y@>_hNwOr?(fmNlXq&kE`dKy$ zMCKef?zX<2$ij4REZ+rD#*tpYxFz4zLT zSkO~ag?Ja4@#ja*+Kk8H^k!asUpkEbVWX6kloM1ceh7k$7CX?Pc%BG^3k#BAAZVH2 z15jF7SNZQ|4E&ELA}-;cKdR#tr}-zB^tkVZ-ZR$8%k?c(osFc9b2KY|g!XDzdC-Maga z9u3vh> z@tDs5f~Pzd#XfzOtUiayOJ2<8xi)cL@#MT z5mgT;3{%tvKCKq|`++ibLCxvOsi_?MME-7`3!1r<1b$4aa;sY#?ko{` z6)S!7jvf1{VQk!fOlZQ#et&CeS8=&(*S1H;7Ufgah9v;xy@Gcj3PBv-I1U%Mi(xnJ zaMfDGIfsX~Ke>JXqNeoXQIYt_3cH9VL&?xj-rMGpT@bA@&VT1%ZfV|{GAh_QRJD53 z{P|sk3sd4v0W7GCxHZXf)xhwXVeghxDA4G!7Z^WrefIJ#&EcANuN$)`sM8ODrlw!b zytwkkL6YbQ_FP1vq9X6&j=NZ_gR^JPj-j@hQGUSB&xdCP`_@5Gb$lLyZN-{3`)K*I z4D{pxKqhQ-1ZFTF?Wu5KmRKl>CqSQ5Csq;FNEm#MAOmbd$F7nQwS0bQvsKu;d@9cN z%RfI}OVsDN%2c}|CTk9V*?s$*l6(7AcY3MWQ_Ru|KdyH%-tR=fYw(#v%ocq{psy5i zd(n<@utymq7HSh=X?|n@Jm$g#PY+bCBQY1NpdD7)*(nb-JT#x9Gh7z_ zEtH}Tho5b$=#Nb#()vLRVD~jBW;NJe6K@iR$Vry5S}UHmlNv0n=k9D8q=lhm@iux? z$X4I)e+xQuW~BJs6p21rHMND)vZN8RH+?NE97e;(F%tK(KDLWE`S_~-$fTfAONUDe zAx&j&mgaSXo>ElwhaB-m1<@=Lw~>@eb$9~Edm_g^>iCWR%sU7Gd-U^og9nFEPX_vh zG;OreBNwaF=IxK;=oObO%Fn(N*Q-!u2azL1_KYcW|Mm4nRDlQEl0tcjslkAwAdtGRZ)tTJo#XAig=)qqjnx3&E#%4*25S2nQwMSTR@N&Y=XHb_rHxEtK`z9%!mau z#o)T+ET%N}!S$#1gAmq654+TbOM%0+MlY<&x1SD+&_=K0NnhWl#=O>^l7)|5w`J~c zBtT1@Z`X;0A%-(U?SxNWgSx=Oh)RB$l;npQ#`N4|bAZYvq8!sq=G0?m4bY)j=^?4& zf1{49Ez?eK@0rD|N~N;&vj8*f;6$hQv@tZ)lp0r7 zxTra7#-eEr%Xc{5;?edEBEl&8W4KjGOlhK)wd+#p31EPPdo``)mx4LmyQ$bmHjiEV ze8`MmHOtA_`2?!biOA$)*Z7KPh3 zs%vd5Yg+gH^SEuf?`&-$9%QQbMb-ul*NTTK4qLj_`oR_h^--g~k)Rf5z;=`KBHI*6 zm(MXZ?aqE7cr3oVOf?mx+|FCr8Ut_Sm5HfoQCpk8+z9o-y<>3YeV_FO0fB+aM6d-O z(J=Mul3_$Jqj9yli$3SypZ&TxtVx(w!&)o4D7w(nZK}HwGYRU=GGT`VY4(I5JaJFn zHAJcgrU^837!u;bD-A<0rr<~o7GsMO*KtvX73TjHNVE6kM0E*_1ovKGt3=%))(jgl zV(8$(k~M2uU1TR~X+6oyvkjayabiy#t(};^<_8Q@X(d$4k)@zj&%bI&z*nx$2*kjm zf`YdBr6)Bs+9KM<{rnI|@QSwgHnS)JCJqdf4)BgF+Ae4T1~>GEY& z2Z&a~)vJeLk=P5`{VF)dN83kH9R%nQC43-<5`SxkhqP@zsX@SvsuChWvqxR!3i9B2 za!}M(J`R==X|Ar0hv3(5Vjx46B=eiCTd1LDo0^&p9OHQC!2@m4xdzoS0B+0o$Pv$t z3Ma-JCQLobAiur*{v;JfvrFGiOx@kO{F0q(dWX4u#al#%N_|6)UkUCXG_FN0{+dl;&-uKC5gP1Cya z5695```Z)e?bG8Cks|Isd{sfr5m+El&HNU_-RwrIq|)gXu&U@vUgs<9-KZL}!_^ku zot1;BH+F*o%yU>V?;sB-rln9f_I|WI?)KKN67@l;c(_N%*Cwdc2&-5%AwgtkTfz`t z$o}&LqLJAUZS7;NSYJ})7=1Id?wHahUAl5bXb#y7%{b5?Qg#8a1c+~o%51&b=6qeF ziRXVSuY=^TX9lV0{*H=}M4N&Jg@5?mnkr!mr%IVQAkJezh_+~U2HZlKMGq$tc|_3HfPmeN5LL zRzgtwp#1h$*L$*dH#<2^XFl~U=Co031ukhcwR3O~%zjw2B;>bpYcCB+z@KwA3$h+W z{|N^RynB42Hf#NgMz!}|lwJKU(QMatXG2SSZ=o`M`qYQ!?1fdr-2i7YlR*_GW_h<$ z6O_+29+s9*+0v3#(QF-NDDN{dMBDl0rQcF|5NSY%Utro5c=3|0&AK-~Q2U;1HRhje z59~&0(doZ&fyzk^#@#zvlUu#xed$(%v^f&Fq7kcXJZjAa?y-zsDGkA$PT-g8H}Tpl zO>%z{T{?bn|Bxy|fKNgQT5x6V01CT{^Fno_isy7^(y~02MG|G7Sf0WgVNf)ww&nPs z|59Na$@`Z5#`?;XK_0#xV6{v~huIFfdgYz{d~yklNrrvP#Utl%IqTSOhWt!^Ht2Rt zOnStEp(k=`V(6Ql$UfL3)mCOXG6WBFFS{Me+!q3>Pho=FpV3G-f)>Mx_HDWovj_ee zH#sCc#AkO>ifwLo-b>vlDXm_TbJ3iCh=~Bk@4jdAWXPslbd3>OUJO=gR4Vl`W1Gl~ ztf{r_P?9j%{>%Nbc=-3gUI?R$kR!N*zUV{+bg5B0G`RJ%)q^gTUAFA>>C*=(a%vxZ zEG{hE0~0uy(fhT2otm{cZ=~YE$3J-y`AwagiXVr!?w*TBg3n;<{%dc{!v+GFh+6Jn07pH{xWD0 zCbl+TKEL}+b=+MGcN>?0kv-Np>uD&vhLDhfgfCt)UG zZqOJgt#8`^PId+>JV_WdOp+qOV zJ&Xl$AMQ1kk$r4?;!Kx#(`9}hrameQyXLIy&!3}q7h&L}gc~K8J`90M!-vaYYI%;= zcMNmk5^k5uh=5OK@>yO>0e_GOt>WQf^E3CcESG7%tYK?@X|0KYiILIR+2ekjguu!V zg+HWAZ4y^>%9W+c3{XpWEv!bFr=TyK$V*kw_WifA*{pcf)Ai zqW~RMB|D=z){{Mx8ML~=Z5=XHm7nBEokx$I4-eiSU$Cz1@vPRpCW&tAmgFsNZfd&4 zi6_FBIYHq-2ds9>3cqY6I|&w$icV$~^nO3d6Be+n{E>cP@9fQT`t%r~s@f4}uyNiQP<7D0gco3=k zd>W!5RsYDCqYaXM(LI9gMhzYM?EEGanQW@5>1W^pylFaT==KG?8#{?nzvwkrX_RX_ z&+FjL)(4(qEi~s=@iff7jl5sHiL!Zxo!wq=N0cD%=z{Hx(AyT2bI@qjF+OXFWh$rD*Mb0LXf@&gU_?gLj|Iq4py%!9DNms3wVaFOfTi+xCzde(+B>LV zL?wmDOa62jFyOjzE1KPMJWy<+X;}@3lnP-Z9c6P??v|qh%~+mt5nYXlz9e?xeHeB7 z&v#UXTZw9)Et$RihU#3SBHLBfB`gc&>j~p)-dd>i9-M|?i}~f&x~$PBj;w;2L6oOv z>O#H#jQ5eZ7}V=h!bjP(wg|LsCEuY718p|n*pPJtchmsdo5Gr`W^JM)?}cZiJqsoD zN`8-bx&^pv(&AoL<%VP7qHS9))QX1XT8DExmTXC+s1DHZt3%|w((Wau=Hhp z*(Bz_Gc{gMv}Jz?<^}O`GrlzCsSrJ)abnBS)T7lSgpML5LV+sxQJnshF}|<72w1R# zLf2-D_Djm-!yplr#W~O7;$Ud-vy-=VVt$8~OVu#ZKE^Z{Rkw>g@_|qd_lcR}a|5Ej4LJpX-plR~ z4ZzBh{PJ=?Vb`EhHOkd=YI}T0MCK$aec>|@Rs_0DW?~#oJSAG*g+~+RVLz0w*nRNM zZ7I1Ag4|BJn$i@uxu#?RhM{~KeP=~0+#PusJK;(^sFv~W+AMpCqz+yu@J^F$XL!>O z%MEg;wbsvT0(%J$2BU%YAy4Ro#Gwv39$Vq)NMuO;p#lV*(Gx0V%<;(hk+l@_OM1Tcz1LT6wv|9Yj;98YyDK|*CM()Nyt!wytAItUoEH$9V`;eX z=}|9GFwRfmXzn`Ax0}kRrmG5)v@??w2+MnXb>4rm&1f(gihq#GR?vCEmnZHV3%=w- zWH+b{hm72RrD@6QisyiMG=Jdc^@k8`B)xUcPh=tCq^e_j(=B??MbLu*dP2ovRu6=P zXgz@BBIw=h7&}?$tiu#+U$G;o{$3Fnp6f=92%Ox_NUBcLnrphzpDga6PyXYvFK=*4 zlAIY1S}tI8%z9z4#23mL9Bst)iJOBZ1yN1HD$|GU2#gaF4qq{!A5wOn8t>3m(7u%R zfGZ;I5Zta$ri*Jb62e4`i6$$d?=wPV@VZ0a82eU zNDT(#80X^0Ntsd+Hxx==IJhb0gcSl4f5mLaVu_@~8YBJbW)I6wVZb>C`na0$|3Z^L zM#0x-nrEC@QQEiBVi1;o=FOcKX12Qdx{f6)_X>)m`eY8 zY4)~T%%gUokKA(UQlUTX*|SGbn&vLz9H`QN9^I=N7-<%HoPhHhS95?4X7!$u406=M zT8_24@+!Uw$Apqn49B!d4QAyp3Vh4q8QdK~-HM0FgS2BA&^~vyP_(2=jwzd*j7a8U zEF`bkF6O07HsijWH*Q2ulJ*v7#RRsLyc>#vAmgTO!ou2wxL3)^3yc1efm9Wue8dYkY+OJ0d)-|>rz^I#DiK3)sv;!KdJArxlmo1WQGleJiw zQO=lNPY_HQW|Y;f7$fA1TBsgOa4FF{w}^_0c?Sk?bOG8{^B@O>TV%88s@m`?SNym* zK_OAZuDvq~yN6(DN^uD%u7i_i;KUR@y?CU;)Peaj`p%sI3|Em=gi|X(+4Ikzt;Ay@ z3B+vqW^5h;K#>~E6=CD}Gf>f=tuIdYcn*DvNN|a&r3w$LFD+B<3^Lh!WN-Akue^5~ zJuz`9tl+pU$GkMrZxjGst&-Ki*n{O`!vE@+RW#*BW(ap4*2I(Oum`VS|GU;v)jCZb z@zyVX>fYv*X`CAjRpAxHi~7-(EbbQts~rekW}8#XUvtG&;jIYh`p((8xnY|SsRp@M z?y7R$?y3!edI8#=GT88s`l##RM|p^&MBy7GDHdG`qj8ogD6mD_txGrOiU&GV=$?Bub;2)6UsRMQ>QG8avVV)G$(+r6-j`=Eebc@@R?O&SlzS)@0t|L$&(0^giztJ}Q zi=?y)AQDwWohTXeP+4Z`Bh0{IBm|9zee8;$`EeExc!@Wp(;3;nP*RE=pb=QM&*sQbX1n6>mH)ml-dHEN@*2hov)@cfQ)%(B9W7fr|Kwn=Y7!CR> zY}xQ{+nk+8F33M8$_4QivU2m;|Nc+>oqVpU*=>aop#S?)3;N&8If+jH^IN#Kcl`g~ g{QvSzC~lRS?wS_-{KdNjG0w)wV6Og+8OwM74^w{Hg8%>k diff --git a/planning/behavior_path_planner/image/drivable_area_plugin.png b/planning/behavior_path_planner/image/drivable_area_plugin.png deleted file mode 100644 index d63e7b71934c31cceb0229d69fb78b0b84655ed9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 156302 zcmYIw1yCJZ(=C<|oS?xW1b24}?he7--5nALuEE{i-QC^Y-R$As!NA_g$lAfw#_JGZa*A@TadKpT3fR`V>Si%r6{83Xvfu?~a~F zp2-}C;eG)FBTncw;^~u{SZ#(J{qw?MJUtCKnwUHe##e7CoTlcqiew#$se`Rf1o*xuFQyOj1)*ZSC$!33ETwwR6Ndnc(vpkgbDWW(Oee z@8BBE2A{&;Mh}>s?hnQ?VkAk;{&f`%JO)D6Y(8qLWMFD`dqbYmLg$5L|3`aUbjF4Z zP7&QQ)c#m!&!9)Hl4sh5v18v%6#q>bs-?~YiQn?e_*q(tYl}jcs{FtCkhh0jFO}RA zdgQz5^o&w$Ha=OmGCi>W)bw+jHrYRn6G-K?w@sMlWa%g8;~H7@Z8PibfW$X0 zvNoa6Wr5gR`<}VAzz_s?db<&21x6ZT&+?sZ`mt?hjB~nZFNxAw`HGjqY z`@x1vCYuk%-4UIl6$jn~5t%+C78+ZREs`+Z?z65wm zmk67WZC%}PMRWWCm$$92+sO6F&iYp&(xquj2sL;)hb(uh_+Ql8-?qO7Ail$B1!9#x z?_ti<;ST&1@kSFbVG|a$w?`2de{YXgbRLwB#F2-ThU!d;sfnm9o-sk2hc}Ma#7UHu!9>E_vaw^;)HMu+z)O)e`Tfu1Gm@A?yf(^)}UnKHcA$ZzY z8lBwqq)y-V5nI6}CY1F!jNur3WG;{I-73DQy1xIkPI=Mqf6<{|l8;$}313iTbj)qM z@s`${QLz(wGy!TgtDjv(BAeC~jS-}_S(S&+?kbI(AHqo4)P z-(49J@`y*(6Ymvi6OTI3z{){rM*Gw*{To~p|GJlLFA}Nf{7p~2S*ns|B}%pZEevL? z6kM#iGTkiZpz5}Q>i2*}WrLVd%C3L{EejvzGZ@6`W3vm&^^_>vK3ZY$rYmIj^B+ULR{l?Fci*Q)CKT0#-^y zCoSZ)9hkdjq2NDynLi=uqP&n&Vcd7oNecf#w=Nec_8J|Yx$uEDdmG@4r+o>i!t2-% zktaT7Kr^wNGCWso#Gxl!Ae6EDz=D1&8nLyP z&-&BXuv0%aS z2|?-0R10r=y!h{o4u8dGRnvX>8>FHMsXe)1LRmy1{7(2EJWUX>Gx`le-IIA?S#h0=BmY5>BK1`fFd>?|yPF*#0 z(a>%7Av#ZYE|uT2IGEJB$I*ez)Fypv8|_;$;p*7l^MS?oY{vg}R~|lumr<^1+N@VB zIoDG6CINaXyE|)7iPe)YHEM+lYo&sU&Kalo_g;qsN&Of67*mymdrTh*4I`!t7Ypgo z_=y>pBdwQ`xPiK#78Q5L{cI_iSH-el;6!fn9S+i4d7NlOt+~a@+y?8%#Xsv=z8XXE zEVC9E1ui7I@dmkIdP@cBA2-M^-sEp=|1kJ7SS3s_+3-viwh|>YLcv$HTW2rqkihU? zPl>LwLLwr(>+y4GVJB?kn$C_v!hPt!y_QgFqGclgSy9>HhOUU59E0=?QBhG$HGNpB zj#`1C{0ee(L#?ePHJyJF+PF64^8B}<5D9^c*Uo_LQkTJf@JYF5$0Vzl2jb|Mc~RVm7&g z^u@^pgHY~gWcfgk2N~Bpk$mxv3P6iN3Ks7}DKA&|w-B-&&x;7&T;4k{`Q$!oPpQn7 zi^yVU(0|<6`O-L@whyOrz#NaJ{hdzcd4A>crob*A>`v!Nj;3*8{v;9%Kt@Ks{1!tJ z^5gb+jzTdX-k?8B?|8NdEDWEAb7Si>vB>2(*Tv-o-+Qc7w`9@ouAzFZY1h$ALEc6@ zvhZo^6ZQbRpi9p+ATaq5abAkon~(lOk#eYvkI#HX1gF78;$2h}Aqw%lWJxwinu!`8 zQj(Ik_V?o%s6$lTb)z}h|A6fsF`A6ysws-J}Qdm26hm2(>DSJFRPOdi`i<^!ErD~m3S7G+{2d?wo{ij8g;di{-( zF8YtJz0&IQNl8gL0^q*qDP$=Wr5{=aAPkA;a#uB(6l6+E^vhX} zFwr{b0>Ya#WyZ?b*z?l&V26j?#}q_-=v{&(@oihG&{!EeO<5!L7 z`)ZAQD{-%9jr51sVx%vGFV*Vi?b*2zi7=>43Ag7hRILj(!c zGZsdwUBnl;HM#I=ralEJ3XSRMo5FbMgXwCY09AX6qZXb&BP%~0I6YG!>##SB9)O4^ zVQNaQqN4IUAb`#+nQ&jAr%ONB0wJAHLnuhV}ixvNfJzLs?!hn^HX$oDil;!ph>=cyF&1`Ft_; z#@KYmy37!s46vxdzHro|wZgCIGI#85%Gm-9Loe9!vu=Hz;Urp@c9mWI{fMIX_DVKP zQAsVzm`#z5cuw8gyz0Wtv~6?{sNfX8L#~=?kI@;t z{Pqr?v`|ds^=bws@dYz>b%ir3r_5N4R+oCo)T)F*HTE9lQ2esmN+{`=i-> z&AB0Om#yTGdJ*9D-V%N@;R}-Wen@S`|9Fne*D0;4p%kL9ICE354A?$_S1{Mwv$VGk zb0is~&E4zTH)EWQIs0#0$2ywzb`uUB`R^+7Xs{bRJwH`SgayQ3Uy1YHKz|oziE72w zv?Lv<4^zkX{mlz72A%OV8n$+JdW)5MrD`=F(_}>BD3$HU`Q`b~2096RjHSYBvGw9O zoX7iKN{L89@Gf{|JJtlk6076gl+(mpon!r~WPX6i-zR2{O6W}Nj;`uNpRD+s7+aYv zg^mNK<;HpZ(a?-j-XhiVM}m~|z$nOj2WTwXHM0j;0Ke9oeFPL;cVL=s~>V5A( z`chT-p`#TiC>l*NOk6ZxGg(k_k5@I)db=dDdFpBs*O}H0CSx>#9|6?MYg_QXye3s@ zM)SFK}g(Fb|`M<_@(mG=JYi}V7}1KrY{ryI3?x!tzhw{hplAI4N>2_Ml( zRxZ$MkqpGl*wYN&J+N9HY`g2F^h_tT$ve)r+ayS44zkHl`J6&!b!=ojR|WgSaR%Bv z?ibs=xGvgfqX~StB<({Yz|X!fH9JvdWo5Ollp%UVXcd?h(pi}&7@RIvm1?&o%jbyf zCA!Ebz(CGl?ByJ*f2DgHO2*o$nNP*#^<>YXP~G2Jbv&L8?(FQOcDXH9F2M*y#MAE! zLHB%nJfPNTPu&|yFoCDjsHeVfaVNnybe>>kE|pITiTiFkdBmfVKBS}^{le5E2mu2R zzh6gikrUNjXO(ejp3?mL_iWBi5PGUORII6Y3J7+B?Gs6%!Y71{_at^fC>+t+TxT)* zuDO&ckKyt#_0M}-Fzp0$aUxk=N=3K02F^lRV9UfYW(q`6of2A!K1B~-iPK~PMRN22 zd+B*KM8@rUNjSjFz`!7t!JGCA68f)iaQB%}2*qwAAh~W-jm3rPe&$a2Y>33ufib9g z4<8vTtr++NNP*fgS@IdET-xSE z9=Lh1FVGj?qvk;2;l~9C)VrGv$-T;TY@l_O@YB0}oY|xs@|uOZ-xgwtPKgATi%Du* z@uc&OiZvD(iLdlU9U*fkstGiiXK`C^V1`$xq|@-$`L=M}9qLk?cb$e$N?J^dVn-{q zwKvNV=#fB(>L*IycqFGB)g&aDC>v#KRd8SvO+}(q8YepZ0)^vP@Nys$?*rkE!FHVF z@8`O#3%EJZJ&ojEzm{88GYutw(>s|?`*JLy4O^?Aw(bk!4vUhTbb_lj`UNk6Z$l{D zy0UxqZZ-a-ov}JGuBByV1!ME46jrpbY;s(7+n<29%H*&w#p!&SIJHr%*<@d9wGzKn zV=~j^a6m2KiAc#3A7S0t(o)dAid(6)7ymvJ|GG(sfoLuxjAWweRRWq1@aU~L3pYuz zY19Lwx3$pY;`S&f!k^Sq8)zx>y|lIOZu7)3#vf_cIqt!@0#RxNl>HcoPCJ(C;`=#i z%;TD)h)jCO!Pf!T#cR#p^dSG5S9ID^0p?CiN5H=mRo%$Nv8hmx|4QmLTzNNl>EP7W z;EvSJ{z6Yc9kM~e!QcvVH$$FwHt=Jm$5?6FXKUd{4jVaM zg?w*y&zI^JWY(HZZ#Lm&!?+e69;vIZMN{5iHr|+n?YRc7A8lYbO!5^B%npM5YM|d( zIIp)dMY!2L6GPp_*xP*dCO+&OZOiE9s6HO+I-0l3!0)vD3jgHj(7QyHn7*MU{(520 z^>Oz{J_(}rIo5M~N)1B(ZdC`V&9<@&j-_SlQ7d)yuFm?`%yY8TNpP4BrY31=O4pXn z%|n4bXX1yO9A4(~!(X8uAJpM>CRli)PTt`Ahi84`H~NZtuf(Up+aC{{)|hc=Og zIC0+UL8q$uNQQvTOwVa41%wDA@iaS=S%S00%2WoeadGI{+S-jxO?uYW5h*De5qi*p zn)v70a0ix&ENd9=!|iJpUocVnYlkcvlhUh3HJGk598$SlqWkDL^w?Vxw+Qg^UZ6`B z>%2Z9RE+DNR)-$OvD4!51gvysJiJC~mAY4e&zqBB!>3K;d-+tmh$AVT@ELE(krM;8{qROU~v&?)a_hXPhbm zKW+==+t22WFU`;WpWSreB;Z&04o5}{F(2Uw3_LcRzodTkrrDUG+F^lG0LC@u9uZV@z z?uqwQ-S_())14e}sY2#swyy^IjXp1m$4M9iAwA1=7HUoQBygCty$cHop_p`6ms^5> zi!}gv=v6f}JAe&*0SyrJ_V(HyO_O+fd8swp5>cs^Q!i>kI*h%;WcF6?`0+}$ti-!@ zWNa>`UwoPGFvto6}+jl{sIVXYgJ&Fq;S#tv#oW)|UB>sL_Lx4o^XkDIi7{`& zRAxS9DBS>BZJs!y;yFUsAhx^bO!1Mt6h=~JefKGN%yW7k$4PtOC&Z9}56i`1LxTZe zFm=zUXw~lB)~sak8usSG3mR=bAuEbhuJ~ki&&T{+YZMXcZ8pZIazxcyT^U?1){UkHot18!jAskwXNwdABk;KPJ2Jmgp-v~N zj$@|+5K0);Wl~_covm%>*cbvG9bIW@DHuHqOW(!@fuiD!X5e*ONyIRUiLA?NtFP%y z3k~mqtSv1u79}%j5!s=6T>3Rvy?xm^SU~;dz*xa&NS*TGJU&F!yj&TJgLA)<7@YR= z`a-~6>flaCylYhU2)>ImX!7PkB+=tL@u|vsezut;?}S8pr-W+EwZU*w=g;)+?PvFI z0I*L|>EvF(q9n0cV4TdC8C-65{k13Vx5x4o+C1^JTEm-NerhewG&RO!`tzk~Qi=3L z77iRF@rQxV?C~ePo0u2XmP>r!0&R9z($KLU%)KXIp@nbf6`uZq+j#)Ry?Ef2ODpkGtHW=p_LHxRS^}T5(lzng^7OPL_G6<|HFej zv`R3DEI8{0No!r+#CH7h>o-bT1{!3!p4HgQf@AKrqdvB93=AATfJ+}Gr(1OKblW=EPFLbfW0uAV->5IpzkWkr9*Cdyb4 zrEE%i8K}`SV1yH|fUR^-VaMgm3@vhGH4WB$2gbqOIayov)a()t0h_Alu)A*Au!mb; zmI2Ph_qGGMNqgFf*B;lUpH1lV#ayWfEs`PrT<9-pa5uBtqbrNGghoaTAqx7YmQS!9 z9=L&*LX9N_p!KU!dpw;=tiy{+w_RQDn~cHTaoVN?V@e!Nt(AOkl163L8m7I`%{RJ22X zo3VArBCMXr>px!xJ>G{E@-b>(Xh})ZWZ|deg;JV!{xqd!5c&F*BwVi`KvDz(=4F@| z|D>)(6#4Xz`pBH=u8vYtW1>6@@lvxnL0o`mw}sR2wniQkfzM>fiG}xe<2s5($v5j% zUddSfP?tx>#gZ#JzfcVY1%(J>+Za;m?SwS0Cfj|qi?(}wu;Acecr3=>Tx{i+w+lKo zW;6M#&nbo~Xhz==j{)!ik$_jq?<2zGk)v9GgO*A@zhIui*6FDf01N^96eK;T=l%KG ziz=&Ex-;V9@pz0W^DZ+o)@SjTiVHMqzGv7=>s)h5XR=xMYX@3!3=44`Tu!l4*;50_hE$915c0mT9tyks^T z8K5z6Kv(r&pKjmBWuJd8LRp+z(iGmS>rl7Q>IW~8$gmRhf2Bi3Tv0}7NByzBUG$~O}p3+dA6b6}!<^~Os>O!uwfdCH(o=T)+V6<$YDaJ6kNk%d};f8!^#b13zFDI0k zR#<>RRnN-eFX(vK(}eeDvh5k2U~H$S3Kb~8C7gza2H;gN-F7M59~@8o9~VGwR=c%Tm+3-P)~dX?-dPy6?%Tr4 zJ0WAdZ5bv_+pJo>&vB+NkynbLB>}2=TSu5IX~fnT=f?K*o0qXPj?h@x$Qk7+-kE&% z*PvM{cH@q3g}wHUZ({53`>NyXGX`eKQW7|V^+x36KMX9=I@cO!FO*oF7jsw1#HUcb z$$T5jY~;q>Y?rwa3cq82E@Qjm+plXSyY#`x`<~$7w(CK%eDRNp)J4mIQgC#QlD(-B9{sfI`_a*doa0*k}E@%deo`?k#j zvlLe;`|&l$I*ffG{9@rQuT(^ws)Fgv0Lw_4dh4?|yOQ(ZGJ%Y|-0XTQw-3+7LUrHz z9D?Y`EFRJMBwqF!QyiZ;-An7uX`=(uwROznMx~wSVhyFkaNDS84cSbMr}h9C$xdQU zW@fcnPc4t4S-Nvo-|7&gGVQa)?G3Mc(o;gNb;ivrkCT@|pz`A4GQTG-=;H@rtKhQm zx>_f$+oC z>k!^8))ITJ`GT|3rRP-g5MS{&2FtV+bQc_xRV^!eW$7ULJ|`bH+OeqL0Z;5AM#a9(C8_{ zu@Tf26u>0GSY&8r*c}tQ*OST=MDv(dH}9#L6oQr+!y_Y=jo14x3NK!MvOsEpm@?~K z`sGo_&ssj(KCvAXvY0Dz()4+)0lO2`$N{Btv0R=6`d=(^{+x+rhS_?ReZZ!zt&J%l z?g5%xskE|QDGPKg-T~``#j=tlkfN>^2uo$*uuagLWq;GVc7w5CecaUtHEDnSglDCMf3SiVjo=N4;6#ebFHw#s5&U6>~}mBuEu>% ztzm0b%N`qB4LEeBc7?2|LUD20x951rvt@KK9+)4My5K;TYyY3+DFexSJ9&CkX=;TXT#CyCoI57iAQVLGPbcbYKRee7- zX~-AI2cytt<$C2KE(a>Q$ft0MHV>xFYi!)dTxWIV2J8#>ThOB`YRWj$UR!1>Rp^R&Zr#%w^-X5b=DBQY5<)RBs@L zK-3Mw+!_Uhl(d`TNSW zm<7|(vQm^RndPtgtd>pE7vAd}wATCSs;NQhT!()mZYil$ho2Iqm#5i<}YUeq_JWc^kEt zCg=*5r@A=fza>b-dZ9F+3=MSoK~I_2r2+supk?4iF0{V0ot4@=J9sm(4}rZ@7(djD z`Om}?h#(h_RpQ_3#=!9~;`e(8`t>T!x<=0UcGJXlrYwz-T50LFVlt!-TU&|t!IYb4 z=IUs2$chVjK@Qw=nZ*nKcLCs1>FZ%wuf;o-LAw$2DU)E&QqZ4R-n{rS7aH2ICKm!^ zMF7e`O30z4kHbV9AE^7Kdh(wD+r6Y1`r(lHpR;*Kt8D;37t1%4@Btl?{ch(qEDhnomYEnoN|)in5_ZzSs6 z-%Wm?Qo5Y}79BW}(mWVj32&Vg+W0o!gpIBhCS~oqy2sO;b(Wj9<%`&o(nd^+w|qFPEt%T(MTt{4ZOz9~$Ck(kp}T#*`M%4`IqBDu!0ILd`r z$(S0cvS`t!7xEErs65JyA9cEmEpw(U_0SiGy!+u8zZS`KNWZFe{cgR6U9n%vPzE&n zn*+%yuH9L&zG9R?;&O~L4>suN21H%Plr$gj!{pIV>#4IWp)Ad85~(?m@9Boi?Mr?T z)w{-iMeZkg-W7?6h!}>)6%Qok(M+Eh4ElFI?|&Kju_o zZ@?M9Wb~oGdQ?{`S&zoT^rYCagrziDmU&8ENOJ+{E$lO!tz;B+tbSL{!|YKPttnK6 zOF!X>kWP@?k64hGmoL?9ihjC1F`3Pttv)T){2{TAYAp2!{s0~5pHPK6Ih9#z$j^E}NJlBwU0cWOKP@2Nv z*5^8WiYIVlj$X8yiGy0NJux+|x;Gheq|si`u~y-EqhMe@XEr`!pi=p64nMBd&q%9_ zRIxzommo`yIv$&sYN3a(Q{L~h`5nW#d16)j_EWiB+QGW|;0A+;&7ALv0o?`YZ!Y2n zlivsBMz3fN>#34EkR@KaW~{H%uQ2q5*MuJLSe3X|56O7lwD-nFRH0`!uDmAUI^Yp| z-4y$KU$OKN+qKI%7FbDs>s2wrNr24OPu7Z~WDp1`L+}1mzqlfm$~BW<(J3p9$FSEuucfuUZk4f_P5A*h)b)Cd?Juqec;8Ua z(3sZ!ZhJm)RB0w&6Z8vK@K)M!o1AG_EsvZJH^#>%buc(9$&;CKoV39t-xg63hElbd zq7k#aU7y(WugdB@uVf6WcNyz2*Dx&&y5NRh9<)WVXNyHoR7q>LD!6(-w08G4SpIlb z_|%^6U7Ly{-ozO3;rJkGymr}xIzub6CWcGCMxVso3Ad}brvCylkK+Adgv#s#-GTkc zeNzI$Q%eWa$(%^+{awEOy|imPUphW7_9>T?p~|yZ`=OFwCS`b{Ger8e_ zSzh4M;4JF62PdhPcPIhXDBTMTS!Rb_Y)%91wbcP*V{`NN@o|VpI0$zdVjpqwq=CNC z-p$v7SM(jrXOmkOy~BG2Z=>6gbi_UE^^K_*7gu0rvbnW-Ihkl3((rUABp zpaf!qPT}w#1omAD)*D`KoApw}79iS~RfL>9Y)koqUgxs01o=t@7Z>w?&z=v9uHc`& z4|}~U98fEwUXdq+3LK4)kt%(8flT2m87TYUXR2I-&7u*p6Xan~>{fg|NOim#d23F$ ze0L%B(w#NRp*4BU!NTjcf2FlyxbIRTT*pdaR}NC8_GqBYe=4!enDkrT;|7&+#OAP& zg1os}zQ=X-75Tis0cyapaRj)ey(bkN=@*W|cRD4dc9o%qYLSGLN=1S#Y?!w7)6j*0 zV-{6KmXe&WQe$4XOx<(j{q|^LzEB=6Q$S2lAB9RLBUhx57iI>xy+4-n`}c3#o5LxH z_kA@(ef{n~#G?Z zl;m|QqzU2u<$40EgUy-i=sg>V2mx<7Fe5{!-$BNDwNU_w|3AUPQXcKX$QR?zr)FF2 zQkBko2~aHn00geQggEb`jhL7iAyL<0nI}_Kb@g!Lkh1tNO6o3|gDnI-!2S6M|K%sZ zOZ$cCda=%9K3muYaG&5ZmQBR;d{H0R_`$!?e|~oZfbCrEHg{ZL=mLHp0hZ5yEGR+w z*q4h4jS!=v1}^*EPk^h+UovNmH9iL9M}WNT=xY;+2mpD%96-j1P66Z;fTG-^|I6FK4P*;ymObn7KFaYKXpig~ZVyX#i zF`x+Xl_>!53Lw{#4kG^yq-|A7`ntNnfs-UP5R1RhX^WG1ro1OW7Lc13N6uEFXJaz~ z5Qc}x$GHFTw)EcLUYSiNe*$>@_3Qlx00ka9NCK{qe?tQs4yz?05FP=!@N9*m!`UL# z{QP_X--MQxm4$$WT&gmF22$AB8Vx|+&E6jfzU_AU5k^Nx0nc5as#G-oAT>8P_X{3| ztc)FxiC~b)P$*q{A_Mhv6fj0`i}_MLARo23vcd#NwzRB_!|m$Z)YQ~y5>ueXLitpo zJn`4BUn{GswvOjYeyFK^{`~n@a4-P!!2lGVNPtoY#`}7s7*D4YAyd%P-=Du2(a`to zNbo;);2(>nYLdIVJ1{J-?gpC;8GsG)a~6Z0h=>RPpaXJqzq#L?4!t}AWaxStV`F2- z^VKAOILzr>anxefiU>bH$esWM1JHJ#Qt6MX#d$$=92|{JdQ$*pRO9Ro6-`(tY6qa4 z|IZ5aFF1<7`yU(8BvD*%IdW-b#en_`KuI~g?YsR_WD+To)1^zVYhy!qw)c;*E2db; zO9pJAnr-fJ)kY({k7V6^J@6kPRV%b=EosQmCn;d%k`;BjQG5t+! zY$Aa!qEjl7ALag!XlRbc`G55WL1bBSUjN5z+!klxaJ|$OFA(@2>rt+6U_f&2ubKf< zmED_ky3$aQJ45)7HHdtLEb_k@JR(G*`dWP*4#0?8WNpYGrM0@7NfP zK`PY$Q7}bO@bM!6uH@Nrok#A5%}RYZ@NyU!2{F4HfWdu&gY(Eu3II4yR?D@bPi6la z-#&_sjTKs{w{n{ui20iV|I4}AaS*XZ0rCX*Z65E>{=qN_lqn8np2wAd=&{2;hK?w2 zs=F~`OZPw6?U?iSQ}Pf67pU>s@C=plZSEl#5u&^!T&@0PcxOKpDHTV{d=Cx|3L3O~ z(-V^*b$_P)s%k~J^@F3_xRn-<*B8?CXrA? zz`P0_{aLYl>_Dj{4~ecqfEOS7J@Fh7Buq6qK*qoP5D1MJV@n;@8>(vSQ{p4?GujKs zD43cN8W*7UB_=27nJ3rn_s-5T6SIr^?9n6%>a>r~>YV?{g{~|5z&gGTrBp6mbBAY! zwJYZSMc@1+BC_J6$;f*@0fmr&IQ?HXDYsWOK}W`%E{TIJN{xYwxh@K3WKk&U^58RA zB4+`jD7E@8wI)V(C-?Qk)@mUPV7O|&r~oHUN;;0ZD>x|$D4aR z81iE9N&b@9-~47i_wfc)^h;ecFZZK2vP~Npnuk5z7%N z52lxl2~rSWhyUaC!qtJln8N5OsB}K2%7AOLAY^ZF8tcX8oy2NO|S?WocTXwc63g&Z5X-S zPW-qs7Ph`n?`!q##P5zf`s>jTD6?aQ8WRcV8i;m`MW3Ch2|=e6v=+Xm z%1aPEXV1M~N{dwLKE^>>$$jR}6V|+EBYtVc1Dn!64?WcWA-QC;Q z8Qfe$L>a&)1V8V5${&|$boThAp+f`V=PTKO8N_7|Z#C-$JcYwdHN0?$Ze#6>GHWL5 zuf@h|Q8nJax_8^LWJ;=gr{rY&GD#TYqq;+oQA_QP9Xcm^XA7zb`k8-I5d zeeIw7CQf4s5ykSxj);Y>!G-`H+k@+bek1=s~tKcm=3#n-mt<6&w9*nH^ z#^M?uGl9NyMYYvUI%k`;!2r5|>z!q5sh3mb@1qK2K z&u8ZrEafYsYSQWuU#-NM=A4^&R)k9+NToh^gjto4HkBKcvydIR>@%u3WYdIn3I!8e z&cS;7Y)X{Ovs6Mka*!(MohgQ5t``cQ>`P+t>Jw|c9SMsG8eE4SoEA}$r%x#MD||qj z5h*BZd|UoNdjjd2r^;pCR02lxd7QLxx*=&eX5Y%6plz}nogW(N2-Yhs_9B2fRYm3+tff) z_U|X)=W@f7pChq1bSMcrDS`PhGc7gG`ywLy`N4 z>40}1p|uCjy10}NEdmP~V7=_1f%)y4;_#kvOTAJ+W@w88!ID{B+q14YaRk|6Uw-8f zdk-2=b&Aqaz38oQB1FumSPh#pQO|@O2*5L~wnQ0e=N{?lEN8xyK#-0NBDQ>%4AtRq zp^p19uGJdZ#f{8WGo7I(bfhq;9@gp`dAb9O(u>B7@YiMx4*!r2uF52CNJcdPHiyn! z!aDLi9{!N`&wzww4T272O|zQeEn8JJZSgjEza_tH8qeEf%P1G_WT{( ztK>~%DThIFzkA=!vJpM7$l?Pw{L}A+6_31m=fs8F6DowpmmZXMzUiNlE3JbbJ;aa3 zb11xTkKmkjALbFqV=Z>CF0{I-ORn{yeZ1A&!;9(IdYEVk4s$B54xXH-+wlaehhYz@ z=MF(#{Md_V_KKhWgtnSXhIy$@9$l%&|MhsT5;SymslR~lfQ#R4V4aLyF+&mcH#RnA zE}Y00DFKC0-(OYARB{$hfRcitF9pk027yydaR7C^#%KiNFH`*XWC5HU;D@49spJX< zBF56`yfLWkFi^PsV6#Uq@gl3%cOCocH80kkmDKu{m)?L8mYsDrlOP~;6sJ=u7nS_y zRFxDKyAX|;=C3RsRP`WYMt7XY$TKWR2AdD^Q2=%iq7xpj754le=-K zj~w#&*{90cQEWG~h+TwL#>`Zx_XR-YjXOlzJ6S=`j;H-^D;vhme(5{t~wqkhnWyoX~m7`nwQ6 zBy5!VGDVJ5I78WgBuOfm@V+nig(A<33k-w?dwY9}R1J^y4)KoD3>%TC@$lC#;fB zd)%C&5;BFjEr4`qWz`=Ia#*4e745V+CTKkKI?e&x{RH(g5&2l^izXU6hf7c?^w<7E zG!Dtn+rbo;gwd}&&y`)en?PZWB@kBsEmlHD7q+*zk1#@KwffF|2LDm89NGi$)zJJA zV5bY%*w_Y^mXe~Pke3^5Wcm5QfF^e0@JoRnzohHLREUae*sauAVA819(z{PFUpFB} z?cMb}-(MsoqY|aZwnD_5&g@|%8hYpD=F+>IYyQot1H?cK3=AN08-hs!)L%X%F(t*o z%uL+S@Ed{G&F4Cc1>?aeqQs=6y+RiGk~u6))#(i;X#9T8v4TjtGjIv#rnO!&FLtk% zU7XZXt(JHulkwdzHsy}$UW zl+fJtMEnhEK!!z1l-b$Ye;GpK;}HPEjNbY5N4`{&Z&H$4#L-NO`>#J_Wqf^IgE_-& z>>N(VXjUurW7EA*gruYaK#(_8q*xGUHj{%-KtRxxOeK`u&3raYBbUVGLOV1xq}k#e z-rFl=7X7#EDpuiW;1VcFI$vuM{r(-o+uM6Ig)P!$-3|Jof%IDi&az?pc?Vi9Fdm>% z){zqr2*d>|7EGYXkGckc6<1@~3yp-2jEyY;MAhk<#s1`bSFrf@B?3d*8qw_?T8*~9 z03(<=XD%)#Mjo*X_czK3>KzzB#mAQs5`qFkF92+rJajx_A^(6NlHSj61YiX~2x5{d z*SRSaDpN3G-9jE}FK2}PR5DceKvRa{Q(a=6nx3^bv% zl5M)w^z`KdeHx*^`oaKe@6GpwtRIp`U$;mwxUVko$y#t`vput z21b>Tu%j1Net1_!Qr}YZuJfDM15nUo%8YF`{8tv-d1%5!U%&dcxLg=>pL}~=`|&fn zY5&{WD%=Xo|8W6kR%MF8(W>b!PacSEV5rH& zgrzd)9isL7)KEooP_2fF6SZ;KbjPhwcO1v7dt@IjUO#J%A1QV)ealDw1M#EV&p{Qd znkM>sN_`u_95>C%bSe{`_+(MH#CH*n?ZH+R&4f56Sc(}4J&7wznY=U}uY3yv3Qj7} zCW>DGj}A#xSXf;5zesKmfI#e_NZdY<%Nii-O97)?0~7_^6yT=BgFc))K)_D?PMm#N6L01x3v0ft{X>ig_pYKE2AfYR{t=Jm3Ftmk1r6hhKO=JEu_3 z-bSxf(#x85c>U#Dm-ZoI8O?e<)MzZ6?( z02cpIz*$y9u|g(|bE?W<02e7-MyKJ_1%IpoGY~+qO6CB7X|hn+l-Z2V=~&WgH*XG0 z4*t=ST3A-e_sZw)oQpTa+-mc|##oXyMO#ev5INTcLP3cCGn(+!GX$&(wQkq?h4NO2 zyRv0aTh3SEDqV0PaP(YaLKc28qBfh9r2ELIsNdgO!~zdSOnAlfQ#qK3xDJwL=;g$Y zu?Hpz$sf7WmY|vE-_pA{BP9-a?QSZ;0s>Q~LwZVSQmP)RtUWy}G}fD%@Q~_QbB<|M z&ZtF8;#(@CQR+X)SN<5>hgsFUv632^QusxI()#x^nRJ*cRvA5DwilE%Jm zn$)%_h*v+qQ77`SpFF#i-=hpUBkmPcM^bI*PuTHi-p|zPWrE%L^bm}q^r8Kufu&Sy z&@}e8p#ELSkUznm)6bngc4^9Sfc=uN&-_+!OPh0Tjn4Nt$k$dkWoVxOK1M9UNh%E0=OnbTIHO4?^L~$fk_rsfH)R>gbKErb+&v z!XI=HXEfTjLV0qv{XJBp``!8`HDjiEAOyNfhNa%ih31FNkCxHMd2c2KmQq%K)Sd5T z)oo2x2fF_m=|WNOeiS_Qkd8bm$4ntBUuhIP#Q0+a)vqbIb8+vOu|uyr&FxcK^h`+~ zdGCGW9CSoc<^E^Wq!(%k!GpWQVsKQG+*p$Ha;78+s*fB4QUYhXyxU6@i=heD^u3R~;iHmGS0`K=rv zmJjIf68Rj7VEXtZo3^GDf`(Osb?ihM)Uy$+t?!dgi*IW>M40eoQxY{vIS`IvH-n3< zq~lbS|5I^_wPm5{^joB+;(>Vffp*Ek3Oi+2)E}2NP;H%@gJa?F%|&+@#1aE!aC#xj zA@m!#RmJ4@gk<3gPK?Q&SkmT%9~@0^a)|+p6H63b-S0t zu9I%?@GY1No$XdwX|pNh6Gj;~>dr(-$>ia(IRp+yZ5AUoJ4UMi?^SZWbdCrv(P3S+ zpR0^fL%QPj4^AA8Ro;n%!6iRP#KIDaQo8F8;J%fZ9P5x$@`oDLD!l@{ghUO{xR1FV z_5F@&w32!Qka7YORshZTaNlV%9OmaUEAnhhSgU(S`Q7C9veDzvNhS@toJ0O*fO5uG zq=6LceVF{K)1)NvLJ0{SS@j-|A({h%{5iwVDbBip$`r)EFpHCB@<7xZp$|X-1iYbX%B6&TW_3DGm2!9_AHCA>WLng?T zm@*r!m{L2h@T8##W^Ev-bBwY3$we|L25$96k6{Hv#m%_sq`_K!(kJsQ2q#xwUER64 zEa7SL*&%Zt(_KYhzg<)P?((Y;>JFRn*&%Q>l-YR%3|j6nsIyIY*;X-w`)pHJ0huMlxIe9PNU~Bn9?I(|8e*)+9 zXnw-e+p2e~czOVwL*c8Oz3BIEJ~A}j)o+b?UQa?NJu-doN zimlH$CEx7g!GyHp9^OlmHi!%IyaalU$G)ok5XwVg-qL$#ZG&2*$Q) zi@)hl8?mmh0>OMWrsK)|3)*y8AQAUB5s^NJ(Nq-kpU)ev?iE8xTA)4mMU0`_yE}r{ z>#k_t-!N+8LJZ7q;jJd@?QVd=>THnjbt`y)rj^d)KvCfF<a{+DZDoAx zWB1ziqqi&Xshs%d=^Agq_q04Cbt}*%8d;|Nfw|0PN40%ZGNAZ*t`Hv2cal>@jcfgY z=c%LvnlgjK*68R@UMN6KS3#i%gvH=88-1Ve3Ng$rrvX7yh?5SaL8Yr{Og6bF`5b{A zIo(Fb=Z7o}=N45!ja(aC{kLC=hva>w;Zfd?NY6ncLqE%2AKI;6$`o~Ow~V7KY$(i+ zG3>lP0hXKbw{5dUC5kCJou zw_@BtR%<{h*Py#~-&c@}My9ZopYcZDn+_KbYK17J*S1db-u&IeZxoIr4hm;vu|Zj( zSYCIhdqS`yO?}|wEQ45KP;UPA=Dn8Q^Xp3BFz%lB3r=%KD{NYyVi*}~_fk$kK+LyB z$`H8)GWB_GSYuG+Q@GhJVQ=z4NL9tz0zP%{1E=l}yJLI9@neSrt4`TJC5DB4w&B2c zZ6{0^4Jt1OUHX3|CGF3SHpY{hy(JEv(GM0TAC+>@%IBjkHieU+Pq)i zz7|;fHRrb$xr6!Iqv?*b6NldySce10TElyr1$|%aEE(Q3!BbAD(=~Y#Hj->1%pMVY z8RMVGcGL8RkKz{JQ^5wm8x%ky0m^fYVfk-3n?*j4+@yjA+H;pTZx&wt!}XD;sZ$?k z4|sMJ`t|G7Yri{vgmrqzaKZJ75_Zw#3FnnTJ10R;UQ*M1s{Yv79xL*&LA>lUe(3ONi--F8V$O6YZE_DF$ zO8CG??+mEUnK);ELHrEgCl#k1$5tu_Jedr()UkI?b~{Bv&WU|ycjuve&)Inv$0rWu zVTIoa-E|PkJX*}{>o)TA{WAkPn3-ITj%ls-f5IQ)0Zh)A<%Nd)}wLJV&cYp7ghNPF{8QBVep7lDi(vfrA zjb&JK!U6`+v{l=2DuPIkI&WGWJ(MJ}D>#B!-adZ^>n?--Qb>fvdtJ*C&{unG{ zT|~#^ON!1?{3*V)AO3cG{V~K}Xo*X;QyWF1%g#tgg4vAm$0)y;X!K|tG{uHQ+Scdi zO#cAMV3&4yS`I4qt~r^x!ar<0{?IUJHEFO)VC(%=bEK|~VPCj=L{5`QRNIe&x%nOs zT)P;dKfd5Qv@CV<2a3<=YEU$qx!3e=tb4r1RTZQIf?!gq=^biZZE4U6&AQrnBB%(w zdCc*DTrSi?KF;#!6me~a_uEv}FQ+PMja9EkEL&17on!T3aB^!tbqKBoaCe})QPNm= zXs&TPQA$hqVwsf4b_jclajz<^zou0<=^Ecb&cBAShI@a31!a(wi?5`9YAM>ds47zO zev5|n!zJyql@5>0-AkK?)2-elrvBf&;pEorI3w~6lrUu|E(h(J#fSgk6CF%o-~!g) zZd!H^jW|BKqT?#)8Z1zIM-sWJtZe&<1EXp0Z;a!F?H!#CbO~kY6!hW)AJ5z|w`h{3KbV8{U z#VMM%S)^g7x|`xSSqbTumBzBd!7FvMhw7A=#D{^C^wGyQ)Z4+w_#V6di`rz9j(0wf znYQS3eFQUzUo#uK`WIwF>-@A?9h}$a&6eS+`?CP!a8& z5whQzM#!`yl;u=VE!tjz7?hbJIe#p+WdOcU9GuER*}U*3SgzJRmH%M5)Hg8R6`;gZ zXmO#0Al}e?GnfHp9=VtZ(lLioSP|hnbGDiaX@DJmeYrj+MoRW;Oa?9nIcZAq?eapQ zoSg4~)4B2tms6$Tc?=Rc_YWR8W8=ZmuZYd`BA*b!EB!6wiDXvkh>7NY8s_+diU_Rz z<}C^c?=Q;x)TW3UW)Tulg?|(hu&R8GNt5ovt=opIm@V?%o1Ak%+_9gDQo4J+uW)mG z=~FbG-M`r5_ZJE+bcg!fU=8PxKi@mfRDW zS;NRLt4v<*5`@$Q+2WC!qQc)e5oq33?NIwT#kKHB8~+0F18L_uiHMUSco@VlnHE$L zX=kLA#~w(T*&!8h6BNN`BI5l%atPQJ9LZZLI5HUutXT6h&NaB`TMO(F>%Qc}TFgZ} z)C|FDx@av_N}|G)oST94a}ltBQ0ci*T1AV+PFO}ad85M_K-6njSZ4-siH9u+hghjp zxORqS7(_`=W~u12ztYs|iMe_RfHIrnwR( z3p~EvLJ=WXkDuV?I2Iy?YHv_Lv3k^}17c#a9F$;+&fViiU+i%wWcy1X_bX)&q#SZl zvV@*T&DX;xmfPx*Fl_zhKF$#0T49Q{VAB@FEBJa;U@Y{!(s4GL_@PT#<>Z(_-z@HY zQ`XaTC6`0t{rA5Cgmsj)%U3V*p}ai*6jQbVw6EH89>RnaF~)SV%Qg2-jWo^>PB0?s zDiYU4?J`S)f}UpcTrkilV~bkhz7Jj9K*F>7Ngb~078Ry=)GSptNL}?$orB1b_QLK_ zg1s*Ug=TmfuWuHc4DqnogDBNKzL$~&Lj;7wQLtDWy2<0|e2Co!tWdm8%L;0W*5o7+ zf9oYdDB^O=9YJ=WS`--rcd-6F6guYO$YGGQG$C8;t@+S;U<^+}2?0P>t5(XU6c&AJ zWMwM4`g~hHHu{v(`5>DdR(?{=MK<382fD3_xXB{jwMIUrWN62=y#gzCxc{%wi3_gF zUjhi%dRh4xh+)H=0nngJE+4evSk#cAK&ME6RaHgS#t<#51uN0fPXq~*ra=X}*EgRG znBqE{29UJz(gpdP*X^(#AnY%^qPICbhKStcaB4~|aOuZ0%`($!DaMobu0~o3l6f#l zvDI+K9LxkMp9+TlJHHb6|9x*rm<`kBoTb|k)2vFU6sdt)InE*g{0=m>AW7)|Thj#9 z5@R1{igf0Tq$3WKw0GrQIR-Qbj-9j5=>9I%4%O4j#IX$pC|@lJ0FgTXpO^10H$P0w zw-YI&fBpR>pl>aKtY)WlI+!p73DiS>H*3&=oR304^t0Xg|Cp2wEDu`S*ICX|fQ)&x z*ay`270RHXpg>ksDIiX(%DFWTba{FFuU~(*2q;V7`W1(!@Zle6#fzq%n4O!l&j|j; zGLg>?_cwT%DwCbRva+I!Emgs#Os{GUdVk{8>tJDGf{I<@A;`qOuZ})ZN3GniKYa0c z=b3h1)FCO;@ZIeDJNRz*%sSX<;#&%caF=o`mxQfa!_^cQzHzSU_TgXJ?gMP_7h^2@ ze@DxTd;RNNNFrw~08NRR(5os(ppKgh67(C?FW0P|tD+D7Cu@3}2nl>Jt1?|73cH+5 z4(<<>57>D6zfvXfBM3nhE^0Y4UHOT&TVMpL)`;JrY&zbDhX**}jNTKaV;quWDT5OO z=u^-1!=~v%x`w}K%^)&G^)FWBDe}3eg+jIZBAhY={D*%eFrV3?!yuIjJxhTo#{GEE zE#}c4Gt)e7e03BhDxSt4SebR)(LxoOGn>gp=i4A1bI=68bA;(#+L=^R|h>lI~YJ(q93c_)hY%LO;vdVV&MO12>S* z!BmtO&c{~QrJlSE@#>`k7!>UJ-yB6*xy|i}e!Tt~N?9G_%FU3lBIr#Omeffy5rcwr zJKK#D^{^RtiqpTyBVY}e+>Rn%2~xbKF!A;Lcki^_v`)d|q^f8%x7Qd2D(y-GzRSYN z7C@ALO7knXU$q2*bq z`Gh!MmHUjlM|_pL^qag457(oJPPZ$|xk3;K4fB`?Gidd-EKV>F+Q7o(u$5}M7voHv z49X^AXoED+-vHmx4%>1$*!z8cvlKPUy<^4sx_n+rBn%cEuJ&%Cy8!#Z{sVvYDQ`rm zHWgNl|7<0DG{H-1q_dU~9bHAL4o)*&D?(fq7PbaO;eyn~982E&GqW3eNzUfNT)^e}vN(;K()|t~ZGtiBzMm9Ckbxuc`hWO*0eV!|Hma zI|;6*jV@j-;A`__%LspiI9DSk(_YKn->1Ts60(}_k2ZQMj&JC`wwGvS@_T)fT@W*& zts)G8%wL1J&d@G?pv3JfIL~T|t>IZSgNoN@w`jS-0$7XXsKHqFe%%X-spEsg>UX0t zHS7x4%2%~95A0y214Yl}^w*^T z^}K2>CFTpA%laGALARs0#WXb9XHb3vXM)WwIptJC*&g-gv2Sv~%cXEcUNRzTn3l2Q zC_f*sd&JcyKzRVhGe|=f5~{zj7he`o@+IYom+vS-%Fzf+ZBWXw5)&P|44+j~%ejWU z+7hEZ^K5jM86&BRf2XxvnY=&!X+CO5r6@mJ*sZQQH=C-*zRuvCp^Jg(v$WkXb$c2Mtg4IR;o>w2Ki|OdPiw>V9GdU=UPAuSM~PNdOi3C!^o1lS`AweP1uxz#dO|?=)E{1W7&k?xpM6Q5V5eL zG1In#<`l@1PAx}YDWKO!sPrMmSb31!>u6kkIu?Rn6wH#XDOWsV>p|-|dfyJBRydgD z$NcAz-r1{JwgDYnbE&24DVM#WTi;bxojdcxlV^V$KL7=uLjSAY>}8AttrbnJLX%Dz zOu@PPR`KR;cMYCg#Ot7C>uiHL_#1m@c1o|df|?~H%b2{T)2AEVpkT~Q_d0LhM6voHri%yn+n@i*xmMIzctL<$S;i^Cph@RZS z(#-fVL^DAty6rW=VpzI~y_8!eHLRb5Rum))a?M<{a0U^Phppple68duh);GmZ?9qM zcl|H@5LOms*`1R6^TC$ho%NYI>oU8=hOe8yhN2|nyU0Z{-SNtRAN|U-E7v2l>NDT1 z82=)uIky+<_`22Zray4RR8fp@#O8x8gysdnK*`HDW~)%z#wdKwn3g>Z-(_qW6&y*tsxyM8R$S)}{pn>md&JGXgIc_@|1@RM{31OKS{ z0c~KuZg;(rKBUh}b6+!fd#nnsG%-O>qcp=_K~7F?GvEdFBQs-@_++SPe5l5K)F;!J zC;5b!EK+^;2In8uAxe2Ti zK;jgh^KUs7_XXOnd1{Ucwh)jEFmEr7=X2(m4;>0#AKufA&7q*JI2&&*y|~+WW1o~# z@j>gnzIQW6$#>=mzBG|;wal@leh&X3H;&~1nR5jD;F9;k#(4WYZMj3&mE#_gy*ig!`-9Hp%z^LkBXlT_$C?w#bkM2H5eP4@7Ea9b((RGyhj=1(I)H;GN;z|1-n?7}z5<@y?FirR zMUjA$Ad%r~{B#-nQbzDad-Vpo0Q4fpY*^{z!fn^hrg#0KE-MTzQLfK-9799HfvD#& zoqn%2RlZaAI&};e%1c(nyUd(BgrGJWVf z>g*$dQk6%jEuKZYo|(Oj^@Y|>xzuRq4QkuK?RIwtUlOhRL4H+(R9La1Gny?-)S;g= z@*K`mzSehBg(pq59?rLM zUM$5l>jG!i9Dc5d#07_efyTmN(}%0xw)}5_30%I1!G4Iv>g{F&;+&*3O;GFNYarB> zB`D-?u#bG$IRE>}`YW+d2UK@&wUgh+m8TeBcJvv@n_Sqq7qFO9qMjP6Lmv*Akl-@) z8d+hMj{A~>``X?(IrKoh8)scj=|0N2wlEWfH=AHh)MX686A!U-SXK)4Ee&MI%6?8^x6&NI=(3So}}^U zZK(Tm@i6z{6fOedjbo(?m^__c?|M48`_kL!cRTO;Oj7K8)@gC|iwnQ0PRJ z)2%lNxqH@nS*^hg$dyJXOOPtL+FlwDyEq3v^^qBuHsREjWY~I2X(HHY4?g{zQNSU)j8EVL+^Nrd@-I#)QF7R?3+hIx813)S>qKFhz>F#iH?F4@w5A^i)B zAdrgPmiRp&Jwg!Day~is&*6CL@SSZTuODH&Vgp0GN5^c5LR{}0E72r$Dol33hMx~x z-a6MC+Apn(ks>NT!{N87!}T_Jd8s!}!G)qA60q~l;c34Cxr>odT}^{cjU z^oliljxvq%^6lwuO;IswN7#P#4GYf7ttjkZAxv&cq~z;i|s}+wzJBPFM9f9F@~}6W=U4Yja1o-6~T_bFZY9$M^)aKTYmkOpv)(GdzhC; zMRx84BvyR7J)P#Ru_Ls!!iK(u6>ydil81I~zTOUTIh%$4Qx`+_mfl3Js43#Aw~jdX zH<40~Tih}MF@z8Zc^a%9XU7b?;o#s>L9`~2Ib7*Vvm;JTP!MF!AxKq1pl#)@oE~!G z-MY;vWg$5dM__}4BgOQs#HZi*aKQ%N1W9sWM-MPp%L(*dLX`12$K?^rkod4+DcG!B ztH?%cZg#f5yj+Z?Wsu$J{Ly9f1~FZk(H;NCka)U!vNrtOxzkCYB7}Y$=w^QNd>)wg zK6dWS@}a1tf{9MFcBht?SaTHjv3o&0Wq32!+(N}oFqO>N@{}x!xL%~Ss5UYszc!f> z+@E^Aqmiy6rgW71NF@hU|L4wZl=G|!n>|eU!xC_wTLOf(#SJE9Q6a=NcS_$ zC+OPWq}GY`w(lHK`63Yro3s3xNs|R1u^g;|TeDMvOEomvw8Z?)0lO+cwX>%Xm8Z-n zFy&bu`#9YX5510Azobhv1`)2#OvA8qdqbkoN8jN)!V)^dCorA{V*YteN6lA3mc#ht za?4{38JM4wvvq;2tMk6Ws)OZpgdo<{?6n`;jTiwRadPaf@1Uzl$ct7owVSdTfy=&U zK$%*n`g&6mSOZQdk@%zuI><7Gy%FSSC;}@oxvE%%Knj{3vwFkk)e4G;(UFlaw6xTt^=FoY)0qC6jF)kun$kkAW61G>~cG^(^z9m?qSFoP0n?I47LH-tz z-MgIZ|8iyU2}{e(CUXBRHjSg6pR++(QV?argRHYqTO53K?uMr782AZU@JjHu>ET-H z&~wGoa#iDMAxDF^fn;G*_L(tblq~3q2_5pz^w9%cCf%1(K4hcMpPaX8l7S3Yh_Al=b^YDCrRdPB01ovg@EmlGRWsSDYk*qht-LCekulJkH z%(;pJv>Wa}k#E|8OY}b6RZa?jxh9mUi(7^NRg(EV4c(q!^WRovN;Bkq0}^yn0<1Vt zO`t;iN1Jrzn$9PU9mMbj2#G}gQ0o;hA_TVSl|naKPxt|CZR&!V8Llz9KRXO5lEPe1 z^j#ivyoqkSo#5K}eZ>w%6H-Y4*$MEa%y{b0uO8iRVNbw%{Vcl_9E`5sFIdK#u6&Vg zz~{uMs6GS-B`@dI*hw zI99>s;gIM9@S^|Hq1WT1Y8ny%d=Tkc-Oe9iO+xi4R{Pz2@0&gkZ+GKZ{R#JGByuhB zor;xGr#G^Ri%0K+g$$Z}z71Kn1>}{Hn(ZEyLWBpnMdJ-$XD~Zi^K-JbCgxrEr}hXt z$b@J2hYw_*8G?Y@XAHba<*;N*^0BcdP!UICi0v(4#j15YIBG-ZAn4$9qMyAN^3G|Z zBOr=8alCp{&uDdPgjmO$oPD5l3Sa-?)=3z*e1p(GSnxAuj zGrC~(KIx#COC2N@U`HtmaVjV!~ zH6}^xtXy6ZBnmmxZT$)TB?!g1oa-U+ z2|b6!I@e<0PClKloYPLt<1_He@Vh5F=`+= zY8tl_g;_mrPgV77xsbV}RUBTy*tgS})OE(F z41Cp#f~D=#@{EU(qA*Jp)C0~|qm{Iz;dGM+UAVlD42NLVzrzdEiKSIN zVX18&5AwgjE!dbYVS8YlkL)6wV_-`|{97b+2)X$`2$6`8lth4@Y0_s_V zj~m$reLdTx{P;|?aWG|SWD^y(NX>S8LPBh{&EejzPY^~{B`_5Aa8+pUYt^9Y8g$|J z*_*ASA`U_H7AZ|X&=r~O7_GmD7?`T7H8k|b!&crY55ZSdIbJ#<-_3xE3Fs3c!|K%{zebV_zCAyq zjG@JD^~I;Z6z_Rfg_k&KHHJ-B6!b$qxhGn*50zf2ip1{Ra?BN~g!Z(P)aU7ZdZ7dm`viTBq{s(jRX|d$G5V2~g!WcydwfRe6^J3#v=u{{+ z$_jrZr|1d>t|%cPVim=I$8r11)xt&Idp?@VGNb|iK4a5&B;+>G6T$Isyl4Jrbwn~n zL5!KUs$Iv{9;RBdg48v%lIE1RRF&Wf5&aAocA-Yrla9}3e(B#1l69lJt&q3h;Y|05 zZn5Y!SQsK|pkq4o{UCGvvcD}96YAW$(d79moZKGX^RB#PSLI!wR|-CnDHL@q$(A7n z0E}ArxS5=+9i=fbw zYmQl;Iwhfs5J?+XW{-TGwwUYsO00R_(ZH6m|3Zk7NWBzzmWgiIcf7w;8bkm1=VVH{ z+oYa!T{7U?SC*Nd^R|!KRr!CY){r9zTIhWn=;015Plycc78+D}Xxc zAw6Ei`xLUcQLfaho;s0|=mLQ5Vy7Z$lQ2?mi*~xUV$c>UCp0EX=+4ucEi`Uod?k9w z^q9YbAOGkn^?P(qAIu{2!6e zHOO$<)YO!c7vG!!lz_iXu0Pp0p&0yXdhnlu4TV{4xvNVo7|lT0A&xKB`TG>EDW_JA zr>yNAr?Svn55Mny|LhR4)1g zLI(eNV<&N|QF9Tb_g@0Z>kUuovEV_?WJpMQS1r{4{lU-MAZYqOS0D`C#c3D9{?gQ5 zkgc6R$cLT9XdtZI2NA^0Rt331$BYtCg2iNh>UwJr;urg}cnkYg7Bte6V!6yzx=Ol`S(OtBLqykwVEZK0Jx$^#l)BgWU!IiuQ zaBMb{r!E|khmyUUtl|bnm&|q$K&l&th{(v%@p0Z|P1IpcclW=Z2yB)!dnV?8%l=$Z zi#tulmhOCb)eJ6*Cv4@mWu;8`LcL4S*U(KI(*7E-f!+rG{=CBe2G zsF67xA|D$13Z&(=f}@7eW?Jq>DbPgl`O1W9UaH&f3aSX=aM^E-PDXGEgXCQRkXXiY zrQsO#HE80Bf%5E>3@MRlCA|%jfn}LLiak?*8WOl>{)-3-mIu0Bek>x@BETt-YsM9k(_YG zf;>nBvYRpp$yyBJ<#{%S_@7Zaj4#$e-{KFgpg1c-g$nohh>jBYt&vI7gVO#|Tztk_9wRQ;>Va*=Bdn&5fg!l$4xnvYZE~l@cT* zBnm#hS6w|w-eJy`^YY(PmdLWWlp9yLx^Z3oZTFwR`z4I?r#E4?>z&OuQwyd53${|lSjK4kZnP#+)P znM~u=)PigJ!fU&OIKw)&oP2UHrIU4vSK+e33Igsd$6Q>;#>dI%=%UO3>3LKU6V7X3 z{Y*>QG8a$;UJ-Bz^$#SpuC(d09_<(cVZan8k3z8DJ2B% zNKEugJ}z{dT`oSfo&2DBsl~#+^Rd8UCRO>*`NEycA780C!rrrtaaT#ecwHbV+X6L# zuFP&Z!p;?tb{96o>B+r*Y8VBE3T~*V=#S=y3hNu&&=f|ATd@ z_xBaNg)6|1(v9pjrGVTsQN>p^(8oBUgY_%TKYnn$j!QY%)6A)rI?IO_0NYg5%uSiL zkE5(s<$N!KxU!C3d<~wX*c&>|1ww|2R~0Y#@HfnM=5!If?x-0A;#k}N-kQBn zPZm%b7-MAjyv%>j_Zkk_y)=@z26*PYM{SEjEnMz8%;qL|axI5i2X$~-Cxkw-Pshs> za#xZJ=BWj{smys_o1I}x%o9+aUBYs|f#s^qQAsjOeBN|-^&SK=PMGO-fhX1-RdIZ8 zYLC??&_lkHT5Sx{)UPt>1|H3pkLKDBSJP=UKpm(3wPGRQ1~FGc3~PAR#T5NLjn($>WAN;KejzxB*+B*e{gjtNAiTPSTva~EN!<0Y zI&R+ecs2&nr<@pLMAxmz9vks&_gkBV9o$=gtE~zd2voKfct@&(%fd0k7mkB%xNrquTzmM8{`~!kC366k1wH*w#Gcx95W&kpED82_vEEQp zJJIeXa0P|R?*?(^rnz<}mMvt4?eTyb~O=L%urxJWd_v*?0WHsS1;9huy?c5|3z zfZc9n3PVX;Nl<3z>EnH)dCP9!eB%2x{6n@=CD~`ewvD&1;}-%$qY-3V2BT!y_J@b< zqYRFQsc)YVVhcQmfh|@uCRN9%9znuo!q>?1OwW3>j6e91dc)BqWPn&~@(6=8#GRml zu3SCqU1sxA)}2H%i+6Z`tnD}a!15ri+D_bA0I)?iquR8L(%j}kE*-BIQ2&UEE(q=r z#WY9x+CaVTd6)0jEv&fq{1DOM3aZ`ViYAd7N^G~JX7hg3$()6tHM|CwN z1Drh{zIYUE#_VNRixEVA7oNAbeq8>NmdQPx?lnpD`iS!KM`W*z^NpD+<|$Kcf&C5C zbxR^#388}IOwMiD1+1)6!(8^8S=WTsN1hGMD@1+3`!98(_H@@)p!;LFLr2$nA+n@W zLK$v>zIKoKLm`TN9T0TR^_eT_2n^XsUUxWJoBR4UVB;6x8tn&WxxdtDv@LMv6{3{* zkKxw%=rV!rZaK7N?7USxy*7H-G(YUU5(Q9&2e#&Bg>L%3ChY_cTfC^(c$-q_UjicX=DLbV7{N9x#`$Am{FQO>I^??gDbQT5mDCv}=D}3VKFp zKU3!6L5DbTcE8o6`^Qx?9j;!cJ`C~Sjy?Utht`{n>gLC^By95!6oiTQ9$oKvToy?N z^-k-)l;8c=7Vm*dJHpGfnmb(~1An=8(Vf-&!;X6E;Vhd14!i-nkx68uUIZ;ac!z~E0BP%=19cpBkMGN9S_ z20UkLTn7({slqpi*m*74+*?_o$i?grp#<)o>I1EhB^coR;{|<9vs$s$AIjc{w0El? z^bcTsATI&FF%_h=pPrlo)qoes-HRS}{FH$ZTAvRQaVA=IMHG)@rtrK{!!DVl;GvyQANuPkfJamy9jun+PS7s{Nc9Efd|xo%CJ1Ug&_byN}O-FSr&kM{-6h zXe)A0QTqCLWA+~*e)_|i+j(r(tb!dci0!ZKH`NRQ1_Gf0Z^rKD?M0O?$a&3BSFZqK zKP;44&fo)=#+SPL-C8Jl$1X$+<#HBWgK_aX zW`TwJBR|lW9xAg^@0qvC?i;sYoohf>CgAiVr0H;mb*&jsOu8Arigchm&EC zk3}Cgwy+d5S0d~pjZvNYkcPHm%b9vjjyJIoXG>vk6D~#iDr39sn1Z$NJPM{A{X?Ty zp4dw#ge#lvlzr|7JeDA{u4L;EVLW!=nZfJ|pk-#m%)OAXeLZHKNMaSnw_mj_=k1BI z+!EV8S@8Q}5ZBHQn#G0#Q?qxfIAr|CuH_P$pYDJX3DVOH=&iSg5(nr^eQDqLJ9Ux0rWjwiS>Rb-|HjE}$!O{WSer z!<7=Vh`4=4Eu9zvtBtsRN+6|LIl9JVP8R6{eVAq~Xf|z~f}-qZhdg;< zJLiBDI1&3}X9kAD={*rU)yJ3h=U6iH{#g4GtiRM+SZ(GsFE06JvcD8}~v8V`%k~H7zgZJ z%MF(3AX5O*MHgq?YO4yJ|4uA5Y!Z{8oFi;zg%s(UqC7_xk+HHI(~nXvl1Xu^1Q*G- zW!^6jK6en+<-jDre#hXH(y+hUN!aonZ|3qEy=1YtPmp@gFL>Uag^%v@dZzHnV&+4u z_?CFQkr63x_ZuT{e;1pzS8up$->>fMV;R&fmMVfX#?SSVq4idZCJ2m#1m$z5L}-wn z>USXpAx}lJFS5T#gF?Hai~frXkpH<9qX_)I6XEMffoto?H0;(U@9n3Yzqxx`tKu3L=>DI^ka+A}iGdMH`(CvcjKS4kW3NSVr- zWDk<^3zv)GpVQr=CM)_-WmktTXY+#vni^s-RwvfI!te3#s8IYd(c(TFWCd-=XUO}- zNu0l>w8W+$oXlw+Rr*vROJ(k!U8eOadPfjfVeyZoRTEY^mgf^xSDVpzhC&NBV~s00 zVt_vMv?37YKt_YmfdQa~!%eCLzolxj_l=Z^d|bgY2g99Ac!&j{hby`oL?Gf6QHxmyTnj* zJK*3pRUhy1J7!2uQ-{FRPEk0aWZ7 zBx?iboNitu=};ibj8Z1TixM=@6r&viGxDKsU1PW;UY1)gKA(qh^?eO1O*Gf(Xv>6Ebk)Xq7i zNjE8`C{R&4^I*)w;2Z0pyGiNd>}J(!A<^j-_Xu}6-QEj-hWKknQf?GIF+a~LR_~Ef zw=cGPLG;dx0#N|ACl3rp7BHbO4oglkZjhZIbpGv*29JY)cZksVj$k?C``$E4-{4rs zeg!n#+ySb~2_z>Zahul%PypSbTnU%bl2bf}66l$G$4UnVqM$ig?+WFGsw3~70+60h;fx{ouSPxZh8AbU!HF9{j-N6sdu|WyV z8sI2<5u58=xi7f!O;GxDncm&S$z;z5VkzQ&Hsj!Gdq&+dyw07eE@Mtb&hP{DKqRHD zRH*gtQli+ObEgCk!!UV_X*VorDpp-nKDt^*)oWx%=lftuKbY+MVk!?$nQs3<{9YKo zlw3A+n&Y;g<;Th;*)`glK-ofX8jt3bz}l{M^TtenSM1`>w57Yh9Nk5K!0OotDKo2Q zES38$;63e8Z7_qIE~gPI){e+zL#pq$vN%ud5g@<0+oXp|dB_T&9S3JxPQ$!4;v}{^NLuL|~>rzic&@ z==3lPu94oH{CYlu*4uCKR|(;SgtIeCH-)vud|xnLY*vxT4GA_Wrh#35{6`*B+m*~kv%lGG~Ouy3@vxl65$eQBfv7S4d zV@uT$J4R2R2bj*T@wdJNIo76GOR?V3dR_a%x*Ytb8KI49`h1p(yP_#KlG~>$e;?5m zsv+~9zGmL~CTDXsR67B|?>6iFHHezMFS^O36>O=?Eecgq{LltDgYod`{bb$|CV#;Hciyf-Zz2AA;7c?Z|3;gO7T2H#+ z9~{ZZf8d%c>S3zV@prYyMZ!JhK=wOjnk@BVkOF^B54IZ*x;6UmRO7RMR}G-zUy{Rsl((yzUg75;VHk;aI^j|y1pq$(kJ?|jcMDqZTGZ2 zZQHhuY1`JcZQJIwZQI?zR1@CuBe&GtOo;v~C~#-nA}B>iZ2f)0yew{GRWfKR_8qEmrcG`;cr zhi0Tx)&?7p59!7gtL3GCp#6eYRVJuS`UL%I`x)XDNtn_MMSX`GXaqz4!JBgi-ZeH@ z54+`%+UK#b{<2_o1mQVFtAYRT>_GkUk>Wi9Ggc-J-jW&LB06|a+%A>M%W4pf2SqrH za%az)=?@be8s3_;H4K-W=Es47q(1OYNicjhK4tTjOhIC`tP}<1s1{|ubftCx{lL`K zBxR!x|JgFn7)H#Fj!nz#ywQ$7w8*w|_X|8DjhDA(NjS2i4XA*snObmsXLbxTrYKOV za9E5cF@s*;3RqIj?(XVL!WKu!sC<}}CUL>cj^)M{Ju)=uxXI5;2N*o$cu>^hs$U7OY$rfR&Yk0FO5ljp%|TyCHZ-RRx|-CGRf5p8 z_D+!1EeeGGFU{S4W(;TXAfxFoPA|j4*QZLHM;vsfg_yv8Kg@G_nzq#DyP>R&Vhk-s zFFq0@a@KSlvGI*#>;3e%kG(izUjxhMI^204#iBUOQjXwT z7izU+OzS6$lB=q66FMh~9VvZNo`z0@SP{BVs+f6jFs-?{;sP)Rn*O=qaRkSz+i>q8 zkHrc08h^9Rztb-j{1xkY5z4mfg^1QK?$O&bQ28YmVRza+ueK~G7qrH?Cgoow(+ERD z4w^k@8J|Uk8OvkXF^*%JU`Zy#8)J0|O>3|aYAq!fB}QCuA=xw~srJcs<*+O-%%!$a z8b4)P|4@X(gX$$e~&-?Gj6&IRF;k0WmEA&#rGw}Ndeh%7>#T-OT*oD2oR91gAVXIyoqJHp5pkkox8 z8guYt={Dm0w=RDmP_lEzlR{_9LDomygaIJohKNgEg>aB~$)T}!nUjsa#2_RN&a|w) z>g?2&CYBlBxvc!^FIcZC*r^#EBR^-b&mf~(^k`C(vAnuGGbOK!U}P|g(z0EX5O&(| z7Z^3@PK!WQNIK7@gNC~hT;hydF((T455%F(do>F@S5TC$0A-TWOKGOkVsxZ*$7xMv zzoNtsHO_2b^wqypIsFtMDhlqeqdE#IyFDQQ(ddyFJg+(1&IEv#`i*GEzomz3vDNt+ z>AEW*Th|v(86lzAEJ7pAU|_3xK?D^j*gmabT_nDLGWlU(`r-V-zh34W>Z|EBpR4W+p`4;pa~2+-W^z%g_!!1CwNed81F{|Cw>EQ&(xbjf zOqnq)^K5;Ua*j%uZ2G$vE75bqDD&Lj_2u9!`xPq_B;t+5#Zd5|7Hv;bgnqS9dapEK zRjA|{4E$zT`!88bjiJ+O?li~vx<|#a7_Fb2;)E9Rhgl|(vgV|tOQg%COG_*Dk7`ZF#%csyf@b>mUE9T1J^{i zf25ki;4gxClx1u>xa9bB@34OcsnS=YfXI%FU5eVWmsr;ImfvC?>B+{C{6%hC4h9}ZQd^3b!Bip zEs5lO(6`e95CAXvc%P<5m8k0*D@6!pIorMw`7a#)3kj@54$fDzTH=X%=BGQd!WUrD ze+zHMUpAB70l>`>?_M@%eK`9YIbQ^mDo;)M-}vBA2t)zIwqFRq40gWRMvGK(e7Pzo zEo~GaX?D8Nb|2K(MyF9Eo%$8qVlF9y|B>Mlx{1Ym3pbwZ4IdXM$v3Pv&_mp{tvSp= zWoc6OjS;o+VnK_7@Xq4%#gp{Sur2lP8ET-&e3f$#NDrxIAlTz1kM18N0Wa%2?t(25 z7GO4ngoPyu$ey3Cw<%ay-aYD#M&SRsj{*z?{;Apj)1(K8@{!eMO=l;1t>9p%`aSUt zXcYgY6K(6(3imR>kWX%XpJp0RdVWS#a!@=qL(qPJ4YNuDd&Z#%f>x+{Ox0xE{jc~QO_ zo;pLD@&}v_Q5(Ia05$L3!(w#}wW&WDSq)qxL1btqobJYtIDj@Y zR#Xi|K8fuzjlxSrc{@pnYpQOUi9a=nlB3)`jE~ntnQM3((p?o*uDp4ajPT@_6Myu_<1r_q~_9H2xf zm|_C3Qhx#IQlyM9)T`Uw4jq7wa{@;JfrS08I+XG$}yN37v=y zy?rxWYj2%9eb+)IH)agB+mH0XftGbQX(9k88F74hU-kBTxfZ_v8qe<-o8uF2MgI0n zEK~~wNMttKZffqR&YxnyL4a~+$1KvO?;r(CVyAb3A6qwwH5)F4^+K*+#ILSD-2Pg8H7)nB8k58+{!6z4A*Npj|2LzYppfrgp3{|&7oL-}|GKY#b) zX)25+!}r^X5r$FB;Uv<{LUk3+ip6Tf%Gu=Zs^b6+R?=;Gz9fQ1Rg;b#zv=Yp6`0t` z4+Q)maWS&;vlaBqR@HpU+P-Qd#O`Z+x#q#2c;XLcltBg7VmbL?b|vFq^E$faOoAC- zQIsn1%T#fJq*ck5v~7_{o#$MMx6q!q0fL<}bj0A!%#`K{!w79s3{u-K&ZHE!@qObe zQ6obks%!Fx^hcWKA1YcVbrm(BYsE0FiCVsnv=i$VOy|w~PPbw1VBmG9R3xy*g_^NMf0``OpA1=PJs8F&bD}cxoXppSSC% zO6=a2^7s$mU1{v(hao)>uz%&2mpoVYCYIsZTB79~meR3( z1E-t4hldxyk{aS_$Na%htFk8rsw*FbwTEfBrz)2=z7`$X?-T0=cZQwH?!x~JQ~*u) z0Gxc{xeH+20O<3liI3i3q980pCVDVce1a$1&h;);0XfW~LyY*mEx*BjAQ3=#77g)l zljc(1n8+P;j~3n3WMOYdVd>tK#k;p(lK+Tv)8iPrzmPezK!)CI2!bgJRPWBCnu1SJ=#4FeB!DOmH}0N#R~1!UeIYVzFM%>csxtPo*QCkq$I(<165fx1Q2aW|lFO zUWRv4EBLc#wF2rX8S2xPwXprU_vnEr(A)7MO>Hk)lEmVun0T+nBkHvhCurhhD22Z| zHYL+J6OB)c`9#^|w_o#bhR#OPExE$1(1_5cYvh!0i@8;nE$+diZ6yo7YwPSoRyC1`A6! zqGUA8({!dUX`flqN$$(irc>jEZozE7j zwgIh$RZf5{TEUucd25otW62)+<%a~25FKx8El}hVZefHSxaF&tA)~)09U@-h;UJD}7&ksBiY0(ZKhg5O;-V_w@P_@z%WDPAQgr8JIIZO3Xad~t*Kq^m z(c`@!*qK@?S3?O5PV?{kJ_%;kEg#61tu;II3_nL zjP^z|msR6y0*vHF|xp%QYE3|pX| z9x0Oo605s7>T3&uK6*YQLs|45r%N9Nhrs?>ZxmMi)}gtP;F>TL-k_nkpXq->PZNFf z8Z@^0DwxB~QW#6y0HPVi>YQr%myH9Y$8!jn4D^4TOgO9?v1Mp=%GSP6nz!bUaq$PL z>ugH*_hYg{ps|%`v@2Y966rWb)y$}bRevF4h3G2-Z4lHOWN_hikMr%1N(`*5jQC(?PZT239J0vbABJ zDOsH1ucNts&-`hcG`D>ZUe=CQJ6Cl-|H<`uoH+T149Vq)wMFI89A)R`;5mC7)UKw# zI{sfiF8m91-HEyA6;(utl#?_~hAVN+lfw0+U9nu#Z}wcMuy0EfG_bb{2dPriFYX|T z6|5;tJCF#s46@r~s4GPVXCth+4)nIFBZ@3k;OHFvD9l82ZrDy{_YUY3oyN1#_-6IY z8}|bRnEn>`%aeEjWI#foJ2sv_)>OW|A%WlKw^RKclxd}%Jh-is`6_J8ID!_GXv^&RsZ0=Dv+5E zh_%?XVKE6hsx{EnP>h+}FAUeg+Hnq;^4UOa=wIo1r9AVUSiMu#kWoymtyGP272O4H z1D3iv9wG7)^md(*ES?U7l3>P+Viwa7OE4zY5VITof?2Jvrp;D%o{_xGU?4OL(U&DD z#?_Qj%j_J9RPVrWMKE@7f8@3uES}$9i24GOz;uQ;T6&va zCUNhVif1G~o51lzt}jKCE;Wu{Je2kd5(V%NT!{pSjP%bElqG$5zo@%oi=?hVO5z`m zMArns$&`UYvE6a|fGiful2yJem+lN3a0Q{HM3oE2?@7#*Ee>*nq^D1ln1N+rtp}=5 zCGqkkemD~q^bwEAmKU5Ytp`N`HpaqUZe&=i#T_aZ&5UcW+=WvEZgSFtU`ro(5nX?+ zd|l@(r$(njV9ZJzn)Jc;w0R51!fVii)?#-gYqr!f^?T$2#Q^` z%;3&bg4I~}7c1qO=Zi2|UoSDn?%+!;w7#XK-sOyG8s}|4Mai)EP_Ix&-?iwE$E8e+ z7reo8fCT@Y!-#rtrLfx{PApNRLz7>L?JA2O_H0pJVxjGEp zf#X{XFQiknvM#;U%2ln;ltL7aW;q5Ab@@m$`i=*4Uw1`r_g`y#2C*G~QOed}O))~= z+>OjICoiNT-(W7XzIS-@+MfH#@keWM+H;2IT-yAQNv>+37fR=)qGs@XvKnu^t%z-WwL`|8?BThE@944EtJ~pVy+Q5=l4^ADuG1Y+7Zr1 z|L||$FKo78?!}WJq`lIu$NX8ykLDN0XAG6AW{%ICu@_ef^)L1S0h(BbGS?q|Hk+|u z$Ml!)W-+~4ex*@3-o1!lrH2fEl<9kexin%Eg?WdXJ)dBc{rILk8 zJ0n`2h_E+teKZ2Qr5lKVN9+!}UhP4R9M~6Q>_AQs*U}KuB|lE%oB5ui$?T6dKnFJ!atNkXP#1Y6T<{)g$jpz`Oiq)})&R9&zH()@)}K~*ID zcwuczRi*}}04dZk8EUbmB6@LIKP&!k4|0|aN!F&Yqvmq{F3>v)77Ny>JTWUwwn`ZI zc!K%5auVSWm#@XYh9Yj?!k$!Mv^q3<`x(a-l@scbAeL%&omm8M6h9`#i?(3Rk!5Bf zS>np&3_UKh8Z=st3-f(ha~DFFr}#}I^hK>7n6v@<<*#va%HDyeE3(*d$NR$qH@ENE zbvYlvmp+$_BHMvyT^9RSVTI{AMp{eu^>ZDIJ_XEF(8RWO@OcA+TTwZL`}_wSn&@|x zOu;@=p?cZ{{r)qh$&TTX7{FkSa%eY>)ZGX}?q)bnW~zB!oAqHFEy%pPgiAWhcdl(0 zzfnUKpGG;J8VvO0dDlIZnv}$;CpAV(g;XRib?_jWB4#C^>qDROZ1~fNz65Sw{aYNM zzv5D=Ek4?OAvvOFo97w-4;NszRYLyXEfYdfNr?+!9MN4jNA_9?xFPKA9IOI*7VNXEn*O-^UC>UE}#1$CXy4yG^tlw&Rkr9gr7%twwaSHy(UY0DCruSS|z zn85IGgT_v&f;QR-9v2-4z2bY4O(t=PE9$2aeM^+NT+6(^2xYQ66t-+HZEZ1S%-7Vzv54|HqO#-uJL3N?%zo?xV32ti z2$8zdT?f_1-0mc#XR*4SY<95B@>drIhlKkkTO^#nMn>F(Rfk45@nph&P ztrmZ3ld)vBogn{{M^%Y67oN^7UcO}CtBm-oOXht2-w7L5R76%?T|GoGDU?7eBP-hm zu=I3#klJ;ibg(a=SBZ!WML=;nhIiq1CEXiGle=C`v=i~E8fPEG|3RDHH;JhFWgk6G zU}Gkl%j|K1$@wj+22rg$RyNmAW~bQ7+goHRD}}>xw;pfo+0-)4&wGjB`%VHH>W`h| zb1+n0WH~jC*cq$${pBBEg7331dYhlsMl|o`HdzZbiZd`!Hg70GgFd!~eS4w+qNTPyScT|$s z=dlANv&aUf+j7&{c3!D>3 zsg!>77$Ue{i`mS{P3nf!~zsv7jl5Jvb z?(!uJKNnP2{5}A%ZycA?8Y`l5JK|NOi|eMVaJpTo_i9Fne%;+di;h!EQ5MFb)Hr<1 zUTbp{qqx0;KmrOE<3VGK8Lc7dz^YuwROwZfI3p|fnOLsF5^~>|lZ$-lonHfjAB#XH z<_m4``y=v4pIFoo?Dhksm!xhFZAxurWm|TbvOS;v2-~@{1l&`$jG%-6I`Q80pChNsk?$_g& z{`&jj$(IAckt_Vs6h8C*J9}}Z2Lw{;_3p}{56DK6=?sSCUu>5Zdnz8pE;owy!I9Pf zK}GJJWQ2$q=C?2OnuFAzrQEqS@_PINlM~gDw2X-Hs3|vV{=o_}naGe7F~Gp2xIDk5 z5GADL$lVq@eD*06cE@iobi1Nos0rqVp65clns+mu9baRjX`Y#BZd|N?BtnKAdiZ_T zln%$5PK#%!CtJ#`de*R9r)t1fYlj7Hw9!cWZOeq*<~Ep{V+>RL54A>;f_fcVe?Cr9 zV47ri-y_QWnM_g)h4v!rru;8Zo?CsgYLyj0#9Q9}qO7@h9hxyfEiYf!|wNnQYgn1KVXOB%24P zIO1-n-cWW_6+3>+1pOj_H(QK!-P17Y9KZPO>+M*u)0W$ar-oG5h0y$6uQdb0d9TqIJ=$f-=&K5)0C#0-u z2*8;D$bSr>z_58Cf)4|SR8>_;B z62j;w*I0d)-NYsPbO%=SaMq~{+$(#R?zcV*CM+yAYZ!po$d^J8A0H3!KFe3d*#5G= z*%4}Yy&V7ge7D$ae?&Qa?}>~_vjRxWRqc$Fnk%JHA6`hYnmkK~G6iJ%ZIYJ>HU;^I zbTFVvqY0?3(s=m-o>DCV6cS#cTDxr|#YLyxIo#hL2w(~=e19}VN0<}cr%y;k1dM@^ ziu}F|P-IP^)d&RGeihE~uKe>HlPyxrS1dymy^W`HOR4K@i0-m(h{5CYOj_3Ux(qO; zZ=p|mcCyW;dTyYM004SPoyTCkUU$Y>JkC4D=S%J}m;uX!;Zpi{1cGwB!w6P(hUZ%F z7*^>kv$^SYJIse~zCYo}7=OLU8wr<1e0}FO^p;&vs$I6pq1-qE%+CH{;~_UIEaU5o z<)Zr57xy=!yJVsf@cYYuSyufX?F<*dDy84&tY>2@(_Yq;=u(RFZYt-{n9sAu7OG22 z{&5TdJ6}y+XB}FE=;3DUUy8Rba}HG02;=Lq^G*&cwSf1OXj}33H{I`g@qa-G7_pJe zK7d+DKTYhk{y~EZQOH$pJ$Eqe=RU3D+YdtVIyX(bHy@O@mGe;mUj{HbD*<~c*O=tE zQVyIop;CI64&b553{PX6HX>xGoxih7jZ-c--x)j~7zl@)T-W6<5Tt3nf35m~>VW0< zTpSGgm}LJCA+H2L_824dK#V>d-Z&t)yJx36Ko3TG>hw|iS1L?731(%-YwOpWfJEfo z*@dOKicxj8I(pyvz8tB(#Y{vIKB9Y?!js56!(U0aV63AIQQM4x)pCsZgMkgl3qDVG z#KAPw_*RldZyuq0N*<}TT5$Usj6!x1!?dL_5hn+#{*^lK2WU+N%-91ePS&DK`Iw>s zl_!xIz8_W$V2_`=^C7*wq)e;Fp4JWe<^Tt;kLPLGTlF9g463WKoH`hrEBWK_V90tt zT@?4?m+X_?p+=(Kcnsn6ljX&)!{!@iQrj&n&-PLM^|Ph%$?Z>y+fz~uLHDmvkDpq5 zyT)+66m}ehq<`#B)%fS989Quj*5vttWW|`TLuEfYJ?Tk6vL$3@^L^S(t!cT2C9Xs< z=XBC$D7Lo={q#a*HkRbmJqe+WWKiqIWB)^ucfl2`?UBEHIJ1Db)Hn(K5vc^f9v{{H z6im0s(_4)Jm?OGvO1P9eK79}2AJlF=oZ%B2x7B9?Sh)g*4dc-@dsBS*F98@i(&^mR zslb6>AD-JchKEc)gtMrsM@TyMKYiKJ}tM%QN*H~+GQ|?@m z3&oO+u_W-!%$|=I_NQStT@(0V#BR56vQHj{JG^gRnU`X0(z*~UaYqQYVgIzXkQ`}B zZ+!4Dnf}B)Z8K#S28ad$tMKC1vi{XK)cuj0GNA6lblI2wr!;8Ny@K7uT84?qEzf%D zS>xMHZd4)bGw}a~${~#W!6a!Tpi|fyN#Ab>dL`qUse8KzlvGjNRR+09GENpldwxGm zoMZhhV?V^B1yn~1R(r2GQ?rhjiAC!hlP#XI-YpsU`BOI2$S875Pve$eyjBctcV!OQ zg{)f>NMKU-UoY=DERkmSF(qT<7I$y4?{iracb(G&d}|9kc`_-npDMPqOmU7V_`3(t^5Z0X4NbD zbhUxv^z^h+vnc|=O}^V7oUT;=;_K_{({96-OSCk3F(35;$PYHS2eli~>Nz0Ubo`aE zJr(TBCguLhT1a0?B(dOfAOau)4sOr5=I31s*ZS)ZcL`;ul;Cf8r+;BZ|w5Tx@v6V;jDV_%Yn(r0*P4FZ1qHmD(8 z&>+2Snv1zy2TYy*1bZ!wOEe7ot1)NZ4;w81#{Bs{2L_=c5+XBslhgOqf+@F zj^S>Kii5C{xf%qd4blyQET{nU+PMDz1+$DRth*JA@gSRZ4Ij#!neSL3&QKP(;;nld zRI#|bEc?QZNx6mO%YhfkEonu<8y981Iupin)r?l`mx4sQHp||S>1%1pOpwTc>j#Sp zpI@4)Icyw35q*$p;3?v%K@(!$C7IPb%dv4n%mN6ZFr!zoNhK3b7D^C&-k(gCDm4a& zhHiboyWKrKi6e*sev_0-Ik;ZwwdP3I+-$XU7fVu`BN$Hdd+d9N=j5!Ty4NM5K9yH* z^Ik{D(>-j-*g&QBH48CIbd~<-tnMG z=#ngDdNV*JSLdM$Xx|1ejYauUi#|u_w@rDuI@^VD^O|O zePv+o_5ftW)hNd#mtsa9$~M!69$cqb6}Z8LRbza#S+QabzrX)d2Ua#n#tkxm1fbji zC^!HOK~Mm|Cr;OA%s??gxj3ZYi{3vDtHTKMN%cxjFDs%~A9z1UR9#vf`2zXg<$}&m zGmeS|)ycozL$?c^Nl*GV#-lP+0Ga-H{15Cn0CwcxG z4zF54eN$^(>8G!$r5oox6E^%D_y?Mp|7=8t116YjP`ewFTFncRGsY@%Ca4xUci97eRw>)};1q zV`?iTDFPQ}7MLjLu|iZ2u6e<=re0 zFnaEW={Ea&s)~*Y_@I)t`O`D>5F?>AnP_Ln_~$Wt4s2P$R7&kZJ37wLD8scA$5>cM z7u%&)(mshFOXH~a+as^tXG+ZYNaXgmOTV0yvEmJxuawe4o4idRO}PK$XN6zG&NHU) z*EH!IrJ;?9lm>>^@6J;p6d1-o#z=`Mq*AB1-hRy4y;)m{qq9A$8F39tOGxpwL76~` z+yY1E+7OyLZscf?X85P5Q?)Mwx>;to z8SUNdsoTLYQ)j=CSV?~D`iRa@Xc1t54$tP05+VD`&9u#d%v(OL0nhbi0V zX$Zm%UY2mBQY!ttKXF+5!JmZYOU5k+(icB1M54ZE!`k%ecbNSQ$y{m&`Ej94*6abJDO<{_53AF2Hj(ABUwZjP7FoS$ zb}?M6uDRWx;l77VDmapROrPK37Vz{mL69TEoQER&%9GDX^hZS5obuVlkEt++tk0u+ z`J7cbQURjzzkCi=2Ea#4I#NOekKc*YXFim%JkMUqKbI=A{1mEzjE3;Cf`bBSu@$KW zd{0oCM_eS1Wnq#N3M*!Yo`V2$Lg5u5LAtfT<@StzCpWc*ZuD%IvdyYcp?4bGOHE7xhes9wf1B`P~zP*DmS5?+T)Oe-4Ddhv@WZ|StP27}6^L?|_5 zY*UNLyG^y9Y&7%S;@k)8Jq+rw7xX6)!ul ze`*LMGYYofP%%7tAuJJ>sw$zi_8a*Vp*X%wao^TX*i!gMhcDcIdtdBhK*}pf1SH1# zWK{7KH8ax@F3HSk8yfaN2#~ZT4Aw{O5kp`N4q{_*Qd4{@0n*I8%PDF1`Hb;(s4xr_ zOX7Mx1Wl8Sw==O7yDs^}WbW7&Sw-;3C!h@F!nBbJet}C{TCn6mN1Z*3ing21EK3Wf zs04Rnte}yhpIS|FAp$0@S0RYvLVX@f9#5XJV_i%^twPK%D=a30C{nM;B8kq{$}>tz zZtSqT#}_!yX6?0|%&Z6zDmQFTi>8dt#;%#Z=nSj{GfLAT-|mnZzrGhP^s_-O8S}bO zi2e${J_V`+b7%_(IgnDn3T>`vB25!O=;;XoIIa`;eJ}y+vKj2Z#R+^w+8ht1jHR6) z3IekSXO6!}L!?&FlO&4cZY75v_AFRS<43PfknEw-rf#jeR_Yv)V2+;ihASb!uGfbk zx;=ysa>39dDiap+mz*t@J&4F|jK_t};O~?pW+>96V96O&5)%hK_Le4IuJGJCQ zMjMBvib$xKKov+N^Qzy7)|Va&t-F6Cz-VWI2WNtNkxek0V>2Dj8n&+;@W~CXb>&ec z{l~%-hE@y9-LPiH>*TR_=o9fYbAA_)*^>^omWX5Pu>0+bBj;M?aUeu zHKA>Fzku%{pHNpT?@ig7ZcP}9r4ded<;!{WGo7pUg-|mxHU{JEvbJZa=BFw>U8!L2 z<7WyMlnboTVa+4ZexfX@}!wy%y=JEs`-ZkVP!6DxsygUwe$EOzJZaOR1;X5yN{>Jd2b*0b;N%;7^37%v3d zP^Z7sX<~xJ04|IZ@a&ENXP7F?Tm6}-Y%#-+-XDUEz4J2U#7xlP^DipT0eU~%EDmMQ znPd40$yl5wB}kYg5fBD7i0S{9?-JV_%yblCYSsAH@r>6~{&zPASJ-1ZNye}#QuQ3V zXdz+-oHZNmAqIEG#k9Inl!7;R=f-FCdP$eq$%gNN-13LorpmAj9Gj*ie0=S^F1#)& zOxr7Qkmi$RyVS%Y*x~X_gk#)aotYs>5Nzq#gazjMqQt&Z^L{$)+luPOv zi_azF@>xA&zR{-_<3z5E#}F!t0^?bA`jVA9m{r{)Znfhc28)82=#v=%Ft^p33LBlh zeJK%fNF=wQoY~MGO66z=3rV6EmLPCKf_BvWPdzYW+f7-rUl2x$tOF(D$MRWml1Y;T z5iwGu>{aZADrnM2+S0@{+}S*i(6;10+O??N_)XF`7m;E7kvD(F9%(CtryYz2q2?fHXlUSaJBO)OX#(pT81!{qcSmY|HY!=E z&sxuOz`k9=6}MRS9vb{~?-ByP7;+}A$s!~zBy$>RF;P~a!x%+H}I~ z&=3tZ2`c+VjKR#=xSdrJ ztshVXPD(~jQdl6>^UGQDf!>JcnZiZJ&9cK%qRlDZy{7xYLO=TCK>l$a%lmss#JBb| zO39EjJ$buGsn7t7O>>~sK*v7pBQ8b-4{5LFzN8wRr2QS^G3-Bz)(e8tUdv0JXk@8E z(T|)a%YZ)rJk>;8ys7kT9*b^wrbI}uh5T@qs?aQB5d?X1_y=J!{vkmVszid84gGr^ zEVJu**lL5Au`Z}$TTc(#SZ2zwir0W>MJHDi1aR7Hiq|e#{PfFkOANDVqka>fvJDEmZG^UMsc`9lyJz zbbXdMJuxai>ljzE=P&8V-!bmTT@eK-*eMaf3IGSW=?8<_g8I7MstnZw z75y+()fJdH4S%XGqGN8T)%uu?2|657=MXMk?X5V;F-BrwRa5H8iH@5TD^!@T7y}f2 z#o=^(6BUsxHKIHUHj;PSm-}b?BkfVa!;@Y}Sv*Q33FF%s^ZxssW=vWe*`=}td@ zTof`i6qKjH@g&hI)$?@1X1dvx(>2}KG$Zoufi|(!(z&I5LUK+x$O%Y}{w+G(0!7!v zMoA9|zuItR z-02Te6wg>o5!m;z-PphT?er{xgiwJ%8^ZPlk9T`Bcsvp@k%bO3IfJ>}L*0+((mKH; zmK|~RUHjQ(>6S;r8G+OmVdi@?{)}+oZ>(DpFF}DB}W@mEDdH~I1vj%_*7|D#W=o}hoRlD ztW8+}4nbcK<6-2=cg#*JjVviG^6I}x({G^c&df>gKJe`0?#8AY3M%#{7T6w7fR$3h zt-VO_k+r+8%%ybEC!R4NxahxPl#|J1raf5|@s|c^;g8?vPv06Hv-ybdkuy=~E>?1d zweuk5uuSV!q)4kOj1Or_C00&Nj8}7fr#97Jl(1LLEjBkY39*=+L;56h#vJTjocoj;5OHU8&tb-?w2d?*h$E2zQm4BPn#}k z0Jf9=!v!e)C6mq^5(J5`cX=rb@U3ugbtNY!hiF)xJY6U$Q>j3wqM`yQL;^JRQW^Bf z>FKW+f>40Qs(`;UU-`ai+#U=V@O>SSc=Tw^nkMvp#|X5~$YgKaT{9y*DS7Sp!|8oZqI)s=*xw>7O61_L<< z4NP09)7W-_BiR||qg$%Gr0Y(bnHBO;iBLpc-EPT%_Lj{cJp%>`$EBlYpooZ*Uj`ok zNcAGAZcbvqGbCJE)xjC>tFa>7nk88|N6qj()5t5~(s*5$8CHAC0g-XWgR|kU#LUzq z-7zFRuE@ySRLoaNh`t!=R7I&xkL{$3y|J*jTigvh!;!TCRt+y3onH~D7Z+n`!?(CA z*)s$^1VxXoc=VbfmEIwmI%f@)$(v2ijDLsU4(F_ehpam?Oi9OHLRCyuC;E|UvxGmf z(Bq~7RUwUfcL9MFi@KK8(Z&-j=3-zJkea{SuCK^JW+O%uG=vKvm|2)}<8b1={DawI zZ?FZ9ikQ!GktoG{3^_+_h{jbZ5cB72-{;a^^@`wE!@Ws_d0BvHVYdkU?RhDTN#GXDA%9$N zE{aQ+QzccH`31Krh1H+U3?PvJnNFrT47B@xz5$11*GGzBepJl0fC(Xj3AG9+0~8r& z;PHTFC6L=RG*BNs-RxHH$i23*%F9=h04$OMDbKejxZQMnaqmAMF*y^2+@eF91M$Uw zFC40Oe0~ovq{fac8q45OfLstU%tVNmP>}Ze_c^+dbdePPUOv31=Wo2@*egz*9c7l2 zb6tdaEKXJ%`mvx^HW?cGGCL{#Q%(`RW9BHXfK8z=g2qLMTHQcWJX5?sZF@78o-NBl zc{5v=tr`Lc8#)_ILNmh!;kW{ypY?gpNV(D&)xV;IL`XFIr!k!`zGoI|-U=#hd2mAm zADq=YqpO0BD*Ro(=bUWQQb5V?P^Q8Vo+bc&r9Pp`@}|aEey)tiv*X4-kFVP`F4=}i z&xnw9F&0aH$uLQ8H#h#`Y+$l4z`4r0SEwl=t3uzto}@AZ2d>(6=g|tYpCbs=gLX1R zOhxBZdHMBhb_AI_+L?`$inf80Q|NfGRH!Na+nwypqNXYlXvmmMJQ>Qj6`}#(m1Ize z=t>yk7lusfG+-`Vi^r>E@(6J}D%}XDqV#1YcP=lvR;cedNHU(`=cdkblSqR-1r!)fh*%)J~%3jmKy%Y%=+z)qKOB)?pUlZiIKiLuR~Zq*u~ z`dO)JRW@W;hsvN@k<4T?Tnng@YL$x%3xn9&+M=D|cDtObzCD}{6w79w09xp5vReRW z2jK<+yWN(|-*T0@h6+J`epJ20SONjLPbyaH+hl;;ao}S#@-Q679FXc;B zS}b;3yp5W4+}YLcbCyj-=+R<9VueB}hdAhx2~u?S-+aOAO;#9FnH=K3e(;c^Zo(vg zw4LOXotSB)ghxeHx@%$xjy77nJe&wQA5Vkvee?DuQbhJ1$SGA>zaAnc%1yX)TF#-O z#wFF{jYG7vIWYJQpFs{5figX)=SBt~?XHJTcwEI)727JsyOR7$$ z&6{m8N9d2C#if%8t%Yc-6fmTDbncmbf=T-CB_e=040UfyK(s&oD732aYbSOK5{V{f zdnpD9f`RIy00r=m%qI1m;#Pw1 zC{QD$Ck?kUK;4RK1Kr_2n^U^fk}~bQ#1HCUhZK1GbxlV=-~L+hw1gb?h&Zi&$S?n! zlh$n&N=~f8nEax(g!?QrLQsp6=6zC%Yu8P{eA!Y{@ui~i$U9i?nwv&E?;uL{I9YsS~GZjV=Kn9E|bbP6RzCO`A|f=)c)PBYc5bEhAPwLag0(o46(+BZ0+8TioWGb z#@wk@iKT1?;eYFj`l7gREFIiTpP^LSXOA)+}mv1D;G27|THZs+T@$N+iS!^D=iUA>3sGE&B##C-cG4;w}XQ8ZtT zQmps1Z)dYJ@OH!Nou8NV`!D~Cwzmw5D+;#-0|d7O4Nih|aCZytG}^ekyGsXm2oRhG zf;++8-2()7cXxlCd*@cot9kF%tErivR73UQ?0wGuzO~l3)~jl`4!!o5r8P2{^uQ@*Ak76_s8*b;K!c$oFf+l6j*un={yQP~UaQ`z^l(aK7fUykzN zW#a37G==+_gRb7hy{|WAly}@C`lsT)U~@EHxEMX*zt(&aeJoU2#5>idr{)OGsrIT*+c&c$_ zuNUfZPtZ59(1#O7G@JTsVD_dhu+O4C5VjDRswTVfCz*-OuXC&Mcxk*bjnJlQ>A_PQ z10tj`KG>{~qFfu~DMgt?uRXS_y3J_>OI>}Rz{#zRJumRavHIy*s1@^gJwJ_5k@5T{ zyFO}FH^JPTe&A+>?um{uD<;rDye{z5UWwz6maK=*#LG&jnt zZFMFxP~>p3T#R~V=fr+*@(*JcYPz7w)X|G)$t4R2<3hB=K$D8*LWsF~3+dH@H}MWs z*T-f^V&8sF--Zj0VcZWHIeCVT>O*T!6fSgy<&$M$*cdo6*aLFQeC4L4ET-r$Wgyot zhwz4V0U)}#pBa6NYj;TsFf9Mt^@|) z>sKVrB+I#q75P|zI%!vHAK=sT=rnuTqaXZqa+VuF!?En5G0x(z$WYn_DfnT2HdtYR%G1Fa(*zk2?cEijftIF?&EZD-%?!sC7K zcWq=pKPril6hbwZ521lZLPn@r~P1flCoQ3!kw(dy~{ zV|8mye}BWUc;`;%tuIghxl4jxJ$_ITr$|aOKZV=toEttl=Ff`nMqM&49elO_$N}wq z_(U$WkO$Am=Y}5G7G8O!&#_pbkqc8qav?VXtIAJ_f8*?Gw(uQ&iw_gPpV&OBuYSFI zky_LSUo%>|2F;dtXN=o%OBpo(9PKy3{pnLL3BY#k6APi;G78GzM^+D=dU^_K#%2s; z;7b_1@8(-7t05q+^6wvuu1};i36$}Q#~soGW~U>_f*6LW|QN!wr(CinZg{ zXPUv1zIoP_xMXF|S7T8;6TkcLHL%sckN1U@&h(N!jbCk7dyLb)!&(f0tT7eODOYH^F8*qJ^4r6NwPx5)7&_}i@O$CI zmHTfcGRqI_w|YZ>q4zNuS|$nMfr!SQcH&slwAotowU^wLr{n87jPpcP$|_^qy7(EN zsE8ajX)(qnV2Q~EcoN7!Sw`av-EU2!jW~Y1nSD(*MAb@>t5z_97;7K6taM*m<`We? z{zP4+W+;B!+K?b3bELS=Mnyr{%um*%b$@~S6c%gM9hQ^)U6&Qh!cV!ng24bU1=fli ze|i%|`IgGHQBo3cYFJ<|)cZ?ReB@&cgnKY!96?b{btqVmOfp#moRT{bQ|0QU@~Wrr z&cMs?Rc6Dy%c>6QFr?*qScKh54Gnmn!_wwXced$0Ur7 zBI31)%*%d7dFa3!uOJF?V~l@ag2F)5yavkWFX2_uRoDwN+Vx38$y8UD((*#H>Mc_w zNLPa?AAZDo8mh3X#SGi&gvaIs?y%HX#|Z#x234q@MOTV*VUGD9EF$nrW<+EvqI&}i z394z*=bbfsOEKC8Gcrsoo;@VD#E&W8J)nX+2F1(W>oGn~I zuM>zuqxAYNVFc#W_oqdvb_{5PMHxarzWpRPw)UEwS@CZTQ5e-u?mHEb&anRU&0#3z z^zkb3>cPwTi(`ab;JE8UbDco*GEP7EQ&01}m|ytajyO2{JmzM8Nr{SYPQ=ZRlZ=Uf zj7d}TxT$PPV0&?c!F*zJcgC4&czUuzo17%-d;A12Jt3?{`hK>u>(VdN!wkT-am7{! zl-{g?OSG8n{?;e`o?kUmzlA5xah-AnEJJZ5N9aAa>cW-(``QAA)5XQJjPY!S%Rm5} znTfjDq_K(gNH{akT1S}VgKBApx&$KIDo=oacH|_}KCe^YOZ)x}#J>alk!Juhafv57 zd1iFjjt_^hJhXl=Sno`=87&dpQFONo$EgPgtLu3NL#3CjbLgL#*X@ZlMe}b-ib@|c zYYLf+t&L+znoLZzzUS03609}5Ua0x4?~60(S!zkpi8u&!lQ_@2^FumW%A34(TTFaJ zMI9S#Oa@MMNYC~iwy3RmkMLf_v?96Y9}R&zvZ|cmC!A(^o!)9T3QwNxeqH+}`ghW> zI5=wX$4Hg>*nUF2o`oNH)$z!_LHpy4G!&tul9vbCFPBz2ZG%NcB@sA8k*g(# z>i0ExnSH9+*|005w?;S1{SE4L;tY1;KZZTS3MPj;T`9VxBzR|BH**{5$02fn`e1?d z2@NGvKHfQJ5yTX%1W)Ha_*tE5Ma9jb)>#{hj=u?B1c3ETX|OAUAuS9-=scUZ`oB2HcQ@oxjYGd3!Y^ zuDRW-HbO*3h7{k4!A2Lmr!dp-IZK~0bQ4!qTCy~R^xo>7I;Phg_eB2-NTGK}*+I5z zh{G-sf)qc^oueT&2B$4UYHmwz2{}+*Qk=h&pwpj2l-!xB($IV1hon6t?p zW%0|)c@yPp{_DCuJ+hF&6DM)p6LZXMEuI+dg5+LyANsAaGG)vR>Kmj`r~rBA;NW1e z|L2!Q9rz6V*UN%2S177buchGcrMtv%43*R5l1(){YqJ`&*BS94;&#pY%aG636wz4} zTZ$EC{#?%l>*+>*6!`WdKbBseISDYYwuYD?Z2bY|<`0j%`7zr@t*<+h?@7VA%K%}c zMtnF=ZsEyvTahCoAB12@uy6XNeWQF5?gDc2<>bYQ=MkD2x0FqlOfb((xam8FVS6)X-A?nMm!Pmh=Xi<%Wq$@%0OA8HlnxsVtB3wo+GiiK*RS zQRVZs#g6D+VXo)v1v#}4L6k&0L^f)8Ck1W%>vx;HkiBw}9;W5UexjQB#2@`k-k0-< zn1p0NuY1|-6pi*vVj+Fi3uNT=Vuag$ram?SS|TE=1+K<-oVX)1PhL%2(@Qt`d1Z03qM!BBJF?w%ecoM7`T-}=!lJd5Rv(WkhF1i>vG zBgPU4qVUZk%f$eJoYmet_PxXhl`zj&?9Ag^8m%l|w9KWzOv7K#Yr|vnK)>iFwoo>q zp`g`V!jCwe|O5?zy90a#Kp^WKf6Mc+F%9X;)S&J@=! z$9td03@v;!F}3n{t2$+6kYLv)17QKsE4c{>mh`EJvfgRte{|D-1q5IVe+YW3ML`5; zF)_U^R|Rf2auePiOFtK@Kx6IO{{}PU)T7cY@vXX<+E8OZVd`#{uhlRYudA+vR*+&n zi=STIm;f*zXCf#L9WWvrwhe`;bK>wnvl_5Df0h?cWEW$$v#7{>)pz%*id*5uC!pAOXi{TM?8!oB-BF&fS3?qQm!+Y7NS!cS5&NdiYk*TvH<4h3& zRJhxz(#?dr7AD`0zWEA;k2!+eh^450r2#S*ipzM7#i9F^jxSrXds;JAVz?(QrEkMW zpLa#VIHG?pE^SdP2THy*0+MgbN$eUwD_37OS-`MkTw85PG651_@VD+SUHXQ9=<<7( zfruw1o$kGi1s@{Bqy(6{PiH<@c9SGSAY(;JxhbrsD2SM(y-Q2!NetSX$H#JVa%g5X zsZiyVN-2mzSy>sn_s-8981>ubbaZr@y25=SU9C?&2CEDWCdmI!s%gA}kW4FDd$8Wo zv~t${A;M((rqari|BA9;Q|U)33*(envFLsp3txZlaXgdS>F|+|+s;jCM|y(*aI9kT z-pd-<#|_ofG)qv*j{jDaFc$Ykuf*mZ+zNiaa&_8Hvg?hv0@3I?Jk$ij!Imsk3of?p7dbRGEW&uGbJ?>t#TzU0lE-Co5U7Jq_tHBH_(KYu=L$auzSl$;zH&dS@k$eQx7 zAt+d@Apvgu%WZ78gNJjJ7_R81&jxy(mkK`^@Ih#%ZZ6VO0f` zt<|C4k)n7#g@LEbL50jHOQ&F8rHA9E6C?%-SMJhTSe?kg&#;~kf1e#PxI{$7jWlr$ztwPrvQcBsoAuPf$jI5n0NecmwPGhNGMn<+VP zh6QhRbkXzt(impjUhWI8d}K>aP=6PcK-*7gI6yfX-*KXvh!`*W4+af(Xdoe+HPFQ2 zmp6lMv7)fsO}2I->amcu@twaa)=^TH)P`Ci!rJ~xYKuUsZnC_|wlox-P+1ZUBycEI zPQ@gvy09}Ll#H*QhkP|OH_r~qf^*eHk*#yD&y8?~!LKQ&gu1m1vc@pp{w>|?r@(xg z=F2{}EVQ=Zzq2q&Na(HTS6BxW9< zP)XG}kqPBMab@6GKo?sV!{M#o!d=A$m;(0ptq2=1$~Zrs3t_R}X~Rm+j_xJ2nTG?p zez~IN2p3A1WpKnSy7THaCYwU_F-UJ-@g<%Mh5|YY$Hmov;)($+v*~;vuMMHnW|!0Dhx&2tf4KfBVmg<7fz?dO z{DPVd=Uk5UB@~)C`11>nPQ4<}cIlG(1JjsQU3_L{Ol75g@X=het2NYmG89xQUO0`* zq*Y%3H)qn~j|KZ+wNK9%U6R)}3;(CH&&w6MEf%Y-JQ2zU>&u7#r3FaYQg&fdz1++3 zF38C;)ud)+y_`j$MM>pE&mt8FJ6%rA-pc}bT$(^R!@IV>FMxw~7R2ICnF8^?TsKn* zHQb)$e+&_nP_no49FekJUPqFSXsEZ3p`r!aBxVh=Rd-duhU;YfA zR4r*gt?m=@uksiE@G86+!SFmH{nrkA{Fd|0MIflfR`gmkr0vQ&^{CyeiD)Gqer=2J z-?9Wal#1C!LP@Vy*wW}Ze95F1zsGo~(Ih8CH2hZ?1spOA@2CcMjn{*;|3GYE8gMgk zG|EgF|E*}ygEaFoX~)Bq@;qCIiHj{Fu>0Djc|+qz|QZ^sat zaHbXx{iAO10s|s|C}#qT`@DuVS^qAhiO3b_z3^9cWiLiLx6IA??#WR?U)vyDC>!$F zP^|X+bXYXK?BXD@!inwk^xp@CDef9tENkHoB^E`hacZ=k9q)0Ps??e@c-JkEH_yOz@6@4kQJ5H z%114^wF#A$t48c_)A~FyYKCyb;YUh^p9x0gc?IXMB^rX!G60ZC4RW{8@PZyt04$(V zsIXHvr)S(B1|9t3ovg9M#RIp6?LD&R*uK!JI;(sV@_Uw#DJWEK1Jznihj7|zP3NVt zRrjZ#gKSastzSOOD6j5)&LuPU>zEBN3ik>(FxD*~VSE<(4bkaNQ9v)=JqZ#v@2xw0 zyJuYJ|6h|k?>NWL=KFb?;8c>^$EIU%vaMrZqkMMYcB6{axM6H|xvuMLw&Lt-B1ag* zbVrWh(mrgPi50qcwmE%bc=YY{qxO% zkT3J#+VRk&@>ZGM5$HWQ(J7|zPV)1ACu@MbLs0=_o=xxXCUh0Smpz^WR|PDoS8@U< zjoGb=w|Atr6qyh>uCgT_u=Di=Lc#?A&eCkf$2^ImAU5x1vLGGAneOJDP>+Wq_~YeN z9>$+~F>fyU?>D-xAAcwPoA+&P<;P>v8)ci|@3|am)2wxXsWBVdR2?PInkgThFAQaI z-W~N;2529<`K>02?qMdeRaama;4m1H(uPYmV5O=iH*`QGMO%CrZ61F}SKjRv4-aVY z^y07mAZ(oHym(Qcy#6$YGm*|NQaWVq(X1;3YQ)&Rfw!ORTp3<4WxD$7?j2qu90dA& z!!&X&8lO=#x;UO2}Mx)|@{3>0k`ni3;vbWAI`$KWS8FQ1@)AIDkHw zL`(j^I26zC2^;S>$e=PmPVEgTo&TOAX)8@R7R|L=vC!t+ z-^!7}H7gO%mnT#aJ8Jk~E&7S09DZiEuHfy@$0*W;ShGYlQyhb>(K-7oTPHff`CBR= z;_!Ewu@s)cwZzrS%3&8V(YkuLA~)Bif{(OuBVNDFC&Yj5&WNw!{df{o#;CUTV59dQdTpM-!~R+U1roHpq|eJ|`3gTa}JWDiuiygZa}NTo8ANW2Sf z%F-;xD|2(>$N4x|da_bAQda zC^60tj#>jhCgr2*7mV>uAH2Mx;6)b)`W8dviK7GqwC>P(;g`DsPmiq9)J~_A1>m+| zp{=Rk^L(H4Y2NRqD+#{`{5uZ>)HdiA|Iw+Ao4uQVk*ThX91nX-E8Ar%3)E70n$iF9 z-zR^OrAsMl?QnNp7>}PV{|}+{po9MdXniaoTca_>NVG7S*?h0sbBQK%Aw$%2>-uXd zjoc$^i06Rw5bLKRlUm1D7ybnN%#FD+>!sp_Vju6?cj8BKZ<%TyeU^3PRg{6NOYy;fNAUkqQ@BgFeh#=;71c8qLTo!bQl9+#IM?V)6{ z9<;Y-YP(i$I)a*=%R-eoXHuH+^toN#5JCan(&>OPkd=i&x#TC^f!48V0dTclUQ8mB z;K*~$9Oh1`K^<-O%*v%r^W3ni^t~B-8@1iQ378BT2*OzZdQW)5-)oHaAIFK(hV^2b z9OS&{P|lSHLJ^UAWl8ISrzRpBD;%AIOKV(1o2{m)ZzQxZ6MYL)Mcim$v{%gE58|xe zGr{vL2?7`Kxw3zU0LbJoMC!DphU(%x&e=sdO|iWhBRytdIyT+=gNLxYKkb`rO~?;? zYNZOD22)lyKq$uSi>ihvi@5zJlpQh3$A{k@)kVF(hh5V68o z1AXP0nw$B4%>4=XJgS~=1B5%H!yz$x0v%o+h97*|c;dLl3xxNYeO4Apb)mutp(sOL zn=c)`PnS6zVjcrt$0tSc5bMu;Lg}&inY+nl^tU>o1JW;GvfHLcuJwTVif@aCic2Cn$1^Ot`ok#ECw=SgP1!dI&cmEKFJI;WP^ zVI^uJK2E_Ea{rYv(it!vZfiKP%LYNdzpSp(wi&k|?d|0xK@t)Io+oKNSMRtOVT_bJ$mc!#SiAfWE%%;!0>oki zcpIv2({W%=vb8Zi;Sh7o#n~o5Bx8mfNq*U*3BC0`KWyfX#q`7a>9Us%U|B6gO%Rb~ zkzOHQ2$SFD%Y@eXbID_`rKG>B+1)vgf^X#0t z^6wuWs%#cmySuyRTiltn8|?Cp2V(N_@;>0;1m)&Z#8W!%juPOAf2O7mf#NGT;u{O* zS#50rR6+<7PjRvn!1XJ9(w#Pb0z^!3NyD*B%F>#pq|)yuuWX*ypO*SryD|m1f!e0s zT7rE!_Jw~YWCM-_2ht9KRW^0u$$IG%d6GiZOU2akv`29!O#uwNtgoU%<_8OVsl3+Y zwpdqj$2#ZNsD;Maq8qtrPYSKawd<>k{Wzd+WedU(LtqY`}KNosQ~^Lc-yiF zr~mP`aEF$o7|FQdMG`;#pcwn*7cm4IGsZlcqWF+7>Q^+RX~k^dR(a9!(UL)h63To% zAXo#Q-7Y4G2adYf!GxhtXI{(Dp8PK`mU>psjWLKFEjzt1DhO(GhMQYTiVkukm7>yw zFNgRK$IRK0{LgUPFj1Sze+#$$-!<#X?*ZK%KsPteT#0C-;h!|nY>5x{_V!x!HsLij zY%DA+Py}BgOHjUCt4>N{Yf z=E?mSt?YY|M5j?eEOwS^y{~JhF6>Rne+MU-N!OtT-SGhqh0E;RO;5$xwCZkTg^slm zeI-UMi?D`!Cq3!Dt;H^-vHO$^<>_9VVD`*N5d6YwAk0m4Fz}-(U-vV+6bmQkvrEcI zOZ5ECj!{mO2|ycxO=x)_6pwC*8eVN`vbmfLot?a8QEBBJ%Y*0W+a>Tg6V3d;5p<_a zYx)jHe6h5cX=BV1-;Wqko!TPc-Q$0{gnrO1vgfsvk!}Ngt0#TF*F`}Fj8EQ;p*Ai_ zZ|`U;1q3ee{w2DTiMb!v)QRfo9R#u>xv4h&{4&)P1kS259)M+r4kQ!J-W<(gzEe|+ zqb$B(0~2vjMA)|r#9Eh^-1C;^5kH1E>}6&jo&zl%?x?GwO3M#HExQFD`&VQkKOEiJ zHb2^b8Ot%KADUk}LOyrPlTP6ZBx?ESk$wdxD7|MXa{5xkRP>(xI@frzNbmm@B2=F; z|NjvpB=nT04k7f(Z7@H*HF4ABjEe&po|yn`G11LB%VkUjeR}&_;w*`!hmG8Gf*=ro zLO+bZt`B!B8OYuGG$>N9(f-Ka<6Yv{l1EKcMopESs50QXE!oU?BB{Cd%$(={;RoF> zQp##KOf8On=Us@!6S)brch{;n<<=zfO=TZBSwl+lZ^KY#w*SBx#2MBk*o z_XX*#F()>mq$D3tT**!Yinnm4qnFNTSygG!_eIWFnU1Eg*sQg`Bpt^6`0+hGT{~Ed zyTNWnCQHzF9vbin;d5^sHcwqp1O>{+)4I92;V!oCr};eJJMy~hcMd1gSuWKZ z1x9F;gPsA1i!8`SkmS zd+^PmdKAGqt+n#o?Qzt`uJ!`($7TvPhZMGdO-#iYvLt2WxBiD4ifE1R5?(73pB$pNQp^>tLn@Q%qN z0Nz(?@XVv?=1l^}tsTpWMJ%M=F%ot<1pyK644)%VcYx&D z2uH7TNNo2kyLSOcvndY`j*@6&X4uAXlz?YZD=e(-m<^^DtP+!Qh}4}w8J4eP0Q0}P zvg5QJL*X_va`(a$`1@qr?f4p(2a|WIfG$zaeDsf2`mgOjQ70_tQP# zx4#G+HM`PYbkLheHZcYw%(M)U+@guK)~4yw>1VIDrRXTB1b$o-t9I0)BR&&${I?K_ z+wJHIATq6>z}bQ?OfYfk z!F9oFN`|xcE52rv58^B}keOK(u3oIZL+B@G9o>e_UKBV`P)^(Zf=OF-)LfmV$zBvT zBYNKZ{j}3Ou^VO5^YLQX8f*GzO!a}D)v!Rx5Ayn2z-FtRSm|G%tUHF=H(|?&z1d(P zl%J)&(%PMaZh#;WePjL>hPjxOsxl@8H=U(Kz*0+s-}*&b5^X z!ELMGYwYD0+uD*hjpT%`8jUxgY1&60W>e^#+EMV;<+IJFKlnhR_tC~xPcLYml5V>e z{`_2EnOh9{IUj3b>aul#yMQZ%_-}RnU9`KTWn_jS6_PA!Y7dN$-kDmDXl;jg+kyVh zw9SA8$z;|FNjTaTg2@Atb2O`Og_HV@dGBl-*DhTuC+Yd!tcN}|w5+Wa>^d0rp@r08 z4y^TI1h(-BqqkgLBc_M72vUfCcP4{Y{DDzP$E`#9O-G3a#u&wZfz z?r18PP<9oSC>bWT_ZI6cwSLPl_3^jf%dhCRp%~dEHvcJz?lMlg5+hPhiDzRMi`kw4$l^O#j zm211H6?G1bY;`iC=P6{|F4tcrV@XXO1{Fz9r|=3J8EhCU0#kkY?u?MFMP;*c0*mJ9 zspSf$BKtso=SGnaKb4G=3{S3Ti0+Oz?(Ek#Q#sZC;Mf}McOLKO5<^|sa$C%&B=qC1 z)THKH($*M5F1zDhZ600#yX}AD&M|Z?3wVYL%ES9!EUWL1w|^`L)ia3k#X#Rk9V@n` z)KD{{1nC6oje`Tv!lRx$@N;M5*}!zJox9+tbHCs_6}H(+ux`jzg0+5s2UoB}Vy%fj zx7fBgK0j$KOu~$+AK99}q)3$DGe^t@1J!`WKxPUc;Nwmyw$_rF6m z{-v9)z`y(lHyi=S&Wpq6M@F#@Uxq`d^`7^k*&g5T-yAwl=!M3yZtS$Y$bC|0X6M6; zYf_$0pY)Vrp4?CKv&WrlFR+{~p|JV$(h6uq8mb0nGaql=V)%+mfqyZD$%K8Vop2B< z*OKpB{=e7jyCliLUhxq?6=c#xqq0hPifs2cef_F8F5fEIHudV@MTNqtb5(f(#R3Uta|ll*1l%fMf`lG<05;iX6?>^4xJob{!t+>3 zL1r(vw7Gkk0HayXoTQE+w%EG@^|fEE?Cx;h>QTL}M|4rI`x>bYbi;{R1bD~a&VOe$ z(X+M%y@f#yVvNnzKb2>3I|e`v(tf0+p>#&z(%oNA13k~$?r44Z<)gcztmtZ-FPz2~ z-;I23he}3PUnD129odi5jr`eQT0MZv`4<BWl$3^R6D{t?@=!T!1s?piC3DwMCtE%T0x2{F2a zipy%^m+Nt{Zq?p*r&uFyW^T2)t=eGS+)26Pg6cdVHv(IV)LW_7l z*qKzs2de%o4u6E~CRXras)=oeedpxgc+a!;vRhUHA4#^2KvVR>(VBSSV0+k!O=X1|`7ihIB$w=(&HKq=WTNDYb43 zfyLOpOaIKBZPsGd%ZNCAIm_f?w(VH!4L2c_y$$c{uOznj7Su%TkD0Q5K<0-9-k)~F zap#AuiOGvH#2U3haC5pVGf@yZPZMq;tI^$LrpKhOvL9YopynSQ2l>gvxIQse&)#oCE&jBmwZblQq5S2Z%u?&SmY-_t|o~ym% z;`ACmET*iRAN>=>~F_?8SMAJ46M~T-+x9f`rF)9 z!U3+d%pBkY3cZsDz|yvpviK`@Cxh&7=j`MJ2LjBD)m47 zXpQ@IBdhdljap=9Z-=As(o9mkixXm5v^W-<-ow1QICQ3tGFjV{mBIln**1jM^DAzk zH6FcQYl>2?#LnXc z{=*t?P??LQfAiN;s$85{x-6PaB z!f=zc;^2t+bgHdbp-jV`CN}(Jsqwl;YL`MQU>TA~MUuqpfkW~n#}Mrr*zR&sF%n_g zLgPX8e#C5~*gVnn3zI~3cc~t*;O~*hL?w~3*)=hz0#Z(CK1MW_xJwx<=-`(WgpV{*#i6Mss|dqc+dULWpMKYqa6;zv_AJBtHNf004O1oxX?+?8|%k@wbNT2U%d~ z@rj+^TJA^F=rn@;-(`7SmrS$8Hcf8MoDzv>MQz^S)|F{h1+}XIuEg))pIIBQ#jE+` zV#rNyEvOk+#+sItpw0t7a!gPF`K`;_X1g~J7OJ)Z{qXDHeF3k#1IfzUM8~mA|ORWKCKpK5e8epgmjwm(}=L^ww0)ouq$ z#YCLlZ23sWs!^YJk~WSbU8(ciw(AGX>-+J28NLFoUM6I9C^X6xBjtp<%8JNrT&l7JDn|AZswpr?-yNW z*$S-D`NuY!uunv4ZWCGe_)jL~gM>1qYQ4lAEKQ~Q4E zBa0@+^ZZb_B>NMCjWe42B)WiT;_*1_Un%r->v;*xOe%3xat5c3eID)?)CXQ@!MtwS z$_hKar;TQ_?8j?xXIlExR}whEEpn2*)X+Nk4c*i3ertRCXQ9HyE}?U~@0m4Wq8(Ca zKpU!NGngj^6eD-W%~829TlW&A*^#k+U6LgB@+WrVNI5-IzG zpBjz5V*)aw=@JTR(}+nVVI52qKXx$m0DT*^yXEF zb7S*Ikev-mRh(%2cE%MTac4V)^s^uFq+9O{RJjgNT4}&aakD>!K!_w1cl(VH>a0a_ zIek;AAK!0GxENLa>e~)RqxFR>K+>mTMioW0bGx9Y`k0-GHHv5*KbJ^0Cd5I+`yTANE=*V0lG|fqA zb#EH9Kk?)7Vi}o9es4Un+L9IkJ+@kHFR#N`D*cDH5=z+7kdA?aGcS|}Djf=;oTO2q zZIYQ&BWY;?=!D9kwj^uyQ$v*BVv?{dRS4v5o=I^d1Hd@NV_yj$te?DEQJ-VJfUwl3 z6DCbviHkCpzh=j5UFNq8jzySZ?-c*OvK;QLOrP3%srp;Q5$ee&l&kl&=gYP_xjw2sB*?J%uKQvXl!snXh$&8Y56} zHW={m@g<>ZMglH7VgN7`YT_6Sg_sSjtw(l7lBK1kH=uaH{o~{1`G%;8X8+n+7WABV ze7dzoz#vY!l0Md|x^558*R)k>QFhR9t4iB+(enu!kIX8YN<1E{9V1CiIzb-$ zI_1M}ofZprQ#q%KXNw9dV_Xi=Y+3p-V{jB7&GafxPqS9d#WBieQaqKM0eoPMq!_il zGv)_oTH}~nNU_F7f?VJ8jmHl1j>I#l32OF)12b2ypD(S7E>%-mm3X%H^gnnvk?Hz~ z13jRx!M6y0ctEAmrwuFd(#^AtiAf^Ki>vco(xW&KokR7WxgI>4 zQ|iw`a)yP)%)WZt0mdOHn;yQa|c4 z&`Y`HmlI8LpW_M=Es4~U#O!t2YBCE(pyjry_;6KeZy}jg^B|KmrZK3C3{zIX-93v6 z%R7UF<7*Y)CygCnH&y-K4O0?_AypgX7PBsTLXV#qS+lvf;lkI}x&*))4aPIwzKn;C zi=tEZS+ra5VQ67@MZfuT>o!6i?@f++ov6*BF3v?FV{3T`8Ubu)o^(Ry!t5_mMDn`W zbV})1{WZIxWghQL?!-(s*$@_iXWt}Dk7?dGI{s$Ah@&AwBTT=M?6=fuur@wQWS0Q+ z@OWjryl%TG+2uOWEaki9K_|F$)B1kC2>@E4iC=l*z?kWjTlF+bh;sUn5LAN zYk;+4wc6lj#C(itAKS}uWDwn3V6dFAC8euCH+uf-j*KKLGPSUAdBl!HW#hdX)11i6iQaKrT->)Ox6dJ-rc96-cPk%U=qo)>xN177r6@@q7?U zkG3rQX7q*s<7>+lTzrENGfY&n<^tfy1waj_WHy{2z5Q2ePddmB4$$EpYUX^JO{bN7 z8p+B0t2yP5^grxGOc`e<|IxPtEs(}l@I$#)Ej8XM#sOF%BF99_MAOfVB~>m(jyg)h zxS-E~nO`qTg5u@z=AST_>1XVpKZ?Y}#7;9jJ`e2xxh3_spTyHD0SveG!Lzl;<^sHe|@S=)gf<}%<)0yxHEi0(hJI3$sF@)Abqc)NO;en%!W;8(CluXN_J3z2O7 z;NXGKiR$04iTLFdpU-s7L8Z$c-u$QC`FU+>%5yX*5nlqo2zfG%e65c9lKzb|XRzRJ zpNSYte%mnhwe&=K+3A?$=`s)Wx^5eN?Y*?8p~7gthaG$BhbfO7sZ!4-KCYs4;&bs|DJ%4N z-V?Qa3FTtp#8*9dTHN?NSZP?At*5`5_sT7)dA{b`HG+UOwTY)H`?rR6a-;_luh6&O zznMiuMLo~gVgAJk^Y9RSho(RO_PjEKnl6k&CAAt=M(|4w_7md6;md;6f%-skGg6od zj{s>k)b$l(invPK`PgL^-8E<#9OH1NpYd(R#a3`^83n8Mo_b>RA|>`Y{XrFr>HH|I zJR`;<*xW174-+aEx`g|f@lP@-g|471NiIv4KWf1IBO@aU8lZi8dWyrOM@&XW=Hu%N zEzOt>4Gp0^BX^HGWQo=1g+Y#BPL|W-=k>3=WQyI&V}E5>K)Y2~q?Tm5nqwvH{e5Tr>*#67M8EiuSaG@ox z1cNs!)QS=d%W3n>y5FZz#3($G`1#uBAfs^l>aN?}^5w>q-M-71B+*;DeQD{|)to}o zUPiFyW*7|ppYEA{*qj{bj7N+By16fzW=r-E?Yq=%K&qYG7RwcREa-=qvh|N|pcVOfi`tuMRq0^h8k3zAt zpA%JWd=O=-lI`MJ%J$J{iLJkE*4m%Kll)#{W5YMh_5vl}n$9 zF(eD~i^P80s;ZRSd#oFnhRiM_+_5qcG;KU?O$5v**3JqP!wj>?zoSYsMn(KnR7(dk zGt-!FR&G_s4zX>`a!x3v7h0nTs^gO?2%XInI(20Ivb|Xk`0?KCy#tnf$U%`uRv`S(_a=U6&#< zU4m92}H8f@EZT67X`Vn36hkhDEW$ z&1n9Z-Yh(P9Um^iuyJCQ80qI{6>;|zmnC#59vzgQ&SiCKw%X?s>`9W&Ov@ievu0ly zv7G)nQANet-`7C2@Ltrd(yGb1&I)*Z25C`iL#@o-Vecjm?ng3k8V6TMy4C*_FlLTX6f7#4^^MR{^kgA za@f#l-(QAL#s;&D?kza)rcis0`{IfPRy7pg9JtJKoOkoPF|m1phqCsJ6&G=QUiY$1 zZXO=jb+QRKX2@!sfnT#8J+firF-}c7+WE6M-6o#j%R3cpbz}dHl5P79fIOyQdX@K` z2FCmxD}HOn8p!wcZajXVk?lb3?Ef%)!7-hBsqju+ozzgRFu>D_vp~$|7x)FEtl?}l zs83(HYjUt|ChKw|t!J52IKPk#=Fr~BV$YHOsocO<5hjecrzG6?V0tn{xv)_Agskb~ z$M?d6(0vJAb8h6NHrTmGT|NG9N@&LqSFm#o? zn^m$dLboXKSnpxX&CMlZNg*`fq%q|(AQ0z72`@5i>3GFb%D;yh_VDNu1mYkkmaFn0 zPk*EPhbN(?A_3Q~8M2g-DBnypf!46tVaxAns%gIAYgU!UD;G>fAOQ}N$at9d9AzV0 z-eOc4`XRpEua9fajlROFUYFmZ&1aI>Z4Kbqv!!!$D3dKGYI&aaIRNVmD{An?3l;K< z;1ZREQ?w(i=U#tViGY%VL`Ajl)#z!8YufPsHx5mYd^di}{Yt*hhlM9bdbQMJMDRuk z??DQ?+3Mi>6BJV^tq>V68<_2Bjw!G&etU&OFd8tQ3~FX@NOvEd2RE-0)Blt- z_YRhW&wuN?>*SeW*u4a5yuH?*gG38t*f=o6WwzdZWoaRJ9=9?g^c%UIur^2-Ax^MD3(n%<}7sB$zhje{Euvu#Q3D!upBixRE>6YUgspSWfuED(l0OAP-PoSVhE!6b>giEKE}D9r?zN zod^g`r{yWkn82$#ZGms9umT_~?lM2*#i)b2)6zle@INSf$KcG`C|WRfCmlQK*tTuk zR>!tF?%1|%+g8W6ZEN0qGxyG|nOjpeRr&e;$l2#S``LT#wbvqKaBdeX&5Niul!Nx9 zX~Oy&9%=T~+CIU7CY6$r)})u|Kuv)s5^d7l`l}eNQM$FyOL-=?&cy;QRN{Q|iA_&i zdUT0s0Z<>rGVlZIlGFRm^O8XX0Hc5>66bo$+8Hua6kr%j*ZE75boxjAV>Bq1wb%2_ zqFAU%O*7~es4hGQRcaC&x_I%ADCwT;u z8j3Xfj8f8$7Vle^9Vd#9D%d~A+x$&_sf41U%#I*q>~4~LE+yZG>Jr2wOq#yE&tZ;L zjkn_#f$N;UApS#I7d4U0nsdQ);BVwR-b&;YYshlL2f+cP%dc`t5}*WnR-g5Nm(Z&k zQwjXAqX!?|1KE62)RvOAa$$`?5(?09@7_K4Xu> znB5WNv*czu=$nirPDui9HXgOs=hSD~Obrg3mi`?Lb7e3|E~D2J`kR0_HitOOl=MyZ z2W_%=rP_MOR<#?syTIXw?y5*KR2N|mM{gMJg@LTDO0RQeH@RR&s~Mab zWKAkiyf=EWEa4B$jZ2Bq0ey>#-`fqo{bT*iLLLck9*CVCD=?n9B977v0iW>=;WO&e zl{uT0#h9MVwQSzXO3xE52Nw~Yddw>lCNxug2&fXNmwP=gd|ynkP?dm!JIj@9PBjsR1p;nG zmIc5o9?O~OT0dsgq`@+lZvC18)MLSt-GQ2IsK!=2VtI5SjC+9*Dgv&&6}kxouj5|! zEEj@RDJ>2+cv^(U%#Ts`6>*0LE9J-IJGhdPuHn0kyAKs*=j0^)ts+J2jRO%QQ3 zTyY1BqPit2p-5I)pP(|w(NZPV_c?+_V@dDmR99FM?n7E)avL+j2Ymi&$^95#D5GG& zS#^bI{cZbhMf_KiOH4Dc*uf$H4`-`0 zoS4@a6msT+w7T3hdk=NnUBD_B;ZpZxXQ*hQX;M=PKtKUCs}i+mm-Y9&8Q|osYiYnO zTwuUq@r%po*`zX`3@ZS;T;oJi?+=bEvy0M=J~VLmJZ%xj@yyAot1XTSpU5?euEPZ* z?shBP7PdACQEF7Jrlk857@bZs+rNe*$4%e~KAXtE#933Yn93`8*rqe3bgJv}V{8e|9U^|97`jfH_H~HO z(-@2fWNuxr$U&TX&&2~AEh;kY7ctpu48X-KT=UDcepzE{%vpNq4Y9)&#U`Ut3|Aq2 zJ)7m`dQJPyzkMP@xMB#5r7WT_=@^`~IbuM2oydv&3~Y|pjN`YCO74V_I_sl8%@ZhJ z_}&0YE0rHi+ad3*-+Q8150?;a`e&H!Qpx1%lxKV457u@Pj4FA4f7780zR z>N=OOyZ58L=G}_AKEShvo*R>?I8XWXlZI!LBBWm`k(LZe_0}ZGw=K{S5vj@~oxx|0 zT2xiKvvO(i`LBcy0zIW03Liuez2PAisSkG?I1l!%dxw8(Bytt+0{P)JXScjn37-)* z)no{xvyE+9v=X`c3_dIqMM$>XrTYA5%;v!n6K@sONBXj9XZ#L%decTfhJ8r1rS+7Z z9hZ++OO~tS45nzl)c*3ifR`r+#GRnZZzfAfrnh1if_kfo8VPF-CUaus=4Jy+I#*7* z=g{^5QTnU+#|dd=gM)p6TF%L9M{%0^w&jqD&5VhfT3E~tA9#CKUS%5N-~z?YN}~r@ z|LZsuenEoMSL-4@M#6HIl6ec_L@WsfsPV(#1>#~n3W+~sX)VeqK6$x7s zXvf%4XI-O=hPNmh=q>}VfO!g~R%9{LgvAfj%TP$^y2E0>6At>%y=0KQ<*O@;UW)r=nxw%@yn#o zFY2+p%BlPDQE9oaZXGjL5*|zxjw5E^@VE{pN2;p{>9?=^Z1-kywcYg$hb~05gX@Akb zn0d^x+wNH@)7|xgG36+yev!fY1D{hzNO^Spsown^ciO~XP`2>#75Z^XEtvWL{`KPQ z?zWPdD}o{?VkwtiIa+X1X{alX$?oj$a9MR)gGdl^kHzc=bo9O4?P!;8OODTqO12i) z@DP8oo%nM@kbP-KhW1U?KRtJ9O9VIF3VO4Ld16tm&foTM-2(TjMUtEQg{%(6R;k3l z@Gyg~OvPq3T1&Jz1nC*oi>u;Kjwyvwmnp`jj_E9J$&yM~2glzac5fhN?t<@Z$rlNt zF6!0*qg-ynPe0g4HKD=%*4oP+Pl=HtrM1nP)_dJepxzI3-vubqJppuAex$6Chx2lO zAxcgFt5&u7byl<4G{GRqeM}^*px<0FB*RqK83D)|wm~SE^I@?<=tjTiMuK)88mu~E z`-C*Yc${(;#|>(1E(e2RE_PbD!^nP? z7HI=X8luGewDpBNaAPiy{m{~w-dei4z1e)r7?npY#4tGzccbr0<3I~GmeuJP`r{od zY?@j&(F%%=nWCNIcMwM37>1>&$nN?M`}(4eX&o-SSN~G*ri>=F%Nb^aN2S2(BG~hvLtg!B(QJb8z~`NG z`K#RIj=}bJabYRbokddP8D%k^RqNXdpMxpKJCZLog6YwLC%1G=&BHxe&Q|pMwT2A! zXDkzp|1~KSMGgeg<(APbUQkt{_OZ$qj8|AyEhMy#u!n6Y1$9kGpO1 z1zQ25{*{~<;AR=i56vjyr#jsZ|DP%n_7Mw#;J@JFlK8 zO|}sy!YES`OC+x5YK}egvT%!Em}R;cj33mzekEO%jn7wT+}#|9gynJH@p?l&-9J$# zhQ-9hBx6@f0WLwQplbN8OX?1^x{BfZV?;$-(@I|kS3P?V+q&}Vn|0Tnqq*vvcL1wm z4n;)3+IqYqteT6gZyc!?AOvswLu9m#QY9{Ht6>ZUKU@Pi+LurY0QL5D3*)~4jp#&% z#`t#n^@jGnco&y6T{#~K{S15;#z&WX-+0roseg1Do*+$+tpkEi#IV!`z>PnWyRlfI z-3vK5q$B)^psFQ3-Xug67->$dHJNBh_10d-JN)EPu=QzD-i=a(SXP9 z*dO_A?ET0jMd3j-s-SS3kx?fn?5?6`fplQ`%s51pM8~?mr|lBYbP%^X6$Sr^R?&(v z6lw)g;_6UaoKzm`TwMY8&1Ssz_&#@mY-v`^hSrj%Lu4}S4ky6lzFeSx@+;xD2&c~Z zJRyO&IKW|HS)${zBheU_(#4g_FNVeOnW&Y2Vap7V725IKBl_w>nW?oftc~i=4GtIE zkuCE3zu!*ZBorrgT*l)z24HVB(fr+eIJbi6W-RqF0Q9EaZV!< zN7(L4($)wVTwvrE!!Ch0i1*6Fn+srOJM4o1S+x;PT4D-)nnX3RD1Uqe2Gdq^v3*rF zUv26{?erkbr5q_njkZF|-XpL-9N8OK(4yTVU45M?&8t)t{fZ zBrxiG7X=1GWh(1k-suROP6zEjhD%QO`Yv_2%r!cRhv`CgO)KfWKPa`e;KoQvNczh` zUIA6WP&{X{H}zX};GNk4l62{|NOTSCL@QZ-o#TGKCatm^i4YXh(Tv#>M6YH#=JY){CP}CPJd}zvg1ySiWMhYV8e^m$SUj77N6HE<%wym zIaOyGM`vwe+DoFa;wrGv{fDWp_o(P9U5}F|>PNt9&3*?%GzA6+Q!V#uF((<1Mngij zTX08FR;=-fBm+KvSes@TA_W*hWT7Q6U>*|2OA@rv?wU)?yFVwpu<|l|RiWOMQN~N_ zWUU=cB9)}CR=XmVA#u1{D*q|DsJJwYCdF@UBt+xNf*!rKUvI6J>Tykgo_*SY=X!;R zj*5E#Yk{X{H>qt!Q7O5*tV6^IaL@{7@LfXX-EfF}S<1C=w%v3by;h@@C_y$`L>Ppjw*g;H7OFTgoQkA?Xw`*0 z-E;@Nj7G)pdj3J66AG88{ed3@V@DJ9;NIM>q9&CO*QKv#X2AOFpBseTmaa_ z0%Zxg^V=QjUiUH%Xn1(j`{NmQF0Ss=_YS{#l(VLk%!geCpt%=!C)|!?EWOJ8{5mZD zzSZ(&s#F5agUzI?$0l!Z3h2JIJxyaI16M;}dE=n!?$5N~A6PX$A0E5AyD3a>TG~3= z>~Ft-n`Z~>B}k0o$w}T!6@$S(qmoK(Eu-S|ewLB{!ftWk3Z9GRvJ_u7W7n04IIv5B z<^ja{C1*T7qk_Te5|EQAW09Sqw!%M(FOic5>4NaZ0DTtS8W zIX+5GK0lS1)Az*gt>Q!3jg&>AQ%WJm=rau}iwTUBVr|mj2jh~kg5OVooYPn+0?kq! z#k*gX*Rx<3rF@&`&Oq}vbrwrNBa`~~-|r}%82sdFyO)evwJfco3bT9wUhJlkr(toK zqGY~o`iS7U@iL;BWg$yQL<9()Pb*de&glBHJAFy*Vkv2siodBbJa7MRT`)f96YyZb7U=Bucm@i$Lu@FoUEck^lR zGWNl^;?_?wZuUR=11Oc|M`5IncERp-21do?zILV5-BpTo`GJ6ef#)l?LuF0;#9lnW zz`%a~l#d?MRTY;c4mo@zsVQJeLR&0g~M1$s%m0-(~ zaA3BZ^nOoNk?WOQTy&Pm$Ldx8h^a09Ky>RhayfW)Is)Za2)VyUvC+1e|EjVedKT~j3?%L zWx9BEY(vFjW^ZE9F??m-qS!n4mFk;=c=%4o9+N%g7CCOs3{8W2W@4HyUM83`#6`0G z(C3~~=VO9#S`+MxA7JNQM7Zn2uO%BCnVBi9A?FD;s?IZ?rb;^EB|8Bg<5LSDyt|&T z5$qdha6bT{)FgE@+d}HfSdI&JZMOgIB6MB|_84s~8`8>XJw!v?QU+RU#(Mp*4+k7* z9AJC4TFCr*1&39+d1vYoGvY!qJH05s!hH)g z@e=~lmoG|X%j6wtA0+l@`ToJ!13Zi9a~mEa!RrxCICNS13j%lLcs+6&-8Zz`8sv!( zR-QV&2+#kzX?B_2@Juf`MX9}R-R4XUJyM1hcZZ;|U6j^BmYGv>Md5RyhdtbRxaGth+l(;tw>k#_gfd^9qI0Px^xuY&BUd)#1B`b?K67`DpzF?c_#Ed-z zEG{pH+~IVcQ*I$cJj|bhF@w%U3@ND;iZl-yr6i|wh4*<#e>3fg;im(+R_9XXWYGn{7M{RN&!3*cQGFkV;t>~({ zqHx&>?Noj4@8C!^Hx#vvYt1l4V--b{L#ZCGt4D2662epVS7-v4H>?U&(!tykJ&onj zc!;jsQF$v2h>5>zFx#`rU`wBKVPfa~>q!aSt{=lG48u zRbB-8k*=^&MvF=+doYanaAMmWz!6@x&2&yrC91*?`*VA`pGFGvh8_HW%kPxZD(~$b zNAUe>&<96GHw&2rzLdeZK!2(~Fw}yrUWR z*l~omcS;1q9xDZlek*2TprW`Kun>|MvRm+2ub(I_gv+OUW~2fp{$a`-c~5#9FDo@d zB*~2gG-C!&@jc1ABXvBWIOiky($k51fC)ny#UF3}spJa62XEn5pNb|k7)Oj(Jy{~- z`PZkJ=@E$1)uO>#h{*Ow*&j`mmRHD!rSt8SE{=yu0f!3l^2d{Sdey>_%1EpCU7+H~ zPAIDdxaKQgqcvzy;DyE!SJ#@0gddT-l>rB5??4Va|2L(y>^2S-D~!!tdUU#L?^uJ# zdtJ_vb|yBh@nfW^j{kp47v(-uV^6Ioqs!^`3`UERVk|Hbu4X*aZ2)OohXfre7vn%Y zZnymI- zNc(O4M_ro!e(D3`Fs(4+Twf+{U1*FBgK#kq4{W5gsNR_0V>?)k=sGYiXUjiz2#k1!*Psv1^ZoXGMnRaN$lSf`Ln6 z<1W@Bte{rO*R>D@AseOmvcy`Za{eLie=yd3=1^RqPU5Sl&W;m$b(s3^{6;eZm_!k5 zElw;!EyvSPCG3|stSiR+l+M|9sq@>!$UinoI^;z{?&z)8OA5Mu4QI`^YEDK}@CM3j zmq-l6X~pY6&>A^snzjv_Y&b>i9wY;8wgwQ_&??N0VXKW(ihO0W0sx%g;trORxQQD2 zWO*cHarvIt8}CLzL2VGm!<2Lhi>;eYC@NWLG$rjIrS!t10by(&)NQihUIVwQV<3m71w;iB>UL4w70 zQdZi5_0P2KN>Q@s;fP5w8PHrzjit;`;zOSYP^yAN8C<2<+nHqgQdErN9z48%gLR8= z&WXImSi5EyTwmYPn69GbNwpG6msf$rhb|8g%aW!5fpaiqA@6XGsojzOlkQ8&=qpTj z#qebIrz)Cv+-Ud8p3DmRt-Fy*NinaAQx@_Wa9zYIsxf1ELCK>-EjmZr3cj!hr+-^?Wo z7T;@S7bs`ln5&?XNc0YxHpa} z0!e$VBi!si`%p`nH@sMW!zdSI$iVr2xcm()a%O^yO`RG!*eez%f8-_Ng_g9&GX0zX zH}RgGUBE0f3e3>(2fs%>E$-)m_ja_>dJTm{ydWK0{@)@ulCd?>df#aY#WZCp>#RcI zo25(Sk-=BRDP4c+G~F1dh?qSJc8H|jyHx69a;08K(+gAEXEL|e(4QjDwh9px>S(tl zrvuf;L|3_WHA8)k@Gw)YVzq3a1AP%c|N7v03iy1|D^?P>j?VIud9v_tBA9Zrs8UGbZa&Dkm z-X$y+^A>boVWlg#Pc-E7ae1897W#2rKpZk4DVEb>RIx)lB`v;u8mZdj4KTm0K`~Hw_wA@H&jV%w`+uvCg zeO447-uul@{%h@X@)>8K|TwWt?k|r`92DBx4!s_J2!H@ zJv$qBJTA7UPN?<%%!Eg1ms&@KO@0jUJ$Ux_2E>JP2H zm>tSj*9u7jDxz4nK8k;NOn!JA#Y7wlLtFg=w?Xk5IyIn$xGcgt;le|QH@v5cI>$<` zltO%|{@SJh(A#VYT9Cj{h_38uT`b@rME&0wG<48kJrBi7HK<4cCq@?*k{G4W=T!8e z3)1}7ZKFIHFf1?;J5qe}8lY>h04Qv+-a%9oQLo^jXKOlTb^oFBNSsQb812g#$(%c3 zI)Dge6)AoA{CcK&##N+(nV{gaz;4eNVz7BU^17B`AH~vI?BnJ<<}BbJ|9t+y%eJsyQt*-;BQf z3k#39q=rs8=}~EQ=0GF>d4inHfoaW|2!p2>pJupNU#$cF>Z2xn6dz^m=Ygd9XtKuV z3DT5^cuSJ?(6dZEhQ6%|PR%2d8ND80sPdrHC zRv2kvJAhEfwW!kV7qui7G=E>ykR6)W#h7b2E91f5%K(LH3u<-$a3kLzZ7{Nw1>^NH zjRCLMANb8FA{C=>RFLRlY8L)duQWMh@vDvc32Bn?2Q-8ulM>FdMU@Mfo{9yxw)ZZ11Jd(O=Mdq}<6G~Q~H_4rgK z7pC(RtK5Ol+^7Rg(Q=A57{fPDwX1-<#2P16W#vzEGaIMQWm?St2fLQ7S=+2$x6^}K zy#@&2nx$Iq-C=C8n79b}jUp)nNaygez^o677rMD3hB31V&)Z!r~i ztCcDT1_pMl|JDJ32|BXy|Jh#k zg(GzqfeX0pokWt7Qp1kAybT->6ks@DrQG}|4!k)lpuNxVq|BD9{*SM_g8U!E+YzKC z>%hd!x^~grk5{Wd9_q^=R_%u~7%Ib8d#5--g())lKMAa+rxi-CkQuMuR3TSKUo&>! z&=XrSl&c1XT|Y}>l~6T0DA`9yuQSoVVHpZI6_lIZ}9+QjVz zNX*q*z|HC_7w<5oOqt4Au($oF^6bG63e#QyAI*KcffX2NymfyD9rXP66v`q}W4~_v zIKbDq;+C{Rgl<3id)Gi+II8~nP*|r7`ARK_h_7nzsu)>{V<0WNdJm9}Xfi%G3F93w$BnVv&rd2Vno05_ zgQ4e}Jxnea>UfXE{{EF<)rGJcs}lsT`6focgK+tI0n_K}omO!L(sLhj6mp5$WfN(2 zFBT!7yq`DY$zGnl@o^%=gnfjw7F@G)glQq=aLIHl`9NADYJ$?!%wNBRk zbzJ64^(~!nG}b}WIXVN9n@(a+iWTHV1CFJO#IJX*B6)lM!rHp@ip*hw_ZC0~5f3mCv4qt{G z7CXH-sVA6^UO@t&qj-}AhqwxdxN2xJ=M|HoelqcM}5JwvsYp_+e=$IplDxS zFiy|%`->8iIo1t{B@&BENf`kMYR4E|UGJGyz8H)e4n<%J$u|;$JwfXO;sXYGWctjP z8nP2BKG??OU4lPsCbRb>W}XgLoXTZ_ytvVAs1DA8(2rLHPDTl%?3G;$>tmocg16|a z5nW>Pam?{XNLo?C;e#l&?rSzMOx0@SF_68-XY9A0{-U=yEUTzcBIJstp=)>%P3ESk zmNAmeXY;GUj;sw*lYmcMtXh<3rR1V#BC`F(c@r|l8dv-*musZ0IWnuBNpsHl*#@U= z(xAVI#cPH>$wcRL&ikRW!3&$6jp^@@kgw2^0jFiNwZX!KKtuU<)^*HO>6ANK-;BL7B26u4I7xw*UNDwdY$ zb^FjNG9zLlLc>?hpYsJrIr8bh*3B?u?#oOhrBb&jq~D}tDg2IOp>XZ{tI{I^qH{vp zp~OiOYGD%kVa>t=k3$5ncTQ7&vy!*-j&)7p4PkXOM2U)TlP#TNy*klVWqrJ1N_??Y zdAL1LHqQcy_c2u_6Z`BvA8>j|N=uVE1>x-4REZ%1D)onwx}_a^Yt-_^Qr1y3l}9Dw z|GRCMJmtj;_}nd)SWtSBNH!VB|3BdXGO~IEi>S2@y%m=}{?1d){ePf=+KsuF31Pn- zZ_NMGl@_h8J{+)11K+yL9TBtCcKvh?o71KybDdB8moxEhN7G9rrQOi5#r&rF;h|iPe#mFL=e3o< z0ll4&YSz3n?yxEm=H-<&0ViSw#y@^*T%>mbI=&s+I5n;}X3JS92?@lCvzj_5Wf7*I zWL4+7_e`Vs6NZ91>2PF?h4xoZt)&_)S?{-7yVX$Q1U=?5|e>osq#A?V2~N1M5smCaS!=v z{-894m)89wQYqVT*D{zSQ%nzJ5BcaY%l*gHnffjz?|asz_qggG|E#lh*S`S)_gTX_ z$$J@oHTYG#T|ID)AivwvV2hB<<5}-CSAG8M4v+t;ZTiRse6Q}w*H6x7v2KB2ycoT< z+;r+_!J{pj9Tm@>vAEB#QiIk>_R*8XC$!w?LF}W}Re1L2;O`6r_|D|P!NFjSL4Vx_ zFTmZaqqEa7IR#0|iCTS4Jzp?DuN$$!qakAy-*?E>jPmv-hQC7Iz{u=J?F_eKkCQv= zm21k_OB_Cf@3^kur}}8lSlh(OY4x4jh&A;^1@wnEt}j4+Sw3aySn4Wl#!9;`HKd5^ z{l5RIB+YlkQA@w z?lvY2CR-+CkgdTNjxF=UL5sOOd(eqL!IL0%p^wFS*M>t*7;>0E^C;HWz!z9+Kz{T8 z@XWN@|1Y*Lvv?G$`2sIbBPB{}V{D`z&UQmBI(W7X8Ua)vw$Xfv0^sPIv{nN4!dvCU zqew{6s4Epi{v~Ft(N`>iS;*)_D;;H@s7iy6sB3EFa)%M9LhQZlWw5I1&zgCgpB92B zwjAV&v}I@ghAB3^H{88gq~@B9>=dBEpl{(&QEND|*Uo*+_52zFd&-_hNT;o%97uI- z1~1e>aDGmH^5c`W?=RZ_T4}#3A+KWn)8D-!2q}Unpd1$Ti#(6eU;XD#5x-?BLpEqE z5rqhvB(FUEyxM_f*dZ(`!z;sRL&Naj(uRgs`f96}=TDF#%JR%ZaqCAJ9HzzVt@YTZ zhna6vonQ%6+pTe|Tq7|in7BDr>hY(h%^Wpcp%Fj`_rOlg%gtwC4ndnOXvy*?t%?iJ ztfB33;FAGYp98!}=<+5sw`fZ$nUlZNWI@QZDLf zh{P^kks&faQe!k-HeST<99e*r48typP1Fs(XX6S4q-xop{dP>eMe zXqkoS=PCmmiv*;j%UG~!IHTX<2zYSjVlrit!%LVdRW``d356Y#8 z4)d$W{iVDbr$Ubv=0hJ2f09ALnhwX4%-_V91nZs_`Cy-bcS_p@+lIR=5Eh7=joP6c$h9ho&ZCPyAn{2>cpa4u0W8# z0HPs=xki}4LDHAnVTZ+1k?@ZBgh;@o+iw66loA~r95k@Do}4X|0@!>Xj>Hn3Z+2q) z`uYO=5o+q|`v(TVB;s1!ZV2nB;{i)p;o-1#)W`syqg`*?+qx%^D5F-nlk&um}p z1lz*%ZQ(z^VIx@-; zP*LdAB31XakWS5mi4%(+YIZ6vSc2q?K%g{n{4M7pSTW&u>dn1>^HK&FqMpqd^vZS} zE7Km~Sc+fFq_0?gViK9b=Xy`*kgH~`B5utbmTrSJq6?Wt6Sr;w%wnhbRoW;si&@D= zR$wIR3Kn|khgdWEDw~v`5GTJE()*}9?s_FW2w{`8b0h~K(3~ie>7Zt=_mXLjJKYF| zA%?eOnbeZ9?->7H!iPM41)l#yHdBJeL+hgabGaxHrKc!w`;5`{oCd;al|j9=(W?v4 z3!evcOeZV#WJF?7#1s_JQc_X?IzmWlD(2|usIjrJ-A*5PMn=ZBeqWLaz^bCf;Q$8U zyiUu_K4UrLKOcd9xmD1QHOsm0!`R2+#K|RCjNW21Ez^9Q>Km-=A0wjX=0Ycl6M{o% zE#CXa>|!A|(e^li(xTkg@d?G6iGSmkl!vkjidN&>;|MRTkoJmrw}O3h4}!2*?Cg{G zt{5qb=xeI%H+ZaOmm3!fn)u3Gxa{ciy~qtUeK!;k56OjIe_Bl$=!#GfJRYC9?fZ}A zFCtY^t=-k{)A`1pKKk$g%RTl}T+xeJAkNFnjIra?rxLx3H!&$Pjv9w+XpuD?E`1|*~{REH-czKkA(k~AmIP)331`wEDXDDk>15^uJy|iNqBOeOYk`=~D zkt?)>y7}eSEj{NP7WI@XPW~4D=0yzj&0PN@3`Y6|_aezHls2E!Hcd95C0y&`LpB!X zSPCcx_bl z;2VzV^Sl_k05E2KvzYEY8FG{5HodT6l~$RZ03shd+d&;!{8?9s*q&>KWyQj|@;S3? zy?u+Q-8C~6?B3Dn$vJzQL*!|V*?lwU(Ff$;&mhQqWovi4{Y$B>$>hDOqFELK>vxUJ%XkLXNhE$dxr$?KM|B1nZ^cIG>67V*oiZ}+F3nY@882(X!hCFr29Ex2doRs?hV79Fx$WFRz zofU1o*1gM@%yFOO1{rEvu@5GG$e&>v861i3>E1n4+*vOI zNOt}amzvQfCFFQK9s_wI;W1aAy>*BL)G2()2K~W^=LS+v)xpA|qDZ*7A7gK^a54-E z0v?*2oTDhkG2&git&tyZNGYq5y+eMun6Bho5`tUNDfz|h&Zj8F@FH{cuKVgD_UmoJ z$mrdvDzyT~tZ)Sj+mq`6JSE`!t9+;G$gB#)$0I9p2kMVP>#rUzmd4XaMOr^xLVjcS z;6esHsho!a+Q^LbS}nldLbsLJFNmF|%-{XIB9nN}#~|6tj!FjK;S-7@Zdg6fYBAO* z0_b-*oh?Rw3%aGHNlxQ!0PaMgT={>1Hq2~npHyh+$Tm-I ze{CKjG?j+O;!I3yJ+;&C`^)oSB5{ITZ4exNZ>12F4$&G2}tkI}8;KSAd>U*s#jBqHwb>FewadmbCe!v1BfOm<-pnxodI zOnWvIXw2!a`Z9-|d|5`yTs9ZB55}hA?;RP3*7_kH9;_dC-8;xqCP%fWLu{)yVFW`I zsjFGb&aX=C+d8>B*>J@6HrkP!N5qPVU_E9D&30xS<~0cC1#p)tRuPlFTHH%l*jq9s zt;`WU|J%qy5`9fkS1WdwCMH^P=XF;TVD22?vZ!! zVg@LjsiQ6uik4X7c%@nbFyYHSZYwNH>1~iM8VA?@;+8fzIvlcU}XWl zdY3m@B(%ZV(zH+HLh^Ag#hGnd&%GpvS6zW-OpS~z6zM%bEe0#x{;)u|uJrlnB%4Kd zy`n5@pnz_T$;0OtIJ@^$icFzY7v7`M%Z0@I>#HeFXG_w`wZWv+%ztYbvLii{>)<2r zk^NjzMyoEY*iBc)dlgkETTH=npHD=np5B9Dk!LA0n}0L=xtKg`Wv_EPdnQzSI00yur3ws8{@f_QqqB~vQt5XC*`^V#hV*K4rMz2*LXYuyHsPz=Et>~{YkcbRViJ_iH{u&w*Vwe|Lem! z0Bz^!`6bwY?9v8>?i}k=pGr@bQ!>@ZQ-gCI8T5~+GyO+@=)Yr)_hlFA1w8|7HlT!r zCm4bpKXbo!)r7OD3X!AZ_tD|`nlGg8$BpBaa;n}1n!4_akd?REljdlZy;I{WvShel z2FL3OQN2FLz(3aUVt=oN1ZFP%wQJZtdSR$gaUmhFA@33ex}11*M3>d8(BEp{_jfq` zt&`6Xd72KAh4E1XvNhRgzSaresPZRy;Iok6d@DVo$$+H+((Gq@H#KPVL~eCC%yr)3 zeD=y|XI$d&@a|5bPwAHU&rLCaRQTZ3R8^13#cHGH$t`ibgL1h>{OvS%-%O0xJ23*4 zld<@hzD4PuinnDfDeVajp{4`C>D783PC}A#;&SS^WVsnIqet8C zR&i{0vEXmLOOco#9|arsBM@)Q@E~WPm|!;(ZseEOT5<#pmTF@jL68Q;gsJ2hnlHQafT!+eNODRYX7kNd47?9hjbbsPzG}Bt zg6_$k;&bv9byi7rqJ)$=Ng-omAa_F0(iO4 zPopCv`T!{oW}9^kAR{9qfU>uI>F3E@S{#f@=D)8;&#w0(+K&!v`q_+w>V{#O%2yRj z`JkBz3=Z@+dCyteja=>YMdh~;%WwZgsH=81ybN+`O2uC7!?yyZ^&`+Q^oF=7!P}t+WVnpi8Ox^>l=GA^CNw!hNdhX)KxfG= z!>nJ(8lxEHvq;=-O<+9UJpU|a4)JmdL@Sg29qjuZJ8{Z;GMQdAH;^ZFOM{!TzD_5Q zL48301g_P!wCbHs6anki91iFOz*D(*9)yFU`fkg&P=L`1`sW5%cdnLo<lL-gk9UeCx54RnlqIGDDfN^o_%wOJYV4ZU^0%?!hh{ zvKXrSp~e=l=DMXsN1K1)4U_$9r8RMkT|UZ6Rolt1YBB!Wr50Z413D4~Y>(uMXQM{J zEy}Ke7i2FB4UE7Cy2Dg_FcoDg{gS$)rF@bM^Z7MTZeTlG2cI8r_vb6|-%xQvLSSJb z$;0VF|HMSZ{=P9IBV&u*4v4I*EI_FJ*El0BEv6L;sSny`s#>fbKf z=YfXeMhg^gEDrq)pF~U1&4%i)yxBx{*JxrlQw$*?k86E#E(?wFR^J!qW=fa*@ZuFJ za5Rt29k}}_BF1+iNnLDyc@@|Kt!_KYdeV>8*02KF9X$#_di?XhG#BN0|1}r?Wjq^C zssMV)!Zb#j8z5M|sy@A~=t8w}Q?RDfE}Qp!qy4Gy)c#_XWnywN z{NCaDa--dRCJ&s;<^0#LU)zaM|7r7Vf^)fE4s34n+MbuAk9Lw~^LV21@$oHI>4Zl| z%f&V={ALEQ(y^(i$_baM0hiH48VhWqWRPa%RJt<$ zOzt2cXDeg}*|drNYkhQ+#Ltkxb~=+wXBa&c40Feasbz_Y%E@(9-|HK?hnRR7ldRbW z%YD9IwEWNirjMKHxY+}?OP6SE@3#-06JdNeL#O#NJmXUjZ>{&rNvV(ToTPGFJuA)Y zk-7#Cp3Vp>9NVChoCv0Rui;A&zwRi>nyvRo^ls0}0>AG|x?kUo)}|$!4WIGD=UqnX zRycGg-cyaCk%44-u&jGF8%_uR3?~^tB7L(d<<#UUF7JPBTdJXSe9l^$8Ny62itU*9 zOrj5grL-`3=a9pROUbuv5j5zu)-9{`43q(gNGbwla$!o{Z>`^SzQe=4ohiPDjUwXT z@$3ErCHo28){c|O7EuyZ{A@|*k*Wz))|*!DSx1alNB}G;qvO$)2o{jy&(Fw-hUTuIcUERomppcn zqKu9`omFg`o2^PZ>$qVAz{iRl-1%(0i8S<#^tln1^g^od6Zu|iXLuQeHvGS6RfjMz zw08ILr`Gr6e%x!yf6T(u6AU01*OAcADjCUFP%i{P)IAr!xvyFH>Plx1vDnoxi|ASN z+rP;tZB6Vho8jxrn_%$$2HKE83TExyn1OIK;+cQ_A0@c)VRe94OV(EHvhokH(-H;P`WSBZm&?@GeS`I`7dgqdcT=YQYeeZ#j_PH|&p<)_5;9kDUoP}1{*h+L)udE~&3g2h+R4DD{`9>%#j zy4?uiIDxb5v0l=rJU8*&zPUkW&r1YiKK7y!P=K96pd8jlDra9wQg7ZKku`5&(Ln z!^Ip-Ad-L-2?~SB>;{3z7~*SEvb#pd!{=jt;p#VC)n;aA{xAfH3@6r|(nDE!;jO7X zEbbSGYUMGF!B9Iz4I4Ty4LxF?F7R{aGE=<@5L|1@G3%_gsW0J%;8Ua|K7%W$ykM_? z`Y|!SAUa!erNyZ~+D*w0-7F7JZKk7vFc$kA;!61ojc@hW>)Wz1ryZ1;v6pG}K4hNE zp=ev1%M~*d84cmMjo(n!dM(DrmaV1|x99uNfWE=zDqHsUm_8rUmFeDfBMF+Cfq`%7 zXJB%frhk*NJK%7EKREZp*^sA5<9EW1sl3L34`*gGFQjd-@9Pz;@F@cnRQ~VT4e@hC z01k56yf$+UnQ1tWC$W0-c{%5Vm76+t+-U^@N*s40i;F8PlH8EgC{t*>C%JeuTjgFI zC9<>p!tQ`gATlupJM%Tk#QC!Y&uYp&ebL&i{pVO!aTm0|7{>`bvdM8%WW7w7Pu z6t)aGCWfF_o|SQRVds4aBX2Ap^T#bT^n`q|7~fLXj1Eq0XBL>hWfpYbV4y@y8(aLp z^Ye4RP`5~oN;4d)bYR@Y8=)1>qM^i|Mcr~>3fE-|sWN=~7Obyc03l8t+#vY{h|B@! z=jR6j2s{0ec>E%gl3+SO4F|+j_yIc1Hie``&|esy+tINVYoVKgLlgF1oK;@LKh_Ct z#iUqVNHlTdtf5HYgC-;f##9sw@POnJEs9; z8A&Yo6XFr({Snvu>jx_0|MO2dv*uY+7O-)}|F#AA*I{)>d9p zGF+l}{E}Q|uHj_=e){BFi_w~NacszUPMi|g6Q>MLYK^Fs*=axGwXmX+dr0@Y0@_A9QyiR?Ub@frq0*;# zmr8_jVq80a%Lzo%5sR#qY?!K@?z@%Fr&BS(u}P^eQ&=O;*j%TQ{`*#07UE~uL=zdd z-|NI@j7Bc}$$DumF@9g!tZbxNkIyCs6(AYlDq1T-euiv^IEN`o%=@3h{ldSq%)l`H zUPKnm<$VASUG<*VWe3D`eoa$gv{OEID&GIn$W!oMBjN>Cw3 zI^wG92ZgYiA7G+qPpxjQqUKu|?GB#vnGq;Hpc4j2 z3wKsvB!aO{UPSu8C5>JuLo_@ya~pLrR1XbB=6ww|rR}93ES|Z~ZolH0_JfYF3ru>r zQ!d}H7N}qATdb%2c304+gl-}(F@w_|PIXcdqd#n*xt@+k4@KV-&$PnjAV_QSx+3&8 zOxJANM_;ixG1AunQcWk6MUa1fbrmi4$REX70ao6x|p z6(`H<6B_#M?rc?jyDtosmYJEDlJZ;JQ3iJzS&_^v7Y)c7(u!Kmt+nEOh3 zrgj~;BHCzZlzkOk9m(kw_E4RvWL-y#`EM1eFm;@b++@C1`s^7!*t z7GzS+XZjhM@OIp~ZlkWBFJkL@>$T&F_QNp;pxkI6OMFMl&_0ymBj|(kP~NGd=e7oS zBJFKzVY;|1Js{~PmdDmID$R0j78v#&Se?;&cq(g6B5rZCztVcqfh3sCj+0d=DIA>r z0aF;_Fz!qX-SaeKY(t9>nZ4Mr##ddYGnH~z#w)`9BLk|`s*{9;%<$TTmG4rncjqHr z`z2amj`I#<>l}jQ;Gcf+H~)i$8g6pLP^L<+n}bSa z3=MnSFn0kN)l=mq@MK;JPd?I%zm)SapbsW1Wbyc>=^+V<%`6rF_z4DVm)pW`f1;}Np&3oo*#lj> zg4NML+X1&sFPIl!+59#y;8lEwWB{(oUHbDA_<{I;1S588P^Y|q_{b=h`j#AG-&t~v zbQ9mY=KEpuK14KmzjFiL0tPz+QG`T9x~8V0fT=z$0|NmYTN1FYsWlpX0H04XGO~f{ zk6E*FxyI(z?(jIIl*BZ{3!KW|H_(6z{3OMK=bKZ94B&8SfzIs88;6>6q^Hv1pD@3=p);`F#(8Bp zbX^bp{26f?J<%K45nC^MI>=Q6Qj7^h@Fht$0Qb*F(~@yL_X}|~4H|2yB~ZIILge+8 z#Hk{&yKD8nkWG(j(hE!*36$`fym7%qmC+nae7LrAP-C!6TQ2H4?0Y8ZGafd^HzH0q zlwM%e9Tntn+s*vNOr1`*JlaiOP478%LBM$*Ul@*1FH3U!>^1~Tl_93c{aYbR9#goO zj9VbX1V{M51ss{HB?zw~RixExSJ6oFjrso5c&=s=Gm)JP)sgpF6x?jabVU$BFJl6$ zt0wrcw_f0{3#*Vn17~K=D~-0}l;*3=Od#xOu%gjdZ^%HI`ek$V4&@gjm{FcsR)Z}# zwuf=%1Vdk|1kp+>2d%z05BogX>x=c;0g|7l9#Wxt#V0VRTB}iIk-;JylOa8 zSu@La&FS;k!-Eh=pDH+P9?IUW-MYiI`pQ^pFruMFdA)g-T2orEG&wkeYkCETTcf|u z;^;H=c6UEQi{Ty|PNhPHz8RZ2uo$h22v_8OW@_=0Y^X0!>=>({h~SHcRMgUuKtc{JEznWwksI)sc?jKt>g07}IX}Tyg$L)%Jh2@2#(q z@*n>v?Z24a&Tr!=Sx`!tPEU}XU;p+)B~{z^k62h(Mv-qj(UMbmA_fd#w@{grkqgc* zw-6jwmeB-j?&MjMFX@G|iP-u+b9EDsw8{Fn%AoIOJ|XKEW|n=t*;daH;3R6)Wf&6u zUgC{})Ly?Xv_iDp{`gvQs<7T;e$t>SRAp-s?*}bgNqPyQ*`*o<`D1o2s;9SEq#ZH1 z(&FkDO75xJbPn=dUtzrYAcHkFo+-b&=Wz?g@*0|1nf#9Q4rqKqqJL`CqFygvkSXQ+XFvDGV@R6HmBW&$ z%_3+8t3w>Ms*#w7pDGMaJ~E>i($)vo_-SlUy-m36{Pf0*mC?qHtTN>mJL&LRkH| z+oR*sY^*zqQ3{6xW-Pri1w~Fb0L;=TV_@w)A_e^O?D2Dsa95|3E^bR5!Z7S?he)gIPFz4`BK9$FPsP;!|9jk?dReR) zy3j+AI%MXT0N8TVNaymEynY*F74J4Qf6NhP-QBgv;<)@u@y^al>icP0UNLc*ZF?*G zUI8qY^}#9IP+$Hpg!HW~f|`}lbra2njprp1FS)E=rczVJN)^DJJ?_KV5tf7-+Oa4< z-w@2~fOGSaE^~lg^pxltGZ$c0yS#ounsGP|C|zgWrCnhWQdNKjCwB!Mu;7#PX@Gp{#HbE1Mi>msRJH;!O`kf2e+kIm{K3JiOod$qHit| zU2rTx50RQ73jSbz{}U2N2i_OY`WVP?|FGKXK>Hs75AL`nfO0z=6cp4sLHk^O2e7}t zq0{@%%qV~;RcMWdqBA5inofzwB{k9ff&vHxVd8S_ZVbP1$@#}0FMFPnd^}=$$ha;m z&U_q$wp3Uh^lzz>ZfZmETWK>gpaO^PNUc_X2tw=lv@~!W@xah%*qN6r zf&$#Qzun7^*0}$`+-L5_;2*d=uWdm1aKzL^*7n&L@0VItztg`eN)q+EZ*PMFp(eaE z!x<{my~!!!JbA-29S0ARoY2KdfHYUIHe3jVQv^#WCNoLIvY*bm6nf~I;!#fk`lZ}@ z;~*4dM4RnZOthDK_@TW5QH(IO^hEY*Kc-}$qbk#n1~;v6EEBTiqNcgG{gB}6{d?t&L8Fr{7lHfYpj3q!;=Y!Rnt&VnI++i? zDwSA9>wnEyO?US%RQxfl_A`*uulNXLj^;Gn@~vM#nocPXy133?;Ozb%HPmw3?S{Zu z>-ea)^mkm2AWc?8^c{aO=Qw0KXc1HH2>$IQS-wwZ9JVx7oNWo#cub6;9P{NdRwlx$ zKHxLeay}{UPQJ~@rJ?DAy+=S_;tdim_O}Cmw&~AxBqU|fRYAsS$(#~jhXPotrUs6; zt+Xa>O}GS!TS>B1i838`AsWKQv8ANgY<`c#BL8`k*W##Ru$;m*OlDNuCl3rAS6fV& z_}zS`R24>muT$O0fGJv+*{I}Aw7s2MggU+{X*{DH{xI9;eLhh2vJYKF+CdvtI7GWzGI!F!4q|3 z_G)UPDzf-n2<Y7I_Od|Ng4C|ddiZpk*dzwKxHqV%09)}l9FqfB|=~h5S0iL}y*1mHY?l^ac zqU_`(p0-&aKtha;is}UFdDE3fI*`7;KL3D#EVBsx3lyR5rh&1U{4=CUHC*eylsFA$19+~mI1Nb;+!46*O;Y5Q6( zmos8arYz*KYX~t7JBPbRcTL3|8BQlY?|zL(g6_N;6PzmXhu5h86IeLBBQ{0tB=XoU zE+|^;qR`nZG@Pxvt)i9>Bef@H^%@H`?Lrcvt1y<@x3776_ z2OT30g*pJP3h~2(WOG^5WMuP(beIq=+_IvBnMikHGO^~Pt%Njg73uw<75(2CEkE(D zpXmt-Yj(1&%Q-a#P$`fjWe(z(WcGr{!Do1(m_{}jb0vLj(;+~p(fGvhzDw&G6H2z|D0!ZO=~&F%l99@4`vTk3s{n6^ zk5ktDundeOx(Y^7LzAq+rq^|maLnyC$NU`}OY;FQPf@C|sZhm+9-X{)+plZw*9?uH zaDS9b?YZFg+}O>78`(bleQtb7vY`9@MM*tMTr3E^^4-Z^Yc_^vaWN>>4_``xV-Td+ z>S}?8LoC#(tY5Oc91J}J-_KS7bhDq;AVFU-2i&lZVzKTWCoS0!?yax8`-DAJNR)@g zqBlr(c7@NpdUGgNPVbo@w?4-V64Wllw<+NR)awDbsH% zNtETAgzc$IGP^=1^#);T#nY3^Y;<(=*gs##sTWU@ZjFb!ne~p9N*}-UU>Wv`z~=Gb zybCH`d#4UQY2!hFtNgCf@zz~moxTN`ar`4HMMAtzsb6r{Q)>R+)7lU9@J3|6;x270 zetsA*{{g-}D7ze=r-Brc-|F4Po;Erk_eY{Qsy<}FoPs;*$_;!`bDp3pRp+t@n`(4B zlcwZ83DQOnifw~dv0aT%Mi$R(bWi5*D99mKjn;!QUlP3CE6LwBSzh*`%Tkn0)$VMB zeL_i)EQicT?Jh#F}v}Dyhno92JDP(yuwzFP?!NvLCDhe&ij6KKz`F<=gN_^7S3OX5;`&2( z&48R^PH5A~5dQP>mkrc~q{1eS$K7z)$fl&$G*>^hslRO~Yn`$uG_Ua29fwkEV2RAB z19Npz3f#!zCNX^uSk7oE7m5}cC?cYeKZEq=#}C!Fq1Itjdre^uTtl~>T~{mF+0&^< zUm(9i8e6(azL+PB2W?20-t}5MDK_=Yj7gd-*`nFsy(L$qY_9OzX6|2|j(nS}B**{q zzF~v1eyx91@A$0{pS=sopM~r{A~49>(ExCQ{+|#S!JJ7>IzvOlT}h0v-`t*0mComD z3B~<&=JT{HEHqQYn*cE@UoZsaWTDE>$HzyR{U5fp3+l;A6CyxbY^|!$BD_!b0ED0~ zFE1)BPE_37+=5F=Ig>U(t{M=G7_89&4ue5!K1ZoQj%-%PZY@`&AT1%5hma>1#Fyn_ z6is*-1i980Xyd)_>>{iN2x@_4_Oa3`+)38hK784*{}&#-sGud2YjUF=V8UEc`QI|& z#lHZgl-7HCCN&`%F-nKW#NMEX*;--kSEuKzxi^gQ9&{dg3i9Z_yfr>An-3@^Mci!q z(%-#p39-z%n_r4LXtU);C)<4v36&nuXrrN_+1wr}UUkT6#=fJhVQ-~U1N)D)lLtbF zW{dj4)$sf|9mU(1jCu!ef`7R3(t6}~qeq*O=aeN}9pQu1G3Yql2e;rP$%vuXP&)0` zSYCU=XkJ2Njs{QPyVydqpIL@xt3H!qjk+WeOh#jE`=;w6?yZq_ zY005XjL2mCo~9-c&tFh*%B|Lfydj#!O&d2H5aIHiJ7RfLFULLY7nVz#y?T`J1fSl3i12=oXW3`9uOxeXi!c3ZWt|86 z>jL+}0WMkkKA)`B3*aOJB0(UWI;fz4#PMimFolzovrw~z8Hl24Y-y1%Q7UVNd^79} zdg*5-_Gb1CQ%-;9NxqwR=@ag&KFv27L-fDbyqV(vX0hGb)wKS7!;E)yXi<|L)?{~V zN7{qT+7$e!g8Mi=H+oEy^EEiS;#0NVI_RCH_ITH27Het-Zvo)1dxUKD5F!+0>8LDb zA{FDnetc=M$`tQd;j6xY@HXUZHl51dNmd49Wi>|{8+Xu77*&=r{|?6^sjP>~9KrQ` zU&CX)G`R5F&ALS|0I?(GBe_Tr24OvAL*RM1fw7L9|6*mGl=5amLt{K4M%nJl$!Q|% z-#AY*Z30eay#W6A!E70X(ZDunLvVI;x6|FFpCv|bHcd(BbHJHc74L=IW z=?`?Q{>BV;(rGQkF?RiJL<(=;q-1}s99R#zyJ6%jj?GH+#o$6TFJ=zWTeVhgiX+lB zL0rMMq-B}oFS8DIoZS;BYZG{LN)+CYM?}|v4vg+YQ&q^-J!d0absu|VJ$7aeHxmr2 zHbO%~>aUlAi`VdA7m1}MS59kQTXWf$a^$id8H}6aVijER`KeJFN=IAYGsu(L)PK%B zi4cD|%q~=0%B#u%(2taIwdN}poL>hir1sk17RYP7mHqxc<{lV$Y2HD$TfwR%qh|u~ ztO~nN4oQt^JlDmf*Zs|SUtAUXhDJc@+R=BDy}JWS3%nZs;pN*>Ya<|fGPwzXy>pMx zWtnsUa-Xi}4HyWLiuC$S269O-VPPyWOxaqAQ)S6AU=#PGZ#L)3&dzoLY?4DzsQB8S zA%=zgD|Oy9fY?2u%0Q~gHVg!GbWsO~8;Wybdd6M>utU?s148*!KKw_wUFN%UaUC-X zFiZ#_dMnGLVdKfG2aBt>NFGpfkS4c6JOpnwItCF_doh&g`At}&iIjAvG{K4FnaM8m z?%hOf8?1*PHAY=KAk_B05j=k(X9xj-DVcKEK;C_^r;c zLC31N242rre?e$}PHiR&IhZxV5)Mx6%_EghNZ&^J-a!(TCZ1!{e!-;4t(v-8oYOM? z*uzDba60(QQGK!5irJGQ-B4^_CO>Wd(+_P;QMmWBQuzj>sb)=!q(#WKuucDOD-xa7 zFu>6K;-{LoYy6O>agEnBlpe=Ymb=PdCIK%y8Tqo*n(!A)X!eIG{kY#i^DUzCifnm{ z`1Rg;u=aWp-v4Y5ocqdhxIwuMt;&Gl*yt|*Br1y0l07-cG{QNn{1$!LYv@f=dc-2A zi7@7Bni|2nk={j=Q=OTLq@G_CHq10!yC*!=M{#c{3dZ7j`|}gcT2J}uI)h^*?rz3e z2HrIb>^W<=?69>;n=8d-NZ_`u{w71mc#R|Jk~Kh=yx?}}rs>(wr?ME5Qa6dUubb1< zSB?0oSNmC1Wg=x%2u6D3I`;9>a%YAAypgNtCAKsHU%I5I^XHb#a6pg-H+_<6l(%2&b5&*Mi zsW#oC1%Kg8jGz1|trJ`$Nc3(#9AI!c++dqTLoeel- zHxwV%x*>1-0nEYnwYgjcOR0?U;GCoWB;WIw&g7|6@X?k(LYwcm9QhItW7^ZdYuDbgMg72H9oq)$ z<5A>etupu_Cx1vDQH_O>oBQ*WpSG?^Bk5e;4}W{Z)j)M^LnU(GvextwbPAW9&a>9TH< z{X>;)-)H!^O%8n1ir|f4*BDbgd$vgYno%>d7I{uza{gEG(#iFk3G5 zygXh%zFdz(*N)G8#%shx*D){>9~7fPbI)b1)Vx2Awnu^KcvNgbI~r0N zs?F^_>}#Df)~H1G}~)A{Lf}jLd}m zv3ea4N~sXhi&@sEjNr$5e3rNN`efwQEND_mtH3 zSU~USU|Af%bhai&MMVY9hQ3%b`J4DafB%i6BehIV3hg^<#NU=q zx>%_sdOJk&w@27iKIfu1uUI;Km{@?A+?Dfz@!;L#pF4G+;!peK=O>F4V7XimdKe@+ z98Yy?_58HYHpyvR6JX)+QsqJ2vNKn@a08ZhIz_W^ODR?5Fduc2!mT_VtnBgzTmS*E zf9>k+6|`0bhCooQJcBDqP>Ll-rtCRHM+#qp&NR_4ZDrgL(`vtnC5cK$Bhu0{@#gfv zzyAcS`L!xjEXIWYSDz8uX>51-&+rWT5~MQnPu1p|!oeA~b@~D?)bi>!kY(+Muasdd<=Znr4c&lo;5oOPRj6Oj{kVAgYoC6G-kxibgsp8S7TwF{$Q)g#QJ3Qb3n#Ce6 zbQ+XRT5GXLKfn13t&7k{GKw;n$D&@C=Qd@bTaFqhw=DY_~2|lRS*!M~0kw(^p1`U!p`7~^)Fn4kR1G|qTPtm^8ng03yU~+Bc;bW|2-N9;6RxmI zYaFiKT-13qTm8*O?+#SVc`MK~wY(tnONs9lbC3JeLcg$oUI^ZfOGmDQjO)1oS#Zb? zY4d0MZ|fvw@HLTx2!E)oeEGNuJJrF+#U1}-xMi67m1%rv20)U1r|YPLL4ZnEB-eRZ zr6(RO>&Xlze{0tl+#YKOIk2+Wy_RuipCt`AT0+T>SdB1DVRCR%yu6A=^wZEQ4D>tj z1~k{|KS)VQ#~%%$@Yr0@M^Oj~A!T-qYtOx+@{xh1e5h2WCRnA{`_Y!Kt*v2kIE4aM z28d{AA`%kc0EtmzN(zA}0^n5u$j*U!^5XIma4-P6^_x^-rOg?8(30|RMqM{!537=V z^i^HuiEzF|qmdwri@qZn@SPA0d|%b_bhamhi*A>8XxMo9^O(!XxXg*+mTvL|;~{9H z`OV!Lp8V6+IpDE0!Zqv=X$waS&-)OW9?YLuG9vo2IL}8dMN2$LNNi8A7DLli=h2yT zC&MxlE3IHJyZ2}tA1!bWzR}gx7dXrkFYI6MsVHV+Qrs0KF}k7HLzM12We4MrA)Bz2 zQLWw*k)X+%&Pd%Yg&V)DNFUxAG7e&hV`&yoHwq1|tovC&IOd!`trqrsbd^Tx7;)0) zDU8;SJUW8oy5;e_MPn^h+l*rn!)A0ngs*=uAd}if*TlYrV%AQXGppNiW?nYDAOH4TGjj{#D2u=Y`J(qd)JwsIBQ6EvoXOXcll1VRi zrUZ#HP2kWTLQ`ydI0?UnuH-wm3L~4iE8w~9Inm_2Au_aI5^Dm5HnND@_*?aPa(gE& z4voZiYLgYxt@>Meyt3b8@y!7tClk;}P zEtr!HZTsH$T^Tv^dk6j>JzR`xP9wxL=ryaK-+fL9WOhefIM%TH`S+ zAPX5Vo#X@zFcy}V^^J^vx3zJRNT>GzYBoTV4K(DUzzVCT+}_;m1PTxUV*{s9E~h+^ z|GoyPCKY;@wKiAppOJQVE}{VpwSoanr)-PU=?KZSYQ~iD3&(Z~`}R5z4s&r~1CV|e zT3s1nFquc@tALMqd3njo&c4Ud4lL73n@v8zkro^rJSjvdXRsbHsGTumB9A*N5{%BZ zfR22;maK9<*Lrz<%{aCvO&vafW>J^fetc75r#a~%p>n^}kzg@HV%X4qFs!aEb*cL2 zotXr_8b~6i>y^AAKp}#dqVWN;SKg35FsaQ^B@yIK>0~NWHH%wj^-8{wdxjJ$5m?KI zvj$xBJ;xxh&+3R1h3Kp8?Gi;#Fc)t01aZwL0LQ{4Y;zp%3lpr--xJ)2*YE=c{IBoG z)<=j${{p%ORkvdtWsBYi9tA@m@xIcC&M8H+r8pUu_07z;QXEH5_K3$DqEKrL zY<34iBlUY{sU`sYm>)Yg`7Fo90O0ZQ=svzVv4(0w>S*H))Be!Y#;K;;*McI|8YA6) z0Q3npzGZV&l8aXFKunXm#}LZ+ptF40beu3@{7C&#D!D$fj$S7OTdUg1t^E8kO;VMc zz8UYcH2LvA%^sP*uP*@G3ZfUASAZ6S(-D>Wm8iYi4Ebv^!9Ul^%Iq090RG@su8y6! z{Ofp~$JCIG+*FSa8c>SDVRTQk&AiI4nT%#P;>CWPl0_K#1((0Yg_LiC}mw#o#-5A zxW2axq%p*ll%#n?S!bjl@@(XHgakj8_6#RwLbAQfOcjPKy<*CHtRdxGp^HXI>)3G_ z3OW17PGOBQd;H@=)lJk1qb+3-52FHJcjcOk2b%*$g&f~ZmD8xhT3JzCLog@d&=(gI zfF%i-za%`5DF~W!xwB|p(*LlxU;Xh^YNyvVXFJ0HLP(HGj=?D$E2My3AI9IEeogof zV~vMz=3`e-s$pcx&5prCB$m(t5LJn@X%G?)Xti0&-r(KgheAmv3?=e_l)90N&F<@k z6ue%Fx&HBSIGzsh8Jik`y!!rvcI~HT@b*|b?%q}_m?D`e6nTDriBnGWY7WRL*lX2S zdR7%QT^)k}`&n3tRriFO$=kYAG)-9j3cA!0i{QAS+cd;OmF3Uw_K2mLW|ODaek(EW zVZ^&f%)}0bQiJ$?XzB~{`I`o?#xwDR?;@zzBr(d!hn;t^H`^;qh+-_-%B7N_Rpg3( zQZZgz6`?~oMB$$D%kuNXLHNYK(ULi~I35Aln>3==ZhKYr{5!8^K0e$JR4o$agZ=&NzoO6o_PR5EtP-}(bzerCDEzE`;&yeoRrH`jY)4T~dWMe7 z@_#R`~B{uW0(Y|H_FF92O>yjcB74bkLE4?AI}@^e=Xx=LeT?MWMmwZ8sNgsmt!xYWsLsuN|XX=~PC`MR@SS7_uIf9}a* z_mCZ*iNU5-zGBopV%Srw(G@kARvG1kklJ=D&~43SRm?Di^|+! z9nuykp?GSW#|7Q6if2Mz7IdSADJQ&mpo|jCmnZq4VV8)+v7;#8Z%*KV)y)L~X(sn? z^p@BZ1Py4R(}%dkw>DDpJiDU}I=NwQf9*+UV?DsT6xb6BKpQ97?`nflygy=pIfJ0ljRul{;xo>Xgov1u4;IUV zX;dnALeHx^7pc`0gMD48WWbfTy|5JV)q-m5mHegsfU#YqQ#zutobBmugu79JJMtI| zrmWOG8_8I{uRV2zVqB)WCA7_5K)2K>sG2Gp~^G{EL+FmdRh(dLF+ zr%O=zW^?gG;BYzbR=54iF0?(XipI`R7*PtK zLPzaYEVI#4`sqeq#=D+8;(4S_m6vcxGm@F@a(w?4jV;n~`E07!8m>djF5lGNTDFZE z*oY7SzU@!~O@vTR=ik3S><5zz4J4K9h{@OxV;i{GKtDXJCMPF>!~JunsE9}=APshf zt0Mb)-Z&IT0hqnTo4eZC(F3EN@fY<$DmK?B!GR3f9HGsvt?Y(Uz_G95Zlf79mD?Wf zcn>f1Z~=t>r?JLw{9=u0#4wULPe#g+KcDWUV%^O^Xt8%G5&{;VzlOY_q4u9>vkT=D zo5Zqi;gagy<&OMKF++w?fxp9?cbFy30gr6DUG{oYP|Os5G>)JrUToO(bILL4@L-&nstyDo^s%%;=}`H$grt+`OS6scyFm z*9(UwXIZrA7MwhZm`2Y{>l3wmqRd8&3T}e0S`&VeO0Pke3{`p@|c*^XV(N8KAP@g#S&7bQZzuR)4RN!qTe50<^AsU z>GS6gQde&;n7zF{q39OC)gP#qP*6Yu9vqPF2Rv0RJ;wMip6%(P@0f#K+@Ky$BAo+W zD1p^XwheR2v(&n)4%F_gTy{R!OC zV6|~?L2M@~)rWT%)c;{TXB~%zxI-B^Dg}7=T0I^g&)zGDNK}LNdVpW!5D*X!mK$ic zfxTcPi2+!c@)cTKlvGqf!NK^zQ~VEA=k|8@zp73l?r20NLtz{OLxb>HrSmGL!?uEY zCAJ3!qi)E)gH>g6xN{PpBJ}*EreHkkQIg8?M}G|hTB`Y=By|qD>mmg4V(-@UX3lny&cUVQMZ!pqECRPv%i<_tNsrXkA4);i0n;#sIc^U?`M;Ze?>(7tpt0T{M z-|`?}3j}RF?G4C#u(U>6SCt$v=i%XO-!GuSj}1;r5q9yn9wHfu1&08taW6ssVw@1dYk1o1IY=XstbeKsj3EG7 ziS>mT=Xl%S77y*n>u0ta)%g~eYU`ZZ;pL?3S=lFN9I zKbU{!$tybI_C=+xmb6^F0(gQ&@pWU=Cw3tq?|rH$Qw}0T@dTq=7{@$Tql~Vt^tO~T zv_hB}s^(Hq^MCXP9t$T;HwT|StTzOTLJG&lE z71XG&CovqhP|`q&Is7;}fge6Afzd$%bA&AS6);DdW-GZ%7EnI`Eo!K8onsl9ljqNZ7F4u<%@rIpAmUNO_7XQ*eTt$9xk zm$D6-x4d9U4^T5nmN>U%`Jz4Z0~IH!$GAP*g?0%W{NNx(Oka|rIP2+bhHKc7&Xq1U zij>+wIGv-3bMr zjfgj}oiSx4Lh$%Kd(=m+a00&R2=i{B?7_;C6x(7NF@9;!Sfy%T#ced`425Up-8WG! zW|7GnBu@dvk<9BBqP`S~i6mgtkdOq73iT?!c$Usq(4~AgM(H=A%q%j2AB$BX<;Stk zlmFxX3p#<+Tf!N%Kt_x*-{#t#p#`u!CVPs^4mZ2tZ@Wq_)z3MlzaEvTcB!~ez+dRp>Pwo#2yKsFF(xg|p zo~x_)*4FTCRL1=G=7R?TX6%<3p7=X`w~pUQ$7v^&2OIlIkI(hp30Gb`yXqd(17Ag> zZ)lDXzAa@uVab}2Zk_P5MIflO+3bdObz>8lPCkl<7qlL2R*oFE0|2@pqt{TkqBN{8OGhh9sR#Y zukL>^(|o39nTN?9Cnq7cz!v8E{FA<` zD7({Mz*JyXcbS#(giZP?EVHj}A3y%~_6I{p^b8V}u}UH@S4^=AW;?98{DLm^zit&xj*lNVHICEbN4WFFRnfRH-WydAaTA74_RzU&&=dcQ5p%q6AAB~CIqub7)%Ji&E)iWQ=K^#?EFof+7e!6I)tv?!&ub$TC?Y1FUa=U#2F15tPtScX&!J4+P5 z8+JSd&#GHb*E>_}y|seRi`J-c)rCvjMPi^K2kc6={I{z zwa$T12rHXCDfaN*@WX#0zAF|6x^mZ-2RaI+Qk{*zzNMI`Bh`5!N!*_7-a?xBUSP(2 z;5Yb;j5ob-iFQ$3JUD#Q#$+iR@m&{_pGPRre3t@z@M#NJkcvbZ}k;OV(V+LnD`is(%?$PW*&K)1L z5=<5BF4P+)3(N+`vXUT0%*@3wx^gb)7%l5Sina|UJ*k8CL9 zI!b|Q-M9M5H-o|_43n4Emj)e@qR(qZ*ZSa%`LSJj1N&6MXd!pTJAC(kM_=A}_zWw~Z52#WB=b?^{cX9UO0efmU!8kV*XPfdVnlryIP$>S$20sr(`)MMBxEMa^* z@DrTlvk02|13Z#U#t68oo%}EJ&O+=Cgy{}c!8`>iY)&Dw$A}9Ga$ne=!?@FCI`pUO zBHxZZIs-oA#?(7t9G|i1c1F2M>%si3IMFv#c#l?9=YMFICtu%3Rxi5o6w42fy}ipa z*y~QXF%YS~%GJI8S#0X#V>ClwBE2g*t;*7s0V>s$n$S*%pdeT@Q3&}~PHwUQ@;uxz zrLzk7f-(26(>9<1=b%8@f%Ul68a&gM{AzvK7`+aRvYaEeOJ0MpfICfxYZ6Z`CH zQc*}n`V?s(Xgwr$&X z#kTFFV%xTDt71FpQ}xEzJzn?w)Bo-m_uezk+57CZ_gZtVIoY8L(ijKy*A~-Ri#%h~ zIbop-Mq6_Jg2hP>3qZu7>AhKlG&pm1OjW!piE8EM=4jepnR=CiG!*?1n_~G&wBG_nZ@7uH!Yts%?m5~^ zx`?=$h(daC?!C3y_q_*-Jhag(>Q~Gc)y6Yw&DZ8mEA-J5fD&sA7R#{oQ-=#5_%n$+i#ch<` z@z1RpY(;DLF~dWZ6?RW@BsA?;hXF&<+z}$SX&1R=;oh2HQkx5b<|0s#S=kOd)#Uc5 zs-q}d+cB?M3j;G>p%8+1pU*~U8BA@(O4GlPbUSS&l_TiQKvL8@&km&(zq!SG-;?Uc zdSY;!u!P=^DkCIT`E82V89B|rhD#Vp1e9#h61bO{qTJhG;^>nrQ3Va)65&*v($O*T zx!PobxxOzZ{cnU&`<$WS6{sZpUcPGOn=ZB<6sIDXo0|iw#j%72s!*rYuPnt1E0v zd}@no*L8+kE6zP0 zdsW+XbjNeh*uWP%#K8=8Stj?X_ac$b)QSjHQQ_(Vivr#G{u{5eK1Ehg%WSa_nZjZN zt>>v1 zr39PPDJsAswoCKc%CI@= zK5-)<2umG?b(A*6S@`=IyLWuI5DcjKlEOpa3v1;6qYjV;&O?$vsn1E>gmSWMFnaV? zb+C2=>z_#b#fPEFQo+^$@4C^4p@7XB{K5HrcBOait~h)VP94jyj(o1#+qW%`x_O1M z!`NTErpL))1UrV;gTXzUri;e7b)x=zwo{s2hh+XI~B@Q4V8MNt4p8YvJ@ za(TSO13m_zX5u1Z1Mf007o?gkw+xM~_J=S4xgydl%;4@XHl=|A=2EROtYj)9*_18BY&x6$cW`js z*T*YB%TnLkItnN?-QVA*bGpI7)4i4!=P=ps(xf#VP#xdCx{8UxUd3-(iR(SDF7Md;6z2OJn`|-1rrPF21`4G-SP2p zH%hh?kOWK}15Cq=)fLDU8vrD2EbBQowvmaAj)CE?-vAg`(3m6oFM6O@sV3ul$vk}W zIbOY%+A~Dd3Oq!ql!%HdqOOh+Ak&-OVYrj1|NifI+7NS(=(a`^(*IN3h?3vlp8sA! zZ0=&SM*&Jhr`I)cZY`qs*XGR%xT&V*<{YI`I$GK;pj@dQ8_OU&Ou^^68i(N7$3O~D zlvD$}r=>yiSaksGn2P1?xIg>!;n z0F3(g5#TuZngB!IV_t1KOAM%ET+X?D`SPX3@kA&Do(KYu{NGV(6##9pNEd&W3(7Tw|pd?{+nh>bN-_e96p19)qm_-<&sED43b zPqkt2Uw11aEj2S`R-bayW-rOh>ISWpwj{hj1+7d)A0z-SoF-H>ohI(^W&BTgSuQNKAy@-B+ zA*dP1UD|srzhwKj#M47j2!t|~|3WLv#$)X!;Ipz)cI+omX-4VQ${T)6l4=6)FtAkI zMgf)B-|CH4nJ>Ui<`))TlM3n%Z1K_`2#%!|W|K;{Q!AFzdUbECIhU>N7SVA%I>>*O zWzlyD2b3>ZcG{|cf-fAGxYD8V#ZW(2KK))XqY?eEZv&6X)`6gqm6hv1%ADr z{v%?=HKnVSOI{v0zFo@4M2hcoz9REA?+JNEP7+*v(^3yXsKGW1s; z?~K@pD_#>@nAP+gsN)q5Js3W=ZW^f2yi2(WI#>L)s}0`Q?x5wpJ@5b4Tmf1g$={`L zZD4FXcr=|?OGJtm5|WXj*>RuqkJkW*#m|w0*Rx*~ahj^32`XLR2@DOjQ&XX{^!)g4 zauDR%28-iQZ6xsm9?$X4l+y}z)L=?5t5&cW&sd@!o_sx?{IqXY&>mtipiTGv;Zq>vMwv9cV&Fc)H>|zkp--N9($%G zM{zK$57k?7qHRE8r4fZR^haW)^wQK}(Zv&G7Zk|HGyTh95JFa^$ls{4y$`G|YGCgX z5Ee!`as)Pth_FV|mv=CXumYyh1&ZXr_)oW;t%Q3cdjtLD#=jAj1+sGQ5b7bou^0`ve`!#m} zkoe)Bv<+y^E-fuhwYlCLy1hyBya_lsI2ifj|C0r#XTJQ00?|q~QK|Wy&jv(X zaMNTEHD$OI5T+})SCI77#Xr zJ6C*#bvQlypU=rC%9S8vLH$tLu8pAZaCx*7|Jg~>NCH^Y-^jXf(SV!EWIhl}Bu?** z@|SGzO>Qcmkl!r}0V_6td!rZeJw%*Xkb>ui3BA6r9c*~=+&(wTE-Mdg62JAXfAwdC zegb*?l;>oJAMEi$54~qvU*0K4s=p<#p;$5A8}4;npNQ~W@pt(3R{EXY?ArrHQ}B5D zI4xW@*=>~yOlH$oRvW??YM)87S^PrK4icc=819{85a!^r1#)dfg**My|t4Q+co} zLyGSgsH%ygfb5{)`2H$*ANNSBYrGnf?IE96sv{YIc_)QHV#{@glQlkg3^zrXGCtP8 zCNO2+zXi*FDt$cam132|5&OlD33d=+B%4l?!;h{9mA|~COL1W|nCe%Ds(|uvor&uC z@BSMET|f6V@C>mlu>L7z4Wv z^p}^$zUu{>6{V_xCH=Md?$-ePzuT<8?n0_E+cdgENECxQ4Iw7`#BMN; zNQ(z_kWV`ULVS8T!S!O;%{R=<hF{3-BqwWpuC>UrE?t{e)2P2Y{TkhCZ098pR_=g zL1+3k647zuT#KtRIuNb%*$=e(S{KCLYrW?O%@+_T4<0?cD7kcKtp1j?t-rjtz(gWD zH{;h5<-EcVl2exZ91qdjLvI&7m4N9q7P^*aE+uFfd|VS+ahiNx!eSYeJ+m^Wyv>Ks z>XJq-VdMLp0&kFVw@SPUJ%T^+%&r?p|JHT0K?d{oJIxC)7{Vc_OKQee`a0%*=d$?I zVGBP#MmsDjhskRX3v#Bm-L2`^m>cdd`Zc{J{i!|IrDd|AIVtaES2?(YFg707;K>OhV;GWwIia$!fSgCFNaK2t=xvF%*Jb;8Dx9SAj zdB(%%YyE|i9-EE)f%SEj&B4%px=Zz2$V>9lzIZ+!#^W5%+pzXX1g#SFn-9PD8m?4L zjzvbK$5JKPxzM7@+w{lM4twA{ftfxO>4P&}$Dng^gv$6)3-Pa?YZG+0Y8F3-O0FIY zG7NiJ!j^6Spg+_TFR?BjyiEp9;a0kW1LI3JqFgZ%C<4j5eSz_WV>UG~lk8*Zp{=P? z8RrqkCEkFrs{n)I&M@=NHgGMi{6pRqlWN^w$_O}p0>q=BvSHDkilia~7_(n_nXkMd99^f=+CLO4Fy6S!gAHH77pRga1(qYN`N`#r zbE!_EgzY5NF{GjMH8{l;)ZhP zruoW*SsEuaX-M*KJZOyXI8g11>oy`BnjTefy+-%Ebqb#REjWGb@C0$RylP51%Nk9e zwpepvgBg*!ijQZ1(`7A?GN&V;=}9m?w6<0s)B9&Y0(&|{ObEn~%#Fs^>!gR3UvmG;h|5|+V&0!NoQm<%-K;ILgMyhgOAfi-1Np8(mwpo7-;_NT? z6pxHlU=r9pB{L!XRsuFkrKVVAKl+sn6(JzMm z`W%xWrM1-7?*`vmVai<`@O|r+SS2XjkSN()mldQUOw??#HcvMuc_deN3AJ@MH%bwU z7t_!Wp3P|Fnw|D(>K-cSI^HV0l_}WkVn0=bLkMv*{Wf^TF!qWn%A4h%c+C_@fZBE^^&XZA$LEz5)UIWhZI#O;SP; zsZMGCMH{Bk)N~bRlm5S9HY{ZK`KUNWvKc$$IioI_RpG!0_)4*Ak1$Vl5%2-JR&>u* zI-JJlt10jrZ7EBx3F1;#pCz(od9hBywK4d18#P{#J(TTaIo>BLSv8s3DKem+^@DXTzfj!GA~E5G-nf`&&}+Rrktzr3 zc_WNlo+mHE-D=$!XkuE;FEqWYVDXq%h5eUcxfF&Q^m1l%J1KwQ8x6Aqv4MVcR&N#o zVRa*;`up#!X3vQn|5{J|wB%%ilOGqSr>|o$S7?BT#Le13otpUPFlhaUNIzEM_kk~! z4<T>%2VXX}5%_CTG@CsBVl}`QPCD0|=DfYjxI=K&wngjDUbevxu zF;Cv3$~-0J6RqZ~K6pIRp6Q*p2pdjYL@v7^tS1a;0DP-aJ5oDmF+9U5 z;KQe+B!hef1>M=%i9Nym0_+mB+q=tVJfLZ?i7!bvoirf}2A!jk}}4%BQz45dY#>MVWmfX{ayo_=aI1V$>g@ zHAUV9r^ni4&8Om&sVpNB64&X6`G%v3(pW=1J@|`wzK~KqIkFgk%Cq{o!xrj_b>GMO zcx!HqAEB5^lPnER+GuxTiN-=(_)1v~{5bhqr4n-LzTd{!~SZ~h<6;1Hny7T|0oZfUc%xkMl{GaT& zfuCE_J$1M~t!mC4jwGo;=wj%2rM4`MImzWE2S~gXe`S!=IEyHT7K|J@xXhjx6SE>k1CW{GMM(r7V~_j+3IuM;OWtYXwtrS z+;2r0v}C!y=?pP1%cF;38TMzDj(2qBeK-{6Nu%dQj3xU&5YwV&W$7cb<+8>?5@>;) z`qX~zBFL<+@%_F1pn0#L8BWP`ifK3fIIyDf3aF__-QD$^9T6N;);2ik2_r*48UMqs z?UTm_V*3Xr0s;b1g%Iuyguc1LO3R=eJq0*BtAv-it$(H3{y#~!gV=`H8)3x#Cj=cI zEe!qpgMI6qy$!AmM@q&x-Z&eBv=@sm#|k@3EacG(+8Q|qmqFprg~SCC*!B;VVVFGd z(xJl)LRbn(Ig@{Eo)M2+qJl%bB(5HitJ|``Ms``>BcY6McIX&Y>yr7*z4fFZg%wa` z9haD4jy+fY<`u8X0Mp#=Z~}|jVu=@U>GRPtH#QC`E+&J4fk`>(Q)vN!hj~g#=;9-T zA%AcL)W7!VFN|Ho6TV7J;?;Uj^xS6h5rGL}+eTCj9xm@iKJjI1#j>kOD|Z;vHLEtr zR#}1!>u|`G+ z22tK;4QE>-9L5UYwDxa8paY1uXA{rv5a8~Ev(8S48@t~7Lxsms=L><^4eLiJ^eKXy z(s?OJzsAO?2uu`bzX$_pZ#bo`)f05mOa*;w1>OCdQ_S-o>-9RVk>f-E{K{7XND}hK z6yZL3zjV>$gffYYmb*)H%rSRwB>O*3e0T&(Qg3FXO5Fs!t)-qLNvSJnaBtrJ@)h_<0!g4RcE zRjwqZddN@wM%(5W!2$Qgt;T`0)vMn}gv)V<;2jowAFmpP8B=N_A1G9!G4r}tnSC_F z7VYv(NDg2teFQ6}f!4u>2yN>`{hbl(V)HyAp~IiU>Eq>f-j}YciQ%1!Suxs{J(Vi- z-sjJO#hnMc(6m>&TYC?xGS1Ya4QqurVE1hIp6SKwfi*>^gi5E@z6jF-f++o>-}1F~ zhboI`Pda^Z{7&)iIn@s(w%-B|T^;s}LEVl_QHWKy&^Xg8eZ{tPV#f+35uRL3lut_p zuA99X%!-4mj6XEFuSg@m5@K?R03CW4^K_Gg!~fzp`M<6er8q(|dv0RY#N+8auy*$c zBf!EQ;PuWtyltf9!92gb99B1$83274#VbK;?H;k^wF9+G)nD7ylmhh;z}F3V8znJP z7DgbzO%xhY>Gsp;ZbmncI&rs-y~s-b3(BSW?;K`n>V9&t5+-XY{za06l@@!-4+c2N z05t`s@n(Lm3qd%X&+5ZCRq=LyMnoT zXW~dtvK9=K>yoTxzADw0{Cr$V#N={AC{X&J!QWYqTR=U-_p)JX4p5Y>(*NP_EVMw^ zT1#C+Y5YE>0zd-?fKyK`m8q#I!0!cu|CC7|gMZstI$IoI0U8}2-xmOhf=Z_+V6X8v!|s zyI;EnM8ob>+SMktV0ZB5Y!XhRJ;^^N;S;PQF(DC;K8Us;Um}uBai*Cc#Yb)YeLb-* z+aYXXo@FAC7xxgPAF&E?vHn|43cT?VFw_8ADhh<3kC3Ir8S!)1(3MgL_n6Lxa%cuETdSa zo}4I43|E0wsrV=O`ok&5W3&|&<*YIZw&CV9p~V++c`;}acw7Psh$AbT=P|Cbv>@6- z{V!0TGHlU8e>?5N3BaW~ScZ(>Gf8N3e&6IXq$9sfdBtet-ydN;Ubq?EU~Q?dCR>Ug zikiH-Ya-I9wi@nR=#QRaDK3C0t&v1yEFx=fjqGon;6y$}6ZQk)N+Zr7d{uy8h8~s2 zA9YXX7V1d+Ee}W7;%wMA$ag$GHv>;W)MZzU^4PMeA=y9Imb+p)z#A>Vw#GoJ!2F zwz(n=o;VG*w~+{KzIUN)>4{l1S9YyvD`fK{Jr(@LFq}jO9$$vx+%oh5So*H@yC# zDdlx$^W>pO6ay>u=2!Rk2TRrZr<S!w zpZWy^HK7pu`_9$u&$Kue&b90#9M7yYHPuhgogB{uB(?_HynlT5&Grqwc;cMo)UZmo zCqB=(Nkh;#3M3TO==8#B*P5I!Rld5r6RcdE?eKh=oYaU(NF06VTYgX;a4H`;S|o0I zS=8CNpROB5)8tn|IqRAt20P}eVG-y5dCX>o=ErfTr*wl0+MY;I1{K3|B0Wt+LpQAn;j7=MRKRbSxchRPi44x#~@^I zr$40PuPU;=bthyv#gu4j%!lR+BZ899v+7aN{kqE0kX`3KW65$|+KQ>omA>3=4ToIN zGs4A#BustKCOiq^m@^av~Co<2ww@d)eJPGO<*;2tY!gNQxAaDg{E|0n;ZwsNj!as6{)w zw`WIy+}U4iJlWwW`*r(^U7OELwGVjP$0rGL8KBxC3QAEO#e_cIsFrb|wpcOEU_#uw+CFbgI<!sIIsbq{O6PRHKMh(V z>xm*L|LYA0{Km^8H}VJ7yG;b}EeOx46r2~7Hhemv)S>V@+&@9^N}}d!w2(nd52|9e zhmX#0Bv*z_f3@4gO@XuOU)e3c!+A3%po6s!=!n9I7XvQ(7{lrL9RJT2oLv6y{UZs& zTPPOK55e|_r=%P9dCElm8?d*kV@1t*F3O9Jj_>C!Z!P&o7Nm>J=Fj?`qn`+m?@C>5 z)Y0gsl(d?9TLA;Y{e@@X%Ip2rm0aQX4;DP$Q@2i+D_) z^)8O1Lqe)^lD|zDo(=NE&Dg%>1!qK@0@~i39*@yru-G;q@1FSh_#jJ7wgec=7CJzt zX|dK61DvaX=}%P1e@*;|wA#OzorDjxU5SIDvXD+RI&ry&X32ZK$M>dL?Moqfu8hq( zKcG&m;2CKb0ZAF8z}U9Z4wp5q(@w6Dc)WYFSaS_o1kd#DouJ-WI(Sa-gwswIY!Mr^ zjH&T|!Hbw_ql<%(qV^wa?q6g}{mLf-t1UVw-B*V%;fk zs48@W8?U-*!Y2 z5kdWa6U$b?);6@Q>!+Kl+2qwbe8tB~8d2QvsHjGiS^;Irb$LDE6ZVv3;1S8C#kT5M~FU3ZeR&ziMjF)&W#dF`M&j5;H;_yA~eQXgR1OqzW@#UR0ox? zY}!E@f1s^#ts<+Dq8U|!P?6#xNe_Xvag@q?GQOB&Ip zkvFGqs4ATIKU{#`A{E|Sd!GG+1za4=S5OLt#^eB<{-d8CIeyLvSMj+kxcIR@f*DUN2wG1P zKYK*PBjnGsNVVEn`@_JtlKL?NW->K+kfOY(vuT$p@pcA4LFcbXO52GRCfLZn;%QDJ(%OlP4w##s6LX%Lu-4}LCLv{(VtYGD1-;2doB#04y00+9P+5l# z^R%0C-xJ2zmVcgPrO(6K_t30rsO!&@k$f&|8^cf)a&{)}PE=Azc_6J|+Pw=jVpUf( zxc6IX4er#l)EA~4mDo>|8XPyoBGYCiNx>?kWvT7!t|h$_KHJf?fDF1vuU)+}NR#D9 zKHu!?tBClmR7_v5es8=naTb2--PLyQx%9}%?s>K^SXa3h)tH8bY?R3A#-!hmz(r3l zo3lP_1&L~1p!=f@QP#9Jzb6}cpGMURn_RvZT4BV zJR-iNT9zcGsZt}^whYTEr(w}$Cwn$5?Apy+Yu6j8$s0kYDrUOwxjD?J`;Q;Ru)7x< z1w(1`NF>52oRA9nyKD0Pqqw7PT4iQ@6B=hruf)taSdH(`DP1MItZ+#7r=I%25vEMN zk$RYjk&#i+)TCbRuaX@W8AFLaFe{;2Lj9C^90~dkgEh9J$x_p!RZe_s-p}j>bIr74 zu=Rv^qM(ma9llcDap0eXSnF1VEM6*KcUWszLE~6zk%$W;_b4|b_LcQM<3F*r1}@^` z7Eve-fTAX|$vPa-<#K=w`(NPjzI9t4w>TjZMQ~el48&?@>FXwiKC-9i8T|Pry?j5$ z2A7$wuC_N04OONYJf-2N0aD^ z>4WmBqt)CSsQag*S3vvIH3N*axugyZheY_8%`nE#$^9f(jI^Ov86hPyv5K*VWV8}G z+Umhl33udl@3JJuBx}{Y%TlwU4>#+w=+!yKB0Oj zJ&3OE=+_w=Ph|^Ot(}e0Dq!dx#K+ZG7TO+}+PU))Tks);hnv?>S|K@Vpq)j%fKjS?*{|5G4#UYVkbks=G%eBPmmWbo~X4m$@~owcL++_g#fx!I;>f5=7W8zb|c_F6R9 z8`3>I5YV@^3t5fCAF3Z(B7bs=;l|2?MdjU@iqg4*zXiyjvQ^})9X-tr7w+6eaE)QD zCYcpw)w+sHU!x7Tt*vIIO0vWjzsVd#4E3Gx&mMEM!DXDmR#jyp(A$kAZ^l=ikkrG| zRrVl`z*wfL|+m`LdyT&I3#&l?|p3&bnkr{5nqt^r3Y=b$w za0b>gpHV~yQ*PYZ9{ZBIZ;E0kNqs+@J|?27ljvjQbb0ZhOOTd*Lo!NmH)c)f!q9;^0OVTX|bxBRv~Gzy5L4^YZ1rJjHnF{)63 zuRR~oQaG87+?f!=KF<*Aba@hgUZpgV^N}jLnQ=YR`<#(!uQQ<2qR`f}%7tN)L~x~x z++9pSGQE#2@M$;s3|Q`C4OHokCw*hK`!=}g&XH_aow5+Mg00JriecVTMA`dm=WlI8 z8Ywj!5PM)(_hBuFy$@JLMOvVBYZ{M`<3=5MQkvd#HLq8?`zzuSW$J!-58k;iO$CU~ zp<64F%i$Yv?iRyGI2DDG1=_5#zhMcKgeK&$ptA=+*jCyh6plW;e#q>|d#~ZsT>^zOiDLG#9h4_ca zBgd~vJ|eF(8O^~IKJ5MwlGyx-7YCG&HvW-^>g-+okU+umSsuPOe-`TY-lVlIqSviZg3WOBvpLKR7KB{gmzen1Qo8Q?V7w17@Nh!Z&16fAR?Y%}htddD?77pzECZ1Fbjqydj^ zDJQLI*)f*qhn>@jcK>GO0uL#owGV&Gt7=V`57rON$lRH^ea4ZBgZX;zWbQf&LupR^ zi+7(#Pov9c_Bxt<@^>kP{dWmXbwuN1vNTYporf=rE+k;FE)N5Vc_X*LUkeZB=N-dO z*CSF(EHqN(;cg}=0&xvYDz!Tg4#v~KC$frNUzt2*f59ssG^V4j$Dg}%9<@8-<4MW= z0b>&oaq%rJmYd#gSXZ6JPC%_850Z+bT3iWSJebMN74YSW^pjt z5zS9TVhDQ_vNbbMh41Tu&5D~fMk9Ke30WieUQAVqAf1?P?5E;~^BgW(jc`uiUaB89 zy^6^%2YuuGFFsA#T6Uu`mMik3^~iW)bsh^5!fK!LQf= z+V-@pMEygX1|gi!U)Ir@t!Rq!M&uQ2{ocSbb*%90Z6?ujecxm?Hb>uICgREW1L%!B ziNY|yeoY9a*0z<-Jg4d#DhG2}&juYaPihXqFuZ0Hh*}q^GlaTECTuiAPNI1WQ)&p= z@PYulPNEP7k6L;si%C!7qqoIvZG=tH%Sz09p&_@pmMu22ad`iv>QdK=OQ3hn!pZJu z%P}{nSrfcTu7>-mAe8m0&W4HjwIj+X?u)2R#RAXv!dWA#@q~W_Vl9_G`F&t!e=+K# zyv9DSQ?W?)F#7w3Q=GOZr>q%GjpM3!Q+%ZewqY&}jZu?}>+a_^4zAP&d+XTNNoJvh z`Up`TS6Q$Roda<5)G|$x4_# z<_coA*!U6)O3&Lp`vNrE5Sk^Vh8}aU!H&N&wKn~rqop`w)9W4cKom!)_+UHbu`=Ux zt9Hxx17{BtPCI1dKTvo)AYvMjiiAydY%-}Jd9$yY_7v(g(7im?W>UUl^eClbHp35! zHq8p(4JDLoTu&sQpN)iz+q(|R8*R%Gf4=vL7S>V8<=WtCH$!|il;u6Pi=QOeR5b;p$A%xfYzC#yJ-@iKBTwDTET%1FcC+ZUv<%`AcRgagk*rr9BptO&fKBV*>1ndMW_{cR6)Zq}(YRmFhQHf}wExw8rZ!?Axd)o6A7x zf{{Jq=4nhJ*U=w34}rBsl{xbo2d4qwdsyoG2baM~NJ!GtJ&&r+uv&y4T+=Hut_WD| zcRtrxlZA4$@vNh|B;_~Re>IlUlJZcC$iX+4LE~gHX0zR%HFBKZ;Ost5QbL3r`|u(W zV~+nm7Pd1WI^j<-jDhJt`?h}CT*Cihg40@wk}IF2$GO}ZWX{g@@Nl|Qqp3=cC}IRj z!LXe&|6_cX#DCC|=lCRoM7AkroPgPzD+;hRi=2s?>8ILA>K@DD^(M&759~~J04W>GCD@TFN-ht$>hON8A*Fquv)pb@f$g7ztdru@IrWPpU$AqQ4V{Y2bepOd}K| z$db0S1jJ= z1uv=b?}XzpJCfcd1MO?~T#)Zaa2~K+oejUWnVo8P+kJDejn=W?Hsuw>F>3mEUmF4*^%2xwZsO4%uQMTD<$#q0+t-9pAesxD4?IocozSmp|t21`YmFQb4BqkRcUt&%7qsP6BC{m`Dsw}7X*lhf> z2xQMkOqAmLE*L3Vz^eg5J3A$A$pT^_;}GVB5>%GD@>4i)m=^2bCxaAQEcbWJt1s)E z4jdqHvKhgTh6&(-=Mja7hajVFi8CasxHGD1lRx)ILtnWr)_0aWT|jc~666uKKuLL| z!nT#}zuykaayn%fAtgj(b9&a;Yr2IupyAo=yTUla^2To^8hX%k-|M3(3a1peb^Q&g zl%KxN*c95--sc&@@D}XXDtkDvl(RzRj%Nt96LR;*|6UhqBP)H^iZO_v8 zjdsr$uQzx{L$?nnd$GleV8h*di^oQ$g2jqmv&2*hn(SvC9%1Jo2;;>rr!lC?F&v=9 zBS$3NS#GaMu;}BGHAGUq5=^n;o-%8ba6?g_m%e*C6ShTPkj4$0>O#P;8-;Az8ucc$ zRsZ?m2Z9>(o|45A5(HtL2^0Nq1V`~#sTRlnP-q!F9PiMhPgm1aByh6qh`+Qz%cX=! zMvw03-BgA0BHkgV*IV%OZgH&HMEBP{4OKxMLHr&j^4(q`S7SdzD)$<2BMoa zGOE`0gU!Emtw%?4bI^A9T$gX*N3JrjHN28`M%L=alvF!!Xq97N_A+c4HW{Gk2K5WMT*TK;SUoLaXW^`u@Qpx9UkTym%L-vUsDsfX-~VKXknm zTXlXn?1;3%8v#ZAwUa6h0M$<5rw zp{x{N^8I>Gq2_T7`tmp5Jxx02NnSU&EmKP}w24T?D>tn!>*Gor#UY3%_))DtAk z85h4miZANtp-J#{cXZE0qer!0W#m8W#b7Aa9#FhlF^Sdtbq$;pWhRV40BM2l(`X_j zWKbPU1Vm4j4u7!3nIafyNGYSKIa!NJ=9I0+Bxiz3TI)Ud^Cd+i71xumpF$*FEy?r^ zEW%%}ziqprH8v5-jcE7KS#xVRm@nCH5jpzmx2Uvnjcnw>Eqy)crn3EoyBy0FM`wMp zv0bb+pc#nL(c*yxPa(Wpn1{c z^+FyomKs=`GG1PkM@VUPUwN{nnTdW_$~o$ywQ00xzQ89_^3ab2Pcs>K3Lp-{h{|2< z84^BZ3I8a5bAc8sh{n};+LKET z3%~2#3Pz#0O-SNXy^Gxm7uJ4?;&UFUOgCT0{)*djdH659#_?Dbf^Ay@u^^rjzmi<2 z411h!3(nF>|5T=nVI@5bR=>V7l30gt>Ul+;(Yh*a)_3p2f**x zxQTdOH|xbGcO~DB8<*paN->KAFypMJ?}g&@uJ| zZ}Ei1W#5F|)0YlN_qY7S#>}Ix_823iHni&6f?yVbNcn^HhoQb(AhjX>c%h0kC7i&; z;SQTQAysBXl<#kqwY(N&@RPdg3Z;3dGsK6$sB!!y&Li2KD67lHKc zO5M1oKkJEC3FW+zR=*b4m&f95Re#IUB7~}^rO+DSAS)ioFx2`}p5!@azJn+Ie5jt} z9Zf4@VXHT1gG|g4AZJMbwtgcRMMn#rs~_a?HOf?!qLh!3!eHR-EDo)XPxQ%jTz^0m zRW4siQR6^T-j8D`w~C!TCUDorn_G~ie=kg6x-LHmyDg^TpTCdjNNi8hi6C`(Y^ z;qWw;OAntWPRoN&ruB!4J29rR#EUHumOYYuzg5^9N`t(64G2$4msaZ{0y9hG6EEJoj~#4QCxGZltoI$K#{o zw6*c&!$W7e)th+4){sXr*2thF-D_$ndoXl&Pq%IV*b(j4E>3#FL!sgP%1iG!FuTsa zY!wXh=V#{>mkrxG`$EsF7fH!pjnCm=Qz;mOs!$@53(FsYezs29DlHBz=L%6T5~Rut zEqqFIfOskqu8(_NI`5!HV-x~6J&~wFn%lB{FF06=9k^o4MYtqiwT{BM|%v%cWyv|lvl~_t(zjVJyN1tJxvbpik36LO0$F#amc*;Qjq{n zR!mxSc5qDzImcF}rxERIU6Fd%Pq(_tz_VUzg<;E}+gH%T+}9%&7Hj&!ApaD5r?&K6 zE+kiQ$N>KlHn7Y{vPm53lx1DxvhA&v08D5TvF%)}Bdoe;7|TC9>?Ig{k(0|T^|0QY zG$TXQKBzf_#y6P?8Pon1ifRZ8wa8DWNdD_?;tef6dn2a9H|6qZtponos^i-SmRkL* z(GVCM7Iz<2rdM9%^)!61xi{zE30f!itG&Hb4P1u;ZmKuoQ0$rx`W6)jeO38YcjPc| z%!wwgIr(u|%G4sHeK=9aGAFmlo=mcoyVrvf<4ctpw;|G$vxQlBLSZc>^iSYk<@&-~ z)dyzWBVtGFS3Owo3Chus3;HM7Qs`YTeo>V%I`uuh4XP=O$Kik?G`j9ALy0 zDR&|VWf_X-Ugx4@g$G}rHQW8(^O1CSvRLc&_WU*BW2sZIL?K76Kx{K#qu7*6l-y;y zbFDY{-Q0D5F#zO=G3RA73yUZK9V`n!OG`P#_4U}Xxh}5BS%6#`0fH0V0oTBeKxw71 z(CbQo#9;Vq|C?mE1w(9*8bwW#N&gyLdkA(Bsji|C;t4Vvoy(ZqGZWUJ_%b3%C2z|& z#=>}nEJpRkqFBtI$!)qY1TPVWDsgQ7#py!`Yhg&e?6Ry{hkC<9(TDED)3&dc8!4_b z`S*+qFco|jN!IlRSPLWL;pK`c)nfc(78*mDm8|2&5k-!7YbyQUia__yThiwTzC2nQ z0Xbh(AHF%A+4#~>7rT|MG9EMpQ?6HqYB)o&=v^{~XOnWNChW{{S>N|xuw~L>_aiBG?exc;KSbLiinS~~J5j(;E;_98FBia6N@5w|HXOf9E znb@{%+qP}nwyloMp4gb!nb@}9KIi=ITJODU)jw5T-G#1iRqee$&+}mVHSzR|G8;4w z!9N;qT-E4473F>9-xiqTTPnik_8;v&Ww?%E$bb!{cYH_IbSHC(RQrpo9TEsW)L^h> zMVZVdMF>u^8KbG_t%yOZY$L%^R=gzab#K?A8@1Ey%B~WL80WS5w~Qfsb3GJ^_9yX3 zUr^rXYT(L9uXOHwYzWfkuZ-301Fgh-z#nLkVhXX5l>+m5&DhjcXR^N)CAFqU8BaOH zGh{Mpr3W_qG{)=&$b-dF!ord({1YqFXg59R%hC}}#b_zX5l1`Qs>1Da_mbr12vqt? zM?4ddjFoRFdH)Of57@hxBU;S_Y#!23iqALk#DO((8rZ>M*IbU2(84SZ<}a~9{a(l3ujV_(I%~$uLKYGZuPj3%tA%XYUgHNe&9+(E< zMRGJlY1M+~4&#{X6&Q_~&w&u+j_EP{zYFfz?@(UJqN`#Ogz#!a_0gYiUn)Lry60igsaYa$1XX-0$!?%z|%`j zfBhuls6!^-ZbPFhIi}uqN-$ye*+KEEIQwGm;6WPCF^2~P0y=j;z0~&xDztog-;i_C zZ+y8R`%I9&>~yJC?#erbQl%VJzM(jFh23>QIgia<9Za#Jgu5s`C zNNLFYs05#BRF+-sC zAa4v=daWgpmBDhIfsl5T#QsHlhrAU&%hI|eA^^z-nO)#wYw|_A#TDU;|>T$~t z^~VpNT)Bb+l-};BG>_^Tdjkc&Qts->3G~eh8(RsC(KwFhvmZ(AVG;2?fQsctxE_-s z27MKhgC*Aw!WwvAKm}|2q0(IPE73>}5P6(VG|r^$b!%7IZ)&J7+;ss}F9#!-KyE$* zZGydow5*JZwbGu}Cgbyq0Ds_ypALV0l%_o5K^}bH6J;m_VhzEc4c(`sou@I^Y7kgiPlow=$F?s z4~h40*n}+7+TJ6lH`R_9ugb{5clRXs0R+{$$Xpt+&G)Ys7L3aFh87m1gHaeD@6+;^6mSqyb=Ig1+rdI+lRpYbR-LGu6kL&b8Uq?6I?XBCwK~nmH`0#UIx64CYKmu!Xg>&5+BMycp z1}aB(7=$zRXg;^vtfk&$^(dj#1{GbpDEo(VUql&-ET#POcTL&E#O;4Tw%JV(dJ1&;N4F2LorQAPcNz3e7GnD| zJ1=jml@|1Kpy}&R(3(#`GXsO`>ZpI01b!(#^tt@!JO56+0if^vZ{~?M90a-jHy3;v z`2YW)JQkPZrh5G6H@@g%+rB4?M=lBPE!1w^IMu8>o#}sNek1B2@DF78&0io-?4g$= z*A5(wvqv2&E(fLe09~*kw!^OLv*<~66+6I+M2iHf78va|yX?AD|J~7I$Y#wLAdrtT zh4O+lnxON$(c4cF-@2Qk&0vSM7Mnt?f1?rpIifA-@BjFN{X1RhAoq?AA8p?34Pi~a zKeEQ4%saW6I61DU?{2umwBB1J1Ae~68|T*83Gvp#O7rHeI22WVx;;=@Na<6g0*P*dgMehvq;^Y9U`n!zK+cj1Pjx$I# zw)aUanU~topT%c*Yn=!E8!KR5pmvEih^(TLseT|*cRXX*a%ArbkTKng$bNEyw zx58&vbmGT}EHMM?36GX7BP+R*IMzw?^cCW8VNVRATD;ac*T8?O6-6#-le=@w#dLXW!<1LLthb$Pr5m19#U@bChI9%$q)wg3L^03PX>fJt@I z=_|zjQun==><$*W?g3EdLP=0G&e|WCVwVai{`a5e5o^f`3JGbn+Ug`qnVXxRD5mzW zES{PT;rawvA4ya*oN~Cn6He!@Z|{7lNat-vQMPc(B7*DyB{2U1DX_v_m0_H(QtAr2~x?yLcC%6_Jyvkc*2NecnLa@8TS{(&O7CJOM%>DVCp79oL- z|ASmR_!n47g*K3gDDB+XrEDS_Yb&g-b$|t>r+uI@;GQC591mlOdXIWBy*i%9+T6&bOPiA6p#>uAx)0PU({B35`yt5=rQOkLq&q3R+Vb)}#D@2;OB@;+ z`=_Qd9F=N{=C({dNie!PE`CuS=-gyQ0glw-zT`=_8Q&C|Pv%l{-`>1G^6k(kVJ9D! zb*+q^?F2VwVSFrjHJm9*v&p@Kt2R#vwd6t7eagI?{mb1x`6U^TNBlQvzqit829w*` z+*~4;$6Fz(?%R`)A@wN~2D^13rEzB^V2A^2{dN5cOk5=_L3|33J2=MkU7QjXP%RVT zjUQ2;!!V6RXL8XY&zy*@q-8a4m*<}WE_qH;s)|&6T7yAO4H_fkaaShXd415hqlk10Z zeBf*&t;|;$e`2VNV&%o(`ePk2J3HsMxSSu@ z4c+@!y;VoX2*ZMM-&N@R;lyHZB~$5X6ar96D^_^|;~7T-1#`Rri1$si3pjX+jn)uIcYxK))VLhn0z7g#2OF!{j# z#KnbU-?6CFZc}>VD8g;G&7F%VWxL>e+zSJ%7aIcU&WP}`v)I4T!cr!onk(;-&sJ0p1xxdtnp-e!=5L<=pK z`_mIvZJ!)d@yu(Rq>4Kx89wj9^C`Wn%gx@#mJwzT89ap&s;Ulfu*9mBop}T)Hb^4jKA#{cwAw9s*P1=)%r$W4qk_xpHK~hYEvM@8IT{rD?L}E#ElNMg$1ATjLgrsU>&+mKIAtW{K5gN8;P3=^kPdpLne z)yLQqqA&MKSE|tWe7}cqGEX>eKiC02IomhMU}VK*Fvxrkjx>o*<@wyEctRN}#Rg$4 zL2Ok*yR(olqXFIm0uVnaMCD2R))R5QnA9+s)f@NA5>laX#_C-rQ-&ydSO(|qmjs7P<-gfL>XImo zGG}p|A%ybC!SkH6u1d%drsl)k{h?liokCEEdf?CE1Y_udVI+B87J4xL#P~0J=_Cje zP@jg_GUNmqr?SE18)hj`^LW#h7SCL@{&Asu;t-4=8!%Dy1oM zIqOaDGMTlNjmV7}UXK}SrYAzixVt{UyCr6T_0RMtNptT?q^DcT{qtHd+b;$>AyDM? zaeN_+jbs}0C~BKL#-A6r!jK1K6+_@9j2)}AVxq_yq5{#f7&;E}9gx>jsGktkFp`H~ z&d{y|o(Qq@&B?(SJ#+A}B9^mkPVOnxgyG+{{xr;7-tl@Tl{lp)?CxXZpP((PSxI#p z(}9)M07^*&$*tZoq^3Umn@S$t0Ur@tFX{}XkF+h(t-DWF^iLI(XgY%vGlJM&UZJRI z>mWu~CW#UHHnpz&dkRA;v+zbz)T9GZJ~zvg<(bWbUR^;79tPzvW!|tUl}MFeK6G zJ@TbjiYjqPF!AUg9e^Up;5>tm6%@F2ca)gb^Y5Vt(*Qf44ZXiryprLlW+2L>Vp**iN3Qv@9Jfgy%9my|x6nP9|4oQQ8|G02#ZzkZcE*+_?SghClQXO4PQ&dv@T?o%IzEieM$5W2Avs1|*|#qElv zxm7DnLLk?zqPzepf@TwOrxGHJ)G-buH=s)B`@h-g$t^qOeoizfaJK8KGZH%0hu+bt zhJ`X&BGca?wcJt41!=e2&)Au66{O8mTP28w%-Bgn}{SDQ~{eH(pk*Ld% z+DCsD-VxNS#xE2W=4VrJ2THm=OqExH;S`|gObH-SLbT1D=0nv zx*5;H<#P9*>E>FlGiT(nN-JHwbQ@W-;RKh=1e5H-an0{K_6=n|nP_U};;^?TSW}%a zT&Y(Z@&A}Y{LpR-2_lR|ES9#1#&rcOYq_C+7b}2~8DpzXY8cFmOYAad#6`!X6 z^v?e3q{TI_b}-xF$zr)^*ISFaa|l})Z~$zZb~o!O?N?;1xs4_Jwp zEn0Fsv%UM#wMv$@%-P6wPnA+&EiOf>dtWdis*mLZbm)Dv%O1ECFY+TO#YCF<`Cp&jUWbg;?WbeQGK2Co%e~ zOQH!!Z{gA@A4oHe$C-mzt(v9($DG*#bj9tb>G>L5Zg%G>$A%#hfb=vmk|{Nh8t-FG z+1S|pCDkb_4YhpFzQro2pj#~?ZndhEx;mz;tZc=HG{_q(gT)FRWTVooiPs8J8AC*Y z+Qb#gh4SRQ>ckR~bzdC(m^whouo1cZ|7#Tf^d=Ct|JR5Kw4l#Tz&RQOFbBye`29Ax zKzdr-|F?ll*d3nwpB4=I_HjZV)cwtB3*sJDp!Yhd;bhyNwcIkvqpJbo!! zkAjHz=xX?W@i2(#BAPYD0W>hfu(Ni0AL~InP>>-$0V`{@+ZlP^v(o~lfB)M+J*EMN zB&*d>+<=(t(s@3#C{+FSE<*}|X}IDJo}kyMeq%*jjW3<_JG)ICyMVRn_b8XYCQqt8 zLqs3us^{PR9B_==>FgUBkomd?fL@tWo?IC-V{JQ^EZ&o+wDH#Uja)cHr4-lw(7vBB zWNq;1LrZ!sUUi}~eiJO|zXtM8V!9xNa1e~@3hQFU(dY!?tFydMceu^eE*q3_{DP!a zwB}wP3ytgNul7zD9<&j~KJ-r|)l>0@9%l6t53O=}eWRp`_?{Y75cgWA+r1c)o1I=z z-iC2k=~ns%BxT9z2WnrT5S>2*yFlmhpJ|(FOurYV+$p8^a%-!6j)M%^R4ulh>Mm># zWB9p9j<3{)x3AeO)cuFuNd72M`Kbwn|HYfK0tRjwlO~i}MUa zAqzML!Oj~{&b_Lsw{}VN0f{_WKd5_^!#@?ZW}C|#V-5Pp0QE%*Cv%)fa@#fW$t8N5 zYNsSn%Ii2$B;er;KGQiJBwYHuq1O&tWyKMxYBn3GYx&VERbwF4$L!?m3rmiylk2Er zaVMojszxL7Xo^SSXbX9d2Qm%XmAbxX`NqQ)7)Y6MWi)rZZo-WtyS|^30KPJIXS5&L zviD_%&)Ahi$P}Es@sG_G$qz$BQ6hk86O#=vC7@vn(I4k_NYm+%kKtf!I#raPhQ%PfD&?B8+?K3 zZK-9a2Sn`7F6A@&REdp9qr8CCJH`%BYLegSzn6KRTakWm;8w@C&m~4}`$GHbK|lc* zGxb_F>GNY_eGbOSfZeQ)k?6U;Cm*80z#YvG#`dX(4;^#Oe&o0$qH8vYka4*tT+Y0U z8ddQ)B!+4+yUeEX-hCMw`)$awR@*&*58HuEg+CFU`(b)eaCebz14yy-;RKkDz5r=M z<%)oQ*?x#(3Kl1h*d}VXC#!tY1gj|xWV!WjpZsspiW%|sbmyTh`l7#o9MpR8ckAJz z^wjW-U4?EeZ?mLBb_O}@GpG@)?PB9Vke`+FcyWP8RSGZ;&{km+J9$?==sSkv#14Je z)_TXu>16p`^IK#HgUP>K3wP7uYmy#%1LpvKZk`Fq|Fo&nCiXEy;R)yW=?rgj6*r#G z!iV&^8m8B|&;`z`J|RdZawcnk&eG!QdLFb&k#_GM1+U7hh7LWGOWxO_`D^oQh==X|e4^v0!VE0Ny}VJ$3q z=vMN$HJo~HB&yIAU8!gT1%FCreI9x6>$wX6$1$F16}_$e3vsk#@-O0Y2q+0OLAR_Z zwaxq+8W4p~r%f0F{ye7glRWCHWLl9oJ`6B13A3}FY1~q)loQJ(w{MSW-hOWup$Rm| z;vDDkBs^5(ifj^jFbqMC{EG6062RlQeTw5}lVXejkXlUte0w(*OjAC%+U7cnGKqr0 zPi{l66t}l<%4Y@>Eqm@fP;Jr04)x1517PzcojyZ3m~PkZh5I#)K5Foq^2$+7@6XJD zLVWlQ2y{bDOYa+i9*b=p4|yEapv?1ss(d7!@o3P3L?iRP7oa(f`RGL88ahbuv-a@M z@!Wb`$M0``O#c)2QS0NX72?}p3OK90ZKR;x)oA?4lYUUw=#)3yqhS7i87_Vv4QzB`o&{o3AynCJf`Iirz9JPh&u zR9auT7IO=`*&Hh$JP+PjWA#?i4u=)G)$1L|O@0P^k^0VBhR5PXK%~EnnF?XtzkTi6 zQ@a(@SX&j`>yJ-`4(E?n6$$fqM~S?I$S6t!aFOvD@?t4nF_I`A%0L*5EcosESfZyF zCf|W_y3RtcfhC^+crqD}z%RAx{VZ;!Gm;=xailcCvKi6Zfj<^-t2uUuBMj#U&A)w- z@-o?xz&xdFsTq@8b->^)i6QAa86p!{JBRF+m^;9WetV4U8oClsrstaI9sBY04fv2Z z#F2Ia56D53In%GkuyD8mNFV-5vDj!LAd!qQ+8O#trmzj8iTeh`KyV0Jp2+4!9xJkz zIlfns@xJ4~17}>Z(j~~|mb(-Q;Py1N+33?t?c1B_e$p1OU|Mt&u zy)6-+{)PD6v-gG6MJsG8oXDX!px)W6BQ1B5EyrpXdoc#vV`FBWV>qF_&)FuKAV|u# zYlCJYn>pCy80YVP;qFxXn!1B~5Q~+4)hl?>>1C9%n9R6_Z8aY)aYp8Nuvxtd}>^_g~x@Q}PBGTkSD+{-?iQ#taYp8AxO*iaE>%nOjXvNn? z@*W$7K=`3B?T)NW%KOOKaxpmHN|wMEnIBs%v_hnv-)eH&qP5OjAd2Nmi4a3T*8<^y z)+@x+mva!0#jVqw+j&6v_>Wv{Y(~?4` zDm7pH&+L4TbIMr=kHkAEP2sq3BS+^7cMZjH>~y}}_^NW%W;|lhfx})z-8j0~x4r{eHkyQ?qHf(*y(W@v;c`NCl;kiNsiJOyWDu6!H#S z8oJM6)KAyz_>})jSD&p9iu-+2{T1)D`?gai`I#(?YxcmVgV|uu=C?H$KkG)W^|f>R zp7$_YM2E=v6fD=8aJaPownp2gFtv5szD7>G-Aa@34Hj1N#z%I-l*#RKlf-7VNrHB3X(>%2iL_wp zlmQdoAxgK_&j4hJapcU|q-oP7QuL<_)K>T;a}y8{$P=87K;C)xnmBpLu%{n-qsO+! zlgO#2M+3=yUuxmK*Hp!^DXpSP+8gfI8j zyr-6rn#`Lxqg^RR)61x1JU^#;v?PuNVt*N%+hD_Q{>B@vr1&5lWp651J{1)VA1;W-#J^4qoUJG5^tN)f)}>5$PZTUOtMtgbnJnA80LD5~@*-0m+H z>lv;r#VeAI#I+t74;evv{SC9NsBIdd&Q4LW!6c51 zrT##9x1Lca)B*xhqMS4n`HUpb;6=|AJ$AM{(1-DZ?rRy6>+8!_?{KCsI*oYwf!wUd zFO2Es?j{s{NYaHu?b&TBEBbk)NGhS$yFH#QHB#eV3PtL&vz(dq%j}8uFA!70d54Fy zq>8O@zs9`%eLbR!E!!i-9QHFgX6TSu@pYDOAgINL6{y@iv!$V;DP|K|HSJPA-*<4a zPhvTN^N7wmurd^8 zK$eS`A7?7|2uO!T*fw7m>h-qBl>_`A79e9Zl=~e~Uv(RBtQt&h`+$i+s%T0fGOqWC z!WME-z4m^;DfKE$TOtvezD=lkhz^K67xB<}B_8s2|0OeiK$4^dYYop@ES{AGi#ObO z>Y{d7X)tuMLbKCSn6i`iq9F>2=+6>fc8?26vB+JTmJM-p#xJsz7_tRKT*7Y!#PS!>;rt7WAxV ztOT$c$>noXDz2YlAMI7*;P zaDRn+(z3&>H74GtIbJUSnyokM((8G?Ubz!Oy6RRcPyFt#K3#ddvmW*gsMea=KGO>^ zWX+e+i);}pZM3xdmUVDXI-Q|semzKC!|O*^Izra=@@PEUurTqQNAP&yD_hbM^-b!^ z`wj*=RJH8oifQlDl=PI1Zl^Qw5Obj%#z>ANoAFJ>#uUumF)>EUEx+~}Zk*NHaB?Dn zdE6}MepQgSb|!Q`^yRI|n<)S_%RqZ0Lvv%vfsSIoXU|}yRk?;Cnur5vcrvyyai-z# zRCJ0wLlfRPokLs#c*KE@!`&W9=(omErrgBMDsD0>Y_ere_l^fCgzfjHUGAvO`8TvB z#6CmcT&s!S4*{mn0}sZ_w|FX*@Wyr!?5QyM=@$@OZd)-hzBGq0D-IduN?ywZonWcA zohwc}EWRI`M=Xf$3ooI1=rv}qEiBR1WhO3a`bU{TJk82s*zr^HnDBl@V0^WI`ynoc^k)5jkhT9I+;HoCdDoGp9UQ zxH8mf(5Y@g*Ezn9pbOgW6&{^@Vg9SCU#^f3a&AsbNN;8f#8mlfFUv3TYmVOCKZsuacI-M(- z?v1eke11~JnNlx~!R%(%=7f?Jisqnf4Eq7{eB1DhloIWBy0N1|_|!r=;VVuq@^=dv zW4;0Ur#qAP?eyu1-Ut^54^GJ`T8w)rX_M!U{b;-6u~-aHl@uo!=m>_h8R>-=dfZKL z_#}>}F0aAyn6wKl%Yj@U`(rZXmQirp#F zZ?1ram4h1L{`GplALGN_`5sN1?Rn50q{_7kQN5^YjpqtHl`H-I8*4BNY55|@X~QJy z?5sxA0*k8?+KiDywhUskjEK-rJmyPqwe##=N(G+JW~iLihk0I$;c_vQ#W~0WnL&S^ z(Af05yJA@i5S5QKpt$^#L&_B{k58lGkNX@`kv2#34yGjta2SrcE&trEwJ@BP@5z0C z=Wz64NqzQPDAFoTtNhTX;fv!DO$Z>v+86?-k?-=~`Q5Qft?rvz>*+PrNia*b22Yo5 zWa%$9s;PYAlgYc$cU{2OAiWgH()jw<4nyftB8_eL{{3r9OqC?UT5&Rtl#bcNyMlFK^rgN=+k}qBT#MAqZnigusyRS#DQtE;MJhHfE;|UfR)K zD-Bd2CtT}xtgehAink*zW>b01MaP(tmnIKbD!~I4kd?obx|C^DH_DUi`3L7^i4SwE z@x*zI+xpT_U&R)xMcxo?gqh8JX(|68C4})G!RJWjsj`B)OVCzdBA*emQQUnzB^Rsl zUd0@|vk@EX27bBbGAlKjTdU+aZfmXZ9dzy>SkeaO-(?~49?$dwW z_x`n#(vE7y8gkuS=GB+=*}+I)qdz~wQ+!gFE3)-!fP{=dbspwG6)_2?pVW?tHl8vl zuHl_)ZQ#2Lym|$2uryfo0)K7?+*;st1>sNUM?liWss2TJfUp=8UXwqjDMff@=0fmB|nh&jO ziUGngD6A4|NUj#w6T2~D>m(QHJsj0m29_+9=yRz(D==%xVFGmL1cWF=JY<*B4wq-H zsy3Y8-R@PxKdG~BoR5_<>k@q3Ut5iq-`=(TbX4_iI4PAW!Vl(o5eH90!NL!AIxa0# z7qccRbnIo%W#VY$Nq1Dam|B~oTDL~~AF&lT@<{6au_PK=$JxaCY`%8tf-|n{ zJLNxio4FF-C60QC%DXM4w8Otz!q_A+daufiCay29!HTFsA3g86qq_AEwtPC`KFTb zlH(Llgs|S>OLa}C4wG!b+nENwEt_1e82HG7)<48URM9?o-$rQrP%N<<4hx*rp~CcD z{nJ@#sETJN>BH)ewMI9H=o7Oyv)Nznol=p$ts}cNfs3R1Lo4Vzmzmp5^5qz%kOiWkmgz}{gW#(z5SOZ&-vWR z&XSImSP{u*0yD+V+||(+uh>k91SSlu9TU}tGV{xrY|e&s{O20RA{_^ADPO6pZZ*7l zW^)%!<`WI4|*!Gh22Sq#&YxMC%u4W|$`NAR}JP#m3{LNiWj#sRVd*tU{cOP~}E> zh=!TnpX{~O=dwUw)Enu1tDu}exWzVU2O8iNZ1)0SptdqU*e!k-IISu)y3x~44%Zov zBeqbVh`{S4Xhs0m^U3YWkLW?ul#@Gvm7@K2sRhoE@L*tpz+O< z8vT+fXFKXO^pN>mFq{uv#d6HHXE(4%xVG!DUX5iC_*`On1R{ z`eS>{APa>!MCZt{F@9L6ABGmJQJp@iI)k(6upAX@oi}ap_!0ExaR#4uxw*d+yLGHc zO_C}6*q_xbwDT$!{**XeM{7fA`Pmh)?q)<=|f8&d@ zu?0uSv5gZiPH4fO1j?liK$HP-yKQANtiBTS(%9pe_cut(%8%$0mjmugcng3ca+JIhxX31;brHF{|a( zP~uFksu_#79#gMmhp}MX{wY*lbnnmpExak%ZXk?|Q{yf2Ixyv~J1(A}N^_0RmZIT= z%hALIJ{kIK0A0>ifXiN6A`KL1x^nyS<3hIrwH?;@U_BHed-1SLXfr*}IEJ(o;fMZ6 zF2Uswq!qt6T6{cjqtMvynx=tOYJnDajH_UTg17znBuSX2=_EFarFiJPHz-pmyM4MS zBo5~?5XslV3cYo;z?5Q4CI8?hwzYZVkGwVN9T>YxvlfAmthwQiL#vjEUjWLtTIz3Q)ffj)31uC( z(`P*t+U$FuUKwCsdl#qBUFfpabe&Lk@JQlvQKO5e_0akF_}<>UDKZznSJSd=n!Fq0 z-_i&mmU-1qCL3~aL?NQVC9pJuvqGUxX=E~emVTuUw!ssrV&t%IWHM}WA?-F}s6^Tn zTwkvxHXid(If%rts2f-JS1gfIdO23CgvhPQR9n1k&QRZ^gcF}_5&QN9%{Nr1S8Jug zfhMXfCf})~PZ{@_E#!6D)ZJg`jZIy)&iM>p)oyFL0Gw;3>A#N7{W+ohoz2pE`0Tdu z-!WF{o2`U87$UoCB?yrB`4ZcqSvJhjsgtIc&16SBw~10t;TlAxjlR=_fbtaO z&efdJl=`tm2YG1Ct&$xii|i)i*tx;2ks%mtruyK*@(lDkweIS$C_l;~<2HrZXn|+E z`k-3A+wtMsyv#5Mp*PXCwOh8e`!I~hZ4T|I$J7F^4o>W7%Gb;&saPQ!S?n2-{B%Y$ zAZVe;Hceq{zk95D3r+sWI#xP$^35a|S^O&l$b5%ma@!E=wrJ0EWN?po*RB6LadWyEq%j^h4yxobL*=mP=3pI|+X(xLdZ-BPhO94tml1v|NWqWHU1owBWDN-{RTSW6ek97}7W9L8$dgFbmiXt+J|D2(db z^|NeknADEY5w-8>vJ|Dwg=pMYZ{h>Gqqtel@V^dl)9Ur#p@T&hb9>OSrnVAknKkBL zY$VyVtB2Kj+_*4)F~yU$qPi`{812oT<9j0}r<97?^@t4ZW@ozFOHb`;+qQ~LK2yrnvxw$gwH1YRDzw~V z3sr=H@8kL=tJqSrG-D!d%!heJnT)hse+-Y^nMjkR#^kl>nwUNy6JD$^8mp0mtDuaf z#H=7ir04y%e(-ELSc=^2btuZxDQ1x}8!zLsbuCO$GN0sPlbl5uX8CYR+3c~V+U#l( z-l4B>()*xGSzDcRV@)qT3AbL@0zsq56S+p76`7=*u0m1rYvDtHmomf(=6=8F-g0S* zpQYYK*Cekn8QWzRkQ}L8rB$LVn%86bzD;y8l0bB_yyceiyl=?|qj)}xsgi5=SQ&m~ zj)vEnPP4eQIPLlBui4Hn4|%y--BOKNjlEx|fT&VhNrhgLyq}G&GA7Ca1+Q4e3SCug zRaPk*f|o3sC$fOaE>ykVCQ+TaEV|#!Qu#ILL-`LS#TwCO$bzMcYL$uxHM$9FmWs1; zQ)FbMVnRZ~$@T8=$##F($;bOEB{#SBMvsryMw^3>PPeCuPM5nv4xgWH4zG_U$PQOJ zBs8=Vq-v

2$5|e!i&yrGNGOaoibzK|@C`wcY4QIYPn2O#hwAtyr~cqWs_)Gi%N) zX_h3|ZbDH`$$VK>dI=l#PCe+}P!r?WNKq}C*Ghi6abIb-ayGW0THC~#B$?41{Bl-i zb5g1@=&KtuM%$WK8BZ3|z_d)B1}ITEb?BV8Ic>bh$6eyzmpKPi%68WPP7*jds~T^n zQzTc8nsqbPA=x+~d_8ydPyKZSGkN}yP1YZ{7~DY`ey zaTU!}Ai+B-NYZE|E6kf)IE4Go2;P>QrJYm@3wLz*WSP6(u$1pFMJvpWiZ4v|x*7k8M({9%fG(w@(*J zj?7HfVektp_ncKMGU?RfQWVEn?TIOt%|V zWRfHnGM)G~xd`w-h3)|=;wH|l6y3eD?ItueoD)FIwNi-{jOi#vj3oqBgeZ4%F`Obt zd%E(IJH3J_p7#yeIvu@KbuY@2!VksqS7kMixmBv5seJ34xr%Jw6cylauKL%(N?U8} z;>ttW66<@Y{lB{6E}D)q8Yzl#ax}`_mU~LaikK-ePNphdE8m)rPojW9sZpq)s2yF8 z`wfiO_SVX^+fynGAJGMe{-Q%xwo?4(*%En>-v-vXQsvzWTvcl0N2~>~)%J181L@qT zyX+y>q8PTcQ4K06M>44_A=8ty6d`ezxAw+Z2WP)@IzLi{vXqf)g}lgzGo@CPp!x31 z3HsuQ$@1Y)B)QYcf#oe&L!*ziq5#1sIV?%x*cr;?Fk97RR88vLkzJGI?LC^~V>S6* zM92Li{i)B4(lYHNqhECY*pFYN3d659QMpu6QY2du&QnsajE)brCr?Gi&%Ys=>ob$dBA~X_ZDTW|4;cHsai_Wj(9U4XM{}#JScvO z^my6hbdlzt5|hnlzZM-n{HOH(DZzhA5hV9>Ia_9MdAYN20ohBtT47 zKylh=`1my!Tfka;Uhi^zK3~8uA|e%KW#x(Iq7?u&y41SIaM>?eYY3uL_prI?kn@VECgR?S$M}(bSB4%)|^{^{L3 z*C(H>-SbWR1RC9v8P7RSCH;QMINXq85qo_#7uF(~JkTAWjjNWM9n@HVHpX0eG=1x| zvL1b<*}G4XLjN@`)lYP2$Pbhb=-Od6_th;!i3{9@;BDYJCPzH)=wV>`jVSTrcu9id zzR$2(bC(7^3NmUiaK+l!AR;z4Rtq%PgvaUplb!u3=Hxp_9vKw{=jpQ(ME6fTc!^}n zrlr?bILpW3y-z!^gQa~;U~HiaQ>*4(kY_r^@rQ@Zb&K0a*&w1N{^EuOVC)+tc{1|wOnu<$ zjsC?PkK0{mHYQvN4(smRT=k4+yg7_B+lDASR{C>Hnwmj_|6$M=3?z@Hg&QeJr~X-i zx`7WPD}0l0o3ry*1#Y$O9{$x5ZN<~JtQ3M&F#K_>?>GfmPeaMY!PH@R`$X3wdp0du z&9_U{_Hh~z0lPJt-R`%2mJ-qw8>v+gg~j>+p`jU9mJdO?gL)kSK_Wj}Nj<9yglU0ZJ zSMVxWK3J;6so}&6*NB8~uJm8!E7_idUS)NapLUSYz4z}c-tu9N4d{K~?SxhOh9h3v_g1aco5 zgev|G&U$GzW=w>C;FGLlNdt?h?HA7;5cQ?cYiS_ct?F$FH_k~UKPRIPe$6R;f2MjI3v^sAp zU)A|d{-#2(z?L?geAm5uF~O8E+Z-a5a&SCq%3m0KkY84`mj4+*@ye+0$d?(@6STsL zz!B+2sP~$=H)A2bWc>qp@sbS&jw8=77C>$C8sE9y2~CD6#qc-o&-yt-W{ry9LGEC9 zx0GcAMvd@ED=k<3xyLXk+<%x%YNA0)jbD1lm>pWfpJ^XLHPgj-hU}df@fKRp3csEc zt#t?%%TlUOX++-J<0Hc0_ogmnCEs~u0q+?FYdRI}ZOpY}iq!ugH-y3NpC7xu5h-hj zLh5h*im`efqu^0I7EUR}AA8O4H5WGlPHF$!?A8qdl5A6P6;tZD%aHF;aGN|7H@jCG5Xm*^?P*vKTM71ly65{I`*(L(uZ_;bE9;U?!iPCZDs)|CUcniuOkA z^d_u0*XqVc(~`oAdaW~J6dQJ0;KshpxS;;Chsc6mRmMz&x*@d(<73qtXWD6YzAuP* zcb@p#-$?cnQENs`ss8&px_Pujw?svcW-PwPwtn9tc!sGSezqpfpN}QK0Jb4s5k_&pkADWrX`{b~B zM9q$VTV`7HXW!mG^MiATzizJz+mCa58w{@-CQLbUw%B5#>_g_VUFLPPEZAbRCrQtW z`)WG!VIbid;+_;Tn#bft+1lym@*)kx9LPZrEdyk`{k&)84_78;l9q^whittJ;Q(sMa9;K9#~2 zTm~&7<9Gn%`=Qfa^=d<-GP=R6QTns-fzNTeOvP~Ux}}`{KjAQESgN_}O9yk^Mh|YP zG=JY3Qfb{^TYXi0`&>x}P3n0``blR_CgY33SdMKsjfqLzLIn!;sqYO@W3d_%!lv;A zgFm{c7g)DlmoYN)LNYnHp*z+j&O^`SkHe4eO_?w&H<^{`m`vS}B3kLVAAX36Or{ZZ z%PCEdVG;UBdJtv;dHYsXmj1EMTlfzhQJ$vkTuVdOmyK3e=tWW@UKz|j-X2-u<2I6p zRqPG@zh1Bb*tjPcFdchP7E!YY#H}qHyTcYv!NXbPRAs36{LyID+&Qve!Z`Fdrs2>d|zFQhKwO)H(o)vr~?w)zEC_P>RziSVasm!7(4|AVw+^-36tfealZwk@37 ze$0;kMdU%BR+t2y&@c?7x!A#Q^DEX5yK&Kff6ZNiD9 z{dVWbc^TLF{+`V>-RxU3>4um(ZjH{37F2eRN94Y#*n!*ralpQG7gr0-wcDUeWdGQz zH;|4YR;Sm!#7$>LI+; zOpKyQ9E%DiY9(rn0sV70QJ|{(f;Ov$z>>j#d;yYnM>5{DwY6EuMUIrR)8?I$=Sz3ZzYupizCG|D;NIp}YV3eusWUS1nRu~LfYW1>Q3aZ@mDWyn2hvY+$` zlS)4{>wiQL-6FPwRaIle%$t>*uQz(kW0m_KsEe7*wZQDP8~?aFRlzLZVj3|WWF$6s zbu$Z>`J{i{{bpt|<#&|b*W$#<2yHg~kjdHmW5mTe?4~OT^RY^AJL6U!Q!_namN!^PrvlOJe zhEiN@AWN45<(4>QOU@Z(K~}2!qrSV&D78f@z$LO!j`A2HCa;Pj=C|{{lEa!y@aD9o zeK-Bq5_SJhiR{is1|(W)o`(SEv;2N@w>LqaP0<~*J%SOR2!hl^$o(h$sx*S$!!0wR z9H%aqzeMD{a8$9gMDg}EgI)9o@j0j!h;+L==>VLaX>q;L9K~y(N{dsJuuaH^+LABC z0ay3}n?+(>@WKlZJL|YyC|_?XF|un}UT&3UbMprGdVZCulZrJ+{9Bj-IDflSY$tSi z_HhUPQ;t}u^Akmwmk~&EtVPq@7N&Xf$Cn875Xj%bv!;;Es|c(b88P9ZH2M_{22Yqv zc?>y(qTW>K|Ij9A12vh?pI&DO+uEZ!YL|wQXL?g-YgpROkkAmkN4OS~L9`R@+7e13tDu&doR%K?fZA<%lGMUA-oJK=t-bY;nW?*lC3#)wE^u6s#Ewbppp5)y z-`3oO@VUtnW0=(}ll;q^m*i4UF|)77#q;Y)r^kR<%`Vkh)z8oWd?n?$A7lqG9wOM8hR4la}9`t&MN?loP| z?sr9rfB2XGtZSLsKkKjTGUvKu{HOEXr_^XJ($2pE)h8Y&l;nTiJh1;$6JYW|@OUCH z(44StwedZ}+~&6?u=0zhy|a3695&;K{z4G3D)1fy`VP3Nji2LLRu$^l741CzmOA?L zm6qsSsn`dNSD1qVC0YOI(jiIG%G=P5qt9W;?uyvsSDfC*f;PtApzq9v`67&bDArFh z_R0Qj1typ(ww&j~A=#st)aX@}nLA`{iOcChZP-)S0gvtA-?!c$lVe{dcaAu_cHd~d zT2QP0`H0;>f0X2Hz0UU+8hKuUY1!M(*i7OMRx6s{bTftgYS=_%MAG=XK^t@lkYxH2 zVHSdAG)EUojUh0T1dPoc)5Ue4R{xP}uzDq|L}tYEx5i`p$jc-Oc=G6gt@R$6;Rk5- z20H#V)W1IzRSO`~FF@})|8b>vn;7I4@&nFrd~$m`%~(hIhNW3?F>Y1;->&I^iP@#q zR7c`JamtLF+iC{S@wlmpHV6=5Z#;X}bGI7YXCWyI{v8+a_9rdyWyv}6fJ8+<6%G>`mBfS3)n%@Apo8b2TtlPFC7bJ{XLdRogfIT>l z4IcXx=wgj2@NbDF8_3Cq$@wR(pC-y@+mVP^&p#dok>TPp1$M>Zz~5>@CNmS1hyR<4 zLll=c>X)Pz7~TuI!9#2}>~jM&h`3hwyyLo7irYmbX5lnbR{p=R7wM^MD^Nxx*fV<3 z=aQV(lK6W!zi8lD|05^23sdfQds~7A=l=|w`8Au<3Fdon3B27!Tzqud)C5Ol!M6`;oEjef9!8PW4^Mw|t)fMG^RkHKLPO zAUoyyD)-l|#rdK>?w7q$BccP)*fNzUt=kFhPs=9jg~HCeTOcYd7H3Snq|5Av`};y0 zM!n{aHuR7gr8OJ5Zyq7fP3h_BNa~O;lMbAQCaX1HYzHd44T@H4Xnpf5wq3%FJvmo# zXqj26hWxe%3M*i4>n52&0Mq2Xey-*~p% zEq?7;TH)!b3u)MV-l?7i0TRmU$1}v)9*&-Qo4uP-ZkEkw+Y&Ev`r*yr5N zA^4Mm=XfnXUaM36*c>BBF=Coec|~<6+YMo8YB_B2(bbJ`bH{o_U*etFlIbB#Fl=j^ znW%6J9L`t0Mnn7suHjU_ENq2Fw8q>cJtNVG2$$F4qw!uQEj`N@2cN`)#dM>8|2+v; zLJb!lcfjW7k3=w3qFTFDu0*tZ9^W-QjKs^U8LV%|S0ozdpxpYa$5r%a2S+Ydr?U|) z%~^Iwn{GR}BLM0<8}gNHV&EkgZ#-*cgSwPh+1CyCZWby*9wfzsP=SMmrk$Ekucdqm ze(?oZb69~uZ9L-mh48c8kMTX!MzX8&fZ{K5D^p=_(vs91bL@IlZr+FTRP*}3@VKS0 z*YJ=1Up;-52-$fW;hs_p%9-X?eoaN6bzHs2YZSRWc?W8g@8T@sCcU3$V#RZl^r8mA|EQa>cltTU^kv+s7YhzDso|**P zff$8QS}SQYM)JmK(m~~PtkzSs*KJt#gDFQuYRf}6bKwlfxGuOOFT(P$7Ix-b0WC9au|S{FaL=QysdA zD?PxP@eH>qCE>zc0}Hd#E_$_e(^1ct2eB{-j!~x}OocERO4q|t6;EQbdeBhiU8Ki+ ze=8j%oz8eg=DP7?ZU@>l=k;V8eGLsrx+!_;7 zreC6W?%x%9i0pX}+$SH>BiW>!zCBzT^soPZ+fIl28Df7~%wlbLJ7i!2t0Is^)IB$2 z5a+XEet(^8#i!xPN7ETR{(3DqrABwW^8m%J%1q8n=hF2yxLA3m0sR3<%n-<;*MV!j zy()5d`b@MmJr$;du29emI{N2lRf!IM**R~7vfDgG7U#n$&MQ1G!Feet^I+u%MKqBaqen=)BEhu9QrEtQa}wmpm% zWa*r$!v~&OwK7nPC3ytmDQDb@$^zXT7ZiJi`bInRyBX!#tzxDt22IR4$>r?j%~OTH zo3uQIMJNrmHFg@uha2kB)dfS)7VNkPG{atAbM`ULK$ANO{i_(d@D38XM5MINGz4f_ z`ik4nNT_sKmVVak&lqAS9B?Go${ba8WPP(<{qwb_@j2`qCD1cXkDrzf`=cdn!i;z& zwiPao4sgZ-V{p>*F|WUK8S?V}oFAP3N!j)vK<$rW9&DeSjIA-7e;T)YWhP*)%Yy8- z549>h1cBRD!7KSSbqq~1p;y`Q0H&pl6tbWaEu*a$wDG9V(|?C9U~~08;F!O%#6{vj zj8u#il{8*upiXORZquafz>EH-D$7B>tN8O$%$+F&Q;jAe3IvrFG@_-nqA$equitMy z(MVv(wfYBrpzD7AfYsxk}hkMjk%%| zTd+k7qjG-*Ihr~~5Zbgy<-^e(5Qp?-dO{1kmLpD>j`3l|Hj%4{X%(T9go?yOr zt2|k*B` zx|S%P1|PcnT<8l^bYyU`^v{l%4?>y0UC@8*La{Yf4gj5ZSLme*VaW%8suh;0t_-vCCOF+25zMoHe*>;Bn|lyc#o}Ko-@n zXFa6&BZj|?-7tQ0KRZPAjj+qsOY?`$V=`LZSxaCP3HvcS6{v8qd=e#P)R~p8oHF_H zl{@{9dQ}9dSM%p)32?&$rCbDee^sp02@@9yo~Pe$zXVKgKN@lsAafVht}WFLk|z%R ze*6jIYZC79(_v|OYESyFZPiVLKVMu2HZCPk`qE&a_Ytn};XAYy-z%yj_@k)rpwcJN z;(b`<$>e-xbX0DprkT4y(RO0KN&mIUCBBIvfYNomnO@JIIj_E-{xh0n+h#SQ0CjM5eSO6ysf7;njXr0ZQ zVQb+c31?n36Ht&NFdpPg-d-jFfqLrxV)n>toL1Pib7n9?&(dUOPrCWF2lX%79^cvq z`~9%vq4HV}!LQDd?1GMs64BkrdwA5=d~r_?^u$N!I59mp@L|-%s(20B2Q;A-OAo^M z>n!C-2uil2?z+jI`jnN0pIBS_fs~n>7G+!7$I<}MsuZ|i*tco_>njWKgcJ1{b$h|qRb2<<$x^Tw{bN=ZqL$-uyUii(#jkg)=8TYtItP2sBG#0ZRk#S%KO!$R`)@OFE$JWX#Pg~QK?3lnxU|nvDWh*&Ce`G!jK(7BJ^Z5`)sXpnN9LHZnpU%B@&8KoPcUVJQ!K7GC$){DO|0nE9!p=28Wn!` zA9 zn|1@_LRaKWB`G11tMvtwb*FzU_gu)?rQyBX<;S8tiFA4J=7Caq!s+DriIHyJKe7L? zxn_F<$ejyM!1F-kEcM?wu^Avp4$*Pp-4TYRJNbhi%o0H;q< zodx4FnkvW9KeiTtpvKzTgl@h;shl{b*Dssnu6ifA)b6EcRt|UPzeR-jep)cg9OUBa z(zj{bF%;u{aceSW(k6`mW~v{R+@dn)Y+~Q489PFOxo5KGb*s9|UGMieW~*+wE6k@F z6%O7q)F((#^b{B)tIan$013h0obX_mRB4F5!p&hSL8bi1u(SK&Y_Kzn$!OjB$1Pt| zJ>4J^vE7l7SO@LC+T>*ZfMCDg#JN`=d|O?>K9it%-QKw~Gla4_yUVt@NhT_ujfTN1jZls+$O_JJGvQePCy`!D!5SmC4Rni4of} z8!FmwMXkz|*7oZ9*K8A4$(Fj8t^3V(h4n{W0_2nDt0T_OKvm!M6AOE`PZPvnguao% zkX$UqB94V*uzk%Y|40bCmzPc+C{*z}IQ=7kHr(qmNWSb~Ihc2pEHP5VUb+q~yx+b# zzkZ7nb;HV^^<9GS3gt5RlCz6 zQl*R8jOCzG0y%#ou(Q+I&%e5OzM>|5@BRaksWw3NJ|~j-I<&e-U4&t!1Rt%gJg`hb zt^Mr*85_uP9Kkp|xn~c-RV6Q%-+Oz0kW0(_(`4&q#E+83=I~6RK>rR9- zsfkK$7eFCz7O5tuhvhgKbSXUTkK*rFbi9@E?2c_(6ZcA>l*>szWI`mkgX45)7*ggc zSSZH64CZrR$MAp2E#^#@svgl|H%bXY1(dJSg5fq_EZQN@jR zKpyK59=E&f731%-wdY6!j0pMrP7YOmHsHGn@Q3!Llz^b;h8BcY(l82)nurvSh56X$ zliw)^^?MSBP_ah}y0k}gJF7tfJHnhRCFUmZJ2RxZ3Z!ia0E#9n9Y&BS+px>#~Dm zsiq$hf+c16T8nQekAf~|7^yL+{eu!F(qYa~8r|VKSLMCej-YeL&p*Kc2HS^ z{r+{z0n#v^^fRFn>e3o9EA#3lS#vb88?4sgPsWYm=#XR%o3&MW&rI~aG4tPz1G7$_ z1WtxyKp*)-?p9-I%$B1*xh@+Px?tpu59lleU(Oz0`kb7b{@&0LnFs2*M>O(vfIHww zX=6&{V4r4wZ^1cGjc5h1Rc?mDZBoVxrMD*dfLcvAe@RDKKLuS1foz_7*svQ(LuD3S zq!wXJ-DAnq)?w#akD68M8R*W>{khp)sicMmA>!w%EDpiPA^MDZqjYFyv&n>zIOD|= z?r}rE`r6G(s}7{%H1#g}z?DVG#`017eQgMD&p<41<->hh z!i|V(Fci(|q<*#GV_TWS6CL)3yx+3ENIQJCxrx)nn4Q|4lx-sr zPAFHXkb)!0oURv-iGBSj5Z9vg({26!^eQ({(0NIN_Z@Fpt{BHAgjnfe!qB;RpKK=; zl7^p%OjZy4Q`MU-{;3wcFOPj)6g!(<0gA|dERO!y3dtXt+fdkV9NHj^<0-vs1@W66 z3rC!1T*G}m*C)^towss2lG7V$5?AlB)EA=}J8F@SWq(rR%az3XY`(caxy_h4By*TW z^7tBWOhUf1`8CzGt6)|Ojp`XOgmN70_uc4Gmp>Tuf-oWglb^C`Bi3m7Wc9oxUxSM` zRl~1fWKAA}AVLB59Qh$l&VorAe?7+YTS7nF`QWOrh3BlcdM4L91~ z8sXfAS~?i{mD|j_<#@}cTw%=2lF1^DMVnApb@V3HWIS}pqJ&5_zD(&{54!1SVmoD# ztJi38$YpR}wpEy_p@rQmcKczMcc1Nw?gL+az8;6H`Hi(Zu51WM^CF9X9m2oNGIxC7 za^Ohgqp={n;xT^&BdOeu(0!)D?{ATwLlfnn$>*9etB)%L(h4@tsTb?xtOiX@Zw={F zRBE%fO+YswDT|i5niQjw=I9+&gOx?Q*J)Q5`rG+e%;rzAiF)6Rjm}%wKjTpQ7DW`hG^?lqauZapa$kS74MuT%s7Jm(KUoypxra(xNYm;= z+E)Udpla;O!C1ikSXvoARD~Is_Zi-%-MCjK80n|`Y1FK8(!OQ`Q>Clat4`|~Pd2Q7 zTS)Nhu~kJafz8)z{Hb$5GtK|W-rjs+$irdFKKVWjj|?Q$Y=0XF2WwR)<-Rj5W^Nh9 z(7dEQ9($97LZdOcbJ}e%pji>DHy*I!p-uUynd-5PF^@<~u+UeA*-x*#MHoku3O11+ zV!E$JriL~7O_esd*|^(5?r>)U)%NNE!(Wj}Di09zlzHIAJM^dkm3u;qGU) zBSA$*7M2D#s80J-$hh7hnj=Kq3vX#3V%IitucO@7kPOR)s`HYrnaf%6l2{D$Cm$vZ zWGZpxbL*0-`V%WGj5XD7vswr|t7LeY)^X5Jg|Zfga(~;I**VtByd4m=DkbLJEb2&? z+^63e?+n>~m{5G%<$yicm6kg0k+FTDbWEo6C=h;j@nlQW9IaHV`(C+E8ob=?z23vF z6VN`&3)0+p;Ez@-*_X-_QD%IzNyyt6{e}^}Kw|yQ&Jt>mwKz=B5F95th#%!kZVc&X~nhDf^(ArcU|?6_|%!KOZg(5lm6q z7N!dI2#adWi6wToJ>BomcA`>l-hjK4ubZbEQz@o7?AO$}%p6>J$N9TEjZU^f z`Z3U4SGZSh50dADyjQbDYcD1cBA8#k7`i`|W zD;VZc@tH$w<+m+FZjjMN`flB&>1^fZP*tp^`{EE%2W1vw6u{~!wvlc38#GVtl29V= z^)>W*e66VKlOrV5_ahP3upP}m364TtV2^v2zREJXn7|yExd75RcD6R9wBmM3=W~)& zVq21|nFSDK1{1jJ5V)gL%v(pr@Xt zthS9~`4E>n692%!z=bSkTnWC7ufG%{fOzea2R)?KGhXP~%8d_O=JgV{TFZ=;<~4Pi z<oL=_wiOFc`mwY^z}7PILE_v5;SSl$@5%(4)K1{CZ=qCbH97z zLXv4$A8NFD8cl3-T}Nfmm=qX1&TxYrC;|j?Ro_DKx3#HG^}tzNe9uL73}3~#AhL3N_+x3{l={M0oPmu>@u?wHm}@>sZ8nL1McG5e zeJt%LK{LZaUDMiElla7!N%F!xxC|;8SX?%iA8Mp+&$p|EdMg#C6rPei9jhVlqr}_*lfe&pvyHB=mqYK8R_LipA^XO5O6ahq=Q)hOG)>a;k;Z}YTzFLu32qjaNK1X181&=C?wS;I5646PAb zYZ5*ui;ageaNvfsM=zT9nAf7>x9b_OsJS~^bx4=B0gKd9dU22&VU&YCii7EK0E z8Uq=YIuqbK0vTRO^Ab3iOchJ_2L*BgB8JX``;gb>0~Bevl6YiWkzwHv04JhWDUt(w zi5zt9-+sPQ?!3h9%D+Ca)xVP53s-shH*!ADM?zr`+Lqtsw&N#1jQHj*x$xAa#BZVi zKZ(5fHp~Ioq<|Ll*VPvtk&kcet=&F~aDe$z(@UY0EWo+z1@p+x!jtN4wn;_fs0-AS zZTVOEi1A=yVF_KX4s?f-Il4=r`1$xY+W2@#KQc4Nq^Ey`MW>9J;}=mxli(Zslr$(1 zN3CpWZ7p(``2sbf{#usjTZ0p{0u5OVWQ4mv8>|5W%jNocIhX4NphVQ`ftldrrx*|* z`T_F<9${2qq?d1v__~78WgE$Xr50?JwLY!goUY&8-R0U#Gcp4cfh1vRD{cGQueR zS;?nfXd==|)?P6~L4$I3NY zA{Ugc?5#f;M5m9DmS^!6eTiF{HhwZQwlcOZ2(D@%CW6#FsDalPzYNZHeHlcYW{Lfmqza6TI?= zsEe~`kT|f%D0IMzgcDaq!jOq}f8GUHV^}nN9gI9zYSuzHC%wwkrzN_J zx3n0ENt}8to_7rIJ>B~>KV5NX@07@T)vc}D(|SqIqjG|(>aGFqkyKS;sDjI?U2bW_ z0zQ5)!@eA}j`LuNVImeyT5Hq2Ca8V!$i^A>a4edtVd6s5C-s93cLLA5_ZsnVXCsuf#ux-ub3!`-?@ z7&xA_9J0<3p)=hQp-CCmmdEpV&vR{#!Vvlmnrpk zxex#Bd8cDLkY!Mk}68B(EE~)z6n}lw|U!j3shkvY*IQpJ-#^bncOH?aKhoNr& z9>+Sw*ZJ#g@N};KHVxttFUBy$qtw%kOW^#oM4pobkl|m=(hBVTd~&$(bj+Mr_RACO zm!nzPIU3Ak#?1iHQG)&0;CQwls*EdUyCcjP=Rq(}48RETgf$@{_LbdA zGyS92 z=R9GlHGRN=duHCTff!3ckmZ%l+?+}~6eHQ9-<7jv8-BfGD6V}w8&&(4283}SM;cOZ zoSgi=9Wk&qmr4_$`OLV|42gTbH(;QOSgxgOwy<`UBN8Qg_;f)5IJbCnV~r47zi;$& z<<6sbF|;694}uiOGrXF>|%vtcmvAXaq8Y9Q0> zq5Xk9=j!SzLvDF_c|HXfS29q9w8H6p%Z0KB;PjRb4n6v!4OX`6-C=LvzFnBU0_>pK zWN?_Y*&5Bx;6ygy11iPRmCeoAgU#sz*#IDZObav%@c7_FQ&!bbuyHjI+y;1pTak9q zYm0rE817k2WHEWcmzT%L=YM98FFjGD;!M!ELL0A(Gc z`75PF+V+~)=KbyBPO*?pO?^)nh3FR$fQo|RZIp=R@1=!RpiT^|%(jhLTx^_}nArE^ z#{0fN9P7Nyydg##*e!Qa}v zA!Qq}UgmPmr}KX%6#)t?AO}?-V`23Ib!Y2scV&z*H!FTpDblK`s{>W>gl$_Sr|~v= z>x&M!+@FwR4^9=jrlVz?7O|z4d8C2t4kpp zGHG4POCg&;pv?h<;FoEwYfz4U5_|)b2>NBBYHxYJ%ml%{JuDhdR=7G^jh7H|&t0s| zV=s1Ow!9S5@zsOT;rTUd>Oy<#^w8^{ya8;N!Cb=Am3ZWljXU3!k300S1dK61smr{` zn~}C%@NnzLk?Syt&F^u;vC{mWoRUX)BTz3cUAdfX(|`BIGbAU=6l5C(7$s8ROPJ4E zFj=oF=^rLR`+FHJJ=VT!dcf={OI|Bl1nnwkFlFtv_=Du15i|e5Swuo7<*2?AR!;-M z#$C-ail+Z!n_t2?4EGhLJBZh*>2KFzTdb z;r?hqhV_N3pH&>1l-_0-H(ZUYdm*pYx%hSPoH#xr_cn0qeE1(C6>m@zpRg~rqS}ZX zOjI3ChB;BA)yxwU58`L`3Ys;v$de?+0Zsd;|}ev%DDMF|DK0NDdcAZhzb|nDZqaUmZotSy2t7+tnVsvu$8$I-GTNv~t=+ zEK5`zh9qZR%0#09mJZ$bofBO_Ewp$7ZJUZd#CTNd0y;;^F)gjm% zii#$1aTP4_o`j%B_~r0pby06|rptG#+K~6kAbAf#e?iga#(In%M{l`nqqN$H!}&v7 zc<-eE{2tj^V@A)fb2U+oMb+3-(U$D*T6t)T-Mzvxsef^U6~zRvu7yP3p>zd7mE-)> zw&~tJZ)9f`&DDl{$*s}mDr6Q&I)$UNw6AKvpgcr#C9yL+&&joW{iqNpj`gjUb&ROe? zT&bLzrj~=ZwVAPO7oA8=i}j@Lsik#WLy`sEIy3k){znk5Ju7xJN_R?{eERl-ci8#)F z7`@?uM@J7ycMYYg1Pei4$$N}J!=(&fqSnRU_KX(XWO`4l)}^NLDBY#S@Sj<(_oi?f zOY%WTaYN}vY3JXKn`PLYu$Vt;`~m48`I?TQbuig zAH;sN#NS#2juf?N20e;dSo1|}_^rj8UD^r*Ayn84RaE^pcAH_tg3^rl;zMdf;>bxs zj|YTzY{xxElw}O|U-7I{G&}0FzQ42F(3{>C??qP5%@;ZI5e3J2f~Jq3IBm%n{T*zY$IY$BrS!SGOu{rD!F zAnDyMMZ+t32aJKGf&IzEAC2c3>)ixm$Fm8Mg2oJ1vvPCy?7U4FhLn)sW$%W(osxWBmFToX86>P~D@{;8}>6p=+C742` zQ|05ItG8sqnf5?2SOLRk9GrMW%6}MUD9>#tf4%TR~40mOU+?+C} zPJLpu1MyKmuY0gbTP<9h-j*{AChHtV_}1Lx6W97}YLtAg34fAzKGnIt<*Gd(fyk{* z6zTWKp>=M-Ele&3;31awe!C#%8 z?7Z)TRV}*Rr13?UgnM`X*dJH5^H*eArS`Pd&|>*o9EWeY>XI+1lopGc+iCxs4|Hnn zUR15eT%O9##F869&8bp|5AMG6c}OF)&&7=vobB~yR$F4_Fiugmyhr?%SFos4LAra++d%Fx$4@w(gB} zY%x0F^HM?Hw4@8xq=go}I^1s9MZI2L?LI!ZAD0Lxb>Cn(3Vo(mBcIxY6F^8EOgAqZ zEjfhDrNt5?qB99LRWwBc$&(U|dpbrk_tJ;zax;ta5oZaTdRDshC}2%B$|t>$#<2p; zPzF)}*Lxx*9<|@1b{MxcyM+X9vMZ9Mo4K18rw))cns+wh_iR2Ma2sXlr?Ks*<-L9) z>65BgItmn-Oeseu;_7swLnZ0Q@bgKUv2H^)xlK5slSPv_*w$6h491{wb~x)7L=^3G z^#^K=ad)NKL`6B2!;+685=~M1JT>w))^i(Pnqdwt*1fmDhDUuZQWd5YE-OFhK;Abf zk9up{!*akdWtF0yCce^BNelnwj~-KV4YVA zjoqJl?%MuWOpb{4rJNsf=eIl_3-1RV^XwBluGg@i1G;&$D#TEW-!U~CQ+0r3_Vt#z z>qsGw;60CMe<9CC)xyR@g}NzHLBESn$ojFF!BOb7^2%hKwz)#-gB>>X?3%CFP6@8V zGDxav{(Yk4aev^I&pZ4vf5v*6x6f|TgolZ;mGeIm#gBVbQ&P9PLnLL}`n$tCkZij0 zKBN@s_t2|>cg-yUPu~a2a^?~s2(hBZYeUXkwsNy`crhS6=QY3&zlIv5Jh&W+5kh(n z>CLV0AKB#L4#j*pgZW-lYoOf&g?qdhA14nNxw*A`@TB#bN%2Xv!t30zAW^icGD+HN zB(4mdV4xKo#_F^Cto9XS@KDlf+gH(pcf$J2@{bHE)UbMa_rsikw<}E3p48;Yw7PJO zMO!NLI&>in>v>#KE|n_?TeOE^XI<16NBNXm#y{~eb;G~pGm(Bc$<5_37RCw1^uds> zRezYIACx08NHUnj0zy_1E7ZvZB@I4#_*QjjgJQ}5dXFW?wgpj4RZHt2KjPQj7~#+& zv*n;-;uMkUSb?!UJQ0$aKf-#z*R=D!4JhWvOpb(OJHf7~vEf6<>bw588XRpyls){ur}+GRbt8jbtcxcS4fS>#O*6UyFiEdk@`?XZ z7$h7W+3g!sfbd$tG7W=-L`F?bZM^r-LcK`?Shd^$ZE3wAFSUJD=wWmL5Inb+pJS+O zFuEMcb!`0ygI%WcPH}nOcTl)#7F8=z7i%;p`XhYkzIUpwjW0h9tMMf(FFR8FMHGtU zk<#lBfU)F6zP>n>5IBYVro%U!v2#;&5 z-;1AbLrX;AnkWfj_!*(CS=OYK`o`7C~)v?Ow=H?g!FwSZ|2RHC9b2`4 zNZhr!h!@ZSD3rqCoRRN<{4u~Ejg2ne=W^sRNhh55lckS|)CwVfmH|Gne%8z94$({s z#6)S&=n{M~(gz<=?tjEaB1sSuRsgEC_0GtrhsQ@dS25Cnjy53KmX%%DwN(^E%usx^ zaFM$~udH5$3c^vSM!YW;z^i_sBz6`lMJ9BN{U9i_Zx&yjbws+@U{N4&NAqtS< zk2f5TvpbdBC2I0fgis~vMX@|T7qv|F3KKaUm4tTGX+yk9ZMbX4tb%`>?-#&a3LbQ z)RTB>S`L~L(9SN%3T#|uF8wYv*Z`B0lhB$;rMRJ5Q0dEcgDyOnSNdhhPVEZf8I>p{dN8>bKMO&m zT#Vefxd6v|z}%*b_W7Dj0{H5a&`z+RwxWo3?JquHLkXkY`FMMlMHfHTT;OQSog)kL zpN4S+aVh=LPqTSPeS|MOQ7D@I!#89G1vijIBxKDGJflXDWL|U?e%EbByYpaSBrP=I zul`y;67@r;NBP|`G_e@OnYz(#Q(tTX1fz|1U8yLIK8oM8NSggHUy$P)44xdy2M1sb z!d*e_b#atJB3)u*4rHg!sJ$WdMo7qXz-9wsr6RLtqAYC^!etDQiK5BGxvuxf!suY^ zV*E!tYZWm@<9OPa%`;rvUqipQv;NlC?gwYZjyrRBl}~YIcaatuZImd@s}qpC(<&(Q zD-!x8sS_7B_a9pX1!2WhNN0DTfCS(kJv7|A>;7HX`M3`~r9G&Z=smVrCcy%sW)C89 zqJ z8D(Qo>iaDeFs|)kU~nfx1ljM3>~KfA09LW`S=-M5Kz*vf2)TL9caa_`_oY5<{#}ov d|HZ*G@=#!ET%qU}U?U)e`6c*Dzy0w3zW^z3!)O2i diff --git a/planning/behavior_path_planner/image/lane_change_fig1.png b/planning/behavior_path_planner/image/lane_change_fig1.png deleted file mode 100644 index 74fbf25f863943992eb4881d9a84c8bfcc16f87d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 40773 zcmdSB^+Qwt8#j!Kw1R-NlyrB8gmfq%jl`s5bd69_8l+pKL>h$A-3SOs!)PWsdNlU| zKi~Vg|ApuLFo)y3xy}`@s~7f0P5ucM85Rl($`eHeSq&7F$IQU{1q?LcRfiAR2>gTU zBCV)}0bD*9A3g&=le)gvb=3r0xO$j6o1<7dfbGrMT|my}<_<1aU{}PWRtXdoY7|9T zDJ{>8orRfrL%0|G9C4ZD;#}_g`uUGnC8!Fqg!Es&uT&F5c{{QzGQ*Z+9|1RgRgc{-h z`>5}eh63~dKA}Zd`hRcwzWl%F$&{J>W|9;iE4^`?_krr+C2-UI1 z8YXZ?wsPZwg{kSM^>y=-cQj@Ho$phxl#lP?;-aFWLh-*}jBtszsO~>Kt(8{#k62+m z#V-`c_-mM&3e2s~L6NnPi2v^IBgoMZ`rk7>6Mlom{95+EYwZl^MB=Mj0M7}H{AQ0OrxG6t#qC#`&JeZ5k^4ZdqCV`>su!x+uPegrhU`XB&Oe~ zKzHnV`Vu}b#VOT-vZct}%8w9-T?W1n`TUszU#HA)ne+CL^L)GY#&+xELW)!Vp1oPr z_nLH=2ycepTwh)t7fP;gO%&59I{#M2zmrBBqXJF-)np`hvoWA6#y^9DA3H2Gs{n;bqSxvaRwo?$ORqt_Zkt07u)5UrP}q5%Mblebo{&5*628! z_8%6iWsWV%-05DZ0^w_%Cr{oMX+8C3K15~COIYlmoFqE&Ho6u1?^77UK=_HS8N}rS&HFsR+^KV3F zugzB%_CMaTdwF;6Pt49YdR>|T8vrHtF((C)P*8mE^UGRZHbp^0M;CTl=^DNjMn+Er z&s}Yg+$2I5TV+|*&L)vB3e~c;{z>zYKPP)0Q1vVx2}Q?U0a$(D`vHP#4_&p}{aS7N zsA3%nvzk3G_dV1=MV026SLx07X3-*{r3e`Fp}|GdwP$N2WmwtULZ{{ApJ1ch{UL;g z(4|<9#LX>TYq;&L{bSQOP@(ZsUlGMbv5s!N)9%+~x;qBbX2;(dPnktL~mGfKR8qvShtq>Ft=s6%@Bq1UBsE&R83na(|i9Y!-wew8M&G4{GQc!^+im3f9~ScikXnLc}@vSJc3ri4#+$I8PV5^0dN zXee^VMH-tj@JM2CPz)8VWBJ)mJ)D^$vlDdD(aYw#Lurcwe$-}~v53hR)!xX5P2c(b zh$7~|B%`y&fRDrX6~y`(T%h39IwF(G8CuI&sHr|szNR6z?Jn>wQ|3|pyJ>jP|P>duhd|2yi z$6F5f0|^F)4>{jLzfTnC7CW&-SBJ~ARcgMr7WuTQ_TYo|CP|rKUu&z>v0@8>!bJ%+ zel@FOo{NtE%4Ec1gIE5-3j#7+r>(F0-H;gEhhw{{SCCd(|6N+N7?-RWi}*OX=kUv^ zCr@LJVpkN|^LoYwDCLPhY!H?6o{zT{dahw`WcMbcJH1@3Yk%fb6oi{wuI2a-_>DR5 zX%!JOfeQ5b9&?QLBJfMfO>OwC1onGCBBtNk@$@44gMSxg@f94^AbbiCO)Z)<)@1xX zzK|(5)$*sYEe0{!=HNsV|7h!m#MH`dww^$j6#eIO4kjw@KBFW`Z|htpj0{?Q;Wh;b z{TVmk**0S@DhH#E85CzPpCX)YvHo9T2QKAb)YMo@?jb#HG5j9EQN-G3vCg4>N;lVn zqR+#g!k?f%D@>6hIiW>jR zB{2y_?qSo15x9YBZC2hBX$wr;e0o9C*AkC4(#^(66v9gAiBU}gjUHHT`D$~|%&cU3 zs?Qb`?EDEh9iF{5k81DXmTH!=!pY%Aoiuq8Dn`OLR1p_upmV zQg6F#y07#E*@+5FnnlqR*=x3*5sh{m^DMwVu;DPF2^8beW53+ad>?NQ$HbA%Y#Sw$ zdBvE(_i^OCJXo|YwC;$%JI*!aBq8u)d!Aa0U#N*&@X{!LDfsr|+00QkB;d@la?(sx zb0E_t&w7@8XMAL*AwNy+9@xvV@1WoLyVqCU#?Jk*k;)o%EA%H@x&q?~wMT2B&jUa8 z|3G73uwN9N`>Bbje*xKJV2PqI^`W)Z z`NXa5`ghGGnD_)NrAvOS+#J^T0Pml|;u$ded$5LBiLG02If88wyz2%k8`6i9vEDM` zZhti8$1Nw4g+a{nGrJ#$ZF9lwlua|6mG#8|2_<0j9Wi#ewQz45KMwqnQkkObHcyKo zLuN)#l$uy&N`)>P4-bzt;cLTY@5I*YxmI%rhv?K)(v4_JQ(KpKZ{CgNT=_rx?7uEV zkbAI#3{EaCzOLV|=pj+}vOY}Ay9+g*vg4vE#w(qO$kasCX$1bn|7{44_a?!7bU10I z>M?k<2X_yrQT!A&s+n?B?uZ;VpDZ)}Fe_qVK%R%VdKopdisOf9?F=$yT+1VNc8_@C z>kk^_+Y1h6z~HVI8%AgelY!cVw{RV*Zz86gvYS-R*PrsTMns;YoilxC;-JFAZMeiKSBUcW|wBg%M;3yM(anl$e= zsXZ5D5rfJ>h^Fp=Ytgmdg7Z^czrL6jFUsPX#eaCGcZVTsZ){7;oGypv=Ib?cm)N^i zrI|Wapr7a%ax~%%8U!!Sci+AJdwM-@~3^TXLe+K1GWL*ycpkQ7$5Y|J!`y; zD&;d@N<SBO<_1|5In}ri0`7POLK93P zwbx<34EiIi-DD~HbU(hA`DWidI>R$*rHin1i>UZ^|Mt!8nNB1wp|?Q;!@eh7U8NSax z!_BqvXp?WCD=1hRlsT}$(;2g;X+6a(M|0A3@O7r`g=qg0^fskv)sksgOvd_@se9Dv zn{-^A9wSWG{PF_5i-R7^t{m3_O6#fe6WE zQV^4Jp1#R9%GC~kCw|7th$C6pV~>JSJ&R6N^BWUwIBg_%1{sML?bLlj5*L{BpULD+ zu#c6xHF4|0xrNLS%(~UK`-8*t+Y6uGj|)$(rVR8~n>^_WTCpE# zbsMRfj+}uRelulLM6o9MlJ=P-28sp}yMfqNoM}xH5KnUMABq`n)F*cO@JXKxo$(8S(%o_Sv~l-#0}et0Tnmlbf(~^ z%mvs2@g^ijJWIv>Qj@GrKhTy>vDm(&1JA;Q!ho`yZLzzA6Et=l7Mu|Kq3{{+CXA5aM&_y^&q^~T15lQAUwMLER>;`Y6mvbs%(T=ukwLEQY%8Ma2 z^kZ{WyubC$f9K^%(6}w>vp0F$+P=bsq2dLfF?C%MSrp5eJTb-lvaNzUQlKxx z>t>hoc|U(~^{n+4dtjVbmmFoMvA$kRRNnQ9Z%&Yd=U6Yj;*$Jr6~V7P@xBKP7>>#w zVUqQ)T=(eh@XWqZbTJpe+J2IqFege{QNna!ymz#oQT=uzEZ za4f7v<-!Vc(Qe6rT_p|A4s2rc&d1#GR?zr9XULPei=-*^(fUSSfDY^7{pFk*ikddA z*qExEkyk%qk;8$kQFtm@J9Nn{y!nj=zJK=>u~+A2j=bS}tnYTR_ZFZF4VJB!`y`Kw zJn9Uy=9j1iF!mt>FOVByra204NWWRrrg7vGqF5Bp6(H2EPAzmc*Y-M;9x(N9hEaJ^@}swPPlbK^wyI!*1Ks*3)i#Q2*07F&6|%Et%3}&)kvE5 z6){~2Ryf}@7o85r>X9&+b)p8|sW^PNl;6)5sOVLB5 zwkzi=koLxLmbD?nV92Sr2WTGVWF4SvHl`+AR3unokp3G2Mk3FO3GPFNPPxRpkfBaE z)QQ;>YMbUUNj`?Oe>Ys~??J_jhELtUj)5L3l2fp`cQO1_8UMQu=B%m;4U{osUNfnG z)u5ztY9^iGR7cE=O%<$LRJimc(Whd&4t61`XySK>u^i`>1}^Zt%F-WQ(ER1GIBlI& zFBrZ1xRjxBUCgBYXZrLO5knZwz^+&)MBiy(Ry!(jh-FAy#f1H3AU#6}IukMN4nYP6 z$3G9|`!8bOTvvb!g8UVx&d0<>PL{q=NO?Kx{F!>fritJx6_Co1Hf{YrihLX$qhq$G zV^mj+HvUMUZTh3diXPY^5TX>f`M3-MzYVGvD=^FbC-V&Z2;^uu+zh?y)J&Gnjxj8w)wm3q_l}<4 zTWa6nh;v=PTx7Y zv&us_|5kP*OQ9|vjDl_p*o^j8Q`{VljEWj%3;tc@91G@-6&+M9r}!@8t832BthaRM z<~KU>$(uZOCFV{T$}=-9ziLe*#sAd<3M1}9dEq}zm0j}Dqhd$2qr1g;U^9{DpPIuK ze0!0*XFXn_)k$C9bdUrJQX<@Its3dtYe2swfcxoLMiD+DeAx(zs7EJ9oz@^d^zzY|^PoN3+xCF^Bi$CR5=ez=k9^=XQM9wX@?r4o z?zxY2s`clNi7^hG+=9IQxWui|BhQ!Ow^gE^?$1|tfceM`J3a34prz$M`b+7Dk`-8F>I|PYbw2x$ zlRHviD_J|!2uAnHYPP6NiN$qTZjnxjHJLnF}o-lOn>=qGF(82eJ6aUU6yEO$^y zMDF)2iBg3Kx?7fCx0D0r7~pCN|L-v}UY;=LC|8#*#MGD^i}Kn~V|R#Dns4C@%cl5L zf;;&2eqeaQ+k|(9Q!m8c({EN=#5UH3LRujqLuD01GI$%@=d@@QXl8IHj>hH%XW2=v z_dG#TL<|?hw)2>$?&_S2jn@!Fcw=IMC_>W%^?X>%@ey873fB~-;|tcgCm1i)C^Bhr zb}Y5!$UrHn6z1L*;X~PeU0pR(%!TBc$c0Y_p5OyrLo28C2V(<-*5;9}CP8_8uQE7) za}Zg-LsL+CRL6zdI!^V+H4V(tbgyCOHgE1qKB4-P{#E0Rl?1SQ2P!3yd##g4_L7GP z|HYm^Y5jInyFXG7Z`LS{-$bOyYUS@ct*69n z!N1K)+GU?jqhuhqon{uwS|D~%gxc7qflhfxwZEw!QhX*7L5L7{`Z8wMyLKduHqbqS z!_??p|5+)&%X{lH6}zSlyBnobCg$tRL9%_*&oK_mofHz`RZC+bbzF2$T=MEEtSeRY zDcYWg=hZ({wEmdKBd0-0&77bRZf=;+X%Mlf8CFECc_+BFh{C(b2$d^uX=Qjfb6K#t z7kO;L_sWF2P3nsoPV+LqYpt;X!qK`4ak{tX3lY`4@ZFm;CbAJB_%e$J7q_-#f$rKd zBPq?$$%pJ>)wBd;1=>Qq>|wEpq8Ajsj9z8? zdL+91m3JwSt5|;rY*v36-dJY->*jfa1^9>c#Se4=CRR8 zl{&iGxWyo3vz;;1#mlhnl{b>ennpd16OWjM?osZ~&|WLt=uyfvYDx-vjzq&V43h{P|lu?$K5L?9d+?n+{xizd~x^e#SsYq z8R$|4!FxYl`@;?Gz|x<*b%icJI|)c-IG~DEr?;lC`o8@ol#{M1a~4A}zl8CTUwCNk zg)M#vaVQm=Gji{t{IJ;I%CAAT!rhYWJmpHoNP8&8+>;KAz={Rh$T`#~5mUGLuMJWa zH7dFbZJwdHPp0wg913a2ryY)d?Y*v+d{ATmZPo&AZs0=_w}D+}NHZrusb^?njjQ@r z(mku^m^)3Tv#Z;g=(B|RL=qIdxY3M+txi{hnhpn8vuCRB1FtoYe;E${>I>7xPo)lK zE0b9Y6(F$r%j=w+&ITcJg=#p{B4(#|e6uN1D?|Ju^wgD=^s>C(Ly>ZScr|m|D0hx^ z+^u}3i0=56=t;@MtQM5~jBbc>&Omhr8MS?!Hed83sEtIfkBcZAT_viP^3G!Mpl_$-|N| z_7-+G9JGVDqZJ^3bkV)U<0xJ0a7vwwkmY4@QzUxkTlOy=vrfv8danb|H}(1>i{{JRbJc%5}Q)A%`4E~1S0 zZ=uKA@lupsyX)Fam7ki=H^unUxNC;ku}UojLk88R1o6H@gk>zbR2SEu;OTYx(3tTM zJC-HDTT7?T8f(a6Rx-a<#ea1^{QK7L5PZwd*>c5WPwVG(E^*r{+5EbBWIZk9?_hF2XcKSon+2WQ(>1je>v)oMx@o$eE_S>5 zu3Cd>_xP`GU+Ne!wl+(d+D6RJ;x7+83g{sUdVqSac4Gef(!7b$G0VgyYJP)-{t|_F zT>MBz+lr0{ys{S?R9)S(L2t%mmxz(j+cT0MavSXCKwo?jJ?^T`p%^I>KboesXTV33( z1&eUxB8e{|@Q zB0cr1F3XoL%)yw+dN=<#i`;hXBLXoGyKrfTTdH>w{5-s(+3A80U}&Pxqpl4qMO9^^ zl(`ktzb??))nIJR1=T$HHcRx@KEkj@>1U1f&y&yJ8(#nZZkjRT{V9#>l6Og5s`2%2 z2OvLUT5+7@@6$J9KKZ&A-sGad0@V4?O2EZc!=K zUIm&wP3IfwgjkO)EG~u65~Y7EByltp(5)OID|dyghb* zMC>H+y35ESBt>JlLUKew)zz1c{Lzitzf)(-njXO~I+VwaW*sDo_f*DFYoVCrswz1N z;(svJkOtYihOHYEQ#ST6n1f^a^XfPu=N`u@yn_LgxPY1~S6*z}n01*O*Pp+Tax5yU z(W?XIP294kZC7htkMb#yl=f9kwcWwEI@ZGKR$nu)Q%O0vU2MXOma+1sqZcPz5H9{? zb5D2!*}7CBp3i#j%U890u@10@R_#~ny|mKCOylp^byKn}PS7Um=UkwfH~bYa@D)X1 zM~h;%WUNa6+mTr)}|S zXtAQQQYv?JDM}Eww9*}M*D8z8zLNddNEUPYrD5jG{^;?^?#ZkQ)9@om;>G+Z;FO`~64OX)FI{a;OV6yIkm zi|pVk_G8#a75jWX7FUw}#Oc%cF1y+^*%N!`^x`!E%D6?t+=^Oh2T+_9gul4fMjUtV zf3pC`wFLUJZ2KkeFm2~v2_$?!TzV=qwOGjQ7I|?jc2Xof+ewgDfAvX6H^j6rmDlnN z=razcgIoHywpciukMZFn*_I|IAN%_iQNFlGBzA|gv6tgLIyX!0-z4pk55;I<2`j$K z2z~6CfChM6=a4=|zZ+&bWmkAvf)8nKex^?H$Aq~;>ns!=$K8=lu zPqd(%Zn*QA#$&3GMjd;cb0#|CkVu>acb#%dM?`0D8O%t%P`OUPOPS-LQb_t`xHk?(kqdsGu*ndIBvD=emG?wocE-AcB4S|I&u@>_ zC381rLgdkAW@o!%vX^lE_CtM;I}|zZH0}ePR^j_5N1a~!yO(KfH`Qo%mW!t_>!}6l zK8NEkydj2-ud8a+h>Z6(^+J}sG^}#OX&&Ln5zSU$f%VjWaqz;8f%F`sa zeW`A|)PjL~#KH;u_zc%-+Qs7IOn-YfsVlOYk5wLIwo5>!KDfW{oqElAJfvjqRR7VP zL%oqFh*UB_5fq>uf8w1u--Fe?4oOJbi#PU7d8a2pt_!bbQC1OfYMP*HtyDT+HbMg% z}oXm{dQHiU8%#!lNK5wHY8TUZUBWZACoPjbQo=GH4I4xH2!(rhjq>Ldx zPbh^?rr3Q}PTSeao_TRv&H9JOWGun+`dQ7ybC^1)Oz_9NJ-r zbkDbs2TUeRIG=Y`4^og>yL9=RVv8@>9QUThRu?aPGn6qTJjo|1SHd3~nlA}nGqq@+ zme%1sG{jqSe!Mb(7j^Jb3$FHTvKG@eeXVwiNkaeY;gUdiC=|n%9FM3fD~Tka_N7&6 z{Nilh@jhjs4w^M?%-eL~{>gq~YZaB%j=##-tdddcvwZqoA|BDiEhp$ctMvq^la3#J zK0}ZQ=gk`LCM%)G{*Q~Kp`P?G}qgDfm|HkDJr)t~D!pS^W1TLdl|*x~ zq#sBeGmI$41xxZ%wU3GdQ8OeezKZLxJI3KzBl zJ5es-kf1IF^ENaOV80&h??54V+b2uNm4)4B&rGEazk%_i3AIj3T>00N~c@$S4J6=Nu>0BOg;5EmWR#r*Y&m zAwL*>-k_A1`+{Aiym2B9n zDGDRtVUJ8!N_Z4=0dpdX(p!ZOIH1Yu^HBq~o5EWRxG_jHvd(`M3(D!=wy}lpRIF%j z6=Z3A^R%;6L>>mogby(goLd#PuED~Vt{2_W_fwj2$)wvvLtmsbh&ertACVzj9T$+m za!llD(e;+5`ZL}h`%bTcNgm=E>FG!axZ4^s*$LI~;s~uh!vg0^{Q6xtyOqDuu2|%5 z0dkogTlk5MQzQ*OpGpbfGkzO-X}Owp!yooJMG4j71#lhSZ=CqwFu(Q6@IR7YG3JyC=13#Id+|Da zT>gO-r{ssDjqGkz;m9Fr2|E;lHr3+9gdcpZxi!xPoaEv3OPoW zcFrM3i#Ig9mRXjrHX%8mr1Z;g*#jr|3$UNX)$C6*I8aixtRg8)PQ^OC0+zWuHmxI- zol5NuK`#V_WJTNv7dLa5L{)CtZ5`{yIFd&$bk%-Uh(o?y&4Aw;8ss_O5+y=(!US}< zP)W$~=$P9l8S1wLy4TThjC@0T;y`xUo?*N7@p4J%#ovz^t+@bWdO*c03H=b1tCE@7mW0scOX^4~Y%ujUs8j`WoDREOB)ZUON`*xb zbH4H0d$%HwZFk*yt9Ujn=|VR{YhTDVoXvREf2(kwzsN{I(t#$mn1>kFHfftinS#;X zcwtNusHosKU%mMC=k1sfP1(C5PDzvVPQm&k<6BP3`I}f(f;Tas0N42HQg*eZ!yqYz zs-!QihY~WKfor*+&nC^Ux&=uhp_ne+3y8pxT2~~p{n*#kyft%oBh!O65@SXEbJ;Dr zu26LA6$Z5Bb9yRcW|k$=m3n5ROd`oN;hpZ&D2;6K{*5qVrZP4z*K1!i2SYk&bMOIW zV7F)AJLu;vgM=hvlDY%#3D8K@&Ai8V)sf}HVA!7v#*y(K_D7?fH;Mi?-J%I<&28Df z2#A==he*S^TRx9_TpRg^`9fmx*Lb?YEo;4$m;1{VycB_92oCOgb0YX^#_I5G9jKT$!Il zC<#!7$lomJ!k0^J=j#ujAMoSx&}6f`ikK*+`+TE8el z!!g-<(LR1-pv$uL6Zs2&jqE=;6-V-H*k$9=aX;VWiHpgBoRdy?IW_hD+S(Ru6A;FX zc3SNlT$CN!5fzmR4z__~9WS=zqbq$6AOCQ%{5;rdVEhJ7;Y1N%V2v1gHTJ`0vxC!X zH4`^Q?3#A*x*aLx^xF48F-mswwCyfasbK3nJ^ z$Q^Ck)muZ~U0N>2^26!_ciTA3Z4!Yu&ejoYliv>dFHP=lcb$kZgr|tPhl8*Gj--ltXN(q+Dy={0s8jVp##pyp za?aPCp=r*s{#uuoi)1VoM zdm5rYJnkGl4LP(;s@Qb$BZteZ5RW{|_Qj;KE=D505r?AFl*TE}%7FgFWSJfPiAYG^ z<91y)V)5W05HKLYosQ*-X6A(D*46%MD^>qaCEU~FvS72&Pe8gpj_ILDs>&;?^w}Or(6YRizMBPlC`qQ+ zz=z`Yz7=0*a@&*`&Nqmrr^L`O!5^N^cEY+gj5r}lIc*vk?DS%lM?XcT!ZR&Jo$PkK zIN3yL@)4@EBhq@dIJHOLx$*R69w@hycjyNU!mYFYvQDwfm(fF?zmcG6MvkJ=3 zs@S@Q&mN2A1NKNY|6%Erkx-kM8}`AMbG+}v}njENQ^*W-22oh;<# zvxn^^dGC=oKQtjPuMLzx7*E(FZcmk0S5$m_7aa6ijJ^uc#|7P&w;Pi2{+GtwQA99Z zpF;H9BR!$b>%EqQg+3lI`-4}74Lt5yZr~y`ucjx}l*uqqzqAsrU14-+X;91-dzpa# zPw^#<=rf{`4K~pE=QyrB3SH;7vI(qs(|F@v5`LEHwcKcMiqbkoGC|A(!bnpwEE251 z%pW7eE*jJaOZ#bd3`^naP3tcx1}cnB3Ku;-5CP5*kn?B~-T)5n~dUv<|Kh zzg?B9x359RE|1{i0%4f81_0|w8@$4nSrN}lIn8C|WmCd)R8TGDvs49Gq zQ6+x)Ztyw6DX_7zn@%PT3>#d-=oE##kC`~L{iCTX3|qXC&2nCmpfzUc{J?SA`eVIe zQP@%^C{Omj(zdj8Fp3Yfr4`8)Y;=TwgI z7v{l?6~gFI8APUB)KvY}_{T5=AFKgUf^0>5l{bM!YV|5!0B=AcS5Rfk1r84ew4+0>Rq~Tl<1ry3DUU%A%^AUGw!x z?PM_rPvdL%hd({p5A4hvmsjj%P-L`FV2p{SNbO8U_x8nJA6$MAUm!cdt`y<%eZI8^ zm`DL4JYZsp+#J0jh;LvtBO_nLBYbF_QzKLSb=n}Z_8gH|zznFz$%$Krix$gsmUW&U zl3AxFgr$8Xeey{B$ZO-ZK_XxfS4M?qeO!?y--iPzrK}af#eb$vm%0VW<6=xjD3&9sPt^+TsBhFiX^BrWZlW2pmd+^D6J^zx7xXFi+<5R_+p?GUH zRC7(ZwbV8jZi*>dLLhTqX7IikbuO@oI_Jkaq+P^=v79T)&wV&zpn8AuKOYWG z6{D$X2FN8|UGM}#%ej2cUtlRCFIZTs`**E@lvOuJ#6M{Q?3;b@he875w6tXYGWVOb z72qR!S3^|8=b zQ^up&#oC9tNB?QGoAX%l{H?bC5+sJ)5)_7P5%R9{@aCBFS@xmpA>^B0qRmRh24_NU zCBJd&;Y~l`x|DM!2O3b}mw$bK1$$6OR>nH$!-=T5e=rSf8p_UT$!n4fJVzjGvM`4=fQ(kpvu@S_QD_b?T zc}~Cn{$(1;673xv$yyIxT}>D?FDNJ=Atj?F4xVP4$(ty(o}UpN-V?phuJus&ib02C z1kkoGJYF&Iz{v8VyxgV2S68!?_f$V$6R=coZTmH8;VuI5=2dSnHJ=j}L$hTchLqH( zsHkaVi9D<~EHu-inb1jm&{Rp6k2N=vkWPMX9Poc zVkpl0+t?_Vav)@~?OK0;lD3-?oTyqRscUXs9Q~jmWH2L(bhYmc@3H+Rp!vWmf$UuK zy343L_*t9^uw7zq9xUpySMl>_SE&KiN+5mh$O|Y>@bdBk6N|uW=h>N1x7o9^0O)|X zy8c3e*9lL5=VRyIXiXs`1%r>6!q&|RSj3lUNaCII?Bu2E{zs?iidt2#WuibqP9Dc? z0<7Xey(POx`%hyE#rXzKD>X|pJmb`rcnx*uEvjMPG}yijuJ3!Uxc|~_Za3lXg{o1S zI@kogk|ek*6elapHD{|~F|WJ41)}57MD7qeMO`DK_1qYVm5yL+HcrmfjF-uS2eY>2 z+@hj`fRq4-;#{wi^M)EDfRlgc2(~(B?}HC=7PceIiJGn&ujc75_#~-sa(oEE@jnzW z^(6?9h6|~SCc{e)T(02D@O~=c4n(U@^!cXK;aehi!8vXZN{N-B2pwI6xury2d0~Ga zeM#bb+T`vaWbQ6{mw5e!&d%QcV5$Al9;|r~@N31z#XsllzcH;`oge)g8Q~QY>f0PI zWKL8G{s^89G=77eaOL61ds z>r@##;_0&#(SX8B9K*r;_lQE>1EuG|U^d!V94p zA0NMCji6xf&JG(uU6AQ_zo^5+wPyHoXQ*MTU#54nnnbpxqhl;kwFT^ri6}yJnLc(S zf{($%8aHa3EOTXaeNaqS5O}N%mtG_;Q{!R%=W51{y88XkgHzzjT0M|Y-Qjw(?j0Ro zKkf^=GQALWpiRNf?sTy78fa7e3Pi`{>bcvP7|syx1U6$pAW(C7zjV&mEXZM^#a*?I zfsqkd)M~o9*ls!+76t5sB@rtyFfcME#^vhFX#);V&CJZ#D8hUFjKlb=-!UQ5z-wg% zjnSfzi5R=}G_6}YD{Pd8!%KJW2e*Kh_D9aU$*9)ncNNjYKS!`}2dJL0@!i^wn9o`4 zohi1osF8%ozU>lhIe4O$A=EyaD}UEJiOmtDZDqA(2RH=~s8Q5K4sL2+A57-%Ic8yP zT)qTomye+|2XE-8keG-wvnuWs}j+P`P9dN?)|DOhoSWSjYNqM=; z?kqpY`=-9#IjA*s4p=JV0z`6t1W!##`TH*Q2@VcZN$GV(z9gr3Q0RccQ z9zr}yE>JGF9Z+}_V0sr-stvfUAMUKDu82_7M5Y^!KY|5v|KPjFoyD-bFxbl`&swQe z8)R)A1}rh%SxZO9LqPB76jQRYHh}G=U&F&Z{QR%;HGqm~FzaE>Qgg4cd|E-56VOls z+1f^wmfk5d@OJ?pPeepy#YeX0To0=Zmi}Z>JtL}>oSb~V8Il}|OI6j{8dJ6nz^}{og&P9{gF?PW-nezu3|o>pv#G|x7=Dl* zdcX&O8~*;;&h@`~deDFkv>f>l)ibEnsVV@R_Q8*UhLP!FQy$HnVC4?x`?n2?|) za~f~lA?L}Iap4=LSQUm&IL(U~lfPshNt1OFlASw$&ZbV?Y|FdGa-U;~Ml{v51kJzy zdbW}MCcQZXtf%x{i;3`_dJ1xS4Hn?-isAC5MD%J9C5V-kwWO?U%uXOqbO>GW|5u?ln*_T-&hzuhwLY@)LAQ-QULs_Mb%9QbHdo{C#iQeBMFU#UdBn^q;J z;B049p!Ix*BTP5Qkm2M{^~?MZg}TfBH+$HVEoT9@)s?CR@4CQz6%mbH0*l`cXOWI_ z*k>U{T}uCCfz>VeO;)Kp4A@u$@mzz=bSsyB?q>d6sJ6L$T?6@2Yy9WDrLT6xrIFG4 zQmlqG=oN-k`4k8Yjsa8{(81}MnVbn5ZV{1zL{=RVDk{qlALx#gBIR=BrQaEMH9h}% zmzy5tZEQ(=svz;%yOb!^jxehP#A@o{kqk7Pfo;wO2f^dW9aoV&4Q9X;6*!VXW@Z7d zBC0Hj9aU^>gIL%rU8_zi5C1Tgs>N_pv5mWnTx~+YJc7K>_QqYrlcu0&q3YnH{fNdZyIUGTeFJJ7zNwcD zjnR7Lc*e$g&e!4tQ>`)N5l9yuiBMZ{Hk-1W(^>7^mL~gbBxIWocy-a<^%LFA%G*8i z17`xS58X#suq%<|Y-z4JA~!sk)vl`YW#Xl-mT zG`~koUq(hoa`E#An`Rh}dr*Y#?%FHmk5!Hcl0|7S5h@gpGde)0wkw;PhxYdNDy0qb z6H*HLfk@=s=cWs^b19Lp5eDFZ;gtBKL|Q@I$Q@J(y(4h|IO^g;(CZXEaocv}U}F<* z#pk`^KDR3XEJgxq2ZE+6&~>~S9IvRZ?!36Ts4Pz}+XnEwr?*$#r_^`R5-=#>Sf5+Z z#{xc!jM*bVq8bdcpW8n9u3cPGTIz({Gm^O6;nmjG-uIPc!{7nJqd$KL0gusTR{7>T zDMg@3BqJkZShpFYh_MjGs&l>14xAZ3jEkGQy|1q?Z0JVqQV@b5^1wQ4^?iBo-X2F| zV`DFj(KAa@ZRq3L4@&DKz=^G#Kqs2Fz;=4;P|Wy z4#;E%bABFdYk&Pv067(5RnULz8QmYphd*8RM{kb(S&ZD-=83T1`~vks>kU;?H~Nwn zwJRMpzZ54?Z}Y*UW64V}iH@;+7d{3JfYx>n4r5k)A!)n-rxfY%dnvOSN!=qywuI59 zVK56{UtcCshU7tRettKzIe8^TK%@}JrGnZRc$U#Kx>fb=|HLS9TZz?0JlqOL;^c~ z5FL4-=wy_eAQu3u*MC$44wjDKrc5|)C02u*JF@q&7SG%~f zzFx6-f^48goORBURuwfhuX9I* zCQmK-dl*xB?dP5XgnJt|mJPySl%k@dy<{L}`ViBgTHNDau{Z_1Fj=)f=-q>1hk05! z!3EZN8bzAy626OtN(>>b7_80 z+)k0m z(AnPF-R%{K=>KK`G$ngK^_{&#MM4V4b2N&8P5L73Vy)tL`lUosaxV#)izis3R{?nG z&R0(ML@sy$R`=j7k_yZTWt;_0-1w}RYyHQ0(H)7ZMDt3I46 zjq!y$J^ko$4-aOolG|1kneqvXhO|iL%80*Xyda11+JMR@J|l0P^3m(F?9H3;+X!f7 zn1bvxiRl`aI0LHO-CYyk+rsJFx!Y(bQ_68ZKtUk`@kiSj8^6Xs2e*^p9*J!>sIer9 zOt|3q8kp!VejJ~bXhDR2J8{AcngO1h8M-g z2Oh62Zg->Pp`jrVm}(kYSjij6^vU#n87i#|AhE={XVVg$620vt*$EC%h#ie(EP#SP zxKG7!M~;5;?M~C0n=EGal!e@gH#9avz6tZj_h-~C#79<|k`&hZqV4{QpOz?evJvh# z^d)jBuufyF^;H8c*3Q|pBo4f}v`QlyPA&Ax;rliC_v?Zz?K7Ccz~bJ7Y*<2gj#pfK zdxXv9&)uwEOji<+tdsNbYV!ljaRhbi`|6nwzP_0d=m8b1XHmD^=nDUGp9;zvqeSX zLioF{V&H4PXV>Bp2jaUoC*GOe-LECCk2QgP|L0he0LI-{{~Fz+ii((l%mi4%m(*Cw z)naLm9hhhIO&aEfH{UJ>Z8ren)xbJWw^^J4)Zrjh^6Jy|wJ%^FK(q#n3o(ryTnFM0 zU@!{^D`)JIv{pX#P0f-~<&elx{fqDU9fI={5 zQ$RW_tX}W6_WSqhy#11%^Bl9^!PiJO-qF46RDbx^Mlsq?)Dp!>u3fgBq!;q;MP~NS z-;SjRNC;qzSR~HO%y3Ml)!Y zMW>*8uUAvM>`>R($mc4sMBNSF;6N{+?sBP{7jbI)QFA(vh4+_7RCOWLWI(_(CN(8R z%^opr(~uAS9UUE=|MoA2Gu|T8;5(uH_EUPM8t_7Yl|dhBP_*2pZSLkK4ya}Zdmw-G z@FI8LA|H#uWG{m` z0{{`a?9`(Nfu~%dO=eShArgCgdus-rxO@3)>tq~(;&N`CV>aMq)%4I%LFub;ROhm6 ztsEX59UZ@==sj)6Uu^0YvDGC4Q$VJ#ZVB0mzkP}^Wd@WjmQvIdfD^4m|2WUaa{9&3Uhge{a+RdSKq&?p1j5AJ@^Z0J6@Fx&6!y@>#6-1~1XsFCn*3a61(zL}=_a8HTf>BC(6r6i)PNNVGH_eYf*8vV z4SL|obG+C7BuUo@9yJ;oXf@nEs=%&|;4rau~cl%sNpD2@ND9Pxd-c#wWN02h;KQnTu?7SG0 zZc{e2#hYZ2Y3>eu^lIb5>Gu|)cm<$Fc>II>{E~|PPy`A9sA_H=+}_@9B4zXb)3gg3 zPTQYD4*POWvD^b>dz8@RO@W6eDDL+gC<_24xwaYNMIeFp0zh2w%qB>tfc=1cR(*S2 zxvbw)e_L=^0iAJ=do}5{JkH%QVFh-`0}{2g3Ng#bJn76zb*%*?zyTin4{XvCs$eatv4q$OiSn=H4CsM}$qrAC@d!%W~W82G5ndo)&Vz+Os`ro^8 zEUD?DFtUj8QT4YSH$=&Mu=S{@!12x*$p1+lqbLzFQV~g2)GwL-6Fg!@KKKm*_2yxb z7s|&1*b2xU_(oUn@8Ibf84o5QPytwp&_fg%Fj$^cDU6+h&B>FgN*axfKp^%H4>ehd z0H`WlcAyJJb?F6V%bHy+S=(W*{ih`P@B!Z&a~6FlM1DG<9C zQtOnky~d+!5@+nZ!x_P+c8yYt?cL^b_lmvzL-)%OB4K~QyJXc)C3aV!4xaaalE<;Z zoBxS5o$+d=J%D_}VXMHf5oWDS8Zsv#BirncCIij% zu@9ks6fBWJl)X<PZX%mEm;+aHz~&DJkt06KVFILGV(XvqG`mq> zlO2QBOM)*jf^KC#!ke!e%$={8<24_C2=)Jzn(D5uv6B-nkHaMsFRyf?DtWflO(0qr zw0p*bHd4J7ZogQnwo)M=uD}wjHIDT%Hf8vuySqD3)j=1lX={swdbtWw2xVh|#X(R9 z8qH4xQ|1U>WFH3x-B~Dxvn;Y{QEQVCZt#z~LY`8#i5D+Q1%1<(Qgh?HFQ0`@JRs2~{u?mh85`d3?l+^tFb+{sRiF|B8Y@HV#7HPa$Sz*F7fNeZre$ho7Nl9` zTIB3rrd2Sz7Z0%FQf!H}GjN|Z%Lss>BohlZ`e00WlDDKw8Gzj>YdAm4oNbcOl z^P%K0Enpb^TjE{Pk%|CYbR)S3?hBwIP#}QD1X=Z;Fa#RR7sqG+X?%SisH<==n+ag< zy5?q*?NlV7&H&jyEV&syp=&qme8b@LME&y{IZGjxBRTYNiSa4y9{^XN^uff zjH#jhvu-(caLf_pyZ2MGUAFiQv7tWef2k{Zd>)Aov>}few83L`iB3uw8Bsl4ZW{mw z7Qi-kj*h2`t9L085on-G09DyI+sXK-XY0 z8~EUzb8mqd>9%FLDITzu)3UPuP8KVJrISAwx?NnlDvPXsM?0tesf> zO$Q|CVh$rZa(2-7&UV8Vd%TDp=QSE>GGGC;~aRw@L4Y&_fW0!4jIK<%f9dqhG?BT;!;wgkq!{^oq61 z->{{!qz;4c5J*?RI2=3usj>GVYM{TL)v2%w)db5&N$lhbJuZTIxx|nL)l$^JppDQ~~q-6|5${3%O zfzsR;0e*v=O~`{H`k+Ms>k`&=F9w9?va&MbWl^B-dR9J^K+np-BdQm7a%;+uy8kU8 zcU{l0d$qSe(ZmywJU?xq@Rn7S5XN~9T5PYn{{{FoWp_+c)L5hf0(Lv1w2#g2i8Uuz z9X^pMHrI&E>7vfxpLZW??~yjadGtgB_7o>^(^L@(c{4VrLyqFxiRxlv0-@wbe-py1 z`|e=RIQYc+)y1yEGx;5YeFbGAXqXrVnRH$z>*(oi46}EcgHjBvE}`u0htnS592{Nl z7=G*k5XWQ+-(X1lVz&Rr&>lZ@ZvzSkP(#4e1yXx$W20R83@B?82kyJ>ZJs#;Kuw&j zG&J+}&QPG20wni8xg*pBCt9wCbuavVk<_s>&C$W2B;gU-w^WA&-S)mg;;!yWB1st> zsXVxMZ{uvuu&m}V+-lUI_^cn>TE$4>pT#AhLMGrbdwl?Uv<|CWhY@r%TNogzqxCQ< zP$oE3Ph~wG)@RNu8@F#7BJxGSIaP05RBa4{Qc9;TTw8N~NEfbWdb;qZp= zC;0|QpKQf9x=$eKe-3N$Qn5Ej;yECcJZSy~R+ZDQtFc z17T$R`CQaHo9~@;?W9_Qy<9bBK!uMC57pb#i3W)^E#;w2P_+PT0^&0tAD`#VC9sf% ztujJC>KgoyUISe?Ju8boS&8M%2?PC+#NoO3|4;~EEgw`}t*FlJ~$~|T3z81P0#&K8gV}cHyKnIIpi*?#vd35^slpj(ra5}?q zkV7}~gfr)oeG4*`dDsjJ`TT>l*J&MiVzi#QgXgXsgY#sHr-wK~D*UL=l$GeI*9U%2 zN>ofk{L9WTb_C)ZDr$(7)5@FjcOe@sWnmZ`~1{S>E z!H0EX)bEs)dlYBVl%4@fBC~yPZ&&+B;Re)2xfE&RH9{PXo&@eu6^VnG0w}|H!`verD{xte6<_|dsAzDAZAeJnBT*s<%*LvDbbLp*uiT$*-|~@-d)(%HaLwV~g6_n~3%ZVmJUttR(6&b1AeM=BlA9 z^>HD5WN91w6xftS(j}&lCJ!9TtrsLOJ*dWD=t-0C`PJ98b#?MQrioNk45A4K?AJy6 zj`&CxRGtP(>T4}eAQaV)0xEZPLPOcEDO07a@-hEji>Z~$kDVStBKEwRD`R2Gu7+oQ z@5}N{rcQYORmOh&N75RDQ@za9@;)-Lnx448-U45BG6i9eIj;;5ACOdl#MGd^DP+8(`cl@!%r;@}tW` zQNPn%_*FLw?6d>>J`nDMxLFjx!@q~$zx#WCNp&9tXDc#xReyLzG7p_WK>7)qNfnvN zRK&Ux=2+tA-aR*~>2j-9Nv`BwA6y&K&8s&?ZGMERvroeMgJ`+sdpZqg&DIZT`!op` z8-ew2ad%>nc79C#QsnGw(vJXc#tw&A_Ri+v?LU;j&jfQbxr9AvFbJ^|wUl1u1i^Yn zN7;;5yn^>h&7GgoHp=!kqNaT5OsW?awZRNi8*jzvxq0B_FJNkrfM@a`F9! z85XmbZ~bI(I%1xvCR}lBcHT-p?g?8YBid;jla@_}T=omm-Yh8BGnUhme%-2{$ z5x*l~GqzEXJ6LZj>`m7-Rx!|sn3CW4A;6PfqUoRyC(Xz#ty zj9au8?dYY>VV#nV4El6c+~~fEdcVt-DThs0(N-gI zj3o{pT6d&j4h~FA!>Jgpb1Zd*Gf`gAF(y*ZV+fV8l8E|-s}Jfd4e7Dd0V>(+%eg@0tHYDKrG2-M}l}uO_h6-4iC`_ z9@1z)S>YEKbE^-QPpNISeWpWGWKsfvvS30ga9w&gkE^{ec6O|oRrFHa)=X~xt*$=r zJ6)^BYnEjamgCRv86vbYXqIxmVvCpw)0v@_QVQl6Z!r%Hv9z)pJC+rk2^w8o9zBT>jqww#loa*ySZ^ z!<#5`mk0>YNGM-eQi5KC%(S}~qMtWQEp@ERz|_YwvgQV9#5;Y=QT&ISA=_`YLbM8Y z9;{$r<$DPpK@Dn(Qt9#o9Oih*cQ8M3)S00?2`tSGD(2LV9OcqQ;kl~Zs|mO-X$4U% zWmWB&=hLy-ntdcWdgb3S1$(3;a@idllr!GZ;fxa@KVmG0wn{lvDGaBsWxcST!-Hvy z{dcnG#c4QPF@5raI?v)e*iN%oPaP0cU*X%Av==UoBTjM^Y=!YyRT;UFI8Vk-ziPdN zTy3R7F6J%wVK9*S15enX6Os%oRwc6j@reENXDnwu3s znOi)V+&c%p1i-r+#{$IcM)a8@2}9<9BLS%h{7<93nXY!)+6qV1_}dfR%@QQg66|n3 zPrC}ub9xW4o~M`3^}U{qB_3S4B`B|dDu=;?Nz?u99Y+SQslKiG;Z2Mhqx|hJVXdl8 zX{H>R#1lfqpEt||Rd`Q=nqM%OT%hkN(pw>CjCbE2%F+NK=sn5;WhwPKIy^q@=LJ#It9k)GAAGUqJpH#xO%_w98dn3`*v$-jwlv)%vGZ zu9{UDs~)Vw8bVP6mh%3A9nOUB$vkRm6;zRdElyExe(B{&-z1wul_F09=Bq#|*Tg(e zjp|?M=!i!_%Hn8NQqoPVT*uZWn^bx7F4Nh}_qug+ZmiDkC^X1e?rO&(>=@`q`ub*W zZpjS|yuio+ECOWP0Q(>LpT_m@u4?J>dWYWPh@c#}lMOflVF{QZKr{l{=S|Cu4Q_-C zNRxmKWxr_9{3!rPc(n1R+Mh@JKkD8^CrTZg?hw!7UIyhPZ*l`jMpJY0 zxp#qfqQkA;sH!Us{>-8f#3k?+m+3p})UMZwd6=NqYGa#!OLt_ie_DKkJWvk7aU791 z%*MY%sto>|D1+@Cn^z^mAA&t{M&!|&?q%4U@H(?yh$ z&3-K}{&&=*!=D!Tr))&zaIYz@#JIE2PDbeFRlSg*Uh>OMC~fiI;Wp*(hXfN1bZ!lZ zjUrefT0p+7@0g0QW)*+L9A77ah+q5Aogb#^lq9!gQ=DFc&g9QpI)QAyVcX#%x=>!TSmQ6GKT{|`Zfw+D2*r8bY)^Yim@vRbf-?D&p-bB~XmfPx0JXz&-XiPE4` zwXAlFjDX0P7FlN~MQJe`nfCthFRGkU{kYq=QXuFRabnxn+n6%6a<9Ho4j+f$cq8#V zrD1Sy34T|epyMwCcL-GT4({JqwMlhcE2_P0tvq=TGy}&F$+iWzAHv`HFv{}(O0&mrXzP6)+i0t?mrjoX*Y}mY zF<%XxubSG`U`qvOvQ0tA7YsFj%Sr_NW1tFyAp;Wm8XugU6M)OlN+dmdj^6;UU2A2l z+%qLX4n2l+>4}ULPVEBE6(lymCIVB=8}y=;ilvG*^L1E(UJx!rYmzev5d+i@Y@x9A z`CZoxP*CXc&_WapXAxtAKXkHYo!&5a4xbrEpcR=+s#@$YOx6#SSdSVo)-)=Zow&>1Wf=rnPs@2Tqc%9~F9M1`Xks+_FCHjUd{+eIHy-nIftbUT_ zdz=~Ul1(^L@|SpRMtwHZ;r11Yex8vItaAM6C0@tKqrcz%yK;i4dg*{&R@cW7#gXt( zvAgc}x)?J@P7d2v&G>Rwmudl#}1HBQHO9rEgu-(Sji+t5Hb z#*ROH0lCclM&rBi+)65-fZZYKPA`*@540(U8y^RhWKv^^T-A48z6ehWSYt;1G9CP+ zWas@Na>O|D^v~*5KQ8+1KSMAS1x(p>|!xPGmq zNWV-MW0r7UqY>1gajWJV1U9@>uvE#T)=u-nKbwbYnYDD*=k#Kv6k|UUpBRc57Y@4_ zf(bD#ZhJ&P>jz1fHQT0&**%~-*0r|&`t|EM$YueJ9QY>htBf#DmA6l?s>6Sk(}rJl zs+VbP0G*PRl@-`4SAar^X!SXVm5Ii`v$k1 z|4VM2#f!uTNK%Ez1;`iu+AGswUgK~qCXSeFWO8!e1Y-N!T>tFLelt8<><9<({_n|% zz+ww(91;qYj;Ve&MTlygfqxX4x<+n?q_FXi7uiLbLz{91m#xQtn<_yJ6(gi_Z>iZS z=>Bf?UKq?{DghDg$UcB$%mABtG*!yfOLtFh<-3We?+@a37(N_RGvOLK1 zPI6Wy5$$J0+0(W>4d{7$mqysb1oU_{bhKOf8cgAGtSZvuUxhy%&71JrNwF)cqPMfi zHfQ6U{FthNQOt{1`pckV$o#m2T~k@1Y~-=~1{U$1O#%e%)*qE14M^*-;8$&$YUV0@B!0 zr*EeJb*Vov38pXF;LGCaF`3?!XAVb!9T2cegQ4jvFnx(r4>X5lq z_x?NlelVH%VLlaq*A*s^Uco*(`JeQaBQ(1PrKT#{6aZQT5i#-n++5zWLs%|wCW3Ju z95>21aDD=4^(+MRLBHm^8>0WKneSyEX)_ayrAoq-%E+1{2%>cY|IG2sC_8>22KBEZ zPDh`%@tmXsh!J1LukUVJ*(Yq@?c2O)Gw6<%+hxEz!*dc!N7LhW90!M=$kZ=Rb-pRB zKMyfgc;d5TDUNsnE(0i<+65aMq&mXwkKecxELYb=^`!P(MWElz=WcTz%%ShMfES*H z^&eCW!SSr&IWWLzqL9B7%dQN9X2?6ADegqZAO)KH?{0XB<*ZiyeT@~vuQ82STkVNE zxTC@i4MDdbH{(Rz75ir$v6iRlxh7hM85{&B<7&8rsuCBVn5=7(Z$l{wH0+0|DS2@` zn=2Q`wwNS#XbJQi0+d#R3Rt?Y#MfySoEVbjQgfh*V`*ujq4LIGA(RR%Ajx$D24$mw zYclSoN~hML;`f38SIa0Vwk? z0Q{8^i=i!N5W+RBApt?j?^zV#ajlh9$1=V%l~tg$723=1Mnz3!wMcC> zctjjJ;H-Me*zIw;d!a1vQWqiR2bGw)F8E>(+n|*NSc?7h{gin)D4=%tp>JRgZGiFy|MElu&elk4%7<<(N+vNt+j;>cSQ$08v9rx^5 z!;@l3_xgm|mAti6ZFcI%C$B#Vqp5ha=buEW9;b!Im_S^Rl~>^{{`X=J@9Af%u^(tj zf91umaY5Dl2ueQix=t^T&48~Yg$iOy4|k8iIuUGzg@q=5Lkjd+;36k){8`=BNxG3{Wc4II0cptUH zikzLOFPdT39KD`t+bULlBAV$~<&~W=TFUdja=_46K3CX~2!&SqZYsY|t^_L+GW%ay z3{_zH)X_NyMNp!0yyhk_K>pY&QMVUnhp)X$)Gdb+_|aeAOQwkYtR6#@;YAcawk;9{ zYI2yYD{_<929lIX{g%>&J{w+8(Rn>C;Tet13mMk{SnG%5q@5R8&8VU;`%LasoX*16 zJMkc618%;qs)bNAgRA2DE>)z+?C`=s0o`BR~S~IwMcd%LuoX4g`hIEyOYh%Fa9C-loz^SUf_oJEexk(A` zr32b!{lC=GZ*3BD_CP##-aL5znDuSpi;XwvlEzs}%gbB909oIR6}JGMr*}sT4DraM zhI$o_D+NOR52rj98f;Cr_5t(+uTPXV=-+D4`aE=(^d*6D2s^`wd+K?|^YXTjO3{2d zOf?wU5TSlMli;5U&lky8ri9Y!0HFh!Z>8e#bI0Ef;KLW z8kK&zbEBl%Zn@JvV;p-7XAamS!l>dnq*8(F^&DA5+6_ogiYhnL;YYMoQ>sO~e=T>S z)Ygl*T@!VeJfE+|tdlWzR*Ii9R9FC5ax>u~dhrrd+x?ea>Rx>oC7wdR9b3%Dv=_s1 ziZU~itbpwa{Ey(#%65%M7r}}xtpXK#rKYe_iGoa~68r|;jH`Fs^eAoOeJ3~vWzm8| ztRcn))*FMC891Jr8$M#KemV`ps8?7=BKH!k6lcvMM;1k^IhEGF`L#^Aud!7nCMU5w z#8K23Ei!vwXO}=lYjV7W{LQKBFGM9!q-KNAH}NklH8jp40dSdSkHQ%flaHB*J%mgF zZV6+*Vt+yNWT~G0(bg|Y^zycLAFnUUi7j+F$&#M%D!=nrpl<-Y5kRmQ9K*=kvsuzq0uMk;f5E(Ti8@u0)5j_F>&J=Rmi^RMH+S90*ni+&@LvS; z&3(kikZyMWE9Hk15v!~I|I%`x`Flc+9p^+3R_c&>0#NZmszbUyIj-Q6ZS6{o%;()* zbF*Z}@<&tG;PTY|8rLBA(w+;yh}9({iqW`$d~3ZEKUFo#oT=_UJ$M0Yr~gg`;Rb z`SLVH%zrmYy$E-7T$3&EED5n4INEr#WQD=cC&ezRW=S8*oiGs1aE$S^j7&il-I)1X zn?$~6i?txdVZ~u>b#3IwMHSVk_^5$TzPUCXL(2`KhgAnoE`EW^iG?~PdKmx>g=C-+ ze&Oz&gy5A#&U0F|v4ygQ%kFEqV04h7@wWImk+MvK%pRj=Y zcq2J8#AWA&kcQ08S{1bjmuI2fZo=2~{D>Z3+t*=Zln%A+`din<=udv4i&Ve~ zuD;xxp(X!V8oY5M_hUD(90RkHK}9Sxym%J*&{6 zu@(PFTbC(%(>FY-Yu=PwdO_lBtjA%(k**zXewPc+CL>CrL@W$B&^G`lgIJA|6DLIR z;i~{1q{^81W^4|fHYym1dogSCxJz@qdO2Yrj8&hR7X5tU_O|nz#%J8`8<@BUQ4o>0?%W{*?UG7Xzx$oql{*Q$_D%dLy2I z`hv@nkZISVKk$tt^{|&-^lx zCVvy<(Ow9zkYOx8lrbi`QUUaJqmTd7ygLbcF>-g)q^D+B-h&GML4P~Hi4KPq8@WMB zHN1zG@9dQGSDsb0I5kfw%~IGiC*%npT)*uwqX_bOzOM@uNALF1)^rpU>t3-mh`Q2L zM+f;)$4Qxz0QBKdMdmGr#g>QiY)Eo!to!-jutiF5U*wz;mZ>e%TItEN_%q@ge%dH>q&PqZP9EgY;(d z{nqr!JH~Zjl={tIqTJW^r<-JTH%CEEAomS2%AakDl}b0q?RZ%ZQ|A^JKRP<5dUyO< zy}!L5070?KI&s8XM)X7*!ta-(8us-qZMBis@|UMn9X;n))*BOp@%GNU^ewIl<|6(6 z5WiS)Hix62SvH*51quHgy9PaQS{TfX_yIl>SUE)oY#>T|xdQJT@V~9PPi|=uWF7X# zEiEHivns*Ew6-_VbZPYJQy@oWvT)Vp*i5Xb9o!Vr1&g;;T2cItA1-hn=p zEOIiE;iv#jWNIHh-&A67T1MQ`HSY9qsGjS2p9jvY+p!3C4~H5#=EjxSt2PF0_wuD? z=Xmk^^~I=Ii`?hChl}6P?v6M0AuYAiv=&a*&RQMez>HtD{%=Lmgzos51xBN@1Pd?02`ZtakNjxy=&m3;r}h zcOa!Q?%=W0Dpm=lEABlw|D?yO7yUe2En9rWulK?z$YbRmm%Fa2knDoHYEe1*bM`I8 zML8DCAbTr}zX~^2HfNOcCDO4@aOSMVJe&6Ai2us^ibYsU8Cp@&&hC@>q+YnM$k@mB z#p0>mwR(MEW4d1`1EhcV$s<)cTOd7NahmJ>@i)3--4$j{5AU0yHb>{vfBW1$=fODU zZ_&h>osthsLxiy@ooI4RUZ#EkSu7N6%HWVzko*A&06-i*>OLH?#umSc1KL-Ep09;C z@@X3ukuC{jv}?D{@>cjaEazt5>*Sq1dDA0c(~J*m_SDgOY6q)XV5}po9Iz{(dBXO; zEhyS*)$RO)cCMxOmy+AlP$bViMCAh3=Oc%Xf6qHB+1)VP#u`P&dEg$ z5Mjn~B_S;k`P3@9j}Gz-9^h2g2w1)Q6LeokSitXon>qaG4bf-rWQ>rIU<^)luhJlNe-B zLQ7ZMMpti3hBmY#(rZ{7pCbU{T{W4;_^OcweyY$gbb*+5-efM+Man@@7Q|0=jVOAN zBmt3~4|n}{mSL2M-HibQ8z0mL{De>P0x$DJUT@(G(gZD~DnNF_azcVuV#G9H0Mx#S z2=rakWyVtL$0ikb_6rNN?V`Y?+nlkTwCBgBBI!@7HRhMNoF*Be{#2l9tF*L zt$~~t+HIR^;o00dQsr>4Irr8o!uIkFRS!G@kucX?!+^JoXzpNh80$U|bj{`ytDYXI zs}l_zA2mjeIWzpyrf+Va$zN$ej~jdB7V6E4w_Z_B>{Z{`bKo{aX=c1G=}qmnM?Hnd z{inyKX&z3lw?)$E(w^n>yzfeO?K~sNgUX3Bb?y4*Y<3$TUn)+Kq1ox`iEXCvcUZF3 zzT;8V{dE-}KN_q=PUO%*u^ea(P?a7A!a|DW)sK8}{{EifdCjWAtCRO{$n@RVH9l)W zZiDDi@&L*H@c8@V7wjtFP%XOsGic%7b^Iym4fotVQY7kW%=ktl?DF0VP4*QqB2=`%nIgGY&Sk zb(ss_iU8F@e5HJ|gdIlh&;X%olZ$%K&9%GM>9?=iR4UUyR?0~?@^F+ z#ld{Nx=Yt0BKKIC6Yf=sXxzMei|t0WMRl}5c^t^U+OcW2dcT&l`WJCnSo*nnD!20W z>pHHk!LEANsHo$OL7b{-j4<2KgahB(4#aP00*XUAnszz3kTHEz1xDtx<6}k;N-pgD zxiGav(B+V}d=K*%-FbGW25$TS7n(U2MScAk325B?-QTD>CSxD>GG(4MyuMOu9mp__D_0SmyHj_yVWFe<)O@j z;=zPfRdB&J`4Bs`Uk+_P(n}k>uG&;g2$dOOmG-$vmz=G0MiUa}wa1pl{AA=`YyBZe zwujZt8_d`kt{!uz_i+>?)WOvm9fH~?vk8yjda;mijzv849~y97%8v)v(1D$5U5& z;qz+hQH{LlHpOw94+*TUzsVNi%TT5{N+Je(-<3l+>Q@qV zv~Y}IREWN`b^P)Q+6B})I9LD&zZtAi^yj7Aq@chTPnS$%Zq?~?smGFNv8*qNkC zDf{FiJ14T;m@i}380nOYzfA|Jd@b8cPX7i+oOD`GId+{?^0lP&?|(CpGf zyakWhOJm|umwx>fjP)z;LG&P8amq3-Qr&`1c#@qwOSO@(ob!qBJ{j4{pP@{>hM#A> z%*1TZ?07bpJws?|SM|U+5cfBnsINwdzaFz8IOY}w&&?@%Xuq=lxn&h2Cn5~>or%kS zK6K;77viZq5wzRF-nL9|JDg)5y~|b|H2e+y%P8ddr9lebg`0aF4gucN;R6C&lX^UJ zDxD`mn08DzOV{0ww#DY~+Ff+INNhCSXI4!@(_5GdlXj@SBo6ln<>VnrbkhIu8YkZG zJ6<)FP5Fwi;KpgjuukwXnXxC+BEMw7KwE+Br}^&1rVgrI5-6M|?^F3sBIOx;`I@Bs zon(0KQUJ(CfHj=l!u)fuuDl**hn42~{Q`HaDo!PV1TIjS#IGk}uLFN|TI^HXy}BDE zm_hWNA3)CUvKJt}E`94UMbE z;VJ6))-C;e5q0(PKZ(Qc*W!<51r&`x>E0j{Gi5~%cf`U%b26Vy=lH$}E)}IIJ6OIG zYw`%3Sy}XMI>0pWA!{5eyhDQL&|?k#{KtV^6!~dBA!IUJV)l&k)s+8o+G|NijWc_M z^Yn^;+dxZm4IIhef5*<7%~ABC5$^4@UfzIt_ zEORf*$R*2=w;fm4Pq4WgJ&3`mGS$nQ+LXCIn>K(zAuEh}&b@1xjB_)?5yi@rJj$6gf#{SS(sb{_!;E^i=cTl6U;D>qHr~hqcP~ z4L4FrMJW5m)Yw(*4N}1F)mpMg=xN>0Z0zS9ePmwPoNk}0(oHdY6~8DirNoquy?RyW z>n83=@K)C?Xuz}$0_VdPwdd>ouFso+>4W`LIiaY2^B~vSVSuG#4tK`Ry}GkOd2K%n z^M{EwLyUl1tly(?y9V7wt3b>elSgtC7V(IhfW9-;k4{eUVAkdd7}yyPJh_L_6Wm~Gj=KN#TjVb`N1_++ehyTfh+wzfeYN*+ zUUWb7nZCeAmuot`jfYKrS+}II{Oycu{1X zf%c>sTy$O=S*sR1HY$ShSRnJ6lSGqGj)$S4`^Dcy{@OeX`GIfT`|xEGH{ zJ#vOK?o2i^_2zcp!`%mJu|+FglqXF1%-^AP_&8(fVWp79xYN-bQ<~X{EwwN54So}$ zL4PTn-L2XoY1T?(3wJw*6mc#;ax<^~d2>KWY& zEg2dX@*N$O;byr&oNkF`i5*;AZPM~woLMqofyfL{Ez-aVCoq-9GS@c+l(I_0wtg@( z2h38Zx>-X3VPbnsnj4|pmK^^oV`x+CE>aYuYPDj*>)(mkEKCvLcAewb!0p4i!*Ji#?S24A1!r_+y+8NXgvLGZ&NaBKZ}hJ13_-x@ZJMjd-vT% zR@NDI-cCDD`1ajjIGns|#231@A{rP;yuQ*gYLAIByAY!H?^gj_2X`Il^?WVwy<*R~kwcG^XnH|sOt4q}^g|USr zmkA|JoaTK_^8Ky^En#i;u2@i&(kG91(wms8WIpK%FO*r9#gDtEXtL~RsT0|sgTYv0 z`j3~~%4H&PCZS^{kj8In<}4IGpH4j=f#VL4Jvn}&s_#FOz%*|3|D3rPji;9D?iP{72yE9{yzYoAQ2 zJH?AL`kwLj-CReb2$#$4bM+bhWD-b&q3`Q2k7^OHk~qG5OBbA*@nQX+D;x@Fv@@|sjW&A5*qlC?e-6U$fm1j$(7rIkKw%6`?{bTsqRO>2Zyp_Hf&$=kyZ9Kc zJ?jNkw-of)Lav)K+b5eJl@d+?Gj#qpHwH|^$|(89mSo=oQy=Q_bC2p?wY*Am)XQV^ z_tOv66MvkNntC-AMs;$`lnV?Vflq6XnAEZ!LO&0+2dJ`KoSc$nTK~?iu9g>8`(TH4rGV0>8{^Kobj zx)sx-l<6scj{;aac5PGPdkl}Ez(I$+RMiA*$q#L(Lf*L}^WhAyUy}Lq4=&xT^P;15 zr#XDxJ#|)IMHAu=NgG{1G5u1ISH}(0a1!;;011{hinlK@-Cy!lyk5}9Q0)Tqp;T*Q z@=K>IgoOF|&>hSytr%SSo?^j_VEka=G|Dd#_%sj9&oBA@bok!r+d3Ysz zj2WzX_+Lk%4!~onwtw_i6HybyGv)lpCm$(uexKhk(9Yh@>Pfr%hqU^(SVxPH2z`X$ zbcY}@p4g;d`2FPZxb8c$)C$M>Hg5sZ0P4$8gZNlVDWl((yLFr^$Pi1hp?yIi=|7^L zFe@Ijg&MPJB6p+rmNB_GNA(`hP7Wn^jKCl)q5+oBnoP)?in(aKo0kt}gHps>c{qN^ zV`$~_`u*)S_RYTz^)e{U)~^NR;qtwxKT0Cv!XxWLxIdXLf7kPd)?7bg|4l*t{OPvi z(qAfLV^dG7I2)D%LMGO#$|)!^uTF<92s< zDPHSYe70%n<(9v|4SAev+&0p6vu)^ix}uAW@=^e*Yv@?r+BvGw&|6kG^&4!q3!62t z(77KL`rroI$(KIr!R-nsYo&kWl2&yltK;0_YD6L>WrZHd*CWzRZIQd?0r|krh$los zw!MD!x-R0UkABLt&wX2_hw?j^GA_tb4ZfDnr-GMtkJn3t;l&>F?XimgYWQ|W`CC5z zp*{T^;^eKL=4eg*z;O?ja7pE@+7`*4K264BidAv?V4Buej+rt`#-oQxi@|O7G>Rho zgKM>tZ=TB6mPL+!4n3;1wpGEwr2wZCZGIhHN4x>D>A<*K6giS|Yz{7+d~Ft%Jc9WE zj_Q4?a&E0xE*=ftlX^ij(Ts|1BRUKlWf3fLHiUA>U(58HOKwG^`>MoZ*VO;{;8oErSEu-hoU)wD-8`$tJGt9N_i=H!0=NiZkd2Ga zxTv2b3XM7WS1=#7s%9YdZ|xzrC!G*0w?-+NV3RpaaBCKU$OW=@e_E%|psA;aCEH;8 zqgox=T48>3e~EDTatr4v=dv#EM=^i%u@f=hzEoLWi@Uk$7S=orTDx&yVa}_Ygg(Dk z{4C3Nz8%sFkrBV2X1-Gsf>{fzCy4*?k~gP_-(@>{OCIUWV)~7MQ&2=fSTQ`2Ac*G6 z6D5Z<~Hkh`S5!W;9Rrgt9C* z|2Tr4YBBlC*xpcYX}&PaqhONRI{CwZ6HTK?F)EEi)KlCh-DDVVCB+oQ8v2=7x+g!) zCE@T_X8+%YsN4MQZ7>Y6DOF zzU#mr1&tHMEVj0L^&3gf#S6LyjF~+XuC)E8%^szsHI@Ncrk+hOEg7P*c+pmTi;M!B znl?{WkDOmBI66vRvXLU9`14)Oa+&Cn5Q;tC;mOebNCn$(8nzk{V}jwCQCs3{Vc+k zRJC#8q9Q~VochFSR4LPXCSsj1Zo_BA&mX>sxlqBVxb&-Qp-54MoC);WHp0Z-`J3o@ zrTnj0#D1Lb657AZFTZ zCEHj^F&TS_=RUqY&-45H_t)=t|LKf*ow?3^&bhApzCQ2I^zW;8da-wjJI3>FO=nH& zE}7O@n>*Vq#fSLU2D|@FjWn{9TKn7pw4u1xusmy9?>Sm;B~)t|>Un=2Ckc}oMn{}n zTxmM`l*4G0PK-f&Y5s;+|CJ`((@Wzk`u(k86yTJ%>9;$})9DC0(SGg6nXoUyi(-CC z?Ehfff2l@kE0(i#;Q?#JKS=w#q+M!Wr)WC4-8cQ<7dNM4qEfzda?$6XqKCbuij=B3 zu*1<=8+rhS;p4_C^uUgY8MUEH30nzVXt-F3LgK~sJeqAQWn{B@1n5m^@Y8pIiRn4^ z>9xaMZpF76a|25U9jh=bDEGKRbdo?@P@#%YVNeP2uBe2;J*O(b=uE9EnPktAG_Rn` z9=O^q=i={?kQ0RvDs1U1EOiwVC*<=Am8xFuwfR*31*K#&VQ1$QQhX`8GMmk;bH7f4 z`-8*^N%CBSqk;n)lQZnq@Qwa1CU2JI5ARb2UGHCE<}`Ak`RNEA=JT)Ev|RlCYg@O| z*8$58>Q#7OW&*gnPoBzV)$~P?0KW)epjb&7TiBQ~K*9y@0ea}!-IHxdPZ!T_aeMaY z&5c8;jbpVyk;4$SA_eM>7#L}bN6jdeMLuZTb6{9Lvot&% z-TO^+evKqUow?v1P)^=Xa&FtDt`aj>R-6=$AyhRe{q4aph$N4IOnOSc+ZVFEm z3!|hyTbJ4hiasYTjaxGn4Ap!^hhYYtZiktsc~aA=;$~`xY6G@IbA~Zw`&R)^_|Mq* zYRSf&vLrm9V})5S|u)aFQR=5 znku)^e?x17Nzys_NTptL`HNn824VseigH#$vy<-_@)rGS{Q|L}@U{N&6uTFJ_aDwg zZ!266iO7oP3c+b862`vxi?4r^dc#s;(B0iF0!l6`J-sEk=CjTQE90#O|FC%!UCHEo zRMYbqGB*HT+BEizZOa7(o#_cU?_AskCI`2lY``z#;bv|bF5RmPUfMc2lK5I3MblxX`DsGr-Rx;O3dY{&pcWgme4#!kole4 zyA)IX+)@Ih4U#?sO7o^yvq8fMd&P@!$Q$aW$i=AHvUL7)$H$3-xB7k%fG0m|R! z!CyJuiP)L%;|)N@LoCuFeXHptf+U-eE(kE3PBr%>s8usqa*Axn^kBgm^p7q^AOnV^ z;<7QT%s_<-VRwCfjVqcD%i~ z1mA6by=lIVTx9y|A}kBWCb$ZOUWtwu9? zG}=6~xpXh7tmV7aCnirbF|P=t%*%)4QMddk23(fUP6<`xF1cAJ-2JTkszK!pSrmu@ z*9Z&jDVwrSVCey6=I%}pdUaZIGPnTUVi%Ahjf*sg2tu(&Z~_Fna`?SuDQeK25xeV* zivV70`_4zaA81JceMeFBCLaVSg~Xl)cl-fs87M@6#K;wmZj&wfPJeo@U)5OT(>#{E zG+Y6BM1tqpG?q-Ae|=E8^4GL)LPhNX%vwjM=^RKZd=Z#%$K+?~gVIr{0?XDgZrBHg z#Br-NY-=#Hx3<>?!f^iZ#bzE}zG{DJkJO11+B@gZ?99p^OO+mJ{d%pDp<7P)ur@rR z^bw-)>1*R^dW~kjzdjYVzO%Wn)%0uItMPoJjT;)B{o4%KQS4I;Yh3R-2c8+%DTC$ba_hv(aBt{u?qC>qb`+6{iOn z3uFZ!+a&YWAl7{rZ(<}PIC2Q}nBwyCO* z-H$m0IMiT#DuG^=yf4Q&iMdRA1YU5k4L4g$f4%2ybV6;mw5FM)rH7)jKAE8^yC9JoHnEmulvp$ zAz}kQHy`P&bATWr17_*L%}whFO0C7BSlrCa%=dlp^U@Ue)(KN<6u-9q#&68n@Eyg? zA@$!q3E8Gc5CH26pvq9Y>WIzbva*P;rFqoeY}iHRj%j7TT>(mAJ8^xcj8};Dx&Ml~ zfoFE-?@vW*?TaRo#Yg(By}{)aDl;ye1x=7$ybvE2vY(s}Y+17xKZtb3V-RVcqe8mh zOuOs46bNbTOs{T@MXD4k^kw*!G`q6|T@RGRtFGYsy6#g*B~( z@*|?ZNTecA&$MOiTbNz6UsN?B7k`{(AKQ(uBQ4%oN7|C72Z7IE?Z`89K*%lOT2TWm zW44%pB#w=*IqqZ#E|mYR@ynKk4=Nu661GZ-PN%s|j<{%lxYqF|V`#C&sF3n(is7?= zeSU+yoHdOAzlmZn?1D7@qBP!6ddc*>M|1Nde-fxepyL1)VR)ZJt+e_cl+)m&U zH<2@sls|thYx&fqcO=ii*Jz4obqyfIN{lYi9^~Ml1FYSt zjZCTT&yNI2Svl9go3(H4DGV)WHAu4XYIr!N^yrFEsd-fx#?ICjW)NC9@Jii_9(I+& z2ew#6L&j--w5cKlYzkw~%81nuCZ^l6#Vhjm@ze#3&rXfKPLQT;-!6;Cnts2CJ_o9MV9uzywkO| z!9g{g2MPq{N686LbHn=ank@4FxreVb1I<2JD^f9Em<&D*k- zUh>(=#Ur!0W-pThkB)o8U%5e#cVF(eWS|Uowxp;ZH%oLcQ1=*nt}#_0ZWcLq`$Uj< zf#z&ED=c_H`O;mbx-cC&SILvZ=p@vAgo4G&k8z=xp@HsexQI>Nm`!EExYdg;wN8zp zPy4iq?rcF$Zm1etN$3`;--R$_9mO+q3kNcc?^y<3S;cCzW2m2dA+e)wJJmx<_3Ueg@-_8U@T+#Mj|?ZbBe3o$m;8r3_QD2t_Nt;5l)kmY#-EOx zmVdC^8ROB=T)(?Qe9g$l)>V-RZ&rpSCc?Ssa852xmk$?2FP%zc6P%z*Y5eUHb||pu zR<$XxxJvQ^g|p(w_LuheZ99pig8Zl?p^kN_ti36nQ2bff@a%%|GNd{pL6QBc7mN*N zYG^AO;9O&S3W_#04XU!(ti1t$6~KdQo|hHUUr=K%kUS0-2!ab@t}s1Z)||{o^?o^( z9Qw>;XTjF`1@Y@tNB^%y?tGOUd9A(4i|~A2J-*UDV$Nv}I=XpOhod@!_KmK{Q(oT= z?s!}i`_tgzeCtv?N(&PMc#5>VAY;**|Dc%qra}xa^>NXrui{qWb=Wh#12Z{V?$jgbK$BV%t18#yY?5wS+*rHK~*g{Yttx;dguB~-O-XalW z286UUO(v{d_ujcGSxv|8XY3QF9Sg~%_MQr@@T9CI@_rLiUcMXnO+)}_vP#eb45*1* zLPOJw+NqqQGS}uNdLu^O-_Chm6f88SVV1bK{kB5u`pR_Aq@w+tfCsQw2D|e23JUmu zC&o@$>`!sfMt*?zMdja75MHkOvWeryF{oV|FoGWAbE~eqxdE9XY)xR>0_=gcfR2!n zkD!p%7Xs$37Ab(7u?kXU2%+%i4LgvpE|wR>PuREhruDW?YZ%;_jsx<->q)ESzu_v# zOD7|DE9l=V%r6Yxhg?nslzpe$7k|vW!lEN{7x1cizEYgG-sb8CdTAHKHPv5@`TO|s z%TQV7+ueaSmZbSB6^O~-pp<|>k_`MKQgcsK%T73jyX6*?2hiBv@!uFwXKtnh&V4Zh z9pIkk&q3V#SV6-IXk;b;Xt=$yZfMqd!*LGatmTvWSOT!RKq&$G1c7iunCZvl>Vq(K zXV}O`qFq{s8bt&6UFa3lo(1}OJDE7ft(RKNfCj*c=>g8?B$F7B0pAgQXeVPHh z*pq_9k?5WJ^8%VDkF;%-c)l1N%B(rKN)#}CfGqYO%U~!FMLG4iq0Oe9ckB3nM?$3a9P=V{ zdItl<3i9XtGolP3yVF18y99Vw|9jMzfv5DpkNn^Gr*i)q0pTg*$tY}4)MwbA5Jz-} zQ?_3GO;rThlo}^JEof*3E<34+sL$~Kd;;*s03z33Sv#~~HMz)@@tr~`pePVl!EFC0 z^g6h+=h%V7Jn4}~&3%zpeJ~~RV_g0mbE)x6SS0JdYIh~9i~TpK1{G2Na{~T<4eI~u cnwRgh-83E9BkRZS(|}>1Yphd!-tp$Y0AtXL{r~^~ diff --git a/planning/behavior_path_planner/image/lane_change_fig2.png b/planning/behavior_path_planner/image/lane_change_fig2.png deleted file mode 100644 index 5a87e43733520f54fd8d7cc000b9aa53ac77f8cf..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 74366 zcmeFZ_g7O}&^OM#)(avQih_VBH8kmn6a^`vx6lJpC83wli{g!3dhY_#LJ0{{LJI*A z0qIf#QUW492uSbn9xmSJeSZ0__5B0hy|T#3$=)Y3vuDqq`Rp0Ov^ABfDH$m#C@84G zD$jK(C@zIjQ2a@K^)hhBzvq`D@OIHd9;|;AXaQGk{sBJU^;9(S)N`@(^tN=jrFiM= z;$+M3VeM{f>+E6g;<G(1UXA{eb9E_PxI zxyH})LFUj}|G$-O3=j}IadiFWsl&3_gNYc{-7oxEKFc!ms{#OhXYFGWt@-xF^J@x< zvg>R@zpu?K|Ni{@(iM60)`j!yk90~Z*M8qNyz~D$|1W769e`+7R~fH|`u+O;T2oWg zd`|zjpaNc}ruh-FoF{5?Gz&LN3O7ys3)srp=X|j%D^4q`s|0fK@1A=hD)H~5qNp)t zWw&nyha0loQqzsp5uz{iWBlEt@qTyb#LevJtp7JT|4aLp&{-diyMIEo{x}!Y$Avq0 zXCnMpr}9~mw-V7yN5OF>|Fa%`-F=9>bl&Y1Z)EJ9-y^V(R)_%Gg_WSp~ zQ~IyaVYStujU_fx>@4wB~TiBG-RE*+Oy^E8RD@TIL5TlldRIEmSUk7JU1EIr=bC!6o#n z?+@=fb~>b0Tvz<_i|N!kN4^zU-b_kOM8216$M(k zeG}`t#+iB8b!C&KRTXs_wFWkJUJSgrUr?++yTP7h9J^62&DtgZz{T4Z25Oa$2d`H2 zzn5;Zv}nzwp;cC>Q)8jZJX#$wi9}YIx_~_EH`Y~rPoKB8d)qXf;NnSyjnHVdnZ?dL zho3q#@SOf27DOV0d(tjV9&d7r9(~AlFE7uT0|dVye=*5Ltw z?HM&45X-9Y_`?#^A7)trrF(lhTZdDf)vI06JNeBWqD4ux5%Mk1EcPW+y1M2YIWMJ^ z6nv*8bjxYjJ|z=nh$!K-?tDJ*5FD47Z!3nyqoXx?LK;|}ZX3;g%^JAr82R(0ol^PGmd-7%ix4Yj9xhZ@FU+IHcwuOL zP1>a)vkqJV;uGlXoYH%!Z|O=H+&Vc}nOIhkCBYd*wQ9;}93iPr$ga%_#AnY)?x=R* z%@XG4cTH;8aTWJ>-AiBeq-DA_M*aE**>=OC;(yBMN(MYY-seb@?#VALsIBH9tXF#; zqa0`6mg2cN0LSC3{R;T|^T$j3_S~o2eYUJe1joZTN1q2VwvWvCNd``jqwKko8WR5Y zl)ay|syB5T4L9+I@ZT|OR?oq9I{k!BnnUjUKQ<>=NQy)XT$ncEFEI>uBuXZvek-hG zqSM)*kb8a=gg5HWQrNr`Wj(${$~PI)T7yMx3W3Axq~{?;q-=f8&^OHcd3f85r~bN7kuQsP4-go;~po@4J*K&2CnxZuJ#*?(G~$>3HUhswPbBu71#( z!v4r)Lf{g*0%>j>c<%MQx(mqMx3=qt%E{rb?b>O;ts4tMCE3c`5%P+OR(YJ_;vv&U z95p#{Z#kQXG(zYH-VZtIBA#%YJ?RKhT06<1pFGYQC?L91Za+ZK+prZy8}#ILcRuwV zi2sy-w4{)Ev^B-!Op24&-r4aU+FuRk;V)HX<7Uq(UF4riY=4x{D!F8PPhLAxr`4xu zeN`{>Xr7BPc;mHrLV0rKduQFZpNWc~H&bx7MoYTuBgC&^X#@8Q>^eh|)?EgQsZkh(Moce zN{WBJ62)Y)KiQ;Pzh3}91*KyAZ~H&|iAcfoM2AZG`Y8K19fWDJ1e9*sYoXI%4>fSH z$w>s9j_3Af(X&!|oQNLpMI5H#I_yyaM9g)QvB&Fa)($(Cw*V?zEGtj~TKUvKV>*WT^cDX&>l*4FTo3WG!8CfalLmEFA>_Bv%+VACvfCI(k~s>U&z zRh5eVmZ0>eDCi~~JHJiX7#nx7$+PY&??n_;0W0cHi}>KGQI5}_X>N>ud&PuGXXSI1 z^TR0F{ik@jLtfj6E|Z3BTVvA8n$;CkL+Wg|`w2EMlSwn&+gN4ecn}O>H!pk&?rvvX zby{9*X3m^A%zWz|l;^WxNY4Ce&rfUO1YWrz8jWpv0KY@H_D@8Sn;IF3Ox3Mvw$-LI@ae7)Rz-CBEs*f=PL)2>z#{P15FY*G0tCx z%Lcv9t@``dv3GpH>$BR&hu(9cPgF&RxxE#Wnu{ig8n^lL!v^X<)l8P(d^=24Ma-tL z9&!`qa0yoKnmT&jcIC;~@k*cP(V_w->X2M8(B`UaDt8);BauP-o2TZa=_Roe{a z8d+Bn^=-0TUDsxVqjCQ?=UnbY8coq}LHT+3)BKhvYYv`k-m2M?gI2*>YK-WV*6YEjYRR17ZqWdM(@(v@f4T92TpSFf|xI3nUyr>A&=`NAhHo`wjNr~ zQ5-krg=(_n^({m=_?2fNTiSA>Mb!V~IP4QP5)W$4FCI6zkDQJbq^? zK>4s~Ps{J9Uk>h5Rd8v}L}qmOr0;}PM&mZ7VV8?cItd>@DjHw)(`+lLm-}Fd5nxYg zZ>TSzjE#`bYmtfa%C@gPR^c+;6>B)n`9Yvb{3-nvF7#FP0YVREmbfDHwqMN1C~hi9 z4HK1NVouUtYjfhC3Q&j`ab9eeJ9@5lN7jBp0}l2H#~VtC~GVn-bm+jf(2R{ zuk;AQ)>xZLNx?_umrYsW9ib+Z__DmF6E&H-)41rS9Vkv*oNhop*=7S?UVkG*KE6}_ zK^Y@!3`;=%$$DJ)C%Oqbnq9@*jY5~obg|iV2jZg>S9~uW1us>985OqMNu14%Fv%-EgPnArWCx$+U zd(W~#JUbHflX12%PPI<+&p`q2k2(~5Z_XiYXx89+tS7qQ;bEVJxF5~c6>b(zf>m&= zxhsEFXX`wr_sX2k6F6_velq>ke)VwE0X1oFXBX$Wslkznjc1R8upyW!${P3SwkJ>O zudg+Q7+_A-L&1tcAjFffN zAMKq-{;_Aq@W*QBmB7{qDfzF4@jLy0vYY9Ju5W+KOS%oF@r< zYDDOi{-MQDoe9BKMrxw}d;b-`hg9`+>ej6AL>e(KL!n2CU?l!66732m8Z~#;wcnY; zJfGnn{q=NuCYzTERh=vKjBIBhAn-D(Xgq&LXGpVq)*?`A?Zo>u!8vd@X2|3x57@MV zy=c_LdVpaxe{!2?Y;UXvv4=j@YWLo)xxg3Qpl{WrV}c=YkPDdh!Vcm{8RXsLVW zi#EMY}aOjMDUV$P%6b|#?KDL=>f3F`~NIpb5O)(C^)u0Rb)%rx0Z z*8hZ!-DIqxc&DdksOdDPZQTe{!W?Rx2l+gakIGKY%W$j+oY_#1HqCY*Em?b>T1Qpa zBw|a|lJ%ce+swor&8o;Uc1-m7d^qO?%K~iUmy%vPX*>8T!tf8NwT7-^^C=luN?+AB zbGf9~)V=L5SRKe8L%4r9s3o?usjyJh{jiaCa1_B*W%e%U->uZz-BemyJ!)9s^`oNd zG$?a8Mo($`!*FAh^KZ+@c_cg8wNh-c$MIXuit4sEGj*-=sKO^q_7WE?pCDE^lZJ`w z6AdO*AMVKnyIbt7e`@K|Zohn;Q)l*7q>2Bra+82e@O#56u|)xpYI ziO+`ij+U}XlmaefD1~$7E@$%!)wLx7#gtOQeFxl}u%h5{V2|i+8$d++>#yk}%-GTl z9+*C~=T8`XDY3r&k`$z*=)yctFAznSZ=eh=aF&S^|brC6hAPBD2V8y1g8!!h~IwUO_vuJ zKK(Q--2HVe!>ovMV0q`LUeaeFkYA~ZZlV)UI@LzfAC*0s9(P?|u3)9Q&=tKQZJ{Vh ztMiC=*esj4#t?s9or~itQ zqI2<8ijAG>tm-VKhZCFpRbs9S(J5-OW%JmxC!d=qMqpV02-uU@pXHQX#BNS6>he)W zg`NXaBZiETCzZ0 z+CXneycfyYYA2S{kk7q!IxOCZn_66Ac!E}pNktCL=Y8wL@Mcj9WTblmk@_Tjp!xmR z^$*%N0~x;HmJBnE*TT?7**Hz`U`!l%F)> zqb^sp5QO>8mkkAAuPXR1wz6kp?qNHfm%k79Qc5oP(Mx#aZrBVvUeUQ!IWL^johQxO zDGmAyvS;k9!#tQxx-g1r-LXGvpg+7H83EmvE0j z?QkheP;)~$7S2pB;3CMq&Zk5i4nR5u^VI3A|Kh#op!{0AQI%B-a zy8Ke&-rXxUI$3W`&z#^BdGSz320uw%HiRmYW(xAuCC4s057Ea z$g8Af_5EG9qun|VOognYBlni{CUshL*WnYZZD8VmS#li*E*xA`d%1uwoEO{OSC0rg z(Aa)0(H1!T&A^aX!jFz&l^m0|bAUX^lP@=+#hTx9HYqo2R2xvotcH}5bg=Ii2bbyQ z!lRZY<&-K%*4g>0>kc)&A7(k;APBLdFN54+(!<4k@#vUvuT%jmlNe{Ey*@vZSd)@?bP_n)s{o#RU~fBDrcsT1=_&FkiT_@%T2{3! znE6)5yn-FrJto{&!1o>BfcV{)!V+?uMujm>wre&H!w-YWEVgg*(ut(8jNwnQV z9rD&OOI`-sTGi|-Y&tm`w9D`J^p7{qSZDPDu);=zC*9&TmZY6rb6!CUGrdMHwQ65e z7+$UNUnI~_H)}ykQc}BS9HK)DV3ZW*7tW^sQG%)V(S}5U#3V#oR=eUfAMW%kGPb&3 zt)}-C;XqP#LsYK_6jq2=AHQFlZ$t}HYH{zE-dC@M6{ZAcWL6Aa&Cts1waK%a`eC;l z21dG)T1G^dvVX=O%(x5T>A;zevY)c9+q0>FbLCNzm9tqrX5vp~9>~sAh>y9wBSeX* z)N_~0sAOQD~G?6 zH=A70+LhSO%%#lb!S7Y81m4Yxcpquq$Uz?>spRBKp_mK0WoQ(+iDFwj+Ibm9WWC-j zy23HBm>nP*3GsPXl#u+|7fLdv0+)P+^QL#mh-1gid}O^l98cbq?0Z-THgzCUtB*g- zqqf0arp&P8de4=&($o;K?IpQ?97SWJ-bMwn0#trn7Ody(qnZ=oAYCfRbT%&igW_Z1 z+0Gc>MTh=dG;JxywCT^~9ww$k$ZLD+9C5(}qSD$AsRzUAQYKg^L&3%ukr}*9&0C|s z5@F{ZP?lC$MssPOlen=OwqB^sJtFVf-3O+IaMRQ+VP|@J)5@G*9`EW}mjv$h)tg4$ z!fP#nv#xuvL2xzd@Qesp-jJ?N~yEo%C;vqu6KbVyyW(u>Zb zr}*yi3Wy``LOw2+^Ih5jz1=FYSnEdhsoO2n083R>#8_ovEsOu1(}bPD8gz2tr@v$2 zPFC-}aerwS`uo98es$Cf)QwM`ZUpj?6`w!V6_Gg|se81x+7odmVB=y_L)w(nGlR99 zOxx4fS9|#-gf6?@PTc=cl)D;!VyO#0=EGp{CMN)va6Q`gU%Y&38TBTBOdE;Sp=6v1%sC#YxFbnk|zs>!`HJo`lEheNF4D zLympdlEs)neP*L2TcZ)VW)zQ9vZO^=&O@GB;l&p;4f$!w*Ug)xEcnS@Z9ALOKdY!i zc)sL6NMUdr_$TL@4e_d1;FwkJby#-)OP`aceJ0+RMxG)aHZzXC!QmT&PI>CcOLLHj zzrf)j0Fh7=f+?_#6uB~Ar(~w4nk%3DJSWuK9T*hU)7Y&scy)rwG?VVGmh#5IpX!uv zyDm{&X=&Wq@$&RJL*X?o?g4TFB*ps{u!8p*;3Agh2Dz8PNW0`rf6k0?6n8i|`%Ti! zP{b!99o`OdZ_LQiX)L2ws1WoVOBIp9R@MVK6qiyI?OnRN07}r>*@azllhORpv7*s3 zfsl+;O^_#e>2h`oX<|owUnJZJl0D3lJD9DsJGD!h$g9ql?O&5SG2-Rr zJ(!nh%yBIC_7lKVhdaBB>7HQ;d-v}6Yj5@DXObfL7^x{<0f#dU_s|D788{8!ovhn# zX1czVS!SuMNcWEa1Rs-S8=kg--gHE9>p5N|B$W4Eg}sbkixQ_pSWHX70(+;T5>)3q z?B>?rF#dt{A6>3VU(1J7=3BDhrUcs=8Ia-9hN(1AEhLH9^RnuTM^6ISOIy&s9qtN?3-g$lcp__Q3Z;`b%eN7YS25P z0u?Hyd{6`57B;^R=6Df~)oJEB0y+(D!u9`&Wt@*~OA%Yse=ALpH8GRWUo~zwX zR@}>KiflWQEUfqm4%_<4ol}3c=jjB>CClS;+gD??ES$N$DM0CW#7&tmmDLlSR`jYY z6cmEtfK~ZxK0bg?CWue&v4P}divOtRNOu?Icp9_aWY2`zit|9QJbXvZc8JJM=@*C3;x+o7+Qcu*e_2ms!4k{vJLIxFIz9Ymm9X1 z9B?N#?Hf1yZq}ANy9kZGV0=Dq6I!pkxAnlgA6n;s*Q#AUsDW$BmoExBAE#;w&Lnt5Mp)KYxDt4*pPdcxlsB(4Q+5^g^?Sm0M=D%fLmg zUNcnu|B~8cop_*3*?y=SXBbhvpHGIAfSeX8dZcdP>h6ol$?8w8@zNvZiEA~^I?^z; zICj-B;QXmlCT!tPQkt)LazA=G#zLG9!!So>r`nzPwnR~>GU^TaQH>6p)Ao;`_+qo~ zTCGN4zC@&ydhm(c@?eIOrI5_)gT~5|e_oa;5DLLUDN&ap+8WQ#@$@rzW#KCyK_+iR zekMzbdnc`tW-#0|VRq*A51;&Ri@Q(wJ8{B)SKsd%t6)#NT-BF0x%p{kbX0Rn+@DFJ z&vA#KF($2U@~74++G-s1M;2f5OO%!9z#b6)O6h3suxX zHQ8~ZSIe}x>$O7GVd$#>f*pSRkV6qWWLMVT?b)#3u|#8G0!hnE?YS=a@cy|IUvw7v zbg8S}+PAq`SI-gBr$3Z6=7jR9NlZ`lNsLj})v>Q=F0T0YJ~rRIvP0gjF#1u-_Hd;n zPL{-OljZco)sA%rY#LS)^34&YwJ~cH^_Ykp5Xhd8m3?gB_5m$AFY?-{l55=)CeuU6 zWIBx;l&viJRwxs(OnbSGgpXjg2<6NQf#lJ?=O|#cHkKSc{ z?oowibpO~V*IOiLwfxc>@7`v}g4O?ITv;pn7E~n4nstyP;*U&+^j6|VH;Jtxo4?Y$ z6Ap7ny2fFQHxhnlx^%xMUHo-x0_r9`+)=B|Z3Zo~fR(3#h%o${`q&zso^hj}J>9h3 zqGVR|oh_|x4lEj}a8-4j8EIfzSHkk8kUo9$rE;T3AS0RnR%OPwB>@KF(HrpaqJ$$t zu|n*VrOU;yQK+`^JG^p}Dbc&c4f$r&^g#f0&GE|Ix)C2oa`9u0L8X`jdTcP93F;zOz>9~PqDw8 z5I&55|M0hSdWR~+Sl>`l`<{JbC6SPeq zUX(?9xZIshp8N1j7mo6&LjRckaLux>=pYHq)|0qpkQl1pAJM_t>^RWA_cP4lmQkPJ zHSadNxpsuDE8PKS_{K?`(jgwy_7GVrrdMb7yyK@QM6dIB zog*=e%Po0d4 z+Z=D^g`b2;vv!cgB6YJ8pJDWCUVPAd=9qW*>6%FKZFQ;1!M(lrKfwV8a?^Jp*EDGl z+l2)W>6Mdah*Z74$91CnwW9?&cfTv`f{RT1_~R0Xs0PJu&Aia%Oxej^T+9y2>7D0C zluacgtE3Cb(%p>B7!8H-=GEJDTCzH2cS@K;-IG2szh5~95pm)7SE4AX^LS&n2M~aRGOb(n-u{`e z-iQ0h_uqArWAtf}?%v2)?kF>B0F@WxZi!`I2823|_y<7U!*3zL0QJEaFxO5-m( zG?s9ts)h!1@()_&K^ww*&WJg}oUr7%b$kVYG2fBI2!e5PQc}?>BR&y7R9q68*SEu- zj3N>Sk&C5cs3EmCV_eFhof^6;TotWZd>4H^>GED*)?$G#tOb`6nocCh())xl{=u2@ zrSck4XMUBHWO?p4FS^F!&*F7^Z@PH>9HMSKB7Y_@YV}ArFM%11aGd&=j7dWS-lyv5sY4N*gfpm$;p|w# zG%Zm*;rsNY9`$N){!e?;2>PUNA|RhWU>DkcZO3#oyI;5Nr}6~E>$p0;)t2WX08oc> zDFZ<~feto<5{(qxD>_Hw1J=*heW!ZGdq-agxDb;Yd|!emJ@I0~9BL85bTt#sKXElY zBjR(K$uqLa(Da)aQJm@0|9XLT8>F&iOX%(_v0xPBWxj8uP5A zhhGG19V>ey0(NVp4)!FZd_0v`5}^G1D!gGsY8o!Mf+(x^q|7H$N9e3PGd zz17{Sqh8h`?`5@4KN${~njI<+H~`#QFT*{O)=3|AjJV3nFpu_sJVHg%5F9SG`$yVB zXQDfL&|xHrA7|Sd7x2j7WG`!j)V^^eAGbU}ep^M@9iWl>*DQWypaX!gTYRbXWfppk zqY1d(p_Pk>D>|cY*pqLG%7!T7tixT$$3ZZY++?AKP!8 zvR`OFRa#MIC97GM@`=dYNsGn?8cUpPpOyftq+npx%9#J2U!p~<#i_SW*;8*duaj4wW($D16?vlbr$IFG=YpyT;h&rMuXu4A#XJCSxGCuaq7+r9uA9^hN zb#m&|=*q6FLF1v(%8Gw|94kDJ1B?n)7+LSsfSyL2DvmTB7IxC7a8AQL`o*&!KOLR< z1PvD|`KNqBJhhaV!~v^|0ViMNVEa<39#-E;-&ovgYM}!N1Cwyby1djElpk}t?vnUZ zZdgfo(TmF-V{767_Vr|*yTB~HS8#o`sZ6E-Smg8%Nt#sKQaL|eepW85_Uzp2`za|c zlOuIsK+B(zc7$p~u`XKcEquj^cTu~g-8xG4uF8yjJp$^rsbPEqYd?qTYfa8fxh1D9 zv^C0`V?4o&g(vHIYdQLM$N@bfo*_P8^O~wUrNQNNFwPxne~lw)+KxBXFU-?tZ3MJR zD04_#vU^fAB1BC!(h^tIbdrocZapn^2;Ne#jZm{y3j=Xx{uRpQLCjAdU50G(sV668 zxJ-R5okxHv!zz%9wp3K`GV?(oyQ04%cw5eXAw{mgx9{Xl)`Y*sGUL*YJc`Iyl)+g) zk6Of*$9SePNErxt!@Tc^s)US%@lef$_~gLfSSH-o)A04z zXM|6pLqQS<(Lq&gRL2>-3>|Ib#BlyQ@f7oC4rPz%VjwiH*J(emDS7SKjFE;&iApjk zX>rSGal;bg*f&9u{1>1JcAxsSIkJ5{qw zw0t@bYgXb+y;e!00`~D-D6D57V**uoIdd)kBAX;!vDAJMJ$Zv%wL=hFj-yK8W^XdPADWNn;7?K;B>^o6CWIa{NAr-HR@X%8tD40Vg z(7SdUMk@VXmsZq4n$d}J^$*t;ghh}RCz&jAK@V_awy9>9K9r2>7;!7uyA1K*Q;uKd z{p-fbKzN_8MCV3(=m~06z2mUOxjwoi!7)!}M}6wLA3(cYGF9}(t-pvfi#iO=(~tX~@U14lbe>Wa>AL!j9KQ@&vPtlA5D zLXguD)vMin?de`5T05Xb?cz8apO9{ty@cY0F}`|Rq4hccv_+S3tGe#G@;IaO3IJwl z-+hD+xCkzKaIFZ>z%n|HByzMV%!?9?@@-kbXmx9M`_oy9(D(PUQ;m% z!_gTaII#@}(5yxk3vZ z%?&4$UprSSwy={kw_IYSsdR}GIno9?L^dsjAN7N7j~zw6V&zB4l8UY}Jh=zyZ@<*x z-FMTFTc`!2w{^|=LmDid*5b<9`XX9b72HcYiqN+Gp~ri(_Y}0v2-v-yntUb~RWwsY z62us9ig{q4-6#&=7C`$*2PmOgtS$fOHq(ZeX=6QG@K#s=kg2y&{&QA4e7_s+n2<~< z%ap5W%Ae@136Dd=Ck%vdb7<|n6CjIczsgGbXV{4kwJXjL{>0(PFJdXMV4@(uyvg5~ zLz?x*p-pi^+do7u%M(e1=*N$1;IT!*+RDdM&9>7dhX?^9nHa$UkrFyhZkubdy~J&!W0586y_+}+;Y zYJ0KPGg*MMi;CF?Lq_B z{DboyVa1MAI!O=lX!rvmjYtyVnzjOn&iC%cP#A?HeM$8-AZuV(>+o@6Uab~=<>rHw z<0F@XlQ6z$_Oyy+7w-Mu-Fyd$d_LZq9*>m?JUaWB)aSX|0i{+}h|1IQV`DJSG>o@T zT#&jq$4KuskXIY)aIc_>G`u@W8uD)3$%^-GEQz%p+|08&Pu}@H0c>n)kZl6)`LJpy zXk;?p&QI-g(Oi$jmYtDyHLl$HRWVCNig!a`Wxn0`7sSXiOFOSc&p-y2eIaawIMb)vw*>rkPM`NjYx z;4zW%^Z=~Pz;bX6>Qg?X;DQDdAP7il&FguTH;-z#A3jZd=^0RoRw zI!nl+8WyAb=P7OhI)L9?_9_j?Wo{zF%>F4Tma3T=P;xQO%jD`zHb}xaapxBXm;QYN zNJj=<=FRHoe#0+m;2@!wKfid)feDT&1=|hM-#%BYy$Rqv##P9!f_;B$<^0w!liZ&) z=a&@!U-bY$Xm;M?|4;G2|LV*aNc{c7ALRr^^vXsCQ<{!!p-n-@5UquQ0$7PCzqO!u z_QdKcNN&4hWzK2vbiLKmuCqctQ*+_p?El{d1Fo&9X+TwkxP%1aaA(C(CQ~g1IJ&s{ z@@?a0j@zcS{0~8Tk&KJ2K8-;AN$8ELii%uzumHl$djvR{RLbkGYib@8C4Tx80;I;L zLB}S-bHBcL^wm{TKXQG-W7!K2luDG5CgR!qKYjXC(5Dd}9TOvV=UVS^>Tp?N_4tZf zW(poXwdU~Xj@e>8F$Q)uW#li;wxVg*qUIL>+}|rxqgj~eg%2$D@bIR-d|~_W*uz3X zWDqFX7+cvX3?cyPm6^$GYm9QPLE~^@7%W!S<1is1fl3Bthe9GRA*3?Zj?G=YsY4ac z#>%1C*vXz_K>0+VI`F`cA3qA@Py?+C2B&eS#?q*nbt5h= zuFlOPGiyK-oKq}ZQuYrgNn(sqp6>4MIm^RKo&fdOTPHT?K>oe^OC$bJW z6QBqq9Z1+0*p8V43OHsvZaX}0WXr?^|hXV}kOkJ=IS+Y#7| zjEodNl2s&dO8)iuaJP?nj02oIH)l(#b(_(($Onppf`ct~*QN}crsPKMuw4Xn+WY{K zkPqlNz|GR^>?|<7J?&e(C`vh&{?O>`o0Wa&t&nUBu$>Gvfn(&!6Yo`ECJ+B?4wkBOPT3EX zVvO3_Tc2U@bG9%v`4P}8{7Z4YQ{e~uUuWvNB@$OHc~*2l$VP2PIA z%-LecTI$|)BI}mmQK|qRpP8S^y9L0Z5!l(LmrpgT(K_^FifJcrcY^Z0@R+0|It&IQ z<8eqJ5U6@E0Y7SemYRd1bgpr0W&f7085kN0idCUceS(=6IKl18?F=V%RkcR4s1zu4 zNN&l(-Wl_K*LE{Oz1-VoT5Ki$~a zC-MQnCtIRslkwVRhLe2*xf%-#i>4}HBA_)s({;o?9YMV0N^T#H z!i>L6nmt)I!w@q;xVIa!J!=P~6BL}hz_iydJ`Se$5W&B@b<}6&yj`0jq$JbSr5j9u z4!snr={h($;G3tHudS*hd>JwQ@aS<21Au|dqts5#Ya`2Q7zmdan0Fs+9+u789FF=oF9p)eO_ALMts}ek8V^oK@tfbjv2Ok9ADrA=_=3VuJCZNTHusOs`n^_$EVd7r`L%k6zi`ZrR2j=aA7bUrV@#sBz_Ij1R!&&^VTkPw{wPpq63-_d7 z{^8miBben~zAbLW%oNy!0XtDkO%4AzY}8qXC2jWX9@q74UY-yvB?gTb9b)@&V(v|1 z@Fyc=5gSa|H1?z>qb>_RRQ|0f+r?p97E^}5x%};)kvR$zs$ku7KZ@cN{qR=Y=k32# z8G8_(pd(P?bE5&=+F)By<70ICR~WxT!cgoc=EU57_Npm(qk+h*x9_p= zR?ovmD(X1E;q!j=yInI8IJ&Ie?cLiN75HaBrQBp*8A)`$l|4qLl{4`me?12grf%=;`z-YrBNrWK+4aP=-@Ak-X9WZWQq zpg+Xi9DzC@pp!-Zm}Ta{gC>hW8Qi-S`z;}8g#S>KPa_!J^m1>X5QxhedC>J3wcXcj zCQ$Q3c9JO#mMYwh%=@wsjBq{*_>9Qo+H1%{Pi05dbG2=!y)9O$T2I(?7Sot|vTcqf zc6Pp`HIH2I2PLVZ4<5MPQx*{sDKS6`M_m?=^)3O?Qlby;r)Iq36&X1kbev!S6N^FF zeP!ebtN|KkXQu=#-JC;>_zh%|7VX2Hz&m}ty`7s4kkhJP@T@hSv!1ELa539TFveBo9eJ=GXbuy3fd1$l6P|?Y9@(C>wO65+@`OF zy1HnUILx^MOPs8=seGJmWnrPZ-YFBLZK4-7MM&->vYYDL7RaV zL^uQ(jts~-8&0JRO6n{b)+^Q*6%#9v&-wcG*Z`Db5Gbc7kRm1{gV8M>`ntT~UQp@| zLoAr$Oo&56iK+#<3cIE~7|a3TyJWAKQ)`k&czt4th&Ofp*x|=zQl6ciNavh8FpHgb zmFcOeM#JL*O#sk;o(ph@GUJi>$wCD5b}ElP0_`t21Q+X3?<>+R2DnV9BJaXvZo{^Y zEA>2_eO%TK8{O;PUA}xdvB!>SXN*bl{*73t@d`eN#>{piMuvRqWIP-oxOPx+a9S4R zoHx|6?0%iM&kguwiUG zAvQK+SD%ckZ0oR~_y2Tm9m~(wdSAtuZ0q!8Y`7#iSJW_LZJ(FLxM>)N*+~`HRl@_C z=jy8cvM&oFoHkT$-Hv_I(d{?vRY}g{F*vv@5v)#K$rk9xWSp@z88rR{=k(DUgdqi? zg9S^gt8wXXUX3}MKZJ{1(?fxsBpj?+2XXku{OSy4C*GR4wF@$RDNW)1%MvC0*?r5O zkW`E;EW=qc{#C)JLCBVATVl1&+64)BCtd5+3nO^(5ro*|$Hg_1erjnx$|8mrBA1T4zHiScxK;_K4TzP#+ww5Dl8Ne5-K(mK*MqM zc>S!uJz{+!l07--q!J&6I=THS>Yp(K=e*(Je$y;$-$Oh z+ggKwnMvu(Qo7jVV0n@XpCNJ*YNo{9otS>5sxk#PIq45o3pcL8-UJmmFOG@t2$5<> zT!CA_E2FM@zdFJY2Qx17U+HO>N{2lhsvdhy$wcgN*29szkLz z5nf(!KR=Vayu9?xOs6kq)F0h}F#9~dRWov|LJ-Q1fn~tgWgvM^S6Mk!w>S}~ai_a> zdEvrL#$OSK2M0r=qs7I=Jk&HayeT~$&=vNPkHP?edHx8A;>lZ|5YWe(5M;o!hYuf8 zUVcOV`BUG*BKua@-;U$vUc8iD6*k7n)lTCm8{y)(xSLVY(IrNFw`i?3{)Z0qcVGjW zN@}PB52A@BoSdArG3`Vmv7ooNcR!i7%Q7AHAnqTpwMmRVr~r5ZU}GR4x=&W6fBl#F z{r)xiwlZKE0eb~J9u%iiR9UIV%*;#~+R_DAxOw#=kh7bk!k!CIP+l%%D}48Hbfu%^o)1YX<@~y#igG9PO`LTUAm|@QJD%bYai2Pb$7Wx_0T! zv(akIi$_KFq9y(PIsg%MSbVf;2nNWVIw!*DO5+;Z0NsIr0_*{-^mMDE0X{lxHr_gM zlL_HK5C_Z)-SyBU%|Zyq;4UN*0>FdkV~2HQ_<9#MK`C9Ga~qvD!hol!E1af(|Ax^< z-CIj;T1uWI)t)P@w{PDDcA*Vv7v`EjO@WH|^TA&)%DE`SL5lVDWwQ+hQZm-$9F2$L z`*2RCVbA4XKYf~`tzvC$4d_q7@kN8b|0CBv*Uv~=L?jQePVzaA@ED4Ui=zPBCZF?ub=A3b#?3exXWwLX zX5WxR5{ZAj+SWLEV5#a}JM0rM`oVvUieI&84Cn)>1X2kM%8m40T*?4_O<{pJssNN0 z>#G8PlWk#ER`NtR;#h(rGT<=EcYDM6zh8VR4R<_~CVx+?h6 zP{m0H>?=kUL))8Xn0%m#LL%D6hNr2rP@xAzNzbF4L8)a{zSuCCYvk)GV*Q>we@ z|Fl@#mM))n=Jk%k=!6QpYRb#YTWHu;R&2R}Zd?!UE}N|A-^YU= zT4-cnyc!ksFD0;+PYYm`2YpwkzcaF_458`W_rd%i#r6m1#c8h_{aX)NM-X18Pt!NP z(G8B}K{=-uZ7xD3R#(Zr((tj&KrUZ_#MAdCw_*o^B5U z#4Bqr>wTL)`srCuGYuug8LA1sJvSF)HUlmZ5c$`d$h_F3Q^4W(CvEB<#VSF~3=Rv^ z0yIWt%igx$kucd!-!ATR!46+zQ;2c*R{i!Y zlZ|C+2gND>-0%vZEgtLRz%-Uiu|)|7QG~p`cWzq0?#pFkw2}Y0l;@PQ7FGikQb}*d zEEdVo&`?7oqwAcLlx0``oMNM@oT+-1(LZOL!3G%_QrTn1&dC3bDq!~SNw~@!Kp9$E zlVw6+0a~Ba!FHs*5C5=2R*;P2A=S+Ol^nruiEY)tZ_ipY?~HT^et@dX#utn%e%x0A zK;mSuooA2!pFe&wl1sqfpdjBq9#5fItdmJQ^}rj+me$IWe_w=z;o{|{oN@hLGoB)uwAJqOSKejk!)r!FOw2Ck3*Jn9^y_l2lS z3}5!8?U&A{_&3dO-3IJ~gV1lKpvuYMEk=j&_CJ&sB72C&>u_Q|4kUT|3g*7H!*4|1?=WL2V>bM8OweD zgg_cYi#3Wrv3%=G-L8G|VazhgyGWsv`R_*RN(l;bF>)$z`o)gyeu=*o{|lVDbAdPf zoIOn16`A%$c9j0_s%9FqPwWy3ON+Ii;9341MRt1xR0?Z`SQGj>jhr{yvy9sVuTe|C z+MW0hj&)Dl1n3)L#;h6-LC?;ZW`alXppXTKijK7P3Q-pqfU(L9EK=KmIQEa2VX zH|xNQ68S;qe|8I#d_@dRI!j7chH|cg$ZwVM+6Y>MD3yQ^UF8*6jZ;wI|aY%W?K_4h4 zn;-PQ{~zIyx6Re}X)DL$g(uV@yTo_=zSO%N3x({p8V*yr4ziyldaK?41z^V8&IbRM z{ccCAGPZhfAN^arNUD16E$Ka|MkJ+VdaFJE_v?0H#}G|pk}Mu!r6K$NT|eWqIC-PL zozcHll*Z!uphSuONau@x1N!oR2gsfMUnt$C)Z@-0p7JF{rd&~>;+N)J#V_CSA1`DW zmB9Z>I8d-Kc_xt@894amL%1-G+4}j@H=+J=&IQ^=`*nf zn$|dsvbR_R#{%K4zjGVdUMIaZxM=)BG4D2#s@IyQEmFUop}C@Tx^NfQh!NKa^%)C6 zqm|$gXJOMbZN`d#qL_0mS$QR;XOZ>#udCi~mQQT@#^a5Pi9|f%&^w(ZQVLrl_}st^p9rG>Z0uN5atfX#PU)+1)c)D(ugd79Bzs?zYuQr$nuD*A?_O zLRBBI&vjbJ0Oq$INzQ(im*?0tQqcA#WL7iYhiM&&cEO&(btBh-(~!Ao4jsCRlDG4) z5NL6h-m?cg%FPb~R28f)j$C3O|5D^yw79fnYItbYw-g0ko$W+OwV{oTB5G2TVZb}; z*89OUvi0eO?!u>g!KZ(I_3dVQG2CoY5Z)xvSg%a>H`CD6a7sTAIcn109OvzA1EPjXdi+_{9?A^| z{{2p~Siyuj3#B~Lw*YO+hYt^d9{PDMzpmQw1H0hyXxiIm+uD^HMAP>;Q-w6-O)_dV z6tx{=$@1Q8a`W_DOLd{%>1^xMqv2&r4bP{OD85bGUroFUNMw+WHC(}85Kjw+~!*kQu9=@v-hN`An9{*MuWG26o>L!UI3^tTFpI?Nn2rf zI$wO<%QmjY`DMMbtXmq%Sq0UBRs95C1W5w#C|DZL15T@EBRwFMtk~Gv`WDa0Fa%`; zl e#aY*^AVAE~G4IQlFPPOE?cCl$ELCy>v`Vh7MF?#-H#e~Ug?y6Wq#=3_qs-uj zp&4oCBkLsFq_mhr5}N1RlQLT%K-JWsEFj4q551hIn#`4#bUwLCNKXN+$L|8=nD!~K zJpSmi}K*T)tFqNE4CXkIK7fa`rs~J2eXRrfs)?&#QEdnqoYszcqY6o zYAlO3a~5y@+cTaP)Fl2NmFIZ?3BVDG?VDz2X5tG9G_p+CsjsSslcmPRi33wArKkfT z&@pXp-v2MYzYnLintxY)%;y~iF+!W;Eh_)^2cKJ7j#ZcwjP_EDh%8wW{oiEG`Sq)S z!c}Q$>FVsLK~Qq0eX4I{%sFYA=1kiAdAxr`{?2nJ(=Pu_#c6tmnZXbsz8@o>!0+=M z)U*;aSBoTQ3FdRUc3s-szh8|-kp#@)q}n_`Gs8qp#%2e41o8s8a=O54zcg8r;On+O z2vU0_aZ4HW8N`{SH+hzc8gwQ=Ndm$JoHhDO;NIne7-3n{(9p5+Cjvy}f&EgeZwO*RBwkC8K|?{~Wv4{V7C%Q8u|v_AWL6uZu1J%0SFf)PIk^HpYH4yi`g-&D1u zM3(2EA}3A24HfD5-TFKJKD9p0Z?12V!_qZR#j?x2ZDT75N@Vo?B(w@A(fkE$+DpetrVTgnZIrQN_A^X6w6PJeiw; zKJRwr8vZ84%V-8}aog>ASQr$Z&!0X$CbYl2iNcU`dsx{*FB@rVpM}rS_>FB= z*i1Rly1FP2_63)Cw|j`rFPY9bZ>Ud~J3n>;aygGINwa(E0B-i5L&BmEW0nt#JRIC4cX?&_{ zK4;guI8-wh+P^Y-Qy7)0?z)d)tn<>`nLHN!u`wMwA7VS5rln)#juYea zCC@gM&R61fRjwP9BudX*t0BM3FL)w?g7!Oqqd#2lOE0c}piL}gWO%B-%3*b30C;M= zU|#c(fSv55-HY(14az5ln$~IWM_#nNVhhj+un}l6!XejgGE&oF=s!ZC68An>Uwm&16v6^F z|5_|D0F0rTp+-K(xuo*)@~2h(@Q1D@HZffE5Ywq1c{c?PC6^ElXduNH1?@MK$6N$v zIiFeg?OQqhlz?a=&LmYhU5i91K{1ggS0K9a=J&fjsMXbeX#BB(H3yM4OZd-O9tm`ar47e1d+ip{$x?LghD!BCU^1?Kq?f8oe;^JpuMZv}~ z%>0-+!PxUlCFTmb%J!@g5Cipm=6i@KGg2ds7Zh43*L92=-}(KtBB`4~AxKfriM(@X zoyJ?Ua}e+e1t&DLzn4%nMq*bbGXW~_Zg^IW9E=>fJ9P%lO<#PGcs z$;iDY)Mq6zEA;eHL>#hd6(;rcT!TBv1dJhUW5yH%HKFq9 z%Ia2aP51T@#kpGVjDSFrCl&iEXj{-r8f!xNGmTo8vvl@0WW)=sBBX-su8)5{Cj-=-v1R$fG`vMoGM+;F|Z9J5Xsei#Te`&4pDqoM<~ zcoc0T*?sinZAyd#^tEI>Zm59093nSUbu4x*GOTuB_T!1vB*}0d;$aV=098KuX*in( zl>xf75vp(@>wSjI?CcY?K3yDds{1VnAYznS5bNvf3rcii-*$(-YVLh}6smKUX0gWRfj_%mG(-68ah!_5Rnw}-lPl93QN6D^{x(Lw`WkEbE zSKi^3L2*dkIkzN`Jpo@o!@mg&qaFL2BM+JRv-cr>LjF2?hQ1c*k0m>ShnkqrA z0!J07y}s|{?M-;vvtVn2oI*%Ob7Sq0gW|E+L-}nli;9X8TJ0|)2YuPdrVw$$5wJjQt}AqVL4DUglt5F8Lr0_ z(*MPFZ+x~Nn$BdAE{OZ0(T;id)=$|K33)+6pGj1=0O;lW+)%+gBS7HCCK7Sk)~14l zJ=kH})zsbn5_Se?f|S2XC=iR;v{a)4=p4Wz5sl7EHe+2yT3dF}5;8Dd&qJw1^Wq<~ z!_N<}_{xIvVT5NRb~#JnE%{tm^J~Hc`CZ41+QqgW@c3mO5hKMM(15IJJu_IppxKmV zasv4aSTfe2bB3VPvHLHlYr7)m$>j(tG;Wn+Y>`%InaF2V|ryBrGadzFDaLi*h6 z{U9a^sD?J9tr7ea`SOnQVEpS7hv=48}YT9p_RkPAlyp; z7W5cM`$|N&^<$8<{dsLhpQEg@v}c(buFst{o7MJM)E~HB;hi9t0EezJUlCtBmD4n~pP$MVBPH`Se z5*ou5*OK)lYTKyv5HR|C?)x3sQnCJQ)L$A;^8ZnH{&zM$>;Dc(SN*5dk-YiedFlH9 z`>=t!_kRfp$^V~h^#9_8{{d#sF!s0?EuTN!PKkca%-_OxM)cxXYg1}i4c8`C`3shh zHs0QWvsy9y0GWXkuT*P}3!Y49b2^`5T*klj+5Zv~ImeB!Oun;5%v3i6!k)`zDF>L| z-#0OO#q?&#`#B5OePc#8Gmpa-MueN!R%(UoA6ShA$J7f}%xbN+bhVf+H*^epy5C6F z7hR`qggx-TZlurD#i~EGTr{+{gq@>d0;_vgdMjufC)S3zXBK0UUZuE3-Aq)ZX$d;) zdU0*c_2;|;&Sr0#)LM~Q^k*-MjMzW0xz@QWSU~A=PP~XvoO&Tk*LG%dPt?5=v|dcq zX}UC zR2HRD%WCj*^nk-$cv0*`frFxdCR>MPSKMr=xM|~fP51T_+nJi}J%!e^)~Hq%E5>ED zK0Mj;IPrC&sE5RpJys;De<`OvhiGw@(4n6XYKOVQp=wRK){ksR9Wv5dezkL~Bc;ZN z_No#?{3hP?i3CpbbEeDPA&cLAI_ve1zB**Tk8h$b&5qTD zZCGkL9F$nk@%TV?AzJ3%9j^K{lxO?)2kM0K&ya?%usY90WhWL@w|wwO9jVe<3)2)n zo&2be)$Wm2P~AedOLSb}?A^<|s3^Kz@`Pq{YDeg84=bE{^JQzv6Ee|QgAbh2L5%B8 zl6?NN`fi`O_WWArd}l=MYK`e&lF5{fU(b0v^BVQ3d)sC^7T>zebITaPOE)iD4y5XYT8|{UF$yPFw$`%IDz_-)!1i~c^CDf zBSb;j?~ch+}RHWj-PLN4}Bi#YRV2< z;4V0=pg14lGxRKMnL^O4T{F`?=}c<6pXA8LcX@o)jFDLzY==kHx>_Vtoy27Xr>}?7 zJg+m3V5m5)yQQnagIg2N6;{9YQ_DrXV&d`8&041`u4^%IGrek5XShPIrmOp#wr&r# z6Ft@`kPu$5#Jf`CYNud3KIS*&@37QX)U4$^)-^M(Y(HK$Cg?CDyqXneH{&uUd12oX zsm*m8|7Zr<()(j$^arjSTC**RuzYqQ!2Y{*!Ss9X*_k_nUplGe=0BZqSRERe?X7j| zXPh6oBO?$iv-1Arn1q{dvVHhA`M~2rZtSUwO*1k64wFOKRzqLk8WzkC${+rcP$PTM z|K7x4fYRl`-oZ_wKZ~Eu1Z?1c>dGIbR5<ZTVuZ? zd?CSQw}H}Hamkl3LnYI9a-3nG=L$`j+x&CQdRYq`|BDh0mq_e>tJ)f~pQM>6_QaR+ zbvNDnO^!dVIe)J_O_T4}{5mzfg|ya1O{4iC-;{9Uyrz>{UuN_z`|iDqpXm>O_6;4| zp6V=;lrt2}vj0@{mp5!L9OT0sWo?}XPcN31;1@bH9;u$`KgK>-J+OLZt(GdR-s8@R z#i7$$p99iTy)_Qk^%c!Nq|IG=nH5KO%4n0<3x_K*t}7=Nr))dxTKjEh%R}O32iXrQ zbfvtt>0CMPe5+-J`6>IL(b~XTjEBbyr>fw&S#c=@cU^=Vw^^}`Lv4)dohd5_7_=nUJ4`06q>3XMkMI!v~!*faKTsI#)l{VnW_l*&dgy%bs= z(yE`-%9qUR-Q-24UYEDw^md!B$Sp#v2F}Z(*#?fMGIp9UQuZY#JH~l`ojiA_y(@K2 zUpCO-Bd7GH_g69}c;cN`LJdg|Ofjcq9V(QWck1RE85m$k<}J`)&W7$3Dfxw0hG7i6!J!8m zVx|W;1wxhDOymqMh^5=1|1AFQoq2IaH{FdCWU3h~7ZpVkYVP-%t9@T`-*6z1g+Knb zNhOEVf<^yAp%X5AV4vXcHkEg|3H@#}<+kAsr-kj#58PZo+*v4@71Hv#RHb01U_!rk zwPRSiGfFVDXZCQL-o|}f(MhG6L7D&d=>9<6!t8esnGSAe+O3>)P&;@)Mli0WM(RZ2(lzHrU$v$%SMjd3aT%+*QAvl@c1J5atyI2=wz#<` znKhe&Pm!qw8Vr`du2iuUeE3Z2&PDfi#q+U68NMk2#$x5O*`2KMDIQa-C)5imj_XymItyRTjp-GF^+*CQ)1W zclpW_Iv#a{r`FmQ=f1quAsw!GH6eR-AD5|;T%)dAnG=}`)OpdKRN}Lv9=5Z+mR${n zC0jlRZg18Bl~1lgS~~FvKRRyGj?2bOUUZT9=Ycu5FsPzl;|*eF?69)ezBp& zCE9kgp4eqF5~II9XVN;Y!U-l}Yt633Ug2RiVcw`oLn&L@wRwkS-z`>Eb8p|z)hnY@UcgFPj9Bx?=UyL4-bXXWl9X`PRqFJ`wx2u$O-R)%WKNu~^8ys^^r^b~paut%-)g~J6C59NH{_4?QEkJWMBVm)8s zqT(ZHCMH;{q9L@v>O477l$gyf?fHV5q}i=wbUn<))^%zG^8(F7&mSy}5Dju<>9jLB zywW=hBU4?65*Ld@o;_7^A9wAwoh>~k98F*@O6i9K)HY%(?!qr+R)^zeYaUz?bktEW zbsCtM4N%)2Gn$h8=0(ZGb8>Lte?UD3LkZrd) zwEC`MCa8k8uE*p`e?@0K_U%?Jj(bR6QgT}0WYRnd^9}u&ot@zCHY&~UvksH|>NI<^ z55zrq`PavIDDwwKR(9mhH?D=Q`tXM<6#KqU=-{)_O_kf@ILWnl;^yXnRvS;DsRL`T z7lmi+rKt=v=pgAO$(Xm-?U4H(vhVYqEkaRi21|mAUMe!_Y5W*#Fr?#j@Tz%qrP84 zlJakcKPYhceXgOmONCmC4JqOqx}iR!&hrR1i#q)D0n0#8Ee4er_%oDzwDvGjsm{kBBi_=Z0tw2 z+-CffnYBr`x|a~nF+5-h;2mG*4Bd`4rYY_pq&X!e+03`RyN*LjrOM%`XlzdYnCdFu zx|a)os9EcJ{LS20M;xf+gOY2T?iK4jyFYIpnxS{0X6S48bBnTdp)@b#3Wq%@t4MCI|}FC z6#n!&JhI&S)U8J2vqFrI$4?T@Lx0kd+Q#A^a_Uz}=^a)UQkl*AZ)CQ+t*_jWyH>np zHBxNyXiIW=&4cWXC0P`ba|X4A_fECj4s{o|_Xj!WuBA8+KVsopM@y2l>u(MzYf`A( zHQZG=$L%n5AeQW6dO>)@;WzX81LJJx?*%4V$J0?8v=qC$Xy7RJ+K(ZJ1&u%K+^E~m zwYPnp{@<>@wEs3m9r|Kl0-dFNmG=2?<8DjuPheWx0(xR)f&_b;?(t>j?cB(i6d zNOj6a5-zTPwi^ja@V|x*lK;!p`qM2NfQqERiKXBdFFt#+7cyN$J7S&ld`Fy}K2X zVF-aCbYe5kTF}#8q^^AMrT>y`+I1$=2kJiiYA?GL>T zgk1{I&Y@u&{%%J^b2M5z9p^ycO(z}=gOIntE4*S>FI;-RwgI{G^p#Ie?1Mv^z zkei$P=6c1>4u_HC+_9{7bYM28_m=-~)`G!_-Ly|RsqRAmVpPg>T5xhHv}xp|y1zW@ zYfcDLXnSV#H@FaFRBo+7*bLYo3l}RvVK}%yWaXz$KQw4Una2)HLSf$}@Z;=j$@iO; zk`=A{KT;6tH=(Mo%(aJTG`OLMdUmeebR;1zEV#&p$6+RZ^~bKYAF<7Z8Pr?4O>k{_ zn$LOh4Lpq0Z64@?B&66Od;(kZ%6wPq*&}8hvoKfC%1->E!)%k%fN1Zfm`GTHXtT#I z+7Z;2rV8QJNecHbkiUpet~5T1p2=FFr6f()mDwA@$EeAO4qa55#*$saNfn1()x~{i zHA0G92PD)0TJZQ2y$0SgXRE2!n#3y`E?QZem|)V6Ws1Dv#I?;e7mU z-%iMXP}K*aNu!oYDiryY^DEy?S7U{y zgK8n#vF0Km2$6oJUu!j{aAnMNq_+$movy`;XpDGWE0ic7cX^1o8h6Jm4BP`m)4lPP zJ7>>gXG-0j4O=K#;B2F-6-`9B7X6Rl2ywz9Y0-3)CfcJ9FBc!yUt3*~j(500R#LaR zvNS91IwS5Et;~|8&B@G_IxAENpR87J{>AEO?W)xLS4$u7!@`#(zA`|(mJwQrrgiyw z4X%TWVrMTj+rl3Y*asg_Y1Uz@?`4Vn?QkjJ8#OBxPEiQXewHVuo2*2+J{N5%Eh%?51SU)G&Mp+D z5=LO{+H&ozt?Rrkyi4pyXuurAm$>hO)rDPeBT#A=D`i|FNvYTdO;^90DliAkXsx-< z)$j|w8u_%;b=>bl)Rl=%pC6o!e5kWEvh8*PS6OR$d3qnEKkVhs{E+<0#SZ7|&3WdU z$I=TlpOu!E-X?904SscDkA#Q_`EbEJ7makwr+nAJ)7&%)Pe`sG%jsGxec?DBWLYCv zvJyJ59HzDE_vFbFwK3W~#FwwDgqW|gn3&kNiG4A0m45$8w&qw4Jggn1GgnfgqM)FN zj*d2)>^+a=`*W&_ecQHeJ;3j?(nTDd1`Ooe!otFwCLFt#vO?&lc9_LgV9{A((V?L# zh|l`f?gB=O0dsTnqg-5pt*x!5dB^Fx)}j6S!>3Qt2?-vZot>t6ysod~n+)NwRv!y@ z5-~Jn)_WbaFg?&WG*pQVUW`|tRqMgR^c7wilKD0;(D(g&IecIH@tgtWH0^cRw@qSY zW8)VPP=dv=i^JX5$IhJszscqQ!eOx~F$5+eRbo0Io zkx@}sm;>}PRbRb&#bYx{?F#WZAvJXXE2*@iVp;|(B|9+@1B0*Ch~4LPh`}n7|7O99 z59DLf%(we$flm5QFL?JBXv$o^yc5l27%JlG+t_XC=+-3kIcXkwdKQi8J$(3(tVAch zuA@WR#3Y%z&D9gFR6p9gRs)xpotBrE?FJ*K_nZ<2|96WY(&Wt>1dsMgKN052mH4i;K|0!oop8ho|Ao-;V9H&U*9a$532&Lu2E; z>}+ne>{~Zbp>`gVP++F8{Ql`E2gmLL&05%a7aSe=VUp?em3v8r^368$UHtWm-wyA- z!a#|4T-YKWBbRP9B=_jiqYsspdo)WA(9o1qc$jb`-<+|xg&P|{K*?1pPGt&t~1P3P*l|6pf3*-_$%Vol$08qo82x% zT{AP=jng*1c61=xkDfY3E+Zr3K7!}N2>@?0Gp{HpFwA&eh&sy8e;`L)=+@zoYQ5l) zkVD^7n+(rK$aeSjiR$Vy)YsSdF&fGxHodo<`SC-${PBJgYOf3E-%N;)Kbx$0oht;< zhmkpD^5xAo;p=l;iWu4Y`a8wiXW5>Sj(K`{m9@3mi&ziMI^d5Eg&n?m^Jad2{?=W) zjxjS2XZ^fz!0Q55+0gK?2-~y0)YKoI9+$ts>UhHFgD%D%;}Y32f;)(bi(|>S;mD%g z+~BDx3r?CHPz2W( zW3D%&5YB@W6UT&w z!@qym(>=BS_03vFAt9H~T&=EK@Qe2cq!Sc+F+vIo`*0m@DOoPsxt!*L$tKs&z`kBpH)s)MAE>@rX+t=se9_^f{L;6=>0DSYhFo7Nmk0& zUxbEE&dlfze@-YZE$tp37t%XaGLY%%NecfH0i~U(Iy5#G6CM36@QWQixaIK^C+JU} z^aT`5v!B*mURlAq54X~QY579Xkuq7)^Vu^hEII9=hM1@@F$;6^YjdM*#vQotO|$WhcK2>?9-mR=70YmzY`@`R2{jSFf1akSgTq zCcC?j;QDBpqkmR4IXz8JMLnuVD;GC6t2z2e(gM+^-2@893(ZhzC2@zSMB`o_j$ ziA~!Tc_$|)ucv6y{rc+K^gCCJiS6DthV^B|*YUjn49yNAVMIsEs;VN&J&$O%o$u}L z*2WapJfb+EoMX}doc)txVnARZ<>fGei#9e~V7gYewoxr3>8i=^J#F>%nNHuV(JgyK z!J_(RYtC}2@HMUwFD&HMm9Diz)R&CsfGrIbPS)z4x}vFB)1u{C9dJS^J~cHiHFcMN z<$aNeceS-XZ{PCx`TMKn*^E7JYrqjXWo2bAc+BsHSH=OTllf7kqsv%NVPJnI~B_;b{0%I{W z)Ylikdq+a)xhY588)MDH^zi3TyFeC|_i%Q-F2#_4alox$Q%cFm>@v)xxm{jHL%J|D0kFoY_()l;aESN#d<)7v_btgVCF)A@p@_CVsFOPu0i@fn%&of5ND6JgB zw#NGU-D|5|Yo675^hb~0QPOe_Xl_<4TpT_Dpeki;eFpgk!Gnx;^ytw~VS*uE2e>nw z7N$;e)3H#JBF{Lj%(m$2>20TbRj(|2PftkMzHzi_a zZmsoMQNc#ln;4@c)yzjA8GHhX{xR9v&tP)G=3K%B;n=4|_25 z$Y8sWM*6DQix^m0ceuK`(mKyv(W?$FgE@Zj;>C!}ObX;$keIeTbmyCaNA!EVOieXym~GwLrIBm3jYL>jcpSOHJe-xC zot=_Z^?qF3F|N%qg;>nZUSZb)H zF>!J3U|Lfj=zXLXmynDzGBWJuJ8Y5pla$l%0`a@OcyX}sXD{h?Qc?p`(+bqT@82(& znQ;Js>Y@gI3Ku?%(@xHvTc_o+5W}H0MrVHZED5sq_tm9|n@z8-e$dUhm@V@gB7|Jn z=W(9+XPRpA;H*QB>9J#RogdY1{_O=g8D)dT%wzFwD?YE7HYX=%=bpFQAFRj68zIin znuSi>d!If@ff3s;PgaPFRkS@w=k9Xy7j@rxMNQ39im{}l;}8M>s}5ECX+XfWbY&jv z;e9G9DgvOfUtQN$?lS4Q+6&|Vkzk|q&Y-3-YO>8(i+0$nfSbhR<)I{d1OMQY?yan? zk*zK(DpKy>zaO||a`bgAIR!<(tdC|Y4knXap7e4320RY*`QpWkAG5P%xVvYWh??4g zn3x##d^_LAkI9BdMi5E^CKQj5y|L~XW9~0yk^}bpsDYxsyyGm zecMiZ-k3^5%XP)t!qO7?Rb(d7-+wO}XZG#eXSOhPBg?c)Xqm&C#-%MAIfAy+2)V8zdM^6dbp0?FK?`U}qDEIZNI&#Eu!0@)4;fI=HFC;c01rgb% z0yX|hViT@GPELLoHC8n_FeBp>hKUylotKvvA6_opjkpUpyFWFH0NcKOJEs5X?g0K5 z?U`;;Zs-%j*i=?m-vFFS(kuwZ`*galIb$}6=`-ePY-&1x^(uwEy*;P`y|09F_N_yQ zooDtC;fSRAb7A2qxbo0YL`sTxWF#H#Tt70qjJDJRXH*MQQ+<#hCX2Tme&X+c?{eJU z^5Vuu0^B2bl~OfPY>-&lehfzWOtoJ3**4wajkA}cqwj<2?xCbCM>{4#AF8>#qF=w> zOa18c=-{B)+myV#5G3J@o3*q!bZDb5KLf)?ZfQpW^p<~iW0o*ux) zmq-OD*|-ZPI}$HLrD?Y=MvgZ!1qUTSH4>gg`j^$z#Kynk>gpXxK0xPSFo>}y&z^~^ zs?uQCM!)9x?>NBqxOL-cYBDT9a|mG~A|lUEUf&G4YFSTMZz;`Nm&Qfc3DJZJs3b=Gw*UCo(p%6Xc;-SlBbuhtbgm)cPzZOIXOMU!Q9QCt0Gx3MJWME}16#;@m5LTAK*#bIhZDi0`g(is=H>CLCM!M^sI97s z%F3cNH8n*!O}UsU{X4N;KJuva7r?>`A+c^CJG8~?;X~@#_}EHaI$+tZwbgkn->sFC z%}FYv`ug!l$ho<=EFge1G&H<*m}QX`U9wC(1y$rqR6bHvy@PGqc#z)xL zE~jm%)5l12K0&EKpC=FM2cy5o^XJda>1k6d3^V1fUM(9*Evmr*a=uml$jaeOiAtw2 zq~M$AOx#CFX#wfc(9rNFIuLy;b(edoigri-7>)dlkB=`V{_0YURJc&6bO_hBikdM> z(zdp?7XtQvNGDLyy+C+sh1Zr%B)1NZjS={(xVZRDR+gNWmdu3s|78Uo@YUNa0D8NnXzKO24YXuF)e{K9njnp5Ky zHx7okx;Ji2qO(^{LxZ@ZQFGGKs}_g}s|5-oQeN1A=> z?>7fpN5>kk?f5~g-y5Cz_VnJ7+1c6CNIyhIw&FVkHkPE8?QPH)i=e|M)QDHF9-%PG z0RdBKIo&~I@bEkbFpHq|uN2eNq)jcDqZz0T7mtulvzyc*pc;TmN=nM06(4k<4<9}p z5flu?1tJv_C#R-#P+PeL3;WEEwe04f8&q)YfF#9u`m{fwMH-A=u#%G@)d~s$!WRd46sVxS)KO%a0B2H#O*dx2`XA7R3v1 zzYSnYe(>O9cXxMD;WqBuE^A9&@>j0h0aO8^yuL8i|DN%QYI1B+(qp`uAJ7Way}FTE z&@L&yZP$P$pdXR}qA;F06M)*UuCD(4^v#{y&+V_QtYp#1{TvYniw9h$65WZSsMin~lGJnjzJ1dL z|AZQ#qpf}Ws;)@1-$VI zV}-W*A*=UYmtrhR8OQXIrH~5lAk9MaX=xG1SrZTM+i~msd~JfFnUeAys&6zdhL%_I z!-suDB6df{`5fYRQ%(MknZ>{X(O$fE?I@&DZKNBF1V}p}_3&DVrAaIR#XJ{wEgVc{ zB{J4jsOWD@wt5FxgTUy6bw@EW9%6JySy&zuM+`V{=Abm}J$6}ER`#|OBRw0Nx7ONX z3-IClqYdJ5jVDbz1rYA=Afhue{5EXa`Itwi4g3Hw7s0l1^X93aeLmCBwRrP&F;^&E zKqmRK&1wYYMCn5EIriTVNHk_Ye_Xp9%J)Ewj^NA7i!DWZh!5mw645JHu3o(gwF9T_ znvy!dhPrgF8)udxUzlTKNRr|SF!g*`HUdDhJB6|#0V10tR(@7#t%{(G;Izf>cec`7Js`^g!oykb9Wzv6_Q=e{9eQ|dVugvewZPLoAvLR6C(!T%xB`=CB_HLM_uC8VU3cXWgz>rO-F+o9oK z1xuFyCrdkh!#J-}+W0x?f)>e|r8p)S(V(=RO4x{jMgcN%6kbaq}=S3j6q zw8{tPDmo@+61x(n2r*hj1NMj0Oue}JTeEdkR8)oY1rw7PS44RrkJ!kN6(7MpLP8E` zInPo6==4YV2+F5gxi-ds*nJP)r~!$^kT>~daKI=!t#j6 z#KaRw4&RB2-L=#?f3R8mUhz9TnQVfB(^TcL&&|ylz{{w~L0l%mvX{}}Y?L9WqZHRT z*%-e16nuN@fxUA!U%1;l?FSB>JAyoZnox>^&KL#C63Q`f5Gn@z4&f&uA(DViSnY(4 z;7?xRI&*|)xXa>k3^IX^5!$P@YYV~*jEsCQ^r1Tu1JJenog2m948RU+ zllK+Jt)g2C>lb$^iW8y(C7ZegR1Rc2qzhtn1q1}_h7;oKFy0TmZ1P%JaQYKQ z_r7W}rQb%G&oY{SK+@6QAjviEd9@xgHaN-*e1bW0yt#Uwjn|tuoTw)cy}iFfhSpnI zoQ-NWI2FVZQZ2&S5Bf{!P+Ql|!DEO#?@4G1NI1F}1V2A=lMSN9lttrkl zMEVk=!?p`7nyqAH2hB&F1dO>308Bbz!xtzYFllR{Gyh0Ss_pLN&=)VBbD7X!o5C^F zPhj-A&!0T^am83yrMGCCB5L0rR%jM(E*2f8OAA<+$_{|!2wNK`%kKWJ%NJK$FD302_ zp00d9y*=$($wT@Ql#3*dyug~8%d0JGi(1^y!d@3dRaAmx2Z$AapMxKGfJHft1j{f< zF>!Z~@#{85=US8%6g$`ocJ}sr$jRSh0rJu935Vhw8L;aRpBUIV_%M>C*KQB@>!*Uu zEG_%WsI+u}Yj%cL_FLdM)Ye?<6XC9_yzn>*3x$}OnGcHfA{}B2!zI*50%@T>Lh$4< zCb<|RclX}CHp~DhP5ykRBZxAQg~MDH4WKY{1WE0qpfHEjgR~5FN&xN}R3$?(g?zaL zU5FsSGaya|`ua!s`9q*~yuMcAc5!~%>#e-e2W5Z?q+7ye{MPMmB%_+GQ??yWOODML z4ULx@9?fO3G28;q9nVZCQVt{I$nn1m4OIA9nlk);vFX zkMPUsBjv_uI|0NAiqzYygFS!*zxENFqefleu5b5;ETWUH+=}FZqHER~jh#O49S9Eu zzzw*49~G5Pe8o7g0C+QqPaDSiwO+La)Ajk6nmHE#85kIhwrBfb-w&HcZmEpRl>f)=0ArMZ2XDK zqPcbJ)>kN9rDbKvXZ=6k+t4GP@vpm2sQ2yT6giSbcv%l0YQvHG6nuu%*4EZNns-i@ z3pfdj8Hu=JlpR_d&@3F6i2VG6_ll3$ad)yo9|fu;YBikIx`u}LLyd9b6dqf)Y(e;S zgNXvyA(q9JZ+~UB5!TClcuhu^GcXQC{TKl`nVB!`USh18osKUma{ZKHbB)-k2Nttw z*DjxssVW@aL^yq>YjdVp>rXHBKM&k*Q_LbH6n6LS`Wc6n9RqhDoMP6lFFIm$_L7r} z0M7!GLTB63r5sWXD=lw##Mr<<1%%iNsUrq5s*Ju8vcFsxQXLNfI#`uhT|J|tQXseB zL;D-KU=cwhJ_`n|Wuu<^IrI`B< z9;D;Y>MKi^W8}64ZnLR3;KAN_pw<0e7w+KWPH2^&vd(JE)UzB2cuvt5ZwTzm&-utetEeLcCk%7fktb1yk%a>pLoUZG?zi#zYWKGl?ly92s7aB*>JdL2S z-SrunjaPWJO>OT7-BWNrEpiUNZu`{T-ThGax=m3r!W`P~PvBW|OUvs}Q-RgJ;v1{0 zO%%E+4_x!f$72H4tlzNV(6VA`MPs8sj;`>zny3f{IBfPpGeVZbdC}^ZH|EIC%e!rl zJXDcEtK5s(t^yD(ku8l|)9w(l+Sn)xItK3Z=^?{aXdHl{4h{}LHK-w8H0F*cS_PS5 zO_PY5Ur(BYRdE`@5kl!Pwi?L65bX@{ACc+*;)TGgvO6LX)V9mV?qZf%Sd7KK{jlpF z+hb1Y+3z;}4vM4w^mnfl>v{S4aUh4NhDOK3Z~hP#U|;mKX1TjpJp546gN6;lJRmqb zuPN0W4!0yE3l7dO4-XG|x&d*cHJBs|-~45e>Hs&iF*$s9(0r0`MwbQs3ElF1G$r&$ zp?_{8CACZ=r%p_2GAz^P;Bg|()?#7V=vG((5xsn$hV;;e2wh)b|bOsY!xLX8xj;AA*x#s zQtw!r?r3PZTc)#r(#aF)@!>-!s(+q8gfc=hZOX3Gdksk%zB6G1tEf~a$j5!Cs=AH} zM!16@m|n~ot@{rijE;)Bhc$?#v7egyoi+yt56{Cgonpv58X99}PrD2=`9AO2x33hO z6sExi^h}`K0#^n>^e2pIKEB}icqV|K3to$%Omp{DIlh?_nRMJUPJy|sq@>Ty*A0dq z$|)2fSQT+aMTZMCec;|2X6j_B8r-@?NhdJ2;*tlUft)-9b|3iHc^jL#hfF(=L9bgD zgIt2b?(-?(Y5*yaZF+?E?src|RrP%;Mt3f%e(SV83qH=ljLg~0>-q8^n({fE}; zbzGo*?_Iq7HrMPoZ@!wbp}KCb?<{HQ<-ha#^=bGw-0BnVq;I)ZmJRWT6lg zH@`1bA(~j+7t0+x$4m~&{J=iLjI`e6Z$6 zMmGJ&FJ)ynq$IaGMqUY$Vr-@Ix_Q_IVQj1$AS1+v&G(AWF>nP*>2n6F<#u@y?G?<-kATIdA?epc8t~YAOu4`zQJ`utEmF!+m+;nP4OR8-H*xt+_e|D48$GV!2|Yj-^#KK*Lay@%GEp-UN5B24y6sdpD{2SAQZ38hlt(trN zg3ZZ#p>PQ`5O2ui02cBv*)1(kqnZK-BV2#vajPWW^H64%VDRH_(DLtJjCQjLd3fNY zK!feu+566Yl8pYm%fdR5)}4=~%j~3L!+Jt&u1{(l6b1M}M^Vo|IEMFmAaZhCQuzOH z^&W6N@BJG;j(rGO8I_T;imYhbB@_;!GNY`9&{lSw5JFawB&!nI5~3stA#H7Gm!{PJ z`R3gJ$M65YACLP!_o2Su&v?II=^Go{556&%fr&6|-KzRE4%>gTR4h(ortWa-jpz-+O+bHqA*Bux$Us~C zrZ8>2tZy&vCTag0KLT{c-`n9|lv$@PU3yIwBi?;Th~Ud1L5}h@0JNhh0YUdZ2d&fE zka4Os*s-+&5R_$g1)PWmmjd*FA2w)cXDBrRPHD{-P5-yXV4hEI{6z&-2@~a(CgtB8 z+R}gine4OOReMXe#ohklySBgLovgFmyeMd0y!;5~wK3TzOih#x(n<$e{M~L&{_0h$ zrsq~}y81VX{z6ibn&~+!wL>!?frSX7i>%X3;PSyI<{y3BP+L0(DyE>|5E0t+;rq{@ zZDLQH&2`Giey-w%L6_gM_H**Lg$;`A!zVp2x}9}to1GWJ0}g??Vs~kWS8T?fyP3ED z|KZ{&-1RXxw|w}7qHphgXYbzW;1D@XGGoUy3KFD>txwUIFXH~R( z)7H9l|CNc>fNgCuVb*URlFb0X1T0S3_vFbF(c;c?8_;L)VByZ(yW6O9x*#I?0Pw%! z=537XwVh&@-6CLVUMbX8&*_GX0TLfL|7y0pr)V-S?BrpM<_d$#lFG_tI7c0l3UEF# z@bB7NL?Nn|vE#;p$O$~0UQckA?w1NG=ffHa@kO>nsUir;PFvez`kW$UAM__3AkpzP zo7juWm(7wat+vfYt+>T1u_J$B5VST4s#jr!>(#3{=I$dxcPV^6RoNlcy=3mm+;!_L z?4(VyOvVR>Z3b;9;9-03mZddnU3_dS#S|gSxgjcNC+LlUugTE@`c8kel^jE1ICe)@ zs&FySKjw6!W&fzd-FwviV{6-RC~)${MYA`?m6{JObJ;#+u&Z_ch7d!L;sZKPBZo-+ z-u`_~zwh%~S=gt~`fs;58fPMMj01aSFIaG_stMj7jHCeK3p(TGqKnT_yT9UbO~2D< z@-PiXxNm)5l)7?qax@hCK&XL>h{u!!qsNZTqxFF2SPE*1xT0Ivu3v>H`Ox<#n&~B` z<+9XMVhb9AzKU4OYR;{4%>wj8+XX`xVvn2>kLa~NCW>4v7 zn(bL|sjM)#z0+P^Nf2QaFU4P<9i&8Ut<`GV^}(PA2hWscMR}6U=>E`*&eGf&9HQ@m?qUjWlzV9wJWu?yP!|Wgkcsfa9C7A*c+9IBTfVFYa6F) zI4eko*zb)nI(GkYtD#VwIF>0FC0}*Hx2A3Bcpl!Ev&2P7CkDTzw72o5%k9N z;S&EWw?CPG?xwsy5&r1Wr&alJsb)Ds0mI7yDPc9~=<4SEgkHR0GoZffwQBWa@w0uF z2#pln5yC~vAQU;t=v!V9a25mQAQdlsuPqzxT2m8(ThSuLReP{dtZQxE?vfy z=OeI@bH(0{7Mb^cbUrvs$GBl}etCHkl80_RdWg~#+8l(aD{BG{6(CuxEf6}3^sDvr zdo)Z9aeD!HKKoJH7Eu`*8d^9S!9vp9piet><;roSkE{zJU4Yf5q@NCnhGN1)GP0~& zR9V7pq@V(v6L@aiq>O@X_jQrV0^ znlzVa8i~^q-A2UcHQU?%dVHY=Sq4prx`qa9gjA0sYO4M*iXevKTiXe|4Xz84>SRRq zW|z;ceXLOHy*@kU`4zzm!)J*8$o>RKFyJkrq#aG6Abg5hF^j0z0WCS1;*fQ|veQ3C zw09^=jcOtW{@$ET+J%-W?G}mxt{{{hCnY7-yW_i3k7H|OoB9qMs1g{CWOAW_!RJHe zo#Vzbg25AA5AKN?ye|uyv;^zfcfbHVXeo2r^^F8mK7~>lwTB%Yo{){0K1}oJRaQPY zImO`ar)35P^UchP52f4R{nGb~;+n{QKnyHyDmi3sr_P)?uzc(&NFBHbXA^U)J$v|< zMU6(h^)+iWDyF7t2jq;;Poof#1kqg;xqA${^p40hzX;N%?$F$$xj;?==IOe4!i1om zDH^)!0VBgALEh#5lLF}wOS7%%0J<*)w-(pa2T)qeFUw& zb!*9D^HwJhr0H$w8i;VWOCOq|viV+7eQOJUYjroXHhkr!_*KW>)(2|mp z16za+3kc&-va6$!uH2cO>z;zF&YL%HsG7~2+~(W^NPdUIPO43^OwNY)6ohUuFN`-6glPFaoTK?$qzA|!YNCr?dZ~;E;-apL5SRdPz1|w zG1`uU>n2T_)L7ZpY6&<}d*W!Yt#!{PrS-C1sPjlL*ROBPERK8fnfVeKsecc^U{)NG z%sz40-QB&nat>UlscBJ9m1kt&rk2{|CXgTi+qnS-IX`}tXC5=#(ikn@oRON7lMFcx zuC_D0)pD!%;sHVk7f~#;eoM6ef(3*A`52P6gS!=UB58^&Zw9R+aef8Xoh%YqFVSIB zCZN`Hw|DW<(}v@Px0*NNbZ>fU1f6>wV{V8QaP*Z{*XufBUDWhCnXu{l+ch_ zhL<`)mchUDf8A5Rqi;$HVy3~Lv_Ef|a>mm$o^Y!JwD)!KmT8xzU-M8{5??~L4~${Z zC5;KK@PsT1A!;b%BWO1(y6?%O54FE28HM(c($%y@M@f90f0pwld4s!Z3KkrnKa!I{ zgp>dk#Jes;cG4=ktoa|o6EJ_=+)yF#{caPUnm%j_?JAeQL4Uo9Nn8)k&0|$Kp_ZfD z0G3)EW|4LD#R`5O?ZvENEmzx`t}gv)Izq>9nfO~KBK8eip8E0Q@zDSux9;8B1XI|z zW~KBAz%o=^_J!wGHoCVp_F_m$0}3ZzF$a(LuA#9SQ#a^z94s?xy5S_;ITgej3l0D@ zUH<+fwJZutv#WdKXig8?uWwl2dQ+tb*u=a*$DvUZJ{x|5M zGjry?DktPV%C;58l70Ig?sy(ABAHs9=s&ue-`nTh%C)%xVcC(2r}I*GDTqv9GfPoZ zQ-Oel-&aV&A6OUa(piAC8%H~w16W`5Wl6Y9fWbmt z-R?n;YkvP%NOS1cRQ6Qn9;+oLvwLmlI;|Mp?|Ed51e^5>IDX4BQwQW$4p1_dX;YmXlFW6>b$6AVgK z>d{SL%OF7lqjza7cClmml36&W3K{k+lnsa_^MD+Gi_MMSB91<6aJP^ia*B$|-`8Wy zH6_*5_pjlzg&-f9Bg_EvBCAoV9NiAC1g}8o{d*rnCloFtR_$JN9x7B29>gwmy+VWp zqyBJDsR58D-eEuL>ZpsJGaMvjkjl!{H_N2TPA5`3h$w@IYprAXR9Z{@9XrMYr5uQ! zX=|$@@`Jh^-ou?i|A;gLPwK|5GdEzn1H936YyK>oOjmIN=t|y0nXSr>xBx4IP=jQB zA6gagdV!7($H=^+O5kN8LqV|Aff`hFBN>)4NxU{FO`*$aXq7)Rgh#durJ^=;PWFr zhtNQys$ElcD=8_d5UC~*hRN?P#8*D-@rtr(lOP_NLdmp1dR2_HT?GMnpOO+w5<7`% zPH4E8fLXb6r6`lWB~l4Ufi$A-8lqw$H)c%9`E(R`7u0N(7`tpI>r~aA`u#DeIiV4r zbQVwslmw`nSVQm;*rVMD50_%u87sw03LlhQK4e4K zg#VCH6o{tD-bs+g2&mUX81qW-wtI>XD0p?*m*9gW?!REcNU}m3LCYZVq%CIv{Kyq8 z7w5T;g7yX+89pm4Ai(@%n--~dMq@hI{pkxAUNH~c$SvzrR#!gxsl;!<&#n4$6#P^` zE9f@6Yt~&>u`CLVsu)}+b9tIM$>$&lv{lK6QKDb*0P4E&gw zqzJbf?y0l}CH*m>R1stkiINB=`t|<(eco>o8!Ii;dsB50hNEeEE_UD|mHc)Ibo!&rk1VcZx|9rel){ASD$QrsN#pm)-*g9KkFa zku&WE-FgI{*M#JH5gQvh&wOGkTF97R88LmBGl*`;PDDLvvGayD68~7yt90#p&DU4F z*d(jqz3nN$g;bP@P!gUiu>|T{^bUWpXW$3)5wke+=Iq%Q zG|45WmM14997A`{3ILcG(9s<*4wW_AOW+=(7=mL$1dWj57a2C75Oz`9v7$uByn6Kl z+BpHj(c|z&Pyq57MJh2(J>hK;d$ye)sUH9RG71H6msWd{ey2{I#NdOG(L$gU*xi?lP{dxco9Hsr+Q%@SIMh`Y$XYnsO&5fXOyBaYHP{`W7O=(fxY#=po=j-WjW| zv9YlVzrgB)vMpajkDAf+tN$!}$RyD&k#;CAc&H2X_08zNQ1)Hp*y*iXeeT~s1${u< zb$4Y@5qdkHVL$W+oYQ?tMUIYP4%IyClNU!;tS5)`>3uz1VZTGW0Oo+CoO{*WWHGdN#zxC8s zAR#ka1c5pI{ZcCQaY2tK0)J;`XEDkF?j$jE`b=WA<&!3PQLzsj)@~m_ zB-Jsxt;Xi&8cN#kGP$Yw1qClyu6DVH2R4>lx-8teQ<-^gU+$GL4R8yz4xj=Xb~&<7 z#3Ns}KRQHOJ*V;+q`+R&=Di&?kywp z7Fj}H-nC!`*!e`pwN>wio&?BYI5bzFXvpir$LyRsY}h{F*zSZNp&b#Gb)fOi>2VzC z(zSc{jZDOeX&+>}*|T)IOGp$&6nn?g)uKK%GgAPY=&xyOV-#x@rU znf<*GLX_m-M4iJ_B4-HEUkIj##B+aBg5;By8YU9DaT`2X)7hyxuWWaXNYw|*KyBNH z1SHg)CMLeIUvPRC6Fz^`8of`-XZ%uA9FTaZle*B{G5F0&=Vc&AyZZRCI#Lzwv$)Ti zG94(VpdhLO(yzw#a-y?3q~~LN0fZ77D3r+oE(dVaAiVgmUg|SR3#f;$!)$@Z@1#!1 z{mH%zrsfpi!YS9<`~<2a0bq$ufbvo#CLu$yoGW)^_%r9&BRxUl(I@MGtdhGW5}L~v z{2DNR)zkBeMs{EKcjuMOMBM2~wF#FsT)%K;R6_ctdFKm}TR zLhkefqtTfOQwuWYk3Gjc?X!gwqUWw(KMdLMfa_yiIfPOG6qrYnO!KSbWs9le#nVE1afWj8($wuw_MHCm z#K&meIxUMCzVD}R8w7#ZXPPWanr-4-|L|%b23He26o4WJo=JH2?h17Cc;oO>b)~5f zk*@BHe**;%xPu?~bi1lyl(f$ccf_}n#HnNBGI1Cu>BWN^T~^sJGC}z zR1u*i{CK?2wuL`+*~^B3WXa81+xLjkQggIWp}s~VwvTPNijNKAln)MuGYX;3LPQooD* zd-qdbS=n(|e?f<#8J`_9RYk?)(j{HuEu<-M7O@sWLU5a?nCU>!{`04F);f$6Mnnu^ zI+a>=;ra0!2we~o;@ML|wQt{kM`rkGaC7CKVGkdAAmdB<_))Iw0Rc3J++$oCtbn3J z4BCUh2^6&eGlZ9faya_z@b@>TU0&R~xa?PEM#i|t77nR6aPS~RjR~9`DyXavF0YYU z=#aT6cJX;%w(P^v8_UB?dS2`i`!kD0&BmHUf?1ka52eA#A!9oLdO~R^w00jK%=fKs zduUsNO&zlvzqJ4+!2Rh^(`1j`#qvM08Dj$B0 zyOS5$n#pS%3sy5Zudu*OIc{#gclg|wS)(5u9r60fE4`&lhJ>V6_PXlWrDMO2Q%f|j z#ykoy7P{_+=mzIx$Ly67D>&X`(45>z*MwWJu!C zJ|m^HoSlN2jc5Ps69c70-N4aYLiQfx;=+XE0?HWopoCm2rjiugGSQSU+aONTs^9)F;1&e0bg_Rky^K76P|7xZMT z{TbcPJ_?DMd__-zX=gOtdh6uBzIMCHl4d&~-TPY|B!5dtx@JRf>!>VR?v%{T@owW( zy#g1`D%@tQG_do*_6($_mX3l@zJLF|O@>vF=2g@yrFD{0Qg;93z0(!2Bn2qbh+<|- zNX|hMqD?RIztwLhCoeHFN`%sAQ0f%#omXv#fB}GU^+(i0QMq4kWX-txTR!xt@3Dgi z4y2E|5+(DYQFjE~mzC%9qo8!b!F~Kw77zznL2KTQ93vB+QX(+K51uRB;}5>vI4dYM zal}p>2)N{UpMf`iu8=gpG0+MeaOTXXiz5$Igp?Shos#XK-W`Db=sAa_39YI50?ex<3oR*XJ&>)A7URKw}iQooRp6>B$f{7p@CcG|D}I)~tl z@(0(3_U>)9IOwj6T$zm;dt$&bKgX*1CX=GFEWnXFAN0uzw{5Uj?ARIBrD@*$n^y}Neo@Jx%YW%i9#!3ug;zA}U&m_@<A`U*t3-r^NknDoArQb(f;`P1&cYm`%6)HE+wpK?CC(0xu*&T)-}f|16J~Jd;KNaF zVHm`~7t=`{{ZkU)LRbpXS&P5#i_gymJ{52kdgP+FUT!Zp=6(q_fy*XOM|#ao*)h$- z%WLuG&7=P6+ynfwr(ez06k9*i24TLPXek(oHMe+wt~!B=>*meQuCcQyYQW-RvXYvY zrqoN1WGa?%xgU{l+30{dN3tx;zTDqHcDxh6hfv7a%;+&=wl+9|LLt~j=>H?q>-W2@ z{_}3X$ura3Qljtjykz(57@}>>)4zKCFqDH@7Em1{tl~G#lH=mzi_f2H8=hO|AjYJF zFzlt**-Ya}*;0PjItmCx;%>_51$l9&s!pVzp8R={mI(y6nuA zD{sK2NJSb?LIthIWENGNJp=5{r$z*$?q)Ett+ldEo)K|od<2I@Cevoch&T{7Z)3Q1 z5|W2G{wX{FMr#a$GQRv7v4BwCL~X1xUfnTTIQW<)d;49xCfqY>_e7ogpB8|mLPLDv zg4F!uQqLHasH&|kUEw%n$dI)A8~$R3!?QTM{3a8;qU@(W6IxqUFP`k;qc5U`Pm~Cp zcm#m59@p%1EXzVgjE)HZq6-uE(;S|r?2!3{Ezuk5-n3v7?Wml8mMy~$p#Sf^)#5Sy z_eTCE5331^K(G)KAuKXEnqB&VhC6E!2}2vjGfRtpO^hmnd|9|Xj#g}&GbbpuR*X`C zG@N4lfkT2+gqIZWQT3vhUuJClhW5|0nN1dy$`VIM-IX+zwxhyk_2Jpjh7$l6+N@+8 zW!$>}`LVSIpXeNwrPNk#Y8;kWc%9n@DLB$&koCeM|8_#v1KIbM*#})V-aj`N4M+L( z^yyOzGSzgnvt}$4c+2DPh?KE>G(m47FP{;v7eYzHf1)0c`2a&S+gf&s9-gjbzHgtP z)P0XN|`0=h66rLxSL%UKrw$nAaKA6*+%xirn_@U!(_St{HZd-Q;=-*byFrafoT zflypz1upb`KXK~^x%uugNkGfc-NV>{^eJmYg1L{d9OuioZrvI(AeR>oel99(sxThW zBE*$k6m|v7f(%mL*wJl(Vjh#WD4NTTyk&r9`tEPND<9WNScF|>0oFG+JGwpU&6XVu z7KTch9sMutOGDZWfJA}rpmzt1(!AT?x({mq-n|}oKfMOr1~WX>c5}(-s_N=z$;m;< z*~##902~{Lg(xKZd+EhnI@b=dKmABer{OxcXZmm_W7YT-Py)Oxw60sACQ?LI{;c0+ z)w?+qxZyy}Uh?vt-CjPY3m4KrkZ+gN4yH~l=?@Dh{Q5R$z43`>>*?kG3NXkR>7M%* zw&X=zTn(kkE}jd(#VZknEM0zP*gQAXr%o3rbXdmTIc~H05*k2paF-yx5(_s1#f#A< z2q#K$T6N9@IRWWRYPSOqcW_b)%UBHgBan6$lNezC3Jv)(wV~em(gL3@QsR@hub%G>#8Es(0f@rON%o2(zcp6VJ;a|REpPs)-;p=k{c;L9- zG-q68(~X>ed_4v+!r4X);XoFMo3f3PDDkpkhKaJb7GN7=ifo1Qz9jBv?!AUfa@Ub*fY)6P};r0T9e)Hx{Bg0nL`LrKm78zSCp*a$+BwB{<-(&|fiG(UH ztHLzXnpcc&U>8T#piqe5mYW}0%u4-IZbPq+a!M#v7I~{jXcyKwXh1NS!gAtkR{bMI zf3i!f6Ptu#UUBO@pkSyZK{i2xC_38U@+Ritg_98F6(ZcJxV^|8?A)^hEZkY9_G{j% zRSL|Afp9wj-Jg$pSq#+k_Yl48^5rksBR}ONV#EW|KDh~X_wNS;^a&O^$)&Z$B6av- zPrNiX^D^<`f^otOiM$IJ1+i6g;Ax$(Vt~8aO!$RLfZ}-uU@#X;2HHR2jRXjmy|-bF z@UI|5gj0YxJboEN5C;$xOnBT$=|r?fs&;`n5;q)s44X9R3?*QYerV zpZ{#j6w;q-Mme@6Xs18DH34mW&(0)*frl~f4=!$bt0xRR-zwe>93$bOX{wf1updG;LynG%f^o*CoianoQZKAxW2ky#e> zy<4_yd1?_RyjK{UoiypeN}0_>L;#w0K(~b3r}@>dVt5e=vIo3EGD_<``k^4;fdsfAlc`Au3v zdcBmA7k`@iRjXD-MHE!q-3O=o^l2x!L{l3+e}2oDWvckP^h=6;x@Ug-mFnY4OH0A_ z+Xo&k67_jSOO2g6y$IXoenvTdI$)O;qq8l{!m}(;KG5|}A1Z;N0oq4kHrsClJrfTz z2ed5&M_WQQGokp6ZQh^nkUG-7kL8#9?cqpe?7p@a?oi+=`^Wvdo>Bq;-?3At(^sx! zT4>KlMhIT?ywF;(Z{AD>+GOuzhr-VwE*Ii6lqm%u+TSL-&uWZmDz3IGXzH9PnPEO< zF!nJo%WcqaDY)gY3HfKR5d|-k@t!u5DUAnBHbnx~kMjnfv3lWi9m4Xjall+Hq{w;{ zU@8_v(d$sc&KO{CV>1mn__&P5C5na8bT9ZO6#KI%@L+lcIaWT~6^8&;k;tmHF+Zh2 zfH!U0^g~C^CMrwlqNxlIP)H+3%-KACV@bB>x#1z@zsG7^us3wKNzM zkH^`3skY|kj%L5oLIW$(=O1Gm2=6pXZUn|mY$-ne@nKN9skLn*x!fFWn3f@H+ z>U_0{T1^TCsmmH*?`YJz4UA6+YFNt0k?t`JWQAsiY&e_L!HP#o5$7(Oj5-nZg;28A zbXkDt9`=kXz=O??ZpraVnHU8nKA41M44PrR$38Gcp7xEqu169>_3)Jd^sTPhX2ec{AMSJO^Ija&sK3E1wx~9^hJFDCiCpK!DO)8m zKM(`>>;kA#CCAjY8ueo89dK2F(wkfj7exHDw)sgqx0N#b56-GDAE}_AJ>XbuZ0sO4 zoAH34FH7rcsGEFYZSSw2<^KGr&aXNghlD{Z8%EB(i}pPi6@Kjo7h3Mx@m(dmPsU*?5ba*P84!} zWyJ0hNdyn&hfYCN&|5ykSBPmzqC`#YZ#;zSIX%!o)Hv{0>}R^4wJI&5Bu5C2ksvK+ zES_zf_OBX2=}rYEAbYagz+u2$=t4-Dl5kzPQl-smLE7Gxt$4Uu0N%mE`diyob06@#-t@Y$rj2M>Ntv#K^eRHxd2Bu#?O2QHy7&a;{> zn6Ou;h6`Yi(kj|(vBz^gQ3jx`@StzwmLsK~&->%7A^ezhs9of;=nQ^N||M4H6q zS1$pXrdp($gB+D%?v3FG-}k*iSh;Na8`Ca3bINT5Qp1)JHaCDR)@j5RNCtrxuwqZe z8wRC5WXAVNTdO15nRcU5g!gi3{EK}`t@_HlTE^WKOh`}$EC=cxh%(sug9djuV>pe+ zgfbUyUmZvHyQ^4_AA13pL*)V%aA@UP`%XY|fT~=zur8wsMF^E%_*`hGfw@M(&mrf7 zjN7|->1y4Idg6o_c*XnyhSLPJ9}&UC-QSk1-CMW9zP*osXa;w^WXaRWJ*A@+6`8RR z+IC1L#__Ck7VN!p^=dM`rKmO2Lmv8v1}oAXF>M*V{#ggj#;<=dloHyvT+e8YaA;tS(47%8|Db;n z93EL{jb?~_>5ABKBD4q~zQAa?-X4Re9R2ulxe(IE<_;S-P8e2NF?vWVi6|PBi~qxG zZYPXWDEx(|<=qT(&off3_>2HgpCw|g8_=HnZKBh_1(4{mdc3(>y=~T>fyflv@Cz;E zUJ;7FOHbG379huH0hvi`0%b|Bc+95@QzdjW%ug;rt3mk#8SVY!$8KVPh;k6vqo6)v z#4X%jEXyp9X(^n*&4|rFpal~KE);qLqI2Yr*WbTK67&JK3dB4Vj}UNpU;DqR8XB1C zM?c|)9f@GL!6pSaL#7rURKykD4O{>8A3H9oX*;Cgh$s$kuB?4DAr7112T&8@DO10L z2h-zHC?eE+86WS8qR^XO-JWLagh6J8`frSMa(D~1%p#!#qNoa>$Aapy5xwxH&J5qlpK(%TA_C(mMag&+Ww;eB<3$rb zM0?MW57@A>Q=^qLsF&oxf!b*0!fedY0|-LlJ^GCeeP+#;eBoF6#9O=ali*Q!4_FSt z21*~=0*C=zXc_Zs8iFPAx0sThkuwu>C@?X>?(ayOB;(SubM@$YJ9UOks<9h-NN8ez zf6Ix{QuUI6S)g_Vz@*Knaa-4N0Ewd%TVLzf6apbx zT7(hiWc1j?&{8+n#W*9a$9Vo^k}11+knmn5+h71a(sh?m_fz%TMX#lGXGnbnND1Ys znC8Ie{5j9|0zjJo-%IJE(ehG$%wfCWIvidx`_6JxJV<)r!-vh62tD`?wY#8h|Df!c z%g9jbetg@Kk<1jloDMxq7T`>qiYS(x5XgYSBoeAJj=fOXI3#H8574Uhtb9Qiz&%+p zJ|%+$!+X)<-^JP=s5)%$f<>8B&46qI#V=i2RF!?cvd7ja|HQ&PY8cVVlWh|R1);1J zWTT3x0-1@ML!r-KYgk03mLablA2c?k*n*0v0@~fcXgcdm4F25%bm`G^k2YH4^0O-~xr(~aWeblv@rsfp% ztfAqh@oUwFN)UjBD@=}4ZBM#WL`R4aH*feZ&~9N1@^oMOmYBANHh@*A!LF=4Iv@dF z00mIlcJ3kd&YTo&2jng+M2Oki^??g{=hLT4fuvhlC}D~^mBtLdbs_{R4OScp`?nrl z7^m7j6DD$+noqpi0V7fu zbPBY)q?_o|-|21LFNT%DB1LTm(z0di)?AnuG50Z4b@x#=iynNUi7l z1{*0mj7m=DXK;r@u(A2WjRoWy;hPVpOXMiCak;zv&h{f8_KllX$zG*e;Kl>Dn`F=s zhvT%0VjjsX5aNg2L7S&tMpIV|UpLopS@ndrnhB&5p+tPVb^-xLfWi3sQ~^Eqk(Etm zJ?tANlk=gHtt8aj)S@^bQMYh|zl$_kO@Y-FygH38XocRLX<)~IA#qgagQjfhEhOH| z{hupGX*E*#2?^&^>L~T*Z@z4lInMJ3^y_yYYP-H7%MA@bL2ZGDd_w3X$ZwoVKCop_ zf!HDOdcS3goV+|Dl~}Qj32jtHYy3w9f7&KYz_^-;R$phLgtE#iK8AK)BZom);qpfH zpw5{be-vT|nbz!?VL?lBL_+#Cw$X1WW`*!eSy@@k`tehVdsF+XY#S1EvV>uHk$kb+ zCX>>d%7glU)rN+8R&E28%WXyb+_>9e*1A9RVff+cUV5m*#FPq6i0E`o(1?Ky=A5ZX zWeV@Bbp&tS$EB@RIMV^owO^@e$Q(KyIy#@mkh|D}2!>xV<=Id$FI23Wr?~24OwpzJeX4meMAE zz|xBS$%7JFBKB0ESLzRxb#O2F0IG^CF?!-7DV!i9fB2B6WFVnvA1#>PZrV?xxjo^d(pbE$p$#qDzBp49VRr|V6D}|Po z6Oe?SI_vu`Vm2cLU&1V9d8cCPkP7+nnk@(U`B&zNuU-k|`Qw_`<3!Vm1lO8OD@rUu zH<5lI{mSYugoTD$;{i=UgU(TyMxk;O3K`Hv8Fy`om&%~OP&smc`zV%$YM? zzvP)ygaMp|Eo^7wORT^Rpo!B%;z(AgoN}9rubQ>CG)d2%mboYc6O$2+HxR1q8S4-d z8v5bgyQge71hr-bb~WVPrM~l*LRq2I<_VlGUT<_`;s6-9|NL{wD5(L?XT06Swx=-h zTkru0i*jRQ)Tz!GwaDSP$5kVh z1^u5;(CHxZN8W-ETvXesA0Im7L9B*4XL>HU*@XqIVSKyRc7#jv?j>9w<}|7+D;FB@OI4yp|- z1D%Y=)vMUDRCvfGcG!Q-@_vT&g+=q}64*kbm$r#29NHBO58*0H0%Fko!hit1agw^- zEyirTIGZNbVz|JL0P?BnMK1>o^?78_YpS#E2_qLv>dNUaIR=D?MSj7J70W)?h9+3< zR`nV$p}Qb7Qm~Q8p{Q=rKIPo*a&g&hIoQOUUlq1uoo3SNmIto6y<8GG1dL1JjVZ(~ zjq>i?B%LRb;Zg0TWuyDiIzSCLk>7_o_7C|LMYJ|aS6X%d+L}f47f7A>MP zg#B%OGj2TD#@vvA#?T)j!wSv#H*m>l;ZeciL@H+!vT6L8N7%Y`4ATsVGJ_5l-}&LF zFR5)Gy_O>Dx9Djd`e3ykt0mai06xh5UB04VE!@+$V8IU??|M`9um5fl+B2~?)$Jz{ zSj!(T<0T4EZe3g5I(wwK1+6=F>?jc8i;cm8_ys#q%XH5NanaFp*rRy46x?OL@3TT{pmNLb=rd*w!jyy5Eu0Kd zVS5Z5BWH2A9OVM&)hi!))mrNshiIX#-uCH^&4GK%Zi{|p(Us{i!5s5)6C=VoO{^R; zG>jM47NzOYp@M?pgb>NpR%sQdk?dgVoEDSk68{BhI5S+m(CpQJf|9YcGN!Bdg*1o-a&t%p4$CKxe^peefo488VJ0-0wj2SDFy3KFE9S8{%kt1Bj9!WtUz^UDrS#LgS#1G4{qH|ea#a@p}uq1hdQ zV2HS@uYB+BnfMajDGg1)(7QiK8ark~Jv}hu!|wswO5T_Egja-3RSH0Z$khoFBSUMM)_z zWg51$NUlaJyx`>IQyz6|+-Pr^02pU^tYYjUjHjgNI`UCo2o1*4rSE;qTR7s_VW+AW zRUP;QcH8U48vwWveKfIXbytp%&=21>eEE-FWM0o3^rj2shzxt@3s^CpZ-uB%3GP1peEMh;j1`ntu7^h!H& zc3@O`ebCE|r%g`xlGVH-diJPtN%}9UbUlqk%R;sJM$I3l-TAbwN%{^n6Exr2QPuss zc2qe@sfj}nF7og;aG%bfdk&g(h?}P{6DKmn$7?(Ldw6?rL4djFLKjl#zyMH8V?i?y z!`rS4hlg+dql~j?4=zH*fO3w(Pd*FDtNoI;b_Zm1p+lL1+d1 zll3gu3MvPjukukvDBPns7$Pyz!=s8FyZRLa1u;I;9z{!xiQ8-@=zM8uMYjlAvx7Q9 z&6za)0$L#Cs;9AI5F1^p2Tk~DIScsLZ6T6y|AkZOF5wJl(T@(zX{1`;NO`O=z)x=Z z*cJZXt3P}h+mA#URF*KzJl3<>Z(Q&a)Mc+yR_1+g_Vx7zj0-Sm7_AgG+XwgmlQ;-s z->6E-&fz-!ednJL^Z|9oAqq++%ywrred)hfS>JM#I?t9AaqH7}rJq=p@A)<%VPsml z%`U|2O0l+-4B`}krW{bzEJ<-98~+EBE~SA7uKik-UT%Zn*iljPFYEAu5L*C$6CPL1 zjtclL_$>f?SSCO+T{wc?vtrv$#Avo46)?s_o zg^Yw7L+w|~i2~Mm0gxfZZ&9p+^ugbzmRzT}5T51Y42@;W4&VsK0YZG#ZvoszBF#P- zjgc7@hQf3m6l1%8JT*duGo6Bke{2ZM^KiUA>G5l5cM{gVIupHxj1NE{fZ;P|tmhot z`d5bzs&-oIl9HU`!!JE~bi#a~(~Ssu$}$a$upv~8tex9;?ws)`Li$IMAjNbb)(dfH zk5YKhdDg+sK2$}vv-V$`@JIfcxrrph$(KclfrOPl zAB#u&2aCVEMl0s@y>Y5rs-aiK*1X_~VfHCJR&>~3N|dS3sd9zNi)MTwZxwJB9ICgJ z)adw9M(;{i7|8`+A2*AxOWVS?VD-l|<&~BL&!O5C&J{2MmwwQKF%UVeC+Q9Zxpr2i(P^tH%FEImz%i;HdNY}{_7|2_1V^VC#T+m#fE zHP8WE)hpgChKM6M885^z2^^l{WY`}Pa1#D+7782667ADds<)I5`j($RhwdgUQPoS2 zvY(qFBJTO}U2%A~kyONC87JOvd2Eq&X8QJrX}t3Y)8lVK8{XEbmqfYAooPm{QCccy z2`)_9tm~RjxVZpQ%f`y17omUnx?8odX;j*nl4i9zHR@-ZWBg?;c|3?Z53m_((rV;M?jGVuFkb9HE9$SCe8=4Od1H95dZRdM3Hmq%GZmu^RCb(UO z2_M6;P-F>;SV)z{8BR*(Eg`3N6opjiGeHAR)WlF=BH}C3&{tBU;4jdgk**e?v<3WS z#4pTi2^h}|6j@^10Y3X6am7Df&p#G11`Y0vk9zu4m&7&}2bKBb`tO zc)t%NSXWl-wzPW`^F!z=B+!w$(*LHU(KcDd9)-gEziZ;09+v9&G>A`_zplpc=&Wy zIr4;ovxBec|8M=0a=#!$qwtvx?+K{Hs945J;~f?jHy=EZ49|O6!+@|TZxGbdK1Ywu zS^XwfcJLX`oDkuYjC)~Nw!`0W)nEqVfC$<^Qkd|W%P1E|zlgJq%2qfAHar*=vO>~S zbzDwbB_Ujh?nLJSC&XCLYp9di5NNcF4|I$E-`~Uh{EMCb36>S3Jwl(o1hyX(~=l7amSa5 zC?f^Q2BL#}RVcpfwP)(5k5e@6NeKauVH}1}RLT3tNHW($SkXj)Cdbm#uYxJ%%~54D zbNLcD$#H1sTZ(HG@8>9GWU)xQ&g<~3e2(Fd+jj$e!*594{iMr`39$hmeTfjmEOcw3 z4fc#vs|K7DVh}GcMXg>y0Pu(^k47tg(*WeaYO54SAhex- zm9B$4JRl*nlogQLe}!N9M|bs_u8i@!v^BUC^Gt*-drNCWOw5?-J3&R;g1!gl8L1AH zz#Plb*u|(JT7ieNHYi{>EyANsItDXC!gc?3OVQ+4?v3+{?etK=z z!A+G<1HnkkJI;iGV@!3ZZyHudl--2}woF^mf3Wtm2E5D2BPzqr*kjdB#~xR*`wRrD z(2_ejwJ5G>XRYdmfb=4ln6|6VbVQnq-?Fs)i4uDeq5ekC012q)#SFNx$hfhuu2^ib5Vi52{-zXpu+M?XAN$4sAG_u_5Yb`ZRQT zP14_8tz^4(Y+HoLg*Px}tWumsnDWLKU3uuZYc2|kosHdB%coWl(zCSG_@7O8X;r5s zL!*qB+un>yTaE}~`!ac5Ga@RZ{JiZ$ff7>2H`kRm^cuMZ^}Il%E?Yk7_7tKio>uV> zGk0KnesOU;uRzFkX8Mn~g;uZ7y8Wx{Z6rz8*!QJ1TAg_`qEYBOb@zO_Sb$wI6$3k= z7wrL`PgnbWg%K%)J`mZJ-aKKfvv~1|D|WXOMg+g#Qb2N|;8A8_iZih!HYj2SO#K|c zV_ITxCpDsqH8RUu1|#0Rdxu5;49myWouOaF3Cjvd?;@2KIl2{W7!wkODO*ZDG91-&}4?a^KN$6sWMW0yFk4X9thBs^Oz7kuf3pjEdYSsva83`Z~*oMn)DFUCA7 zXkbQ^0{VlA+dhuwH^q%?nzW}`(h{j;K)|_y`yi6wY!D#vQ3Z1UcpZB|VSwe9I13B& z!=BwD+qZ9zIQJs-$*KV-I0f{a(UW!^+suNXHwAg~BfE6rPzl#7%N0?t-}EjuBtvt? zRuTp_!UdCIMPa-)*R%S95d!eNHN+%rx0)MxnnMFpI7FV%zs=Mqz!e1g{uiHoRHa~EQSaZG%TqbM7;54 z*B)VsHVuB}JBGNflC100;aQS^4JdBdof58ID4<0(PKx>YV~s9N`;Z~y;wNb$4C3+s zC)v~;{d_yZE&9U_f&|2Oj@|frXQtouMl>z_5YLX}EhLYiAH0qiL%L`Dm;*GDaMF-y zsF9u4IA`u}>AaN(jz4A`4k{3&H8Lhs1~Zt^MNq~(!U8OxuvXY7xJb`7WW$M#|~d!_C59qK0toWeg6) zBVu;6a_29qKw2`0f1sV=3JTh5$Dig^3Hg$jS5~=0k}0jm6(3d~RS@LWyW9&jKS&kz z?d+z*g?l;J?HN#%XYe-VE_BlgYQ|j32m@-j`7jyxbDX*n-FPTi= zLx)mD>4hFvoF&81hhWo4{}#3oe%I-e&}!IMEbtZw3X6FPI8~wV7xlx2{kKqnW<}Zl z1u6G*h_2GumzDSt^2tb3^?86?^3BKXejozLmUJIJ=Hpx)ovz^9Dtq2@`bdJeHj|h} z3B4^lBgMlkHQV{8IXsq-y$cEYAl2Plu6_(MxC@#Ge)*oUr1x8Pm?@A=1-4CaA$oEs z&6nZr{UGjP501-fc~ddzo>Yd@+dQEuG^%?#BlT%9E?P9aqx=0UlZMGxA{vTDE=jI#)%b8e-5*iw#|GdeK5_HStZiQMrt8_f9w%`aKK z8i};LoLs?q`;zmXp0#+wP+Uj|?FXV>>GP4ZZ!Z_9A**ZEqb+?nEGpSzba2SmqW{Rq z1Tp*Q@Z;Nd8OA_fp#t4MF7G3eIpgrKZ{|(1s>_DH`!m*u7`Ob?(M16UDR?16wvgNi z7O!Njsi~-Ym_?qT(1|=t0a$lS`pintwLxZ}a&W{3&h`Lp?C2U4qp#M+X`FDwBU69( z?ngt7g7JvKedg=GIxq>(xwRRb$Vo{>EoxIb7#fqVsR(6=FXvrSxn-XzFZtjGTl!BL zT$&gsrOBZ%9fCm-wU}_N#j7^lM=_GTdgF$i5IF&S;Qdx~Qmx{YMsucx3QL&~cw4(p zaAFi?!jg_J$IDo5>eLXga1KkOm1I;U(R=N_vOdh1X6!u`W?q}*?Vl>_$Q>&pT!nw! z2&AD&msK88Gziq`HwYYTo-s|xudJ-@Us*B{HJQNd6^%miIDUg^^Hbr3Om|uk$%aPC zyB@U-yc*410-7@-9JGQv!eYF>Uo(mInjatMs0zL%3O~$p&};~uEyEsl7bo6+zvaTj z4IL=SfhAlSn7c~g5zwXk9NbexZ^w)wRJgF3iEu(-v>Ip5n6_V)Gf;GbFcv6iHFZPC zhvpZ@2_cbiY^V?lI3d2%?^q$iSfH^u5Do^lh%hF)2H?makrmrPJV9M~0{;x?Vkyr| z0?T>j#${b8~Nr?x}JChc=~C8&Ho>n1`wfh=MMvO&p=h z7#(fYhqog?BDW+bB55G_)2fm>fLCjtC-&x7}KEQ9OCpIjT?)RdL`Q60U%T z!&E^cVzCE#%}(`cW&-Sjo_=-xP?m)P=LQL(0e!l#6AFpa+`9h}0SF%1SZSqy^)t>1 z7FLELYzxipr%yf{;xySz@9N=e5tp*lElSdcNw1@aXFhaKa)xK z3n*Tt3ji31mcSadwNZ>?3-xhv|Ly%b^0Z5j7gOIKX7COD7$wVg`Rs~?RDtn=Pob<7 z0~Ptzy*Y*ncmb`;=6Ba-QBWnyeC9nOFt(=pq=BG1K^-rISWFUUDYd`*wVv^Bp{dHW zf&3Yy;V@;LQ*|dqmw0vU=^e*CT}0I)G!qOV6+k+ z(m9AD5$>h_TIC_R7yN+{2qr;AAG`_cX(2cYF%*hs(jJ}iB;r22hr@0!!HPk$F)g=? zD;4Lgar;M*K_UPaj6XUywEHLlB`_5svtAgY?H8%HytSn?*xg}JJ!P!pWa zz(2^;&@i1)%nCmhuDwxh4=N|8igxS@yE0{rqv6A178@CvxrFRRx5tH0mEhn|4 z$vIqKN9WyQm8=`IG3MEiSGQHmw)yZ>Q5_^!Hk88LeavaCSLt+c)|x$^R^;AS<`^Od zIp1SU8i2B)gkA-W`b=U7e6wP5b) zq2`ytTm6x8C3&f>M2NGev6^ReNy9OeX~0L!SN_6<>^)M#vtC}(7E+-$<%WB9@BVh) z$l^W8QhC_IMJML_0;nw1L%4Be*9^B-p4bPP?-fQyccB%wGWl@OW_(GdpCVVp z;AnIIz@CrRPrL;(5MUg!j7^dGY6pzeUQOJf$4;1_&p9uvVovty+t-&WB(1#O%Kl)` zkz1_xv7<-76FM-Bww78|yQ*tc@cm(=o*ZjpT5nrcjMod;8hhXhz%!<{kZ-ZrT<1)>5Of;J^cq+Yt2DY8e zg%ezEGjyD|Wy<$U+XI*C>i*l}93vsCd5>4S7fs^pw{HzN?K7x%xc`#|=VZdL8d3kpUA9bi4wqbR$jY=cSqL+*Fcz%~F zWHN12@T%u~*K)GVij^z77%VO6gNa@V)nllwr* zlMKVHHpI-{7=t|N<#py9wlgMg7`gkluyw1NleM=0J}HEG)-aC{PyHSWcM^NW9o1w^cbRrZL@UE=KggxXj$BCFz|#4*1Z zPtm%iaEez5=hZPqsi)`vkLFd}h!U*v;cx&BZW9~`hs}q&BU!b zTsX&)|AtDcOr45z&9~1+mYdvhcjo z+tNJ_8<$us;pdF@#-FaL6d%ZF&SM_=E7j$fC!6W{!c5249%9n;bwWZnt!avii+gFc z+}|psk5g~`yh8+ZWFZzMUVG+r8RdL zengB0R9wOv9IWXSPKh4`bjLHnJ2E9f`_jn zNk6r0vG4m^^poF(n;(WMBE&#x>hb-#szqd#Nd9d%XZ-z84JuAFeOU4!QR(lTc4L*4 zK7a6=-X%cte_DWrb=Vc|etNQcg~nt~5x>ipQvS9sn zlU27{@}b)A5v-j?xe2x|m~uusyS^~Ey8;M&B`*|Fk=UTzOnvk0tLM+(taK_?nsPEKQ-ii3tGXJS)Be@22DNZP>GA!gaOZFekUe${&f?$zj7#u6>Gn!bG1D)Er( zOVzKs)&4rJOw2k#5s#mqmw4d7L)83 zG%heaZ+ptn?%}J*{+mKBn6YXfm5eU*+PIHtl{uT z955ZYdSJKN8{36~Tz&hJ*(e2tQn;ai2*pmC>+HsZrx-rA3ns+?2_$dJ zJi~;7ANPAGD)H**QKRM&KV#@dgAi7d2VU)%HjY1J#B{Kh^JB!tQkq@N{?Y%$ACp08 zazBF;i>SwVFbRe)+YYgG33&|TIUyJ-@+S>X0#z<+#OKUo<`cOUi5#L?>OI7;l|I^-?$77wgZCsm{ z(KeG3Et+IWi}o^ei)c|P6Y*BI=gA;S8!6EysYz+5q(YK}P*D=nHf^#mH%c;+EomWx z=>1+bJ)!#{t zM=~jd$(X8*kE=g%mb?XcM@>@Qxsb;ucagOck5X((jgKk4X0IFmd3|H$ROrosx?2k$ z1cnchm)DpzYlYNe^C1w@khtZ+82%CM$wwE`5m-ty#?jl-o||Nqx+Yr)+@lhO|AZK* zusi6rv4KOb#CCvkjifnybBUZ9<`r~u0uFTPHi`dXpJz<;$}6@9P@k75Mn0$%U@4KB zFR^K;*3o}IH`hkX0fmDv8K#fSPbjTeOFt3^{?^tUzcZFIiY#E*((WvcDU7C5THPbH z&;n?it28=c*Fat@ninoM*+QOHyxF$*FRe0bA@`aej`kB5uJG?Ik%~$LM1$7b z^P8xasU^fVc5_Rjyp^Uj>H-%A|1{%g&5tqZZeF*~Q0L{@{M`7zfKMU zdK?Q1it7D?ssmt1E!KDcp+kk^lb-#^;>8rTdg!n741IAliH|F<}sNOGIt&}1vD>7lq zDJ!3fVv0v;xR@=!D}hRZg5qLzb`+g=N39vmNyq0FO-MF?69UM9eeR#}zDKx}Y!Tv@{wbCo90I7<|g> z@)TNVhCo}5j*q9qXy9U1lfOPVFRk^xeLBc<(&W8a ziK;)yC>xfhZc7l$A6qHuXv$xC$>z3k|5_)a=ef{S(L3IHjZ}v$Om8o1Y`fT6-|Svk zTzr88Mm7Wl#qS8}+r2Az*}u?HQlIn501p9E`o7g;)68KQdZi=%zmp`yx!394u!sw| zlW(J?9xv4l&)ur0xIEZTS6LYt6;n8tpW(R*I*qtyg!>x;x*QrIS&5H*Hp_E2cOdhF zpkmeael_M!=Are)+dnGx>TU~$+LWAC>{`;;5<_dVymvzjtviNWK9sJp-gEm5u&}VS zG}>5QB`~9~am+(Wd`HNU;#!w}4_l89vf4w79~JJKQWjTST>M>|c1wGQqqDP_y?rE; z{mj`dJ;Sr?eJlp%I&tS5Ez{z z)B=%xq_h4_6PcTaJArvk;_<*R`J{l})su8yhJ=hddv*>1X}6+rZUWvj8QLEDO$NJl zb-|m_7cZL5pZ{RMp|{tOcWW_-rgP@(aZY_V4{`LyL@-o1^$eq?S1p5NX$EJ4?nKL530=nFWdN(Y!6Q zZcSYpSdhIF#XMVDTK19kntUn~yV|Gx61-6eBH+f-Y+E?$l?ir-MCsLXQ&RyN`EK2t zH~n^2a|H3@CrS{MTV?C7PSi;Kd55}F&Wdrzr*!uHSmlvbKf7y8VQIDRAG;Z}M2fz}8Uv5E ziB{WJ`|XdYtlokfI>~rgZLR1LYn8T=+R$0QYIujF2bg58ogLh1kxv!)w(_GiSXj7V z!ORBNw=R|Si{{Vw5%IEP;aG-y4f61iamvTD8cWMQ{PdHw?LEtgtjz)-dL;6>2#HAW zon606;a15zHqH9={iXhXhYydqvRsR}0u(CD4HN)L2t89LyeDaAR#}4SF4kHq1vFX6;Eh(sark0km2rI&|wh;}w zAcB^0jFp<_$lni_YqeI6{Cr`E)mA+swIkWp0r|D2)O^tf;(F=}a^3}qpeuPD0f9R~ z@96W+lSfUGd2yEfI%t7dafCw=Wp`mj%1#t^5fOD7_wO4yuvd2&u=CcR+oTIYh3bRy zsIQ7>3omD?lI`{6 =i9q!hRUyvK{RW z!psVmL7;EZ@qXe0^R|P_vmXb6a0J%Fnx|q(UGDasQFH#3vtnI^Wg;nfRAk0+NRbia zdILK%jV{MwBL=^{DlI9&*I#>kC{?{Z$EdDm&4pA>ei6v3`a|Ep+6`S@uaY>WS-bTi zYGyIE;%R8%X4<+H64l31zCM@DBHXQWN&^?sr_V;bG=|cmwANRr+)*t=z@J9ni;7Mq zwJd}FvR8AWZ*MQy!y1W=C_65r5FX*#OtPqwOlDe==!l@Rl$Lbf+nZGBo(PHXNYZHpb>Elgt`6$63}gFkhwxZ^$KT>X??2UmG|rX8PX9mkdS zD#i7kD|rx>lds%N!<3xt9UrF%(k9SyOAr`lN`b!8_qT0~;iL;u-U^>TkNZllm;esl zsq@meLu?>gy1|q8ACe$9up{z0~=l*HEO<@MbJ5oJW8>P{C0i{7uSYeod41&mlq(~ zb)w>_Pxr1BZ6P8Ab*1fo|K_(7RtoEW`JdhlluN@^X-NL28g@<^Y4YwLGH2X%ji${k zw1L5s6Wy|wYbltry-E7z$m6_Mb`norB>GP~KJStS_mlOics|^p_;I#F)kAlb1Siro z;q3xduSuSmM7h=XX-mWLI;8!?Fl<|0j%kL?`-$--~PgUd2c&oU9SAU|Ny z1N|1rp!(l5<8m0^0)PkEi@f1LxTnqunwpD*CN`*7_dB2M6H5N4Xa!>_(Pzb!M&cEGWK@78`M$H5nJhmzv3kA zFbu4!MKg>kzm6Zg=w93vDhVEEW){NT$LcDdfgnA^x$7+Hf!mj~aX`5Uv4jblMwyWO z;K3oyI_}P99#_p#G#1`_^15f%T!1&Whg9~g8+uhXbQ7Srcf~&EZjb7l_sy0r>NC6g zwlK<^rsA!1nxaVu7&lL6vJj?nNfF3ni#bc<7-^wA|J^P-pa8@v-5A(K>;Ww5n}l&b znRX_e8HBnbfEuf1+VtuD9&b)7ejE3lOow>GMgnMkiSK^I0N2`xz{&MZBk7?_p|ql& z)~+da8sn#Wwl#%~czk3sFZ}p%9<%9QfGeM>eb>0g)J^o7;Q{9TeeGZ($FIrnqGz4ZditmT|RTKW4IH6v<)%bZ{-r4*2?{8S( z@ndLqB;ux{G|o~G&H$^z+}u(8l4Zf^iw))J*7$_Jjq9}>CDy*Z4s`kQT)TE?1^EK7 z*o1YjU$c|Q0&rs5!1WAtH>;82g_J5mtsFh@xbofUcN<||v`HrC#h0X55^I3Im$s#2 z6%8L`tb!*AeYX{wuAk57PwV5QO3xo0_)LHK>9N$VpmYS$^R9rSy7)_6^{_tPV#&9( zZ_hk)c+kIxYS_dn|1eX|iDfFRBu*2irk67-6L)Odd?(5wC)Hzo~%9GOUE?X_& zU=b?5j4?ko#DgWjnb!I`|VrZ`~IXwezpl1Pn$ewDd^4D}XIQO3X6U*NHZE&UCuc*A+=?+3 zP)G1Uefl(sif(8m=g{;SNl#;Kw6@-_+)*aC_A)G~_`Gl;@ExnFsyfVeI%k^11U=QI zO`+quHJoE?a(&!Ao4xn`rf~oa1a(;9^U!5-D}(xSIgpj%vdxPN%oMr`a0*c|CL*Hh zXoS41$)ZIEqoZSl`TgOC&7~#D)pu)M>Y%x$q-CfW!qybfCa}ytdHgd>AM2w5RjPuRs^vW4LU~ zmTS;unk*s13hld+r)?dbI^8_kX&k|_fHs-scWyVC*AL$rEZo}H;e&^N=`!mWZ~-fJ z?D%nkvxnGD-w0raCIhReax**-G4uv?Z3X%>xjbE$w1yTExD>~A>k2{G<{hL7i zaxMx0Uq7k!k3F;*_`b9CK$T|K-Mc7bI70{%oEVDb_ySD`I^e>1Y*oX$nwtG5R{SwF z?(a9t+JlgS+k$Tt5*y>Csj50}LZFkeUp?^`V7s9##hil@F#TTB4_^0S9?;aA;I-5T z^l~6MOvsubB*BHH(TzfJik+|El^6_Iq^n6uF*k2o3I2w(Vc|@9<(Py76M!NWW;tXj z;C|0qJ>WfVP|xa`F+Qn=6nky=rVD`H^AwDgd3?xZp$Gi&&tE{i0zlI8!hsgLguF%6 z6uQ>OCOMJ;UC}{Yr$L1axlxc$a@l)sQf)Yu6i)%$Sz)Nr`C=Lnb;UKoLgp+@NSCYF z=#Ko^9RZ}SFwy(Y8CH1fE|B{=^{0EVy~q@+di6^97X%P9h*T0I)O|)f8Xv~rT_tyd z=~>`Uu`+wCr|aO2{o&&1&|OP%r7`PKbiZn#l?E6HUf+y^p$WU8oaJP_ZlrwKlwiDV zKaXIZDHP&cwe-A^0^AWfFPO+aLzY^Z=(_)nez4x4vmX4&P-S0aNq0d4_HkVyX}c#IVzx z1j|`NESN`Dg==e7pcB-+qG;F?+8Fllu^Gb-B?0!3;nBjN zQ2Q{Ja2X&62H1bx;EY`(s$Jlp=seJj?ky-$fxd+z!upGeiqd$d{KkNyS)mERZ9^xV z7jVRWSj)80QYL>#1e6jqrceMeST=}ph=@eQC&=$P|_q&3%`It$AGnRAO_dj=qp z){T~otst?4qte&c|En5ni6oFmUVZbS^&a|==QjuouR;t1`OE|dL@T?JwMCRZXMZ3+ zQ!ebgvK<4zE(FRba?pc{qwe7 zVZUQMh9iOT|3Dbx-UKjl5N%yFjB<$Y5G}>a)YZLS_Ui3o=mHH|@t^zPqHS)m(fjn0 z>RrB3DJiQS93F0h#iQ>*G&c}DR$7`R;T_0>HzN2pK?8^CK6>&bI&krhk+TQ&i6R36 z;{se?Mnon65)2=cj{nyHwu^x#O_jhRv>lf&>@TyG_?6z?tKUi5TGh*!>f|V)4}u1N zd=q8;3~Di<) zQW-(zW8qx;`Ba|XvjY1I)8$FBVQJEO>#eWWy1Tcn=y@;i*1mgctRAq!GH6R2?zzeY zk9E^eVK!uKuO*Z>a(1{6FdmeP0!vcw>n-goB%$Cwb`-nf(HB`Tbc-*%9>gs~{osRD z7qeSufB)F%>s-oIKV(sn;eoh=xfX_j_YmXD(~iZWU~KBmFDdo$F38OdW2{H3TJF|LU{>*upN=P*aX-bwJt_9&LAKW*l;^Ao3kb9}e95x8(4 z(jbljyzt|MK#3R;^nD@7unrgQUwTBdDB{G46K`J^@+KI1CRt)Ju?4>a@f29*Y>pRO zX0lAa{xBCA{x;~=E`xuWtQlUnm6;lV!>r&X#KKXSUN0K0Fqd1Hnmi)F{0zDII4|N_^u-q5yvR*zBVJ2E479T;>|QR}pl_D&Cxb z@YxJ)nDGJ{L_q}EWKZ0-=_RehO$*IWT7L{K zE4$i6dB72uR8um#0tsjNS+W+7udHyt$J}pkCATN!3_bcE+9jZqetfR1@@T{RkGH(% zefztGjGFf?+dJ167{62edMlY972v?Wehjp}y@||z;MU*29dP>_u9Z>V^KGrl=yw0t z)9&i^uj|VU^gW{R{}=u;0{<}-f6msmk&)?g&d@;5^uHVLARqU?hf`rIJBX!Y7Go4< zyy1e+=6QArE9O;3RZmg0uHPEn?p{;>tgF9mFYh^FVI#VK{ok^%mdmuZ zzVo@OhEXLkAo9}+ErmgoijsdSOYZR>^E)Yf*x&d2@1FDj%DVXYxiN9^c-4xVm&Gs` N&Rt>y=yCu6 diff --git a/planning/behavior_path_planner/image/lane_change_fig3.png b/planning/behavior_path_planner/image/lane_change_fig3.png deleted file mode 100644 index 9e1791a05d0986278e60f5d277d204e45441dac6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 37153 zcmd42^;?wR7d8rlgtUMR9U_R-&`2X79n#(1UBiHcLx&(;0#ec~-9v-Y-AH!~Ih?`I z_kGV_aIWj@AK+oGXV`n~Rrk90+Tkin(l{^3ULYYM;mFEJsv;qwdLSVo%VD4)K1qO> zogsdqx_yvU$3P4}4D&F=-=ywR+U{yjmhN6At`YlH%S#)~arE2Z<(uO>OUq2~irbj6Gd3CxvI?rqCpwJN$~P6(U+YU0}G#FB`yDKNOjx#db~$MgGRdA^FY{PZqYp1U{(JiW%k$cyAu<6$<3kJVe-cWXM-uJz7wrB}-fU&Y zzVv+B7}vtnWwSE0*?zr=Lhm`EZHhbC@l1GjKS-TO>i=#G8alcM6@!y32x1@M76UqJ z4Am|3Y}S(cpS&u0=Kn{_&G8>7|L=1g#3(!r!-ZnyNaM*2zV25}o0j!H=|Sp9?1hK9 zT4`N|fQKATljL$9(caS@FQ$H!mQKyc_@Vx8=}6J5VyZ!xtwXoL8sHlc` zk9e=&gK6@sqFQ72fBGq#+I4pxT{@bI6Z}T@Ci35hVT(BzeIAVjUj*n}x2tc7-~2Pd zGfj6WJ>AS!>&nT)l+khh=-h<{GvNpBhOjtMkefF7>dF0=>>JX-{FhQDMd-JYk`?e9--re8&)gQL zkGFb16#KRUt|AX^jNr%&VI7}gC;RQEp1i-ADCX$xIlfv2(=e*+zSc|Zw{

3Y_L-d4XZZs3m?G~?(wI|#J<=%ne87BU z1yCaYRSz@HTMgNnq?5-TCyrVe&~b~?rmz>U?F2mPn}UlS9-IU#MHyP&Xc4ER%?D(aeq8(r@Oqby^$2IxrvfdtFo5^c)TYagHWpWSTJY> z{CTuHHX$ZvC~i-Bsit?Ptv(gW@KlaZz!^=ui~#X*+JKgmq@Z%Bib~`ERgswvp#ev4t5==pF0^b z0|S41Ppc~TlIe!$z0{^NbM~gF%xWr~hnmwW&5^ZKt=4D{T-$>Qw@*HwuOe+z+O)+$ zC5&k*(d?hwbri&mpK4Y1#eRCoG=ft4eS;9AWroYEAx~4Cu9U-F{%ab+zc!zah z!^TMk!G^p#uKC`FEH674;a1ucV{6PrE@6$6WVjV~{@X<-`qR++G&Zcly+8|oY(U8v z{_vRUBj01x`1x4n)i(TH$Zg`=fA;Hzm)RM1fJ6n*7w()KFv`(rm)x&jb1w!fsZ@c6!i}lN0 z0P6my1EoTQ4j50eauOb2P3XQ!dE1#zIX~)V#It7!$gK^AJ#?UU8=ht%yP2+c;R*c|6=rpf}(R3(_z`8?~;8w!PAsNENy*)CXo33E3Q^V5@m1Q(U%$DkKG`v|V+znkMEerEd;AW(0y_Rqt-b{_x)<-<%owMBw4# zp0?HT`5cWsz72&BY%|3wt+w`>U??1OWTLM)u72*gOnZCB-CI^sbuzNDy}t68uFxYd z#K|@2zEn+==;LD(uC-06e4jbyvXVz_eA_RfOb>jR~-Rc@2GOJm@6|BM;<)??>2HJmxC zwET45=!QO7nEvpEO`THTEQ5LU>*IVRzPzTNJ*LcBcPdaC(7&4W3BJKd$LJwTFN)8poLD zwi&ta`mQuuh-e44Vyq7GL?JNa^SQ3PKw8}U#P)$=v#~Sd4Hjj|xnVUM9_XEv{<8Dj zCQO!jbtqBDKD8I=kFl8fvr?w58m;%EJZ4w-W9=QU18%K2OhN|IdC6C>GFo5!{qddFg zk;1UQmFBzzpnZ@Ku2e6xpaEh-k~%w7@vtvDRH_+{gA;_acpw)0{I`Un&&6kPT+et0 zlQ&M6xgOg3e$}SoZ`yq8{milCP+j2FXSz_WI07+CZOQEmc_YB?heO@>%kp*llHCpG z+W0!;F8sgTUHs4J*E(pVv+hx)t=9sHVn@*Rbg-e?zLb!fc#`cLgLd@v(D!V3?xj4& zES`rHIZU=jeta3bmrPenKLINw3HI2!zKL8T^b9|ztB14HMN+Kcx7zDpKwI#tITzRifO!9~0^%4>%JkMMMUZzwDPV-Bv26LTMyF4gtw51h|0v~L=a=~YaJ)gLa}2W<}0bltb?>?Pk86tG)sD7e6)Rny-F)w()If_;2JUD1CjN>X#X*T^z6^ zB!<5>PcXD4?2Ro_`jQfKl8{AM0O)*TA=b-fFJsYT5wo#o2<4s#O z$bzr7S{My=dOXus4UCL3maA`@&xs_;4j>l9kFZ}yt%`=JC{{^kx>Z9Ze!g7p#QX2L zHMd7TGDj9E@G@&wtQWy{uI>A^oE*;Na@*ufIeOaI9jkXC3;zYO#eZgs3Z0m9i@WXs z1CGnxf|pNE!t!x5I%Ywc5 zz+m)a8G~0%Kd44aduj=@wN@_Dcs6pl>$1OGZrPKL!oEng!iD25cU`U>Pc{Zn=vLAf zTLSh4ySuq#gnXtxv;DKquYzjc&01oT%V4UZaYj*j2UF^9M#C-@%kJ4Cp^V*h`xnXH zUAM-sVmG5BYf>wP4!5M_q5+UV$NeqCUd2vRXQ)^A_uR1<4sdkj?nn?ZDw-2^VBlnD z_!r#JkFS5`9BS?ZP(GE7o~dHB3mREANGllyd^eqD_QlC?c=Rs!`=u37J0akmvXy-= zudet(%y-Jon%7*5&!=l;FVw47kW(+Y*>D!7iPiLQ9^5)rV_SY643qk;rSE??^SE@f zy!h@(jDJ91P-^c48l)@(F4mh;9oBumIiX>p!D{oYUUTd`)-TNsofr6vo7VZ}$CgO? zUm~&OWAd1)2KMQm(ud^+A-oW1TpZ5%nF#10A(BIyK`sPp9=k8Jb;_i` z6+kqxADWBiTUjsS8(0oBqVW_B|LV|CT_lVqdD(q@Q$Y8%M#j{YZ0j;S;vh zew*Q(6jd`v6bHCrACCQJ@WaYR<(f-*n*;2wBx%V>LitTOJf|W#eiw9qG_`bF)^@mj ztt}F8c-LSjQBiPYXUhu_u-s@eB*ZoF@*&TTwX^rm;x(*a3*>7lK--|?RRmFXtemw; zb)S|PZLpxSPS2&=8HJ9h0O%1x-W7(Z(yLLt@rvD2=%Iw08qDON#Z6L~=@~Rt0sh*ie`c;Z_^8$LCkV7ZLDCcrka<+>@Np+@LCYL?WW?*uf=zz52k&{@Bx9 zqM_~X6)pLkg$M?3h^iDowX~*vujG-lbXUX^##?{AY}rs(Kz{Gxq=g#D&_1d=xWA8W znAXj};n*!e6pOxmm9!RwPXhU25)w(L4_NDZX+yM@`;v`iEmxIFe@+OQQl z_;b7b?w&})h7T{C2<<6ZE&4wNWK?B*?G_$D0?r4yme;^~@@gV0Ya5O)zn)LnY^#Ob z9o_f=v_CAcR_vrJ{?s1V*oK3-Y%jYa4QCUUc#ktTs(~Fo%0!zrYC6{RF&pQUxUnB4 z1M`d4-%_R1x$o(P+Bf^EHIQh?-0a%dD?(Q@^4@ZC%FdUaH2x*6MYFHXWDHoScOPF& z{@vQkuxN}~P@%i&knz)q59tK_=uI=)UcUX2`LMz*VSlMj)V=xkc7M^o+o2rxFcs_7 z+V|_!RzDU7(Ik3_j0~2NcB;eet*&Uh-D5{#tNx`*Y*fD9^-|=8vq>1%kPg233t4%O z@jYNUraj^<3&Nti6G=D4HKPL&Ret_5S?S*Nrk5!>Tj0GiRs5x zQ7>Lq#l|ah0s1Qn%Ec;t8%}q7mHVZbL8mkxRCyL(fB+Lx^Yfg$qN2ljtR`%SjaT~fbGpXJ7kiHJyHf~_>~0)DN#L~|_NLt&Yyg;dWrnqf>I5I~aK ze4@Ple*FAkMYwzTViV#Z&)iKvh5LXU#`G-ksL{*Q(jfvVPZagUN6+T??&$bzq45A~ zrYvc2ko%UZ8D?s@-;{jWr>_NeDsM~Z{E}btYFh6Y4(wdzMWbDEYN%|RX}oSC?Z>H~ zT0B4luiWk%cx_BI2R4wX5$#tyO87f@i&E=nZ;4rDmc+J=O!w&@`*4Zve73~0ZtacO zyvvgB>{}J|(NKF%txof9Blx8V3*pR9ceH(XH0fRJsJLk~*>@88v!@t5IJ}|oUTKD+J%c&q7oNKe&Cu~qGf`dxhGnE6Z7=Jg)tcWC{D5LN4 z;aJvB#C$;aWyIg^hX`bxfH{fcNwz$kOTYG>$VGGY-UjGd>uS#t$gmD`}y)=j$7kY@nHgtZWe4t2V*gD>A{2ZqRS z=%NmacnDr@OX0WOtHeFLLZXu=gkYbAD0C=k?X>O30o$zM`=Ty;8dDc|E>*}WN_l*V z-lN8qpD^XfmD?irGDmM?{R2ItRy2z-kJ~*NHXM8Q68W%x6*^tyS$~ z`+hBt6=0BpUE0?<`+S=v&i0r_11_X1xh8H@WC9L-iJLvBy5{IdC7Mvv>6bc23ov;{ zf_~A+VvM6MIGXC=1Zkoy*c$8Ep^iw|yM6hd`Hbz@i|8{Z2Q-MURczd#l~TtemIE#5 zCF&f93G#w1KCg1;qO9#QN0KNt+uOC=&)hF$_dEm=LU$CXz6%R|Y!;ERvks}%9b)!X zsAm(8)40(utcZO^jerebqyH5PXermp*{}IQ&(z4iZ>}E^FNIe`9p_U+f%rP*?gElI zw6cCigr?TxCB80F#;87F6J9S3LKw&)!xtp4t{p2?iByPkl=r?9T{+q*@=6Z*Xt#Pp z47d`0mvQW6rwDgt-m%>_x7GxQZm909XvMj*?J>~P9fxcoRp>47z2O52PkWT_b4v6T_ZM70l6Agt;q>w?x(N!zk6qBb@daz(U~~d6Wl$sSXKmj_c3+rPWgW71*u{r`pkVC1EM5dXCIpz+0y_J8peX#HepWl0zI7CvE5fFWL zlZ=^ehdD4 zJ;MZSnpUejHck6(ty|SA%}3+xDeZzXpJNSlQ~-_PFShnC=ro*I|w2;nl;#p0=DQ zN$$G;HZE~comx?fJTqg^$R#SDuZQfe!TfRu7j|}IueyBkj8d6kXVXFL;3 zzhjgaQE_Yu?(ZVp-zmtr)ScIbz-6-yUU9d~?^SX(7J-A~LWxrrxl_blTSFntBvmd^ zw8Ie3#ulqjZS;ha*Yl{aiVXN=4;SsC(C4D`YzD@Qr*uS5fcxmwxjX{0`s5v72t=?? z#b@pMOTSAaOnq76DIQ=@p+R;=2on=au5of?oCaM`zLn7$IJkG?>7mjgLD#GMe~{x7 zYrLN$+HE8MPBb(Iw>BI;HM?aSbF@AUnU4D#8y*O(_<2gzMYDfs#!AorNUI?~O_aKP zpt*E;-YOqCq%Tk4gQ7zXFq%WH`v5!CtZRQDL z2*=#OHF>F~n^q{~6?C@ve6S?)Tbg1JR6yL0G@V~zuljo*s&UYPmlOqIkBY7n7Z65$ zx^hc5@S8icN|r1EWUX+V$5R#QZ5;ALcPuE22DO=Ev(a+tsT4kX_5?t~CbV9qFc{-! zD{o~o{nU^69o$l=WQ}cNmdJ8205P5J zn%_+hOJXDF!A&1SvrHgLFNlKz^tz10$aE66Z&Ueb93+~>tz7Z;L#a)`Gqlr%o`f^# zvO_%MayTR(b!60gAb>XA>h(#|O(E!&4{`t0I18 z$vvG^4+SlB#pBz>rM%d*6(hM}FC;!Smu<(EDnSFjnG=Qn?wgJXoDz-tR_qlG=?*_e zDPuo%H<|YPQ!v9!lCiU`g!1?01Fhaiobp+2-x~M#LTuDQuizbc9M_Z7Cj3Bs1ZO>H z34OsUiuEy%`hF$^<8#EtUYRI6}0O zd90zIF`4l-nRs-+8N$(CuRI9+;_aa%yE`&FMHd;^%L468hF1FveF_;WRG(2{eJYJ7 z{?SiSJhj5Lt)1&Nad|12KU1VBnre(pu!)5Zhe*Pq1v|vkfc2aA<1^WX=Cr4kWPLwI zCpSCe?5v9T&%gg5$X!1OeTpGMEPOj!UIYKA1MXP2<$jRc0ZJZh9A9HFA` zC#7~G7Yq`>0*>*#9}21HuJZz7)|CB|_HtgQ=w^0oZd8wlTvotEnoBN)hIfxMP?iQ# z&S?tu%)UA45ljI(Dp+0$pZEhI*Tb?hgz*Ei7`b||rm+46Rn*@i?+B$W)^i9n@u)h< zC4M{FdUOZ=pI!jV8t0L$eBU)d;>~+GtYl1G#b?`9vM*5aQBej@>dvH zr)-Xzlc!Mds@wLF%Kl)+-vVul;}vt3agw?91V{bOUF16HB)xZ-TaikyD$2Jmh z14on`t95>!8TWtKuRF#^<*;e|_@I{k#r4Z3R{%1(wm|ae>0hn3p7VD2BXFXz|Br1V zbtakF%|iPCv(dHG@~>yz2t>|xJ6RZB0IP;~QCB|>z7N{X@xwV6pfpmaa@ct_NvUah z3-4Mk<3D>d$gJFLS21zB=k? z9}95 z4B)tFtvH)!zZcqVfXBf?hYkdrLJ66%N(1)Bs*kN6$#{1WN26y-2#L}JZ7s%Jp-<+Qf@8+#P9CY{Vqu!8UA1yZGSCB7HP4f-gVS|*lYiLMt$$5 zRL}ESrkr= zP|Wj>?T;^C_ZjufrHpQZSwyZ;SSbC&yq!b1-)(fi#qypEeafbev`)22By0}%2Of3C%+GDmN2T^KtV8)XHqcr|5*4I!S6|27f(z>f}Zek3Lj z0V78oUu`hW&jPUjgo*^-Ed_*A*UoWwiGRM-Ie8h!XNdd3HZ<1t!mWMa%&yP-X64~! zU)zP95RdSn_IuM>inET-Chuh%Uoz?+h+&S28Ixk54Bp&cF({0o6tvmQ&ZsKyQQ~ad z2qc$nQ;XTNa=)^^?`@A^*K+)`PfOPz&*xf&EDMgSyQL|)J9=Z?@RX25AJHzk`iisR zA|`H>``FMM`)MJ(K&+zCtO8#+PeHq89!E`V9f-=pui}Ce#XGpi3jY{@>Z45xOHELsF~_JA3RU+b6{;+3}G1{ zIA=?EDBMiwMN@YfHt-c%6y#Mf?P;6f@ZgQ!_fGNx_{|sRhm;em9kqFSL@7f z7*OHrVB`O?zjejac5;?w%=V%LqLFI=<5qHSkQc8nem(9BVZV8Dnmj$+LRCS{w+ce`mt_JieMH!Ft-d_g{%nv&{ z$MDD8Y>hn#tDecx(Tt){ZwqhFb1YjuculK@Qd6wYz%Sd6c%0hyeDDe8qK=NS$m4La ztK5$zSSUs0Y&=o}-3kHxci=s%mG8CO%J^Q@D?WhI(7i;TpGG$g3jPmR+@6P4H*mbl z`bU4=yaf70GE|dSM{if3cmviaj(p-d@&FvftACLf0HcmCV2b`2tW=01R;*5kEfGZ1 z0g#BN*S3?554pYI&TO**udp3cOfibe?cX@53HYU~5{iB-Jib+a3=UAhN99ge%y3hG zN32`+>J!l)Ywn^cTkm5VZZZW$MFYOy1Oz^U)vw+|ysbmNcUKQr#|dXqc>LQ+In zc8$)-p+!P;Q#lQtMb|0Z-#jKk`wa7{k2`o~Vq;@bfSjDJC0dG-n`BZ*2}#T>q9ZXb30oryM{+2uCw<%e=i&i^}l((mB&E z^=r9H0Lb>7+(bC4pA-qTkX9W%q`96vh_kFtf{-^A5$hHijW2|jw>Cn zO|fkpK5yME_YJP)eWQNl?_L2x{v@!gWeSEK(i?xMBtUyx0aXA$U`2tCbu_Q2EZ5fX zY7p9upYL#3BzxK#HAG_>`A^M~CI2^cf}OLofc^b_glc|H?Hw9Y68OaSTmE@r9jnL* z+q6mnpK+-tzXIHi9&=qoVQy-ht4dyXVc&F`m;*x|XDg$zl z_`w?%Dfe>`G0{_B8e%l4673nR1VWT*;ee}8E6mO1pL552B)b#X)N!J!wRBS94 zKmV_-Er1z6=!#{;(oJojn}dUa40kBz%`^KMgCmI5@=1*KV#A#Fr?ymA0RhoQ&BWS6s}5OC{tzaz5|a zkeZp9zvQ^${ytwd93k2M(F9-3l$n*SZG>uZ?ba3xJ9|xKr5HsYA9!^CQUJ031zjbV zgC91&6IN|U4d>w{p)^e3-}*u z%hgF3K=_KKE|QU{Za$@FEwl62%ge@d^?>bU8|Bf;t5w1jJpXUbE3^t=jNG^T&1Tr6 z??*EQ8;Zg6fbMdG=K4$jIC{+OvFw#e5pbT_wk0B;xVgEd>nagR4G$07+r38wH2o%b z8?`>AMtw_PUthhxo$>LPSXfx}vaS;gjHH`HuDiMM=>nR&y2c|qr?=Da zI!a1PSXfx>Z+qOwvV;+a;p8vjn#^uw>Eq*rP)D7v1)|A(M%dHw?{F$ty5VR?2NF6i z#q4y|M#jPghXBGu15wcH!5`Y^z`mxYrh3PMHfh!M^&e~I7EhYL@5B?%plN&WbhA)A z;9oYnQHb2pC7M;NmJf@AC@BEgi9^XnhW9wv;}!VAmwikD_ly|F0V&3|c$UU-^Z}x? zaz$JsB5h@H0sj8}YIpAVs0Yif=}#uWisFmBZn@%hb+pucXlCW&;xdsly4(t?@KK(N z;<6g8tgfyuR7x6| z0L85d(Jv*Fv`0v*chp*l6nTW`yW50hxVZ~tI`I6RmkWsGR@`+L&=dJOCzp-ZKiDpq zIa&`%aPWA4=m{DMhz{TImLC(R=tI2E`q=BvJeCg2;*a6u3E8vN^C@qIxeHJVWR4~! zAzKbSoNR-qPq)A-?xaLmsfS`Jk0g5y%|&HcC6djKV|cSu8!^pi^HBVe-0@G^>mb~ zl${#b`!yY#GhvzQUVkhb7?0e;TKoL3&Aw6J0e5c*YuitpcKo)yjLQN&s1gcN_5esD zMh~JkV0gAM^*u)Zov0XhU1+UtU+9~bI;Z!nw+lX^zb3AB$tm-WFI*jauk2yq!gju4 zOQOCVPtcP6w5Mo|!*M1CFY{2bX300X zd4W`tjzuLk3(mTB_ouQ)c?G%TdwIulC~B+6On zIklB(+Nn{mA0?Stfx%$4z!X>(!tu+@`atc)Ip$vukL-F+0!J?F1MT^HE=4*j%F0e} z#saeN02 zLrLu6vw@`~e-PQaj3RFaEL!=B&EUuV;5jx`K-TlPMq*FzT)hF;PG)G1a%ViT!HuRJBPJgfgzaa;QH4-#6d+N7eAsE zBq zJ9fOX3%GpZ<`_kK$JfwZro{D&Gc=A7HQra&re*gd*?8xhGYd9@rVzInAT}bI7$YJ# z0vCC8XEvmHwrQ5Qtbk!IJHKfSL5Dnu+!MCpJ<GhRd zSWH;IC8-%k5YjdUGcz*+Xn2JVDJv)dIXF5yI>fw+G+nYk03Z~?zTY11U~Wf?@7WAn zW+@{|oTWXV{a0cL%DDJ$3~EeYEq2eB2dg7`HD6b>_xvu_D$*B_n6)=;K_(|)0N(Fm zVQ2Awbh9NHf(dsG3L}n;colVvgK)}s5h%V|;~_dBa``@1J) z&xku5Y;5Pp2N(jLbvC+f|8m_LgjjC8@Y-yZ%Xwly`f)X|M{JdkOg&vmlBph1y9;Bu zuI>@Zs8M0o9=}!(KyH#*C;|$+y-83Iy|YL<28S?9XMgA6kWi%_g;;GpZAo zba@}^=<1r9m;@q9S41lA>+i>yvb{`0JDt{LU|;}{lW$z?PGpD%WYyL2XdL!~5NP+Q z)apcHdspTCc&F3y_#jy_q(Fh-akc|utsOFHo+r2i#lL)~<+>R9;kIEbY zE;jmNYiesH(+XaAZVJo(lRXTHoY{W8(}d0c#7y6JCA7%EFQICKo%8y(A)HLH6h#PN z$5d9v@lZF$b#stx9Ti)B(H2|fx`Q~v(7B9(ScUfs=3|(Tb8q#86Fx!ORuGI+SXi-6 z_i&U!hg*}1f?~6(k80!o=KM)7AMiRpUs} zOjvV!AJ)wv6#D{nbzov|ALZKEvc_uya9!;{ewX;7P$|>Y#|P2=F#wAAZ^ser58SKA+b>>*E8bK9XM)YpE}rO@$S5R48dAPLUUkTkNpXyM}m_2 z)C^^lO=@}j?sAgLF?8P$XlivZkr@G9oe`5kAdn`t91_HJsp6S^3Q_-zFJGSH^u@!l z|1>B7G#j?^>8zAbM;juBdCzD3(H6m!@_C70`*%vzNf8BDsS28>@ z;$hXNTKU?G>wnX}S(>1>JE;>dZ+Yxyq4bH`ThxIVJ>p6fwki9#uvIJ%91*0vkYJ4A zI{CZb)16m(EHFI&6|WL;_9E+mPa>uBNcmjoX{Uh+^q7e5xpzZDLr(=zXJ_ZpB@~eR zc0CZC>bq{4>(zmdZdp_<^T!^c8hV_ z9z{@3{C?L!1o|b1m`Q!=K~#|(Q0KqHq|XIiwf=XN^BAx%Yy*zF38mg1zY~$HZ5y5( z8sj+2d=&fD_7MQGrwFb~8ONWJcT?Z?PfjgN-oaL=yuOaDcE2{6@6P+NMtlU03T}3THr!qh7#2e2@ zVPMrdHNm8Y{6s`{MGoj{>-P2OMvu!d0@D^F?i}uy)*kCyT7?0g=|Us zjV>XG|8bKF5yMgIhDb<#H>4nj;J~vzV*6)MkTY8P2cO*+TVF(t?|UC5L8cLxU}>HA z-XV2M=wWse*T5i}VJbnrFvMlK#*Z8n`_X*M-VMn2 zt{Vbkf9P6l_2X6h?$DAEHiw~0%f915wEpQW7{r9hw40_RazGI2K@9;=W}b_8Aj%>e z-t?z9NiXZTkrrVe{Xef|ErsDHYK!=N%kRcBi4U32KUWZjabHf15xT#$x2?+Lg=)XW zAuIr14I&6M*uHndcxqEDf{(26Uiq|stHLYE{BEra-^t!f=Y_8%>MG(I?UHdJf(6*A zdUB=-+q#tO?7sJ2=`-r)ZvWe52dfi&w9@0{v0~*%(x9vCT!DbEISG9L@F{c12yrPU zaMWy^i0~VSm=Bz#Im-oNGSke_tZ7 zvXOm0sV0A{Cjc79H0Pl;=b#Bu?0N;L|NQp*>SwHO4Ky}GkB`W`e}?3Zx;60EMyFhe zh*6Qn-=vr@ey58=!jyj*?=EmR4$|^)7;6kr*ZMPMu(W&RUf7gye0RC0HNHKklDjGKj%CnPRpJEn-0C~~75fQM_6J3zlOs)Hu+{jV6!Rc4P{c`yc z+)o+aL}q@g*DgYD=UX##Gd)fQ3B8{u*2bpFZG5V+Cg%(HmVG~jP*zP^HBB|t z!W1%G^t7+Wp=a(Sv@ zwOJr_ykk7XyQx9{I9E>76t;GsKpF=#hTpumsu^nR9V_z+Yoh{ko(=_-R|d~67f$m{ z1p#A0mmRmjHqM~vOH`vrt}Q2_=xrDwJI1)-`=tKO_mWTrI(?A{Zx>nV&wc13Mtdu4 z-Stf~@{%8)nPG=Z292ci5x)5HmYscUu!0M8Wj|eRATJ>i3^5s~%>Vv`i^8I`Q>9tV zD&aI$5w^L+Q{2N@vFvcXkgLO7?}>e)qh-0ue4GHc*KO9Qj8w|ceKN#s&qJgu-+ZXN zK^YX$j=Us|?==fc(jX`&Q~cqJT{U>xBMy&u{y)6{^2{=j2w7CD6a4^bf2!?nG36#r z25Cwu^H~n)@5Mz00|UxVV<6X5BL}3b>jN}~Ql6ipptaQ?kdics=)d&RE%$D&I+z6G zC6$qcw;xUx2mdMH`A9U;VNw2OW-{i{Qp6Y+KW1b?RN*sWOuUU(rodlonv2fNQi67! z@*i5BkI{!~DZdtQVJORk{uZ!&c^c0tgz$;eK+&*my!9JD?LJwY?eP=VuO=h^$g85F zA{u;*)h5RRzq8GO+S=Mmvp(GT0rM=ocjKA=DbID*t+cnvzbkPng!yBY*C<`owm7Hw zpRB`g2lF5QBze7^ZFM(y}t&|wnpOZ9NflwlV$5y>SI)(!h zPRKYuJ1c`AFSG2J{_m0`cZAfjkc{3bEBWrZ*Q`qVRq?|i1|e6IpIW@gpWp4D@*Q+J zEX2wNopxwPRw>z1Pe1ebgT}HWdLxcM-F7Z$XGfB}?ZH9|yL+I2_N8a=U06((g1dX) zfnFefxG}~Ub%(%imavGkz%ya!z|VjgA(17+d2%xH7R{(Z+UMIh5&4vv85X zzu;eo9DaWQN-R zYGGnKRb=7-JHlR&r&G{ck&t5|R>IDJbD||eN%qybxM)(0~ zV-&K2<}vj?e=$;=OUJHumVeos(v@tNn|ARb$wN_$~6xtU5k}j`oL%Z!gnqW1xN)<_erK z>}1fH`42_@BvK%+Prp@S+g1LDY}Zh--}8>>^*+BfhW~Dn=B-&gdU=QG+2ydO z5_8lJLTlo?VuU-69^%BR_wV0FBLA~zIL~V7v4SUUH-1QW_w-14c~!ZCl_mbMvPLZ9 z>0hfU&lm$FUb)I%S)8CNHS{Dl&982rbDW(*UU;0rP$Vqq7W5-9GdJXfq>7Q$T za(>%Iq*7Qz|Jv0lK?Uht7GEb^S1})p(=IpPUL>Az5O&9M5?P1|HXpg4<|z>@`50|_ z+NF2m`=^1;`IFz?J94EuyubwS>y%5QHy zbF{l$u%)|uBu0Vl{lc_vi#uVw({2?S>pAv3DV1n|#H5~Q-d3=|Bc5(&z1$a4%B)S_ z&gOl(H<-afPAeR5yXi_+Kh1=DE3@Nx{H?eV@jO-sL>Ee4Q^Kbb^yHOxx=~=bA7Wy9 zwWa-t{zMijeC0l)vdNz(BwcIIu1=^h^iJlsVt?f&rd+8XTrJ@zePVw39Py;hXvk3R z8J{}-VOw4Wh5%WuSSf09#pJc^ex~3}A+np@KiC*)hGm>z;|kE6iaMlg@D8lSUh&nq zu?fW^J#Il_ZD`|DvQLiu#6a; zuqESuMznuwaqRwQL%PIB(}Qs?h2#_D=HJY1z6C7ReNUpC$3=y3AN6Ev(Udv!NP3Da z*NqG5`eQp86?g=0aLbT8;)GPlDnogEjyJtA3>+$tXDfTKxPORvxwg5gac_h#;8Bedjh!c*YE z)*~~zzN51eF^N_06mvCOmn6V+B4x6_WJmsD8jWOOAr9x+Z+p1?b(t7QYXDVL)zt37 zJfv1uR>p>fk$oHIYBE-l%w<~s0|iK_?h0W(%7KU5P@E4>EC{4>tQk@;a^K8%303r39vqntgU$%kj`B?M3_SCN-UIl5li#b*idW zx#L`(W{l%KrZ_P*RCDoq=V$97M{hGRLW_aSH4YS)u6CMgz0jTD{H;(~*AcInOthg8 z`ih6{&@MU~TL5K1c1oUMl=OSRGa_3Qh<~1kKRM7NXhWtrSCNvccw)T;)!->7e*=^_L*iz2=pJrw`Vq>*&841zx@w)HOJG&)l3fdw)D> z{nw8q^T&_r$pWsH1W)~iDh!NLOE=hQ1ie;F2uM%A@g4ofkt+8!Dd`3&s_B492@=-?Z8$CZ!NO0!WgP=t3nLGp0;VtK8ao4E)ZGFZ<7q+8fwc#z> zxdXd1C;9kzw^C4_kM_G45`4(^F|>-tJ+74!w%MPxKX~}? z2l(K1iWUc=X_>S?Vfhu|sSJtsR}oY@Ce&dkUM?h5ygGEaFn)LN>Ogt?4^DBZ&(+v0 zvp>I+Q?k6`q&3^f=uj%#%6TF_efvXd8>6z0pVJ5_)i8I1K~@Urgx$g{x?=7dkDZrC zvp)WBZFrd8Sx&8V?&`{)JNJXj0h_2Bqg-mn5@C6KZ=k~GN+(5wEHgI2O|sOPCVetm z-p~=2c)4|Dy35KMJPiKER7Rh3a?HNHIEDATHgi-+OyA<3;B;@Or~R5PoV)~If+Dkq z+biL+oQpdrL*g2XQ=(RCBlL~7PhmRs_)gFBY7q8a_-MOqZE>`7hFN5v>t#jBqp(xC z&QfhcHi3ynMG;$DTbc1@+4E$lU)oZOs>pfI5}rdY9D3O(P}u;(W%BF&l`r`p7Sr?^ zXXI=?8V+86RDUO(X&9fnLuGSD|NR`ql zEdAL=qc*9(zD*kXe9GWd$i=!DxufX8X>>QgH(`K;GzZP3O0MM@Rk}k`BR!7~65ZZ` zQPkW|X^;{&k>;*LAU7JwQ9w+5;< zijZe3h2{N9Yu$@2>lQ-P#ic;*!lI&38K!(cgY)Ollb(Kgt|zoo<=VY3;X85GK&NIhqP@~qBSKBQG0-T-WTxrMcRP)3x__-M{(T0$}sn1`NqB648 zyT;8BDfAY`Z8X2&3E9uFAor zr92QSHIQgL&&+&0>;2kdjE+7AMu*EgV8UmHtp)DJegBA$0rb%e36d zcW(j$X+z9ZR1+@rEE{$ekSObv*!2@Q&&|*CO6GO}d$-j!;R`)b{`*$HK)+NOzey!= zGj1m{-CM51OqtvolS-wQ1e0o_vOkLNrzdLcW}6Ymgq9&T*nyf7AIZ6Ou&GhXJSNmxbzThC%g|bmwiVCF(tVP#3IU8dCH(oiCLoaFSZPWA^7HuUFLe z4U`v6ISj@o3IZ-f8RZF-2Kwx&zq8Q@A`hW)W%1WQ(>@NK{JFl{qbj|2_fLu@r6P0h zjHvD}_{sDErTE>!O9MAp_4|AEgf!djm6n`IH@y-bqM9&ImH$nMnxNB^FQI`K$57NE z<9*)XS_dzza|?rwpKt0jbPoGc-Nh*LL@!YE|5#ybVu|zmI}7%kkIy#MV*$(o^aO-*L+FWgrtap9B?XK(#?t-c=3FfL>f!Om za@}lEDiuA|H3QT@f@#<5eb(VBA|o$(*BR_Vw!1$(dqgrjP%9Z_GDlZGGgh7c9m7fA zm?*NieiX+!+-0-_A0al~Ke864KHh2i36baA`SZ$ZY7M1!lUJ`_Z!H_O6({lYIK=<7 zZh5hJzeQp&yTr;}tFNc$#e8`nt>}kz)wGHA-94}2YFZn5E3RQ&^Du42WvA+#=e7OE zwgNK}*_({I+S-?V_J_tkr>7fkEet$&&bf3=cMSFXuyQDB{S&9p*q&DW(a3sbtKxME zMxa+gcLSstUep;*tO^83JyLphSF#o>Ytr&@G*7reo!;W5?|nDqEOpy4m)(^6d9B_nk zhrc=>MfAq~H6g)o_mrt&-C<=Q2wTDqOWkis{87~Aa6()Mo$~3^Gr)h)>mdgM5%8#J zJ+Zng23=h9M(?U>@PPxZo?soR4Biub6L3Dt@K%|V6ofb8kMnd!p}15{7`eUYffzS1 zFtPxt>I|m3{@U32S%;SON^3VFzl@_EJEqF`#8m#b<4a1hNue@$9qX@9lOR}3uJ1Zp zQRBp8u#Ll1(|iKCN1pLz&+}Lh3jkB@uXN*u&avi=!6p|26jtbu$;VmI_jA)vm5AQ9 z?cjgy{3Nx?;(C+8Exmab9v#FkUrRB7d}M6O`F513k09dd0t=dM?CFx3K%=xMJeldi zF)SS`2Zz{{)7#OM=hlasHJm1gnqrhFD{E`!P?=npWj%hY!5%Bu+cr*=jh1sAd;Sxf zB*y!-gWFGwshan9l!~7Q5NV6)+t^FJHcFjTgOyvg-$n$kTYDf#>{HN!;cX1Z9*J$)tv4 z?;OTF+VuvkTm+XU-U+8Etcw>f_Ltf*E-o(aX20I(9zVEc@)@QYel5cs{-i(msnXSV z%h#F=uTc|+%P{o=*z&H?7i5u|$~{Ny50(gt?b~?nl9RuZdtU|=1aN-}5PR1o{791K zg^9j*@1CvhO}5fW0b*X$R(eXpe5ZM}!J(mb+J0^ck7>$BS5jVVEq%pG^cu3OW2dyt zYj}Jzl6n>LqoDlsaZE&L+I)$cg(TIrSqC<+_E{bB(7L!Kr(Kh*D->^()zwkZqs3DT z+DCrtgY^bVPcb^xRQX!1mcA_QfV)Xasr zqeAxIRZIVzn}r|ePDCQ!K=~+-QoF?3r0oOWLVwzlYoz8l=vrv{;=Zy&S1yGEP5 zPEEk6L0tVHYSvkAdq_B2X1&w?>g!5L{c1&6SSQn5-wsec3qP z(dKf(c&EihN^eSO)-!v)5}Nh}T^ruFh6G**-)9PM%G~BiDA30?Aly07n8d|xkbCC- zyopo+l2*ig`8f)T8LxxP#>Ag)wBX&4j+B*2Pn7YVZaH zhtB(B8?if5eqSTmwUL5=~(t670lLDpLG273x zIjQU9e{(X+NJgDqtRc5UmrR5VQ;%E{xupzIojo=2{$mA#&7RQFU+vfaM1|Y>XJ5Y} zWFIm7eN33K%x9OUuNpi5hZ`|&uJKXJ7O!4W_x;BT(gOI6b2TOBPW55^Iv~Toa_{$< zZ=qtjeG_ha%;uK*erl{~!Gs)jq~SE0$sx%5sOT-(`?O%hVhJQ@r_I{UlSWxr$N~V> zuIwL16T~LAUJgB)8CtK*)GP$j@B!o2)7M8vh|dZMgp$xSwY1%d?w;Zsb_NDXX>iI= zYzSk8#l>C2!>yNWDsSDtPeixdD1G(n)kc@zsk8T(!!vct!X_pj1q;o=LSKXL=F=;L z%#eETCL!iP!y1?#nI7dIwfy_$lR-MF%@aSOofx5b?ipp&+%7v|Z zKaAVOXIB__z9S=<#qC&^VIqUP0;8Gl%bKjepl{rrdLPK9J#>ulSoURls;d%nTe5?{ zS8fejg1JF+YhBnCIixySUtf>+{Fctm%{1qaw`hMu0k{-IB-i<@64%+3sFVJ6o~v*4 zjr%e+qiveOa>BU%z@9;~QxsXnV^hmC=t`EQ_BmL+u952t;^ghbvri=?L>;F(xlUhv zjYRt{Tub&QCZ zq{Zi3f1XjaunWf-it7f=?^vORN_G-&@0_PB$-G>G2Y@Xk*`oD4g0@FJLLdkN6;@N* z+9TQtJy?YAK?kbLEy}<{>IJbiUH`=4;+*|NKGG&)x3^jhQFT#765k&M69B*E{GxB=+a1=9#?lvvYbsOOkM zGqQ%I9W~4R_%NlUmzOBa@Qd4tB7IuKMaDd`+S=MPE(sm}9hfBWKum&9`~^MNryo9C zoaspDSQsdX<}$>Yo}L!mjv$@^_|@In`4!s8H499M5I6MLUOJ(I`7mD&-JGaN0M3Jh zgSOOZL(es{35qtj_ww}=TlTa^(O*^dX|L~>d;83BQ$EeZEmBt;B5aU!K^txN-6has zK_8PmaQ^7zZW)7{HH6;VGOLJhCN|ZtIvjGU&_Ojn^dHr8uoc5#}eyBcnP!_n8q%z%n-*C?V;#u6Kxc>@U|KAfGm5 zTVTk4zFcH?D*Rxa#7BwbDWm+}(3}p*^;udSD2^`-mxZUryT69ml;^o?kMmTb{qSX- zp`Q1yiCU&cEeyV56Mr7Mm4hzmdxpZgl60)++p9ZzxwdS2__VkW*Bwr;%2#BnQsOcC-g3f8*F8V$;kG=FM2w(yD!5 zd2bUR2O9xq)c#P+xSjYG2P6$idBp2EGK=IB#NuGdlmR{fd~9V`DZ{ zYz1M$6vtwg{^8YgkH){fL>#%Nr$5NsEkzpfxSeXjV)z&B{XX#zv)01yU9UbE^(Aa|_mL;zxY(Z;O| z4F1o!@oUBu-P{EE`1p`VFbWZkR8G2ULZn#S2W*wt^_ZMA^l5jR1ZgO)t!~uZoJAyu zZu4wff&#=U&dL=W#H%1~Ku?HIzb6};e>^ucZ|le8f7{)26AWaNa8WhM-Ge@_WKp{omc$ zb(HG*9g+!*R0@c7Jy+SJPWSxl1*q5YT&;&@+$bavz{7cc6ulipBOE!~omSww`UsK& z{-Fr4bK|AqGGusASN4FdQm@amL7Fb0O_rK^dm0bNbNq~cBO#~gTb;5JDdN}I8S(lI zn#er`PxkiqUe~XtmKbRXk;tC6AAfnlG%TLj$+v!ao7ZJY2T*YnaNqqKnQ~IbxdOqG z(4*qQH}wjGwRc;R={{o4&u_fF%x~{1gNYF6K@sBN$iL?re@m+_m0Z(RV3IDK2#NRy z+T)KB!(`vq%EIG%qf!xgI--h_QaQ$%Ex-~a{w?i+hP>GsnrOVTrh6i^@^9~nl-~<` zD6kT;{|DSOEzfttn;-oZtQtQS^j%AXmfN%c-T~X;@c!k0DL>IOA1{0T88RZp-im5Z zPpTB+aV6|K<@>`ZQ|3c9{@xJW_~+?D8N>el4w2sc;{9(6*(d+^On2!|IQ~ZiZkc7(+ijFyX5e|}7WEKnPv69o8f6Bq!j)3+A)>w_8%M{Q4}e~fDIh*Rio0sIRbVz3p4z;;YrF^ z<|;Cson5;Bus_CaE{jpJS%Y)z;n^nP{}$p(xU2+B*hyB?{}>h!6`ACJ6#*g3tlvw= zJz{c4O2|(4LP7@su|~so%I9Ot=(=D)WIE{HDg`OyS7m?Xv~dAq*o=~rnMqhPmash6 zXn6hX$y|e49Oz6+(IE%$%hQl+JAON?iOIyoWH%e0(ohbuLt=;;stSTv#(Li}O32Ed zN`R9me$N{S?}pG(1ac6yX(sl3sR4Cos|ABE@=*tWz5-?b>7LNqBk_NF-FPx(7?{xi z7LuBPr0p`Rw9wyqfO&hOE7(*UPN&j;zQYyE1oSMi_ zRD$u|d*)(?vx>Y%4TP`Xy!lfNo@t9gMOANHft(Vve9a!3;SB@FKfU1)`sD@8{EQJ{ zhxqY9t-8El(At`PAa^C?)!ppoTjo|)fY-VG_$>RTDun8Sv-PQ1Im&-A1ac3%jCp~$ z0XF0dX3DbwhLK%9cdcDy9X4do>vsG{4ow<*IGk?O_KJz-d1*;>T_! zi*QKyQ2<2d>BN~`ZU9t}|GGTYC4XD2-}~Q}9C7Fn9rigs1XQ~|6|R`?wePH!rBx5X z&h>B;Jy7i>oUq$!2Cx=^o>Pb0V;zG>fEtC3oemE$;)+aUB3NHbsyEqz<@j+A;C_a#`Q3U>@7hYY_1wO-exneR$ofgUQSbdl zF*>$TnX_-|@paSz6<$5}ZF!r-m5yK%`b593S5`t}AM!S*+B`W zLu8#WD=W(r=7iv9cf!$)rxL!8Z!|+|C-1I!mmr7OX1XFQg-gvo4FZz^JHEJmSuI;9 zdcelglFen*jRi&HLJcD2W$4<2#EHy4V4-R2&0p+k?J$I|D6uVWSm*T5pMS=2BuX3i!g8+b_g(iV^EzEvm*CwlTf~ z@kK+Uaiac>$3p1lcFl1d*h|c>3Zr;Td$PFmlUtQ1brAbSq^23LBxG0Sq0;xPP!ef`Cj3F045H5{x(f#Y-RzOKO##$i&@S`_U|cjfq{FZs z3c>i$)7Sz7Zf8x4{RaPzrlD=&qW1OY)mLCvgX-U0aA>*`m21{P3zvD|eY`)0d-n88 zd+YtBisgLcCNcyWqQsBv5O55}^3|$jq(QxAuea45t?NQVcf5nbe$Q=mcV?4TX0J3T zDCoL&aUf_N2=iU5TJ{Qo8x%aMKdm6Vc*A+2|3?~n53wlZw$Kd?3)W;3rQ5KJNeC&5 zMApr7!HCWX6co)N&sjPBiHSFyGw?q#FUS>sJ2=?2$iYe-f=iL;H4?lIOV90d7*-&nFW0{n0OC?>36D#H@*iqO*mXI(=2ynwW&Gezd3A+ zYnI^UtY*M6!U4f#*nK|Bb3JBk3i0=`qs6h(gS8en2u7s~`7JvTWZpT&)*MW8#(J(b zWoqO-gYttNOeUAto@4cDkPWi5*1^&vQskm$2p7Ot?(c&ax2B10vc`KX34&KPtWCE> zi~ES>RIZ(dNWrJS+pKP1eBY;|8*xhnc#9vch5)&YY~iel{qp4+l4+{oZkun>dkum4?^soLX5f=~K>TQ(>&@Uj-l~_# z&LN<6^@X*D`8@E0$n<**dp|=3ncBiA(Az~#C+3k5K?zQM2eS=**Emhm2Z^o7} zui3HmR+gyY==iMcaD090NgQ{Am7E^4;i z&Nv&-#28d7Bz9vlLWV_6%J{v6|7D0W9&4k&4+MY@rdes&L=5IMe^-%NOew zvE$ti?XL>)A_Lx&m&Se-A5`xz75K*STWOU{dd+K(<@<`lM!te(NVR%r`p*B|}7(0laPoTr&-EqS4 zy3ch3&a$a6+`?9WTGyZ0XEbWYY&e0U&b#TEMq}Kzz}Rzr4-tdjHuq_X;w7s>#jS|3(GB;fo`VC?Ck_GlY_$#MsH8iH4(Lg&b z!ZtE1*dN;GtiL~qzHZPVw!e_M2FiivS3QR|K257KsElZ>r}ZrB@{!g#TmLoC~}ch)0Ypo9e}cg*4I&RT+Nm)^ld}KL@#ix{Kzbgyl*(g zrKSB1ldJN(kP}7^CN9)84wDpH4Mnm7TdWb?>NjG4>qJM@xVb;-v24;_mTk2M4x?!l z=tPa`>+3UZCUB4E(8&FYv-Kq-JHN@8N4461`kuCq&J)Q*rIK~W+@TvIca!c0HCuFR zTsKXVkA8%Gi4cDg;jl#`d}tjbY>zskn;WwNhgH=etHhR>9nY!PG;1Blxs2wKvnUk$ zdLg-d`ml=SPLeV*ZtQ*VJid9oAETqzoTWc;&h$h0WiyM}#Auc7&cv`AVA^8LVq#)= zr$c4Fb7&X0?j3rc=?6;b^3{r2l8u^pC`#XZKn%1RXTV+lQobfUkP7Gl?yKDI7IvOvyl8)P4HZktuU~m<371Z%qEYfVL-fgqt0a;tGM0_?mdl?EeDcZiH$u$ z^SX%l%5yqnq5)taPX>5=Ta{kn%DS|OFBW!}vsb`PUH4|wb|IidvsSFP3-h+jw8zC1 z9o@O0`yG<8tN?YpXA9vHwd%AZh~?Y)u6k!6c;_LVt$Iaf~0V zcXVj^0B=EJE7k!#kaUR<3)v~_vS|uH0r|}x!pkD`6}tRS`oGTS)Ic-fviEj{rj;N- z80(6~;#f)Ry&+S^hu0}4VY*IX#5kVmM5R{%UDLEX1O)7tWI-RoMG(4F>1=8YQlK3>+A7g3d`#Lvi6AJjZ6id6 z`;w7SHuJ%AUJMKsp_l?-EW}~D6~&*r?uV9SGxNB z#04EVK1v6vF+n4Q)le}~pM=4L@txy}(pi2!Umh)S*S+Ftyt=5lxp~u6q%4Wu!UEjX z2vEMJ>|pnv!(lLBdpVA>7x0ZILliSm?qr$j)m1xvRH&G}e#1-g0|;cmTV{*zXM1!R zl$e`Aq}M6Qcig|OS6PZOnZ5jo09o;9vv_Rc10gtPJ3{`g^T+LE-gW_8v=e}Hljd^( z4)Bxhm7IFfmWG)2xah67r>7ND10MITsTsOCd1zh`Y7NJZ3_~_WcI-!6 zCS}BDr&q@(;fm(CBX}*dXvb5mA%xE7>!$Gh@+K0Q*B5PkVj#+vqkOG=23gQFv zsdHKOt&j`9^{|Ytu5O8mR~1FqHWR2j1##Ud%^GhnwSiDa#W2!#xez=GL3@NOFscAM z1bZ1JBYAag?1U536nf!4xVw<3=0(#mO-YI^Y{>X=^)JdoT@$gUCYA3?KPfHwdTt?7~PIks;97jyQ_FkBp3@ zrBmCRgZreUr=Nlta^s{jeZBR9Zke&2s z%}Wu=#84vR#Rz#(ak!L@{+z#2@wU&g%gp8U0z`j-ezc?IDOAYLJUTsd>)8XDOE;}scd;TYH4J=)o-oPjtCzVWb@R3F>ka; zM=G=r4*(skxX)$FH1dC&Pvk%uWFsMz>){Qq;Mf(LZ_O<%CIBln6GoMT?en&DRbfMC z4eTlSwQiRN0u%k&k5yGw+IlacG8O}zo+JEhL7GiPcf0tpCpBsuQq1C(k`JUp#~95i zgJgXh#i~8W)a{vMsn8*fGWN{j!m;veqB&t+WF2RRtwQS z-;@Ht2bDCP*NqC7|&-`iKU%@?tp}j2n&ad+MY{s)ES72TpJxGeJN17ps z5q~8DH9;xI2Pq(d@N3C_JnwUulj#nWD^hr=G)eob9laI5iq{k)9rjNI5vhd@m6ri-Q$IH&jOn{(&Rt-u*I&N1;YgK-Fj z)B)K-Q!)g&w-Bhuh<*iwUE=3+g)XjGn}?CHO^w9gCe}d^A(on-JXwgJU&On;q zl8Ej20=5e2>QX`WXhQ~r8hc81cJSjHuetq@bBhqsr}>Gv+nO-|MP$>)8w&PEP_)zm zRTfc3t7vbYJH6U*e9!^kgX+Fu5(_9D(xEOF2` zc!qSG2TTwk1Q=5kDd~D1OwyUb4Uq~w$W4(@-Zv9lr^+s!c-_jMJ--G533K-n($ImT zb|8d|g5+OHqf%H-9^Uh9@425NQrmAa{@WSODS)H~FeGGuA2PYneF0ZGjmQ{uj+YL8 zNsCXwji=EyM|_BOqX94+{MD%U%R@w264~gKgrH#Ru1%QS<`?sZv$_=RUjbb+p$MA* z0u&E4z`qi7uj^WcugDceLTQAZb3w%8D4QZX+SEUefD>*I31=NTWIlidory9}Au;|Z zQh~tUglOkTiDLCT`6>M8$blhH=H{^(t+d7tJKBS|(heZ#JB`b5E!67;<~}EBR5-IE zIyJ(tpj8D{(+>2-Jex5w>(X(*)^mM_AfF>axD1iukie+txq63!T}uiYe}SJ&fnqZ` zuYc^$-0@)0pky|Y>+QTHz?cL0MCnOT1SY`!r;&>TK1xbY4?r40p!t&*q{Hg%s%4Yn z*=5ltCtXC3L2BX%In4$AKx`{71a=A`WE8{;0$3Y)wVckU<&b=L5H%i%bX}o&H*^-L zg4}^DIJC3IOt(at;qc*F@rFuXaf&4NHk|^Z0z`A~-3!=SRypJjEgjI>bt@*cFe5B1 ztTi)$LHAGD1fn_8+Oj?7BOW4tBw$muNddVM8_)#Af23&$RPygYF6uxkiz&(ip$tOB z6-2|-E`E{-o((M!<%+1oC6^jRMFXMsd<_WlRD2fa(&C&i0=l}2loW=>j`%O}KlusS z{P1{j#OFcJ!z0ux+Uz}*H?J}7qkZq?M& z*L`1Ky?}8LcUV58Z#UE%-me~nXmet}xuZkf)HD@oKv^8E(&mr3UshHIBB-kEw6f2^ zc~jT{uT|w<1nseDjMBkZMMb^7`kc}zei9w4kOpl1qohA^dS#^!b2yUKv6NtI9AkF@OqX;WTd_d!36BgF?fpSw380I3J>lF|X@PXgz z0|lpECKBNF73`x$J&Hl$@&Zj>bq^|Q8$f;9e; zP(^V%A)S~G%tjv^@$*nkEfuJ55EbuTXd6@3(~Bpp>qLI9q461<@G1)nOS0SMG-l3| zuue%?IW)WG$h`_2^%^Iqy0oKcMHssY7&o!z~kzsk4Nx6s;nQ2y|rUYXjr)@?p+DOQO##)sD#av_vGcF4J?w@ZHkm#Gd~$svmN54 zSPsI3=(Q4wjQ_6ju$q@#y=>#jzTFh=MPWooaxD z)e)_w5V|uC0Wc6}3+%C0v5cp+zLi&25l^U$jE&6<3=9-IZhr@_;P_PUIPw)qs;9Q+ z^{}vH!TMhOJA$Jslx$ zV+-FM#jKk{J9Tqw>$_fyh>gR(N@y10yK$otv;J~g#-rQCI%u?7R<=mmc+GA4-u+(n z^`%f@KE~utVTCkRI2bk4@0Qdf2U;v0W9t%aVdn*un}1EPV0XG+3pLnQ9q8#tNaH z1rqD+n430zFHVs^(AUoa3g}j)$F7k}?|SVtmd+ChyRShvZ5~zFRpw`j$Rl!LfiT7oJ>!Z{c2=^q%ouf_XNRz6KG&1(zFL1_ zb1oyt&*L?g-&?!MhFS1Ht#Ze7GIH`FP?w>*8$4MTS!TGyo?|`*79kVkPG=x@} zJ=nh3JTMZgf&44O-B?(%DtGVtt*x)ui4uYL;;7AG{r-}ohY=!Qz9*$VltheLnl=P59z$YV<~NB1nOIz648 zANwLHf_`za)_O+=N=R7C70!`7YB^d#(JHE{P6H-UO{N8) zYm+YgWC>9sKpuqaD%5k!bU0w%XNTb6LI_h%o4x96moF!xs$>HK?%k6I$dcp;wYV?& z`6`H`!vTd(P_DXq<;opXUOKnc?z@S`$fYFuolXeBL91^KDYYtH^T77X^>E{kP55J+ zfOWxPS<6v%<4SIBWgxdrZSNBp%t-9~oz-vINlB8xgzW{W%b`y3E;<^@<)7(#r9C|> zy`l2+7}`^jfjBs<-#O(hw)cy11Vr%W_Vzy5Dq_qZV^T1114tu83n}PAITV`-*#u12 z#6{Q^Cwy~Qwf4^6^*zZ}GnNCvQML;N!idO7=J0eII(0as3mPb{gGbF4bcltwOsmkJ z{T1Z~N>0fKVV7*E!=ytF_*`DDMe*hi6&2Omt|!RdDo}d>)i@h!Q!SIL8!e?@cmIuM z4n*z{*iCW+D)dBjVj@#GC|OzA54>i<;1QszvL|$0SfkeEh(az6G5HrL%s*&%C0dpr|R#~ z2-+t@Mgy|b+t)|2W)TPF@>ys{zIXrrLv!E62x@_ROvmi;k$aMHO*6&&)*5sQD%`Fcd9Sh;FJ|!jX7uopNCBArp2et}f zM>DHWY_q^>h#y|3q@`IxbG7&{K0!gjDm@zu3l(eYYykfeA3l5mmj!I`BY3 z{RE|a$&z7vxfMPbC5WKK#MA=x;6j!;RcfoNt9w93i{QdmW7WFQY?x|Ywb>^oO2=^F zZ#Z}Yu4Pg(1OccAGtr1K%F{S^=@MHAid;oE4oHbC+}pa*0ZxWahbP#4qknK4#6{;4 z#v%0_y)39|&p|TpfvOGF6E@f^00$9IISM(g{JeFAg@r&L>7$ub^w|rig%ikb!yzdU zCV$TbI6Rc(UIzq(_F52?N!Z&QqU!6LAe%TA?%o{pWR$%q>h37BZvNy+4}fnDSy*AO z5(()rXvs|k4Ug~U&3VvP%~tk6mEC}_VF3wk1cyd;4-hD)>>kjW9yp`F>)@=LM*8na zc=A#RiV@BcUVf?&1+MsZ-`d6|im4uj+8)${gpSmCs*3MN^W1^a6*HN`iPYc~&5ezn zV7nf}mORmpBTnd9_(90_r!Qb^CRy-SHD~8yrgR9EW*zYnLyN=|KE+yDFfI#o^U%8S zle3znn*XfZkkSuwERs6f+uPrC`9RJktUGBw^x)pT*U8HvddorR`G-(i%(0rCovqE8 zpPOTn)zs9)(6I6Hs)jiN=(9$bSdV-uvP928aj6f00D9h1Qgr-GsQ*7hSIc?3SqgeFk8uG-{9Lv-|mz-PGDBbRZ9aj23VgJQ_*vlN8fF{Pq8@n&QjKc2i^rE7NQF`v?Tv)SjhKF@vFVC0KQUOY`%{%C=tZdt~n}7ns zo^3jd(1rjrVwH7=zEDR1n9dbr%i9IF%}ypM@gR0W|KyR8(Rmu0EKmf>bh5qAT*Z0n zOH3n_EJ6SA`*$fo1e;|!+SX-vPMtahbFOS?Xqd1+JLtR#{SgV<@!9NJx_6>OXoOSY z{KBRu{6OWF=IoA<)&}L`?8`j=!drte4=c>FzUS&o2<5khQs!#lFk1ykRplF9avj<~ zcl=)m1@!{kl$Py+$I?{lx=!d-v z4`-CEL|8Urosyh< z6+q6Epcr&^AU+L0I6^J<7jT?z(1^-M9QHQMtJa#?J_y)-0`;rT#?Y{2 zXaRVeKpy(?gU}x*<%wx4pLosoKuhad#Yi@!_G^$u73+h9g@qx#rohe-1eCL~vL4#& zl!L(l^GgDrH*e#!9|N6pDZp5p#%&u-3(`|k?mz{yR$>lh*D?SuNCI`9H-or|j2=1_ zK0`zHFTYFHZ|ff^Lv)99guqwWNx`n6eU+K{E__r#FVNx}HlreK3F7)-v4bTx39u`^ z2)cAcL97vSTT6zFA_m=sa?lubS)7vr_iuz-fQ@7~>?Wij#5K-uS^$;0r=W18TpNs@ z?*$B82we+7l-#$0EnPk@bEFSBad&rj4~maz&<=73vZ#>vK`9tH-;;i>`|%>05S7cJ z+!FzxhG0ntB40P4#E68193&6}bi;|m5m8ZTFd1x&j7dY5hyJWM=C7E*3kN+6<(Yt~NA)s` zzkrLw9+U_;0$+!HVtfCgu5Ol}AO5aq^&9>u@Crro!w1qKw7o#U9ozWOjn*YCkMeZ5 zhG!QR9(Z_EKpk@v+*%Gu<-ouIlm_;FkORySTwniawnG{lACK)1UVQ${kn-Y9>)0p! zF@HG^^n_bNuB~0v(0%#*(7Wcqy9Nw)6BuO%&>TQ!h$+G@&b`gYjt035e{tbOKf}l0 zUy2`Ygc5Y1=zld9p!e_(J|AeBOZ`9@7B_~MW4-eLozfk=8! zQE^$h#h)yXa_(;=CVhIA;8$>wIbz~iSfqdNf<=!*`u_$+V@crs9U;~$i9h%J|8TLl zg2Uv$A7i7Pi%>I5t^WIW!v6QLH`mmmBjmMdfhIRMH>4q4{-~!0017GZmZo8E1du}V z9FNCC-uN+1f}TDH4Jc6j<0Rl3h=@*Sge&!y6*)RXt9|-LZ(pY;`y1x4r06aF{~zLC f*75%|Ux#$ji`8R1<|n9-VaeW6kjlPo@a+ErH(_97 diff --git a/planning/behavior_path_planner/image/minimum_lane_change_distance.png b/planning/behavior_path_planner/image/minimum_lane_change_distance.png deleted file mode 100644 index cdde3be0eff38b89d954203bddf52b325a9716fb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 85266 zcmeFZbzD>bA3usHh#+FnD4=wQlpr7oNGM2+9^KuYib069zyJ}D9HT~VfFdmoqX#+~ z#;7srd-&-0KJK6Q&--}X-yY|o$Fui&^L{;F9r*sG<}*riMsgw|B1$z?B^@Fnk_I9o zVr?=~;K|#{;bq{jE8dD~dSt*Sgv{n0@NWhmWkVlbcRL?{OD|g@dpCDiTLEutFI!tT zZwGfD+~rm|A|h5IH6;bT0LbQ?kw4Q^#@3-d?p@pUfn-vr?r)m*fyG{FW@a0I_Sa*< zWr9a#2WImPvirR0&8ArE;}mSK&-5eJ6eaC1O1CeIJo|wTy+uT(o|5$Y`r3J4H2Wnb z7ndsv9Uvp-V+gNMny3FyBAI+Yxv)D-S_|J@dYgZU&7>j zUk=gsiBZDFOK9$jb??v?0*4O(_=@NCSQizDR z>}BH|!otp~i~j1-w&wBFU>N7htgY7Nk4mw(|6$&i@?hb@YFvDta}c}zy(4PV`+q*B z&G<3qAd$6;Ha`&iy8!LTFZ{mjbp(?xW^Yiwb(81cdku>J|KsunCy2mfOabH4n$g`3 zUmd6oy{B~l%6c0OAl?h=JLobr{-|E4{I>4cTaD0Di#fhQbH2ZrAtJiT+ET6J62-ys z;Lr22f@|L@hC@oAR0eCsSN>ZP(N5M7$%BCy$cwL2B1lWL*P#%}-D>r0b~Xkz6)>vd z7g!~7hnzZLV0|I$7lSpIpoFNG^cek*=PvGXi`m2&n?>;Ks>SWIZKJaNXzT}i6CHZP z(8>p=VGmKsern+%W8?TKrO52b2}1@324{BM5+d0F0DX~h&p>Rx1^P8}frfui_$~PEe2J4#8I0J{@?}vhF6BB<@jH5cc z8GDWbLeO`~+kvmHy`eM0!jZ(7vG~iUhicl<7Uq_E-JQ%I+~XJqhWYS1>v1~vi^$|X zJ9ykuXfQ|v2qQcQ ze0=%@UZD@Qt{uHmJ5GkLr74vq6IZ>=f$k3GTd5gweMp{$TwJQQF-@w9jDwVu8~v&l zxiewJfT7{;QM4q%oc0G)@+;+B?}}%)_7dF{wbKigEv?8QgHdf6foR+ih>5;S1e~D{hQhR8K!=LvY~@c^>(K%mn;`_NwS#sH(3S`4KRvc z8Rf_+IW*Uy#{#|K6MTPIJ@stFRg@me1%ec{ESrq76@l2gcqdmF(gqao_8DaE zMJ~SCCemBVTKLm}i%;Jvnaz{&xapB_Imo(ZXx5}rEX@FX+``UMB>Jtg zccxHOTkY*rAIC8-o5u%vV4lp$um>Mm&|NJLowx#JH@+TuNushF>ssKGqXbkusPyd( zslNnN5D~jABoz*nO;PMGJWT1sz#n%1 zCtfg7t4Y*SfwNmpf!&!+*^=9tBmL_-{%XvZm)@zWmL5aZY;=r9&NOcn{Hj5TFKpv= z1-p;jaoD1xeQo~3a>fux2^b5ypGUZT+G)k-rMN&KZV@@C*sVBwAj3;x9%(k_!l5Hq&8wsW2Yorm!307PITQ1( z24RmDBy=p|zq2;;lUMHz3u~Q?su-N(9Zb+%nLhEPs2zdfC;vc=i$52Ca*=%jWyAE|WsTA>we9C#+4)JgL zm2AvaeR9QbpE~9XS;yJ&Jqjgk#l?w~)@R>dv1KpRT<_3?=8S^-N>J)!8+h?|)>tf8 zkg*oNJh60KV=*ZVRJDct&J7!13Y-Izi|g_f8w;);S!u?mK3R&=hhq27&k75|&qvcj zM(#0Je5(v6D7DEMmB<=fJd_c=<4*tlZjER7wo9&`&~SLzRLXeVmZ|x;Im_byo{(Q^ z!SRtt2VX#F8r6UNj_?K?n`u(e;JQDRcMvLO5s_RK8N%2%`NXKBD%YW3#AWb4rI5d< zM9L00tfA7HcKyh*EU5=PYZUHe{e7oF?eUPC?6{j*k_dVE@cCZXz0ff8QrdzLYVPY# zm%I{*o!=NWrDi;DKpG&k*Uyqedpcr{HO=L=9Gr{F#9q*JmDsSSOZy(bHx6}#E$QK; z@IjXkYq=Vgl5DhWWAzXN_{(vy zH8{MH&OX+j^id!kRoT4xH?0;+;S)bZ!;!)N`sM^NyaGdd>P*d z(I4kZb{dn_J-}HMB=M)~BGs@EHw!UR-)S;uDi=$4NQNt&kZ$HtF{0Jmycg;)8 zMzW9nZDd(U0Hu%;0L=L9+9MV7$FXBE-d>LUg{S2L@2lGDhK$Nx<9agf>G?9Apegmp zbVAQfCib;h`uVQMK?v;;CPrCxuo_|&+gtnDEwfH# z#&KiohM`B5+%+@f@!=t90;Si8h&-m`S_|#y$q5TTw9#gn>+bnrtkUYkHf4*}7zoB&!8GT~B)5-#tCAw}CNzYbP8 z4eXwt?$v7qZ5!^kOK=zsWi!3OxrIEBuWFBRkw*ldMGteXNDMaz*KQYxF#Z5Hd-B7c zK#MqJPp~fp!VC=@!?sntul}dEZEJx2qWc-h;};o|Y7}}?`Dj<+8M*rWtWJAT3^5G9 z(RXAaphJCE^11}?a=~GBiZtvf>{-}QO4P|WtF&i0iJj1G#gh&5$*pa8*FZ_UzI@em z5bCABaFN#;#1-My|MmHai+zW8U9uzi+oBHe){G=#KzHz5}^5v z-R_Hbmd*4%d|S)4{^8&`vopxw{J~W0Hp4>HBlmHw%Y}k3o5S@kW77jyY*LH$GPLES z4`HrFIQ&B31NZ8%d4pF5NmAm?TR+$q74sXtJ_!grK6RXYID0Hf){jgNkuD!%&c1Q< zv5zs(7OK@5YcI`}tDb#?IM~wHdK~^2bI5hThkvu;!V;igo~-X@7g%3u76c9W__~&a zl+J8*mE=fTWmE=~dJZIsfT|S7XSk>uF7u`CfjUV=Ia7ARCJ&Zglzrziu81qG`kIEQl2DD9`Dq(C4<$EfuQKL>IKWaOMW+m7ZSTo zJqb;pz#tbFpVF6ns^_KizC&S}V;S8vNSh~?f54TDRgYWzt$K6Vp&YH!CJ##@DZnfHGUD2?p>0J{loOi5Qju)=y$(0&XPI&{xRP( z<%W;%k-I%)Pdy0(s$qeCs%fgasg{Ib>eiS#mDOs$!5!VUX3POA7|hlC58{YeCC1C9 zl`f%*e1Wilq2!;EuTgRvquG7wdIC9*Kly4A(Z^*#Z)2t+iMGkHKPL=6-9XO?1JGa^ao}u*rIn!(b1lY$# zj9+dtKnLg##nRyUl9YnW*QyiKcOp%LdTB+8h!&vfa$5SwwlA2>-MQ5&K))_|FgU?8 z<&HNW$_DMfo4-cX_TKbc0YyMFLq7kaMAD9X<)}w)vJ(NZC9A;^tXvj{lo{VbsYi2D zWOc$<6)c3UU5;gNO*N;z{is?q}|KKMi4nNW@PiKiw#g5_|dSb@doK zAR!18&GV)R|5u6W`us)Ts|Zq*LOqS63EqMyMqI-yIWFew{Q#D0%S+<|e!k}ep~|VM zomrl3u82fWPKpN1%Sa09g2*WLm!IB{Cp`hYLUgSPaNLgem5Ty20U1AjobwtrKdWop5xx)k|6*JCvFjiVSCRjfo5C>{3RB&S*>>2>dttRj4 zPXQmc#7?J?q+?&WAQcRRK7E1VzvX5NA;Zv)muRzZ>efuXR}OV4hZB%F;>hPWdkSB* z$G*rZbIDV?BgN2HiUY{N$HgHK-^KLcM*0@Sk1&hz>5|~;q#8}nn|;w+g)gNi`fQO+ z2|VH@%(H>4n0WHJC|+y~tv@YIgSG56p!nOcd!bo&>JJPTxS=#xFNsn8lxO=0e^T6i#;XbPQ}<`7KP`WH2k=$G~n* zadG6?QCqXE`KBEH+zSVteOJMrH~A=a3N8KAqm&#!mQM2Ye(j=aXfCYq1Nn{h5ddbU z`K5`OWN}&^~#;|y}nU=nhjFEn|h)Sm+&$|@( zM1$g~Se(t~S}C;oa#2^Xku9RC@mIsj$@hL$6_Bib?cBO!p$ADB24F^NO02i>teIYw zZV1*d-$Lfv?Ly1aHWK%-@a9LOdQLSf+>Rf4-(6-1kIuOYm>kG$*$Y(Sso$tnJtX(; za5vo_rthII18?GMJ$q^CJJlt)a4?;7Wtiy#+%R5KE{d>zke!42UG8-}8| zEG$`5y;Xv%hMzwg0pkKy;b3FB-`QCX&R6$b?+jAvaH{RC{qRXS|A&H?|skX8HTwEj)ALPB$`j}E*;I160HxPUnSu0@=uRnf~=YYy>%A&=u8X4#;E!N*7$%HM} z5)hnbsSzfcjjY2~_(iPJZ7$ytHCjJyDBZ5FA++CeMGC9q+1KPO+SBeapjdP#yj*EQ1$(sn`hX^L1mY_7xk z-fdFQ!;WNwD;*_3vZ5}SX3BqOd1-W!DJUxeZ5Uw5UqSs_{Nzw?qE8y5w;5jqjVoR#^j-Ge~-w$8E_oJWSR;=;Qa!Kff6`)6iP? z&%2c(yn4@80UjFs+)G`F@vcH3Muf-F-*cS2#q|kgn2*5~az%>utbMzh01ZhuFJj8> zzQU?HziFqgJoX}f)ljpxEPZO6nDyyV%~up1ou*!g*?`HMQBU6$62RtMaR+sHFNg3R z>P7!9U+&{_*8Yu{*a|Dx!bvWUMp7>>h4S86tcf#Tt7NIa$K1(EQ478IW>Wf(Gl zr_@Q%A4B_ZA-otJ8oLAd?(oAS_sf7M)J#$0#ihgLn_**i9hcBS;`Uk7xpNa+BNfZ* z-o}$AL*ECY$WMuB=72MQ|1S<^%zsj{j&G81B4LoD3&l&{Nw2r{o@R_t*mr}uAqmp zNsca0cs1QqY|ccwiL5xmq}`&Ky-~083Wj{AC+jg8TwJ?QwlO=fgCKN$Q73~H%~Ein_%dVZ;Q06_SMGS7!(ZXqUeACF9-X=F?JFQ_KJtAl>dSu0 z#%F*{d$cZw}xuq%JR7=NO1`q|a5cR;ms{Sa(&e&lF!zDuBqRsgXj z2l1#ON#7d?9jxyok9M|GY|`t4OMXj@k0Nu}g>bhS(yz~W$0?#Mn{T{$-IkBz3eq~J zd*#H?)7CX!))R12fgRRkb0`9#|&RkW0C+mGva z4!4u1XnbqwFF(&BAH7c7JdJ29S$5IwpZc1XBjos1B)=^;qEufMX99qbnvYcijTZqn4%$D7sAe10K|VcF1w|Z%$8_F z)U#WX6I1=G7H?;K7QQ~%-#`iX2BVw#%hUQQn1qU@80ze+`5(`8HQSsdj%f?JyVw;&>myyzWzEMI+6fyaY1cB{w}hw-V8mK51m3ejyP zxvEIR^&5yJ_Ei7(i@*6BSPnYe4j^IpB75Fc^(Lf^xXA}GT|o!8ub-X0Bi;C48y8=R zQRE?yBhH!&TSwF#+&(?Fe{mRK4h}O!y3Skd{LD8_{zKO?NWB*+*JL)1?}$3{fPIaY z8T2{M-6|8FkzaNNRO7iMUzt-`DR4C!*R?GU{QlrXA1`EC%6bN)qwHaIHq@T#!;V!eeLKs zTV}7y@ZI#^b$kFTSDd+$7)MDx`6Sh}lqK9=vnKURl(1f*h5ms3B|>uLo%7 zvb5Fn%^=x%=Te=4ja)hK$W`Y=NODj+EzjI!*^Iw>l9F6}DrZ&ZoMBe*2*&ses9C5{ z3G1g3J~bF*&-X4RmKZuf+9bi^VEMJcsjzs4?~#E1WxyM{%bc#)q@8V`(UlKm)9-O) z1t;hJNbK6^=!-dgIUf!yO>j@$H>Yyq1=a7r3J)nA4=nR=|3&ErROS#H)BSbEExuEu zQgHR=FFMTy8Aow`8_m;ZXnpUxlCiHq^jf9`x>gT>6urQ3)kBRuaevt93(MTr#sq=b z*GkBGuW9I8|NmwIc027|B|elZN?bjcd>gFM8bb&(6vtA($pg{y28E03m3-7K`7|0f zvEiO@fFEQLTE}F$-@c)-m-@sUEwHf?EP%gVW>*GFa7&>fd8YL<7&fMMEL+q+rL1G3};$L2)QO-M%(KL6FSj42U z^YN5{<)z%N#%q6&gRu>;+^9pQs|S|h=CX&oHk4(9nuh2GE$Gk=S zJerAHGybfBq4d#5Q^SuMZ)Bm^Mc8T?vGKjC{vUpFKrezkAF;e*@4I2FKi`z0E7$vd zCflxjJ~Vq2*Sb{(sTb|!t5iAc=BA^MjIy$+QAkG%}9TXUJ-?q07;y99*#|xCq?>!<>8thtLCcKEqKub}o*CL#CBVk6z#Eg_mqSZL6z~l2=;_>*BY1|Q z^HUR9XbQ9i{bIjZ?j;mUbF3s-rDMq8hBg0lRC>TDv?rLDqAR-U=q!UmgHi3%j69wr zKxeTve0p3H%FdAAX1w$iW(ssgVHT6$XFk2Gjx2{)qj=RIb$-E9j}a4^`LOei@Ui^> z7%yAT;d_RoO~f8pEz`_Gh477@AzA;q%!;iG>z!0vmj{QThXpcKtagEueKM)nVtYXW zwL!k0Pn)d8q~E-yBiuEk>E_wJM}jniE)w>!S>RY2Btigik<=WCpj;^UqI=yY^Cp6+ z!N!sm+Aq~llP%Y>ykCr(NN(CMUxUwxIyI?6TlD2ccH3DAtkw4pmL&Wj<3Z<&H{FPV zdgK_xc-B4f16NdQ@Z;Bs1Wml1d8;#iadul8_jaQ2&eJ7!>#j@n8lx`3bQ+?J`-MWx zDEzjOR;TK~qr>+hQ-QFtz(U75)k5*4)IRB0ria%X=2ky+bIJB}06{kTQ4gLYJ$;e= zj$P_Ze*S{_MAVOj<%T=_|vdf!adk!$AP7U?!#kg{&4~|@=J)z}b z$sVf!9Nvor&LEVPfoCL4ed_EE7LpmZV%O)j_a^`HrF=t`Gac@_6Gp#BU{AksoM=D3 zbd?4Zb~lsd^(^DntuUXvCpMEgrS$v0{vxPnWhGnuoK46Dz25lF3u25Il`dliwj3?} z6}0anX^=gDt?B@LeFeR9d~aY0BppQu84=Uoj5`Qc$r6WQ?LNV&6}-poAax6 z_H^@XSBas~y*xj8e}ooC)+A{x+AM~!_Po%8+UJG-e##+7ud)WDETBg#aAW3GWQSpW zTDjLZ1^tV;n1Qt9Q4CW8{!gd1z@Xqp=Q3sLG=~w=Otu%G_V9w*2G&Y);*y(cefs(A zFUHr4rg4;G8gWTK_;w-@{zCjBkH|kF6|?M8hdVX(Je}`aFtPQ>7-6W?Azi=f7~(n0 z0_Z*L>pz;wyCjHK)b-F7)Y^&a{$dX_{G^U9CG$Td3-7tJFhSi!8+(c6z7uI)Fxs z1vSZ?)GdG{DZ1v^=4sP;y`nK~*qAPCX!O{;1?E-soC6?ON&=V_=zSeIY^s*Yr*?IG zcm`lUUgc$}iu5nH?ZozV&x%Dx##)96iw)%+z#_4yE+E9C+B5 z1B~-D*zk)2q2WbwMLPNeGlKABhHoZ`-5ufPhSn?5Pb&1I02)@bgMVwA24L5!uPc0m zOT=7sQnF2WRrA(!_<=oPi82)!%|ev@8^1FE=a~#W4^=_g3R!3S1_fbDwvgdk@WxDt zXZqu(0Qe05=6xD=X$iEp5baN|gX(sl3w9G@?fC{5%SWNd^|cN4+#4krVxk2zz)W47 z@Dn)&o+R3_n3ZyWu`}6o{9s_@1H?Bek=Bon`p-g=Jy5$4B>x`*KQ{+g2aqz=CF2Kh zSAbl#5g-jk?ChePcMc!i2Sf`;_IGTlO|Qg-jewUZgs}?2rbAw!10G>6 z!ske~MN*;#*JuCEAbl7Hu4hK;d?XDDILGG+w%?0>8_206; zUmxNZSTjBLYKCfzZ+~%7&_4+XGG>Rq{5RMmJg!K$ezfeXHqx0*=^JZCBKHz*lOE<_Vz@VL%@h2oPOE3rmW`8E1B8ZvKOxzGiPOMK0|_W zV;DVNnkBEsho6Rr16*>lr9Qx0Tf^5qcMlQ0OS>0Gm~%6jb0dslQu=I{_6{%BW%hqf zTHKe7URhqY!5;eZ&(6%qBzq3*H9kvXcaq2|V&+QkE72*r>pbJvEMOh?g?nUncD9On zbaZ!ec7ERAZdVbry`LXQ!DBc2KAkj$@g#W2%2~TmQSGb8A9vw|{+iJZ{Mee0rtAk1 zmBSD)Km{)~ITs^a%ohVWd#sPN{q7`$w39yCvRL@~5+vDM6MeixXfyH{D4D_Te)^uO z&=y~hj%SkG|8|uHGV>?=Y%doMhx@L3${nq;2?z@2e2e>VP-cF*{v1qyy829By8iRm ziH$Y$bG$i#ZKEkFA^Ze0scB7c53hB0mSdoh1@P(Ns)^6YrCW^jLXIA1qm z59%JO(bv~!FPxu$dNk1rYMztBOXY^_zW=@*a%L2ZF>F0q5(4%t(UYF&T0S_aJKK{# z-y6e}mzS?%66ECoR$zhIyNOpxo7)DMa&okOBUStMe8Zn9oXde?=NB7uUG(vsTY1RKlx1uNY^k` z_@8!bWaB=5!hEAosP!>c%y(tr9ux-44T2aP&f&s}=H})A43M}`oaxi4+|y0_q8qkf zxB*J-@`s1QPrAY(L6FAAN2l9w$DL;Nd8&|qHUD)pyXbJzxK^5MMnjc9;gA_!}tGb zHt+|8?cXZEGXHPv5mBR)+#7rL14uggf;=$L39R3sOW}V0b<$T48H%P{a%O(VCk?px zVvtCrcb0wYynM1Jpf(e^herJGxNRxCAuEpu*8{e2xLoIOcukNC$_ehBwPGZo?t=z| z)OfLQ9;ek|T?6Rf#^X^j*I96fr`XI(Sw0GaaM%zrLN zP<8nNWisid+BFVoDIU6qQ-OoR)0Kjau@CQ>RUuEM+G&; zNS)4LRxA8y^zTHl2WO64XsP-6(L`oe)~Ht4?j73JW}p=BwAcBSc{cR3@HJm&Od2Yu z{GQBW=hUC|GT8oG`4feWjg1T5rVOrVi21Y3Z54`{9LDu@lTPSiCpQ@}4LJ!- ztn$SL+>nzj?FAYIA5onJ<5IttB(ZDP&x~(vRXD+?Gmr{Vu`7^K3t$!yJb#QP_+UEY z0auCkJn8$-4F#;Yz+5+e&AnZx3EJ&+#%#TbL4H{#EZfS?JuZ5Y#BP7U6XoAuoGC*V zm9BXh5_UHzfp}Y|WMAc5y@-k>{fGJ2+|=a8#>P5j9&z}1@ zk*RV%`9{7m=L^z#lrdm*Oa+SoH36n}^~>~A`5ERi-w6wIfwY3FK@S|zZIFa5Zub3~YOI}8?v9W;k2JJ4s2MVnS!b+$C(ewNN zLy2!&&-JpstLU~H+!!$b7pqFgOViTR;SCMN+%e$BRuL6#YMz(}sp=g4gM$fOlXG(% ztE3)ee_bQsB%=x7(=c=3!upv62M1$@f&v4L9zJ|1x;&oynXLWgxRZXNj#^Dk&Gh{I z#AuNgyr#x`@%twtwCw+8(53txGfQW%7uS@FQ*f{eaA-b0K4UOA%vIn2=9N-CUZARV zVbT-knKekA{$&S7UFLQ;;8R>_8w6|1WxGuFa zhV>f<+?f-+7Kwx|E!jdVDoPFcTfF3*p#Vzc(NT8x_W1oZT~}Avd&Zl$+nOW){-#8P z`_Ly>2Mm%DYd{zuB*4!+%nrd|ke>Ht`)|Q8Fsvx7HJp1DY+|BYq8GFjrcLb_76$IH z(gq@hT7gSwg@4E(RGP<7r_BU?^I|@D2{SsVSWNXoY1QX$r_Q!91bJ%rt_dfthdkTL;t~Td@4WPZc6qn2n^uhYGvb-Wk zvB&lLPU*#qqyyh9goiAIUzUxJ?5zyKD=R-cPgFSC*)4Ztxn|OS{`~3S?{7fZnoA~} zMcLo@Zw&83oVOVZ{nY#=wj3}6Zw~Aamg3VXAa!moJw`<)1ox8Z(&|6#9-074@`qm* zjSi#HITy0k(sI_@!TrotgEuwCs}Uk0ApsyQ6oC4_qfR22C31W{S$}HG39t&8-Yx z$K&;ETOi|g(&?!w1_Ph@CSQ#uufuNFeD0CozkfHl_5e;lg}sMlkiISO-=O}&r!@aG znuaG-Zt_E0yA?WFy?xI9o(4d_?}HUo&P+c=C0$m30Se470n*tzKXG=};x^lm2ZxK3 zeCu-;HgeW4(d$(B)7kkZvwxZ6Cu3V6>%xD(7_dOezbVko3DUmn80>1I_DTPhgniaU z>cP>dG$9G&i(z9x&Prcun^H?s0?fsno4;wltc=X@h+ii?V4MHS?D`I-E9m5p2*pcc zcc5KyfdUbF$kbbN7^w=B{<|cZ`35?6ch^&7rW47Y8>2I%OC8FI?%(u6CPm zg?ij{@($IVvoa9Xk)NMf#=cl0eFSx{&{(q_qz;fQa4c2H&jXYq2w8CI-D|_xXVb8)J|-bd+;{eZ(@P%Lj!s*0q$`l7 zxe5tM$#JZoFQ6H0!QLj$`cRPX@qsJgYK{rGzDNGo9+GtS2VmD?~&)n6G?;P<}v%Uz22tTgoB3TfyM~+X|h%fzyFxF6- z%{NtW2R5DyMa0r{RprPAe+3}J<9*Fq!%n-?H~{MbxNh?Hm*(N8@Fe!e0*1>0y5&BR z=ebBp=MOe&gAZB!6S`%qVERw6zIAeQHn9cVI@JurHf&jqBj=FVsw##L&!1`+Bz9^i z>m|=U*2vW@Iv_43m-*N&AmN`&kr4NsU;oLaVw$tI5z)k3zkV^i6Z*Jww1QjN33yC5 z@JlF;$i$&{b;QZWf zz~l7SC38F#vc72?QCcf9iCudl)^T~`PCMJbo^H*zY9+BhL)}t*S)$hvgy;3gp=Ily z6n0?_g?AWcnG?D&f!1+wdh2e{{sXk!Ot3)E=_l?!;c3vU@-M&A27&q)D3)YVnVhg2zs*<4_D;@-)a^Or_68eW4n4-I;l^d z(aOScEiWm;qLps1`Kne!oz&aAYcL&h9vZTt49*wUI#{a-`YiJee#2K)pBXwU;GMEe z{+8O21z{J81z$jS?0m41rj#^?j1;sSl=XW-+>TRD-$|>`p&IYOGsU9gxd9b5UZj_y!-L#N-KTo$TLy8tDZcjkcOKzci-)V+!F~pvF?D|r)ugcCSB*ps`0KLl&WlONOBj}mDF2*3k*4NV zZbWn{H(4Kt{IC*cBw{ z_bHcgWdP16=B%GPj1A;K8P|&ZQ0ql)F>jbOZ~C+S7UR$q&k(UO&X3&-3;4p6-Bn0` zE8*F1RNL?$eyfT8P5MrR0BMA2nm2Rv^&fkQe>yuFWMIlw>6a&7h2+von&fwvGv~eI zkqK!x7M`|veZMYh;K1#cyrOzk$hv2ut=w+L8!U6ooON>b+_84j@Yb_UtiRC=dTFYU zGHt~k&;YGMQ)#!SfP{V{@7wwz*ni5IcaTQLJlNbu-;PEzt0hsBa8reM-H3_+^4TcX zg>SE})*3?zVCJQ=+&_6Y(;MNbNJR-sj>JjVryjVs8~9I;!jE z^X4~}h#Lx~Tqp-~+5Bvm%jGTTO^8DrD*<(|3XeWG=KemzOAi|75*_@3N+ z%?g?1tZe5uAZSzEM;mV}ep4K+e@iu|;8mz;@-8`!9s98$Qyuz2RL0Zz8kR zq4yY(_6D&mxZQ}JNvM%X>}F*rqmI-`>ElQNEao+0<*(vdGtKn*BGWh16w_dWH%Kfs z1iNRx-)8TdxYx0$7<6l8k-<1C>xbu}QUFw2VfE+}%o^)~dULPw2Eudm1KE5=l}~<3 z7-ZzVjxq9e<9lg?75mtYG(fnoPi9X2UV|6K;SwI6d*!IqN7jZ3&tL*)44v2fnt{^F zXZSJ-YI5b9LdJ8Rj{SWx9d#gx?H>3516~e!7Z5oED9B?HZOHcOA!7mvJhDYlAT3af z5+S`$?I3IQC`q1*|I(tRCBY$4I*Y=muumlCQU-=ghdl zulVNFdph?{cP(l^|5G}X$;qkwDQ&)3XXf{#EB9xEjMQDO^O9YQVx{}DsCu4PDWCX7 zN~LiGyg36E{}~Z&337qhvQLYO%MG}1$u6Tt?$#vV0rT%QTrcoTXJMALb`4ID>aSG% z$oYQHm(JoRs~^_c%HJZ{+k?ElI20%WK7XMpDu*gCB`=vMeXY>exhx?hDRKB}{y6h} z)mLX`FIWg2pE_>=^%dSHyer#rcM?0_YLZoKt#{WKOjVyl-nva84zChRRLXeIhX+ z5#TVLlJ<}FbzWoVt=UHJf`)>Wq@EtNEi|$(nM=#i+&o-M79a2!_MPHC-+qZzQwqL>3!AmrAw<%WTF#rpQ)lW>sP8Ddz;Uz)C{EiyNRNTsrS0mkF|U76)fY+bEmxnoxG#|3I}!$wu+_kjXyw0fZ;Y=Ui_AS~Uk$^|K5B?=x3 z4{-1nrXF_jlrm3ba2N1|R33R{tK<*N$m9{6>1HUZoV7GB?U+g@vH$9brE`Eb1``B$9&(Y*h(R~)U_j{eYIIlefk!UU zP^iF`Y=Basj)K~IaZ(z1?M zg683e9OwJ}^*;IUgxvUbp?6PiZ#CZC$9%dv2(GNIQqF9gx@DBMY_;`nFm#}pW2nuk z%faOJpCL(^`twS`is;l1UrTrY^xQ9UWrOBJ4q{~O5%72cr}3DYgDToolk3^k&1&n2 z??6y^zj&fFB=A@T?BGXVzfhs8mUNrz8Zu1jF4rbprrgyHkbbrg51Np2z_X;m$BF7o zQGTh7Yibo{Mix$9QR4%&1wWtWM#_zK~se!b^i^u18#!XH7UggSDzqfNBibQvUmvw9^-NvSWvy%2EA~62` zi#z*wiM-3-Z2-^A5&Zuh-UToP69XgVp1-n^trk z&Kuq`|Fx#od@_bUpThjNHABGBjSm~Dc2N3&d(D^4-nj$E3fXJUZ3x~VH4pVmcMl`5 zsq?fn`S#DGnu>}-r_eJi-_{w`N+S{UrSOPHO$wIr-b2Ri%XJ)9FU|19f^v`PqT3iX z>L-e3Vkc*(e51|cIbx1Za?h7qrA?@Lw0S>+U?P&T%7u%Y!K76(+_#xHt`V4JJwcqr zQI$XZ|K5qDmWl6&UGVOuiTce$)LheR3#Z;uXNBA*Qd+CN0 z6X_M(0GKQ}RuE6+zKQc{f|$bfCo) zd3p;G3zlFXO;xTa$NXDTc@vDuGglgjlkz3V6v^Tw=v{9r0tcc2UqV5jGU@Y;1@FAMq;ON}l5@d4k-B;s?aJYlef=Tcz2$zNXq3*HP2{mK8_5>w zoA%2xuNCCu;hS~FCw~@hO~Al;pt8Ni4pO++`3lqm6#y;Q#;+x5(hkUjD^=iWdr}2xtjzpntu=Olvse^=ze2E!pNN)M4PjrO;sq;!= z^MqT?jME)u5u>z^9M>E(b$C;$$h4xBV^{~r;&{qsf2zime0+z{T6o>WuaT{qz#XHO z6OnM?t$v%J;6aWX17|1_=fG-D$8 zYVNyxaM7NtR||;wv6|^`wQ{wgAV-1~Gjh@*$O_U^)#;qIA0l0lVP{<*Es_aj{Ye4r zv4&FLn%>>fw&7s1E}kemX%63eE4J?Ye{uEJK~aAH`!GmKiAYNeNSAbnARSA0=hEG% zl#)s}NOz}{fOOZ=UD72b;qT!4`2i-2jJx62b+snO)c8L4?ZceZ$dQ_TUjD zQ;LG693I-0)-AUBB%Yq0A`Irm$tx&00n6=wclz$n{e#b5QSSyktD_HykMep5C0N6} znwq+P1ZheqvSX6qe&l1qB?8v{dZzu#CI5A=lO$azRYLdE@xW43D6@6K^VjsP{+ZM= zb8`zD6%R+p9|TJT8kh+W6yUf6lw{Z5)_#4GfQ0Zt;HnItgYJ)AEty&;iG_ijSFTl_ zS{ReUr`X(+BmY=iD;gS?H>!8*C8IYx0XI>+doL0O%&f!Eq92;^-bL*|3H!0?I?Z8d z@G2y+xr(-n)^*z2x|S^}=NWB@aCR8C>14M{%WQA72TZaGDhGIf{vf{v@x|TQJ}Z5q zI96|YRX(;gO4Z994T^hz028iHJ6^SccbCmW!wA|$sNo1{N27e+*1`0 zGy5nBjCn~J87yy)sAZN_m4wKm2^ztl9URkA8d-=A8h_|DNss?j z$Hb~{ZejD0jrV3nX6+uT4=(`vn`RiS%AR&QHjYZnk7qrsvu)^5ZZUG?fZ4cJiI>5q zcE~?fzRIGC#aL??l%JoE9;aP|~y@uG~u}ydBBZwWNFU8h;y!F@2>` zTqZHO7=2~axIJt=hGehAEn|thL97x+6)*nMv#M#(awf4T?ipUgZ(rwJ>j99Vo1C1~ zGW9%Nr;!cr!i(bTMS+PA>qG|JhPLOblw`C z$>4M$z3w?O()VhK@Ljx+))JdKe*XGt{8=i2E}l4u>zb;0M*|I>UGHM{tPIq z5wt(ofp2tropbT^QtE#A-Lk7vQ?QId5gcAnt=`*P^7l$xLKt$K6p54pFR1Y9Ah7Mad1>7j5eA zd;NQ=_n0kSHhEztfnCZp;zgO=gFIQLcwhFfeWNi2X}%VVfyEtxXnlb*m-k`^I^k$f zFe;ahsut!&T>gRt)>e+tvW1I#?8S{6*^>9qoaSgx-+lJfn$%ol@89zP^N&QpQig{W zKyo+0Ho=`RWN38M1tiNwVkb7dl&<^EJq0u5B8Cgrl{Qsxn@;Pen>yYWU*aUQo7YUNHe`Ji)5)>;u@Y<|p z#l2|flloONyLh{ZQ;_nS6(-}i-S;}0JAsai(}t_w{Yo)H!ji}g8|G+koN+?9kTw~! z8{yupfF1I>;!Y78B)S4$kB%&g)1x+V@C1@v2fXR4rzKA##-DXXKtj&BV6!hHrSB6s zK~3~Jz(RE7@#Mlzw>93Sl8!WXX>i+q@Da=y4DLR=+jEJDc`@&rHJ3cUb~@ZE*mC{_ z#e?kRY(Q@Qf?F!-g${W20x{@tPY?1lGC^K$xn?y6r>y}z`{fp|?b}x%Q{~?BXmS#yh+@l-o?Zrq+p=tlEluBJAmAoGM*xD`8)PE#QdX;OT_D2 znjcznG081(6H(`t0i-ug8fX&s`nvp8j(d!$RrqC?);IymJPtZgox{syQ%za1G7WQo zd;B6?>y-DaMoxntGB5i!;Jg;`O&aRDo9H(kkwbOeWba7=u(6AGEVaC^MnkWQ;smF;on2(; zGjg)q^c=817klan2?@&*$6%8qd47R{0+61%1nOZBTDDIzhRJ1AKF@>vSW2B4ty`gs z+I1I@&RZ_ET3GlA(sy6Yh~nRbUFETvIoXFW$%Wh6`WUd&T`eJNesXYZL{83u(3f)2 zO7U0vTq1O=){nyDT0y#ayUP;vqCOfg>D!yOB&Vfoj*r($(s{Tyn$ zuH5n!dz!){>et&{mDgps_95>qFz$aBW?qF#J^reW7SrJ51|2<%E${)Kyb6^zjIkUgc0Hqsu!e8kD_+>?b}Cgx6m&>L~LO@dg=U&QahB*?6t>cKq%Re-RLNaIANLFL|3y$onZ~ z&{!qLJj91l_pVE+M4qSQZh2U;O((;+#enh)PM+}aXB*m45`(04Dj7(`h+>pJIt10` z0=dp+>teqxgjdnC<*c&_&5t5GKMn^k$V^5Yx3_@7+lM5N!pPr(n7tAY2M4+$m|(CK z5JgHaN>8IDP+d-;_@=gs?#7s8W}}azt5u!AMRl0LkZJg=!k(GUpkmXcfnZ25!$Y#p zFmJwsqmHY4`6pRfKfX__&q4HI&a~qXCRL)c&-mbp_YbbRB;4@XU=q=%ogxpLj_W;l zdfv-kQc{8__Tyq7CDuO(n=@4bC~5!IN^y^72Or(8Dm%gpYz<(4}YL2^+>^Ig=ZMSN(wv<0iS z(@Q(1mt`ygHw!3t7Y)%({L`D!!p#H2H&1Qyu=A+*Uhvbx2$>Qraz>U7N>1EFK2xA3 zrKR!K2t94Q_H3&^73(fzoM7m$wQy*cs4)<65ilmqiaT$%T%}XV=ep^R^lH<~aALoD`i$*S^0sP+?zRP01ypN$ z(!VT`K_~6&cW3@+vDeakE`F}UMa9ysr{9W3{_yj8^iCk?u{uAPdjlkHZ@L5}L54m# zC1rhkIQ8!Lq*AXgj<;Y2diQ_v!LHN8h)!l&kyTl@mIQW)+Q829MrIWf(gCA8Y-~aV zpTioTHU6(mX71i${uOe>??(P~&!Z1}x;>d&^RTlIJ)CHaaqVZ%fdgbaEXP@kO~?8d_}B=|C}QSK|x`nh#h|MT~w6(c7% z6Bt0cc)#g}DcQX5-?&kJ>ee?jf}z^1>bkGbKa6!Kl{%sos#qh@zQ|fGG$}ACeYi2P z!N=Na5N$b{0b&iXDg2d8s86Svz&FM*8ETOFC2$=o?>4o1se&a@vwo~|$T^LYxM4(;Z>U;3;M zH=vTthWXU>qyxj*Tk!Y=l=;v-wKtkvwPJ=oF%%Y#AaVrSZurx&$~5+cE~hqbexLrU zk?Gk4otM;=!!60E4xn^TFvOoVy$zFx>fG9WeB-^<##~xwrY+S@o?em;p*OQO#)^AJk;Zz#n9IceqPqYzLU@FA?_mE>%Us)b4JxzCG`cw=A!hc~oDIS}! zctB~L$N1Gm@>ECXMyhxI{M0zY*ux|7T{IbJy)-1D=jYq&P0!y+wcbAUG#C!eV**vK z=$&+`pckzXbp>Z3E^b?hAJ9g&Hd4)r7JP0Um~(Cpv|e9ks-kK@ASLQ>;X}dI4dxz> zgqE*dP8^CNK|9XYLht@@?z7`C`Ij2?m(lv%-lqHv?oiX&#pAQYzh@`!4X+M^W%lAH z-Wlhua)iM{#~r>@F$M7^8bKrS7NRSAco)*2Jw?}eImCw&gWUB>Ji^mV_ZFrfz*J7w zxz=tGV{vD19)8hUvp}m){klibsSm4LuVfJBA8mNwc&5^m)_YEmolhCt94mj+mW&A@ z>8YjF`CVdv8O0Hn7f&;Ax{J)8+hx;4IG=JQn$tbnhQrM=dZZx%+Faa^nYmt2H>y6~j^zNC3kCyl>8 z_!-t38ewojIuhj>uZZR%@j5S1&90hcY=SsDW<&^sM-S>+(7eYNA-l3cxSG(rHC4OD zE8kdhjfQ1!a>c=yy^Fu<$z1@fNQ`r@iB#$8=yGnC|B}9(ovV9%_8X?k5s&wzfemG! zw{~X1Y8TOh)GA}ice}dy9b2c-me>a$wG*;ho;o4Pnx(gS1uq(7ojd=m^E=Ta8<}{l zN1{2>ZUrTVv&sy-9;F~gT?oFmLj>pqw0(U1Dffn4Kn1s|x>_9UqOb4Wk7^23Ej_*5 z$=#E)t--4)iRhil9z#hG@b+$S)F?F{A>qoAeBvWdkwOmKaC9PdNsc(~Gg!q-zJ{P# zyxzN;8+B+)^>2B_Vdr^b5^AaYP6*SG>y_B*TLT)Tc*qY+O+EG&)52{>Wz1U~==c${>KF@@&vpLwz~Ik4&AYt<+2jRpWi&q7bz>fW za~afj0Te4}xS9pM*Z(|z$~VX#PjqMeD$jxQ!6&e^S0~OWXf8S`_Yqo9Y;83Dj)a#5 z;pFJBBvozZ^rGTMz&qIHx} zk~xdviWWU{>-gXDORd!21~Sv&Jd(s@!&J+gT@HxPhg%6y>mM1xiY6D?K3Zyich}ha zU)f>B?`jEYQOQd%L*@TqSz71l6)shjxly2#L9~rzt47|;p`PbA_VFd;bmP>TPpc7R zD?8JDQt15K@qEF)K2&p7`7vlyC|37p^+eC-&bkCoQWHAOJ4QI6zEy% zj&0^{E3u~iC`!M)ZodApDUE&SR8NXJ#zrrXSaY=2uguWY-!Fq{h;5=VlnsSh_PgDs z-O;gwk*`CV&F<<0@-i&&NmM5qTh~gw23<~J9Tf4;Z;p3)hHE_=FM~1V=;_m~Z<+eA zwDKc#icl%pIx+0jHy!8RLf0ej8k!?n_{Va^Wc8ww7n6PW-KYc|q*C%r%gV-WxwZB5 z1S>)LeQF99bfmU`tc}pc$vU6M#}A;L>3^^Urc>P_y=0yK4tc$deS1g)3B(Bkd>!FC zC53xP4~*6L-_G|o_n5Rljs)Sr03g1Y_fvzR|<~wLp-LWS>%Y=c!hWE=KZ4 zfnFwy+H@KxlXdu{2I|5z8qsdDAN`E-?Kf6gdL_ITgpNx=Y5KzHVvs}8b~lzZL4TRa z^kJFo7lztdV+mwIqDKGlpo>Ds^;CJxd{w;5`1^enbGIG7l zTW5gD%%x)!;YxM<3vPW6#_-Yt!BLW_La5EXvM+b|P4lqWhh|U04;%xZ7j;@y@ICpM zYZ~i4&%!F^h3RXq&o&QH)-R2}>JkNy6&yQ2WW%!K@#S3FKXVrRjY{qxI-D$7cZm0I zAFZ(*wc;e^OhvKl8Q9_gVb;OH0k-70&)&D*^WC+7^{=L%TIkjZCXvHP`!nH;M+R@P zCH*4m($uTfArrP!V}CxDVR2|u^bM@a3$Hy%)CNg1W;tt7lGlQMZ5oR$L^)4KY*U?e zod2RCTBo#a`S}^?aYwH#b_vVX+&TDtchQGRRFJcC3A^Vnp;3ZjVx=Cf+$8!94qx9q zt&PN@6TUzmLq2~9?-s>01*?Ald*|JQ>}I4|F3|O%gK+e{@S}%O5hdb>n4q)6`F1_R zMCNUf22Orj^M%dl-p#e3VS}UEDSY?gv@HnS%cGBI{F5S*X!4g(}%ThT#u$FgzO^R#7988JtV?vvN z{c(s;!_dC6md#`P9$EHzhf>Usrajvs0%%EjpL~S#L^4kEbQCk^69Nf zUL?p7nm%3rpzyiQ-p2PnEfDIEI!NLIeAGE5Ta8fH&?QFlz%R{PHSc&;OH=4KZGD5h zB`eiqnDr445j1*y)?w^`bEPk(+l501>hA6iN@XG@>Ntq-ppn+r)^^N>lzH*s)N`36 z0O|j-Vd#axfD}9raeh8=z+~~iUH~pR)phD`I((^LnDVk9EP>bsI6I0835}L+FeXJg zLPWiEk!Cp5k?h=Q8{<++j6uTmR)jm*H?gdVtjWC<=fk75`Pvm< zX`bet^=FDGyvYy>=xD#$nz5WO!T!jG3d&=abqm5S2j5HWFjY|2u_!1?#qFLrbuz`w zTs-V3#gPys9{&sX02Y@WdMnfgD5K_{&`x&Fg ztlfW2dz%?cL9->n!^bjd%k#K5D=#gb9b(v?wg&ej{TE|{YJ>{Qv*Xkt>?s?ra>MqK zh86#Pp;Dm?^#3a=ef|nM717Y?+y;gW(Y3b`kKP<>%IPu_IVOM6FZQ$Lhc`E=AMLR3&DmpQc;kAa$p|n} z(@#_iH3n9BPqgqDy(5{Lh_a;`r2< z2~Ja}<=zG zH5};7T5!F!WVKRbPHc2Box49no|A&<1dWeD#VlWzI%zKq&z*l>@LGU@5;w82=jCFg zKZ(=vsp^k8Zta|}vIf!zX!Ocr@72)g5orm=QP>&Z$KdYNXn}nIF$ovvf`YwZTgQ61 zB=KPn{INYF(_s}iI(MX|+6;gkIOev-E(IGm;oOa!Z?#!}+t~Q40`QSP0Pm38pi%&2fTD@MP zs$pl$>5}M;k6e_I#;Hku8?3ps%r#Y{PGoT*SVL6&KsS%y`P4}phut6R!}9sstDu*g zY&xnXYKqB`ha;H=6{C|omZLZ^kcmR|r;6I1<2vXtiV4*D)K9r63_oDBS?rhuTs{(_ zMS6TSqPAsuGtr(W*YrJBoe&}@)0tqm@w;`6Pl5L_&U9($lwTprjG3*X`HxL8g0II9 zIGY|e`5VX=w=V-17JYqVlOu^3?qyXrUu0<>pRVtrlP$Z8Urp{S&AnWa2p=^5aK-)W z!duYi62o-p!&NYLL}X-DZSC(2@9k4x{{K1az>mfd)Sgt#2tK|SYN$H|%~eg3zCGeD z;-~|8IC7cE7OkK2|pNrgS-1E5F5aHaL| zu81|OGHk4AmMqOKERzf0lylg{x2YC}Q$YVRRTngnL2%0I7&rN@tMH);EI~4H5L7H}&bHhGK^59 znRI}z=d!o)&mDsY+49=u{eoVAbNXqkQykGlg<{v#=Y`Jjg&oQ;Dlk|jjWx}VBd%OA zqYVbNl!VSbg)#q^`UIKSt}Bs;pXUTn3Cf+IMR`iXIYc`Mo{qXZP-;2LZ#PHbKcPIsc*MRyVIivzW1){^blEe;gP+(*lCcU z2+E#30+qM>o?DWi_F1@~o@{3AOyPTi0^(DL)b-MvlT z&~)$|&x1Sy=%X7SI2V-AZ`|+rwDftLpCJEy4mZ%&78?C|#n`aBZxkNUj6Y}PFe}c; z+CI#?&ik?I1Mq+gnXJs`n@BHvp_cA+6pzM-YkrV6MdXJ=*VHVBL>9OG+T*zmq5=kB0;A7lj!v}RmveDis+>g$LM%57pBI2lGDYVi>X^n4AJVs^+#PJ{6VX`pT z%d593XzAdQ=2=qckK;w1%07bd5eum5i%FUag|!% zvq?0D&>a22PSkz_KI_esA81?EuWOhZo@C9!o(?xnamK7MosF88ebZy9s^tyHH?=MU zUo`ypYJVlGj+QQ-9hRlG`p8aP{CrIZw;som-o)~J^hJU!OKOAO_TJ*}rmzDqVX{t9 z_BVV|$IB8E^3A+&kns?kG@DHw{kz6=au$xyR|4)|Za>WY6{SZFYeb6rSw3>e#bMW1 z+pJjXU|&<$jPhiHSBgR1j1ism1+D&TTl8R-8Fn!wj!5kM$|U=ei18MWpeatMJ>QRf~v(<2Q{X9Y}t9mR0{D%5%^K5^e2ZC;{?C9+7e))+; zCJ(YU5YO0)p99Y4^~UkXe`WYrL0LL1E`ClK$K(~*2?Nr3ebpF3CdR9r^lOO4Bv6o$ zi~f7%@DPo|ouzQCe*(i_Af46V?N~IM>!=T+QBW<6v#t|pS)4WTE&TvNqrv;Y ze}nFqVlHU7VB}}|f+;8uyX=CJb)`##x?Xdyp%?caMp6B)vT= zZzo4oR;CG;19Yf2%}}9As9}GheHt-Tj2*g;FKS72<^O#&GnA%$Xq3w3gMcE=9~Joo z>ug@Cs28uDccPgTz(7I_?OP{t?4Xfi3F%zUPle&~w_23r#z?yM@6{yBHC3=Llu2+A zw0bCV1yf4WE1-4mBbiMVtzU3VIb}#iZn~;XjC8>TJI-yc3SUQMeg2` zNJ=>A4}5)6o=tf0(tUT@$vx&;pCw)^Ez{J;fjl){D>1p-H+mR5CK?_AnO7@)Xgnh$`Dkv336a3fGLQ|lJ)>O|s zIGOme_7*<~)IlPuLfiW0#i(fTUsn>DdVQ}R`142VE6tuQ8k0C$gc}k)(e((vf2~A^ zCKAhjbzdz$m=a1J8MEGFdIp#GWQQ^hT{qCy87`Hex0Z@R!KBnlatGPU^vjKVV0Lt1 z>E4Hm_mD7uk!^>+w<5|cpdYF*9rwrO%b@&oENkoToK`Dy*-C3?FRecs?I z8K1dc&&ev6G+tIs1o`p(&yC(_B8(O=g#=4C)JZi7>7a0rtn(sO`)c@F7S)(?m-5do zDw9UAnK33af_w^9E^VJBJ8!#htsCur{dyp#+pEiXI2e+IgyUopjZ=*;Z6 zEcZpDEd|a1*S)|~VO-n2N4j0m+vIP){7n9FPG%?Yt+r&{F^Vy33^0oK_xA|ei{hxD zPN`Y0_t;f-TonpzSNNnl0$+8I;8iDIaPGV1)Al5hKslCeAq>GyC+03t z92HcJzoUOo+iM6sRN{$0y)Wv2`mpi$_v`Mq9Nur_kMkA$OJrs4p&A8pxRTV?>u7xI zZH`CvmrFYw2^5|k8?Ti>nqtbvZQCMWJ1N=1q@{oAn%9_K6b_6mG^0d&*8fRkl0ogn zPB#zAL&r}mlVs>#?-UHUKCigG?7fx7@JLKdPA0jcnxo0V4PhD{KD)l*KlG1)5s6`E zxrM}ic%klM>`4JbgQNKhF|PV;s`;z%lP02giV4N1ue0$8@pJ28(!`ifFOz#Hkg^wz z_V(N?^7E522rWys3$!aUlk+k^8s2tJBC+aj0}P&nP-|%BSrm za^S?iS)Cj)2oJbB^az%W?PIlH4;nhwbV}2_9(&!=Ib-PCGc<+R{^!CWnXKgW;t)E; zV96Nq*gpdfeuFxU%Am#5>1Y1ie^Vb9-syneAj5m-)Hm%v3@aEXOUY9{RMXZvIO3nk zVQ$cXS#Td8Qmy4&3rE&tbq#ZH0w>G8Yba=`|8rn&zTRjtax!Atv zT|y6&f6pv~#6*j5A!rhvY@%eZmeDBtsv}@WSmLPp+uL)C%aTxqVobxuwlxl=NSaB| z6JeH2JIpb``D&Qs%0JLg%s_uTJW9x7Xayn|OOfqVO_}Yg#5oksg1K6bc1)k}aFazzR9i_jkS2x2~A~+Y{ z?;b39w39O4MqY>cu%J9*bvJ+iE9Ad-U9bMgtaFqE;%FyO=JMh+2ahqoT|*M8MdIj! zFA{6PtAeJ7`X^A8(ulsw;l`2kGkKy*nlqoaDstZ|@(M#@z-tj%mXyeo=w3+S%{uQ| z>dO5mHTZOc=>E@6w7orxw%B%IgbFBCshFlb3OL!k7M2c~C`uZ$i}O?pCbjIpa|p+6 zp3`;LOsj)HA&)IrqeR7Fiat@cw9Mhe*{=&zK3-PK^lQgyl`G_+t@=knux!)M$D=-r z_j)+xSz((lJexj*%5%Q-HyU^Z>X{hGUE6oGb@q{9^r!M6VA07;y9Z=$fyMT2HE0p( zTQ|_t+XN$8|LJ<@KV9z)jEN~arER}E!}{xd%nqhVD-$Z!sN^P1g{+>bdd@`2_r4CW zY>c8*!1*Xz)mZzJpuwS%`IM-*uUfmb0diA~W2~H_jqpZ;+I&hZRR)LqBRxK-u zgj@m%9;S7vV+Z=Vf&y+)+EGyB;=I++1w+?!xDuObV)*_QF}|l&6^}V5zE3t2iD_>x~EZ`t7Gy8nFIKOQ<-&fX>vRW1ByvrF1OT6uo>~B*=VLXtn_XPqy1k9Qo=aaK2^|iIA_;~3csrXr zSNMh-wz}6z0w&<@E-D_rGRaiJj3UG=lV2<&Txk!+?>SQZz`AnU@O56{4)nr>huzzu%Yf7riSqGDy^@55kwo@wZ=w~glfuZ}28^EkjMPY7y2olR^K;kv=pRE7&%lvktlVNx zF@Z6lv|VvH9-*v>J#xP zEP2pkX5PFe1QKITFN=ieRW;P%#23ltesYc3AV3lK88ix7P56f{XznDXr-7c{XzpK4 zU{JhBlTojoL#f8VykOe6V#(aHqWkFK@91*tyI!vu53;|4ql=cD-v_^I!MYpz+;JkF z!i!5#JPn>y7~E2hQMR(4pV*E&sCQ#+-uVp%?UqzW?A;p(w0PsHn}6pjOvJ%i_rvRm z>&D>xi2R&B8)ZJ1V5Z$LZZ75Gx9yd2FOgDZ)*qEF?QJ1-tQl=B_-4X4-s)i7QuzEn zZ_~^)%RDF{N+e#-um< zZc~O{l9Q*RaB&Lt_W&Hz)6}Yo6I-Gb{{=OeLDbUs4yBL$lgQs!tuk7xQ`_H(y-?h+$BbvhlLzD-VHuAI-weCFp! zd@;6`?5NzBs^wJ>9fRm74=0h1Mw?2p!##sCi32%5_I#^_UM26V#aIo$DI?Mdd=* z;>9_w=UCQ;K4Qq6^T}~6osBrk$QINLn7M?DEkOobevdO|*e0^D)^W?dDbq4t@B4kT zd46k-Z-*pdoGe^JQpt>L-;-Ba>PlX&YhP@D){4K7t>ccm>YRv$=!$o8J2k#oDAc+z ztxTXE1miBJAVjs&b%{;c+c(DxA0R**AYdBKoA}PlmGjdVBH61vuC3SqN`gb(`+%kG zOKzT~i{dPCZ>9BS5l+1`jd_PQt zOUMOCF)xK$C&?X)H@OmQ7jNGV)UhPGB$CbKThrlV6$SV-yVo|*<3D93i<5)Cgj3ET z-X@+BhLxWlZp1LUJ@Y7WYWsS5sjiifcY5mN=I+jb-Kb{3jv+B_rAA6hN=!y}=_sD% z4XAA4G{C3u?S|kP?^`!##*C`x;-b@~ql+D8OdqzUOr7*)C{v>?@$G7wd;_YW^^ ze)B)_L_OUQedJwQ+e9GUMlz7hc2E^#+69D5W@Da(Y6!pyzv13NgN> z(6yESx_VN6k@A=t9ig&5CsnW0)WmF7xgGPs_SwKD0eO3oyoO7E9DX&QwuVamMqeE% z-;v3Jw!2Dx{8yDBxe)r-gkOoG7*}})qm#S!7PKz0F#7fWJb1{l{vwp4JcXRt_I;t( z)bSQ8tS#}mLBs1BgEZ^PMRx!-4{#@x@@i;IIBNL)F-67SY2d4!fUKoUN<;YB?HwAD zd>v;UGpVmN%W#$)t6Be-!&$j#{Y;YP#>O3=-7K9M?T3+w3Dbt(;t88?Fp=*4yZ5tg z>^_w=QI>~%Poi3ra}Yp=%hKqcV82K|RLvs%GJ0u!`^y~(y@QdgII4Sxb=OrVHa2!1 z`17#+j~!Y3{QQslI#+)<9wd74$XTQJBGZB0HB$0b^*-rbeOdNl9|OKR)BF}ipBv2r zaGXbwM)SCtu%vty|Bv;ASQWmVx(qxCA5CZU88^8HnEOFGj5L{01u7SA?{_|&sIxZM zD91d^wL)sm^e}n`F}GHb-IdVmot`>q$q@0E&EK7=?@3zro%{hYYA3W$mZLPZj;z{G z=&Y2B961w&4yot_L%usm#E7hFI_^q_bR%$l*l!R#DUa^Pe->U#@C;m;1zQhik;B{r zT#mlN72&1?t`7%9bLC}!@+}TY36)jlN*417ENg$ywzfp*EgSmHVf0LtK=OKzAV>Ob z^>HPG9zJI{mT{)*jAy54oZEryX zZ%wJ2t-?VIZN0?mGbqn+H<$c3Bhe50ytepo?{%<;C8vGLHSGAQZb^Vk){Y3=@g_MkpN8RFo)UEPxW5TmrU-0OZBzjsmTudA$1}p9R70#cGt@|I^ zEzD0%XtkGTHd7~#GV)bZ5aoA%dw==cy`)IEjq(b~mU@!YEX5ybVDy1%Yu|POHZ&Ar zz<(3d)7y)O7FrjuB76w?^}BT~N`g0-+H|ROE6q~!_d3N6j}A5b^oRDx;ou6b#Tb8G zpsIJf=`%Ai(S4P+TBx^UEJsItVgrS~0$jTAk7isy{#p1UB47fG$pu4Wm^XLj`wZ#* zyF({QPlQ#=Fx~d7?3TaWK51FyjXJw&2?+^ty}Nb-0#skmz2rQ|Y-4A4;oUMbPZ&CeosCrcz{NBpTwAYNo-Q-S>NHvdNk87w^xOLwmDenFHOtPlkS#SI*U z4CLLr(Bc@uFy*Zb@CM!-_B_21ey~z^rTg-IuN6E9ooZL!x-- zcMek3rB_R6v%0sXsel@FcXwAE-s8XbH~;tkrVI7kfWDM41aSYgkf9Vx*Ve%Uwep6AMSWn!LjtW$2tauFEq zH~d}VRPQtxvY3Z|r2~KWdh*r(dI3CKTxv!#g!aeHM9nv>yx>HqjsJ32rkHD|q@_*0 z85PWV@mi6N1Z#ino5c5xC;?P(_kd_On^~c0i$trX58g-!jmPO(Qx9MIlA8wl1-dgv z?*gR|gb6=hn%ZpPGHejDOPLx+g&OD7iX*Ff92j^tQsTuQH2*fej$Kb8-88-WzJBCL zutdC&LbDu)`RUE={k)rZqRDR35HoDhRbO+?Rs-w^uv?7f=ePI86&0G?sTWrKSCgnBC^yB^Wl396)#p5-2y+g;nk7@xxOxGY#LY+S}Sr{rnm9 zE*3sM{P85zWe*R55aAVsBj|qK;05x}@3bCd;I)O9oL@vL;QkBjR#@+bK{PWDB0VA*t&paD>NP1DH!qS>2kPwrKVrrA#hr7N6Zrp5TV3|H zfz^Q%PPgL>cKP+yyEu8;!Lq}pW{>l1a8*PhzZhfT@_8%RyPoeoX1BI;!n!#EQdTh?xOU}#9N7>OepV*5RLDV4qcDU>;2yNqO;-lkxs_x0INbI`7AnLm zvu^Ue_(F1gc`MHScJP#X)H6#HckLtJNXhy%vOa6P_iraACU!ktmyD)GU;uX$!)4h} z|9=KirJ@&}I}Pl+83(`rT_Z9I%GTBG^uj_3n0}mid=ah!<2Err%Uf4|N1fg8wbb+} zQ3H+*F!Vn_FhH+N2@C7t8aIYS`Mx(Bk#h3Coye&TNWJ8?(J!hKVrT#M>RptTu`%Fs z(&Jh2t@(3%+e!vD-KeWpv91`K=@*b0t|6X6pIqHjHQ&M7hP>{bk025W78mOm?@d0I?=rowcO!)a=H&tJ!v*73F$M5SLeyVygrfbLRTGvF)n$m_A*xq^L*+^aGc;A1&@)c*1duawNwAP;ui6Oy!0oldad9qZW`p zY}CT?a>X^rYd1gPUMI5!_nX8G-hEE`$|mrI+^OmSyRQV$w=oJCJo)gRY4D$U#dgdo zzV;QaYiKAbDCpf+0n3^2jzK`d`n8?vaOp|BdclYvE=!H${b#q};_iGD$oF3Tg8d}m zixt-46U9Ui7C*ba2dX&V9?-tGzu!vs^kk~D^P{hDCLp$TTm1pwZBjLJ2UfuR_wPi- zAcDhSwHh66+~AhR9fKc}vW)G521}x=O9WK^nyeS|0x6}Vrprr?3v#$iSJtpx-DeSejtZS*?R>FkVUtbzrU4bdDbG=o`AA4C~+)L3#QZZY`L3{YT#zNoJh=T=G5UEtW$uS zmCb`Z9_&AHQYR!KiK9N8tLfd4c|TLG#bo2`3^BZ&pZN_qsu{p8TrN1w07_nCoisSO zQiK^dbHbjmL5was!|n4M*j*!J^^i9ztUDV#fI}0Izdo9m4?GGEw)v1Beoc@cm`2YZ z)ovYt18Z+@9iR#6>AJU^ZfXS(=q*4C-oMA+#VZy}Pfq6e9JeOM3jmY=H_2(9l208! z>icM!vU!fGb=D{vsC<%T$4)}Wuq-b)&b`v+pX^`E2BT~)ogs{ z>&t?JgPl!rXNzS~1a%Vf)EH=boea)*7|LEhMSKF}4T%1}PLvjz=R2zB-5X9^oScOv zC33)rsj8|1CR)Iy?rtR-=6?ufb}%!0TW<#iaF(_8_r&)g_k8PwEBi!o>&(&D z?JE_c6j{o2xd41A)2ThUCr6#y7h z`d;1MdB!BX8T?GPq89^qTiHHyfNTXf4b=_C@RXvm{bvp z&}C)wMdbjP26TuN0BB&InVFgSJx{W}fB!!44gY=F{uy$E-GV_hqNj~lpbs#~3Fc+D zeoW7r<(ljLgjd1>E^qJuGq#T+CrD<9M`sW@x}(a3ugXcR4se=}Pcz`z0-O;GFk-tg?hm0tl=k;fR#eM3a*QWhr?q@mIqv* z@c~9~48T08aU@Sg`~Q9w84>Y_h(cc4k16mhfvx%ltR9@LcKLq7v%r>#aM`?*g`M*< zEeVLBp&?dF#n$mTq(p!a19;*`pbzXZF**6n!2we!q#QvagrC*brrt{fAkIH#ttt7b zX8d(cXGOJ_<=?&;cW>prPxWX-ctoyfJOH`NJO(nJI7W8Ry84CrdDmZKl)yOp2$6xC zBarhvG-m7d{d*n3LO~n`QgtB2&K@rW$bM>KB3qi;d3v?gDT&j@5IC@IOs%+JpYW*}-sK02Pd!GHP# zPB?GU8bB9-f2~|y)!f|N!1~lxRVPczIZpo>Uf>380D8K+Yms{Qj_b{v8W}^GLw0>t zeN%md=qmbhd`H7kV$!UHM=Zynv-?>D(_SrR;#mtAZ<_|RvyZN+5{Wk|2XJqL2bjjU zRNowVO9AqztFJGvs#5X)8*iF0k#Ph*^b{-yi2Lz)V*72^H9y#Fd_PLr`9c)pG=0ot z#JKhq;3h2~`T+EV7#HT{b?-aD$%L;Y0@MO9O5tP7iWTa%5y@j?Wc2>=HFbmR767;d z53pd5@ewESG)OT{Eid~|?;wIm@zk@0BuYtM-U_teN?^^ty#N@f+r(*j-?wdEK<$Mm z^FJ|qj1KDUKy+}riJ8GzS0DQSk4{^7Jt*tx&wraQ@z6^QXKA_%OOrU6KkuKn2Kb$@|`yIv~7YD9Z3d-z*gTsT` z*vJA{xR$=vTpvv;AO+HQa4p4KVpqU*($dn_+AVOqxw`7H|Ke6q1!w-B0)mVkiwFTS zN$=PF?*MRgZ-FbFA4#@FyR$nmS+x`L0D~eapYvN_1c5W-cU*msjErmr&iB3M*7tG{ zv;#_P;D|W+__UYDNwGp_?vlWJ1Ka_O+VsrKKHy>2Tx^dh>vGfQi>jd-0{|}H+M5?o zneTcR15WuXM{>l(uIo*|P^GqP*m z-uD~d_{aDe_ug?8IL|qIuRYhCbFH(t(XVwGnVFfy5Q%!lrlD^>IW~5f-nkna%OOWG zUUHR`t;@H!*3R5!7N7iiMa|M4-`n*NGwuMutd6aYSO1Bru4_y+3Bvtbtv`$dw=`a_ z{tcCal?{#|&%8y&LJfj_-J@coK_Hupo15)13yY6*YL84$2diHQQ`^JQiS;Fs=Mw8m z+Z`(&KBaaQGEuZJY>d(Vv>$(>`2D`VeMwX=;ww;%LoTiNjXru8ul z)>5QAo3F27e|_`Fs|#I3`3D4C5nu>Q#{SlP>K~K|c9^BBrq^Mc_R+`&KCex8yKi~;FSz+%s6Wpggy95>iSg=h=_(AaHsXlTB%Ey ztd1GotSke%?}Ey)V0D zWyK`qSOeV+6c>M(A#~QPQ1o*ARad{kP>ewT^ZW&)7=Ee+$PTZdVB`)>tJ63e1*>RD zMi+cwzlg<+t+ZiM$eur67*!8*8F$d%n5`D3SMf)4%f*5lHQr~ME@_CTnDqayuKvnX zdd0{nsOVfa}NFn9FYjf|WF_#lrNWGBee%#q4_$7p(4W0whe3$H9k9 zOa`O&Rq{yTF$_9?1aQ-yCGM4!n&5p!8R$}VfkV6G_RGkKcq$3(iF@{dg(k*@jFT+< z!M?s2+I*Rd7oDkXZ=Z9R7%>46z>I(*1QG5IHcHjwXe9+6ss-6a9-GORq!^7)PU0Xm z-)lQbj(2p-WhgBF^XL8fO2t)YA0P02O5ek|m&bQ~r-I2ZrTNnylsFu%gAW5C1bdg4 z-?}=inU{D*h_StpUC%Swi906C=U@Hp+f&>U7Ld|jo;0C9oZHqBj&-Y|c+-zZH`BbI z)25qVj+33YO`}oYMFRU>g5#d}|F5py3i^rccC$VO_aA#|UqY)5md(j@Y?=ac*k1m= zaeez4ZVmYqdP|eeeCuc7PN$?`Y*G|FD~=5HHGLg7V>l1_h*y`X&CPG;97LDY@^RoH zI*c(Z4!()PxwRrTk4XIXNO^*}c_4&Bb}g(c;?-zfJS$paa?BCa3L?xvSA9Wij$cVu`tp zUp~yF`oZKRQ*q+E6%n_W;_y{TyQgI6whd3NXlV_O3q&k~Q|n(EcgtvUe7u{O9^xTO zrbohnDsJ?6rs{lSMsw4p?EF=rAmxoAXZ)RU{v!~+Pn@3l1?7@Fmzrg$_ zBMwub_q#O;$oJQ}w!o1)+hh9|795sVRER>h;E=0z(sDrk$|lhGo~|x9k-vbvLVjkW)6NdQ1EG1jT}REnG0U_qT~Qmdh?qm7v-m_=?F@M%+VPWCFBhih_hT!E(x&+v-_5VLu1Gh ze($pJBBik+Q@ZrWY}7k9XN}U$Zoa&;oc9@tSY5+2GWO8zKo1Tmwr-{*%GyD4+ z(&e!>6=1B{2*E`tyOF3uw{c_1;H1IqL_b^HaoV$xYBVfiYY=zUf80`L`H%9dU zJFjavOnTLI15<|cP#w37`1$#JT} zy=&L-tuqv5Evy(y*}*Mq;ktmmP1`Y0605g4i^17PB7Z^nW!{Mk;gw{Zu7B`36YMn` z@!%6tK0Lz0v4(uTgD>Rtg?`Nl%DQt`*s z74F5uzy!mVxHbX@DKQ(ty_`C0a_3k7Spd^VUdwXaNlk$7!Pv#$4~=Mn|XJG+9xDcl)12$0i+kePnSYmMxNlG zxHzFl`d1`i_ex8r+B#75s525AOak3IT^TB08P&P(U%CGDuGUVvxAY{+gs#-({;sO}Gt6AG z=C2aQ3)9swv_7{a5L$rB!jd0a!wgi;&(B9@%6l&N4EYCEgzMguW5sOoRsta5Wm?uoAegKGDw=MwQy^ZQo)2if1ZTNic z9irL)dx{YT8rHVnQq2qYHbLR8t_YCX^IPMHQ`&--v9s0^azeYP6R-MLG@NoFXNFjP zwa_U2{{6z1U|l+uzx5Cz{2fH4g>l_1nG>cTAvHyU;)xpxq5yxR%J;ag&>PeFDTb!! z7R;_?o9iW<>I$TN5v2dGxB96!$&NY!d?e(YqVTffo(I+y08#mNK+~X-nwmfG%&V+Z z*pFN+h_>*hp8trT$jTU}KQ_YKom|K{fkU+Y{dL!{XKhEvoj>0;;|a@&F&l9T$GYv{ zR40uZH~e&_3D3cuXf3$2 z0s;|Ot{2@=Iv)GVpYv)5CmxvfQe*)TH(P&)<-Sca(ELc8H-LIu<2L5@E0s+%#uri& zB$n0^c1&?U_aIYMqp{BQ+=05kG+wdK0*CsYYDXxBAKYdb3=|mV z6m=#Ng@^uM3e$YzuQWZb`y=L-QEs=Ci5vp7uo48LS)ZX$mfKeW6}a)s#SmO^ahy;B z1ZS|Wde4$UI(OjJON4~J{=0rPG4>L<1FwF<$l*D8QmrvriY)NAHlBBHr>3M7AA2#< z{3hyv-vj8h`G<2YrpJ7#TIS zJv97IQ8*{>`DEi{4z+hP#n1`w8%w%3j>lPcyPg~vvf8aK#pzvHo2Wbf?H@Oi1|Xe& z2~ReJoE*&Zz&cY8CkAqv=wcS3%$)(2QNh8VdS6kb=PO0$Jv8lx#Vjl>dj~QH71`-W zZQdJ<5J%EW(pvayuiW8nJX~BKSeqw6Hw+CG_HBxo$!Ga6yo9JUr2KECZE7mxo}^pG z=yvFnm#3d_6R>{_s0*#vgWdOMzMU6&_u~ipEfJb|y;qltd9Z6iNlLt-Z2|YBXb8nc zrfd(UEHCV0s2mIzm_vsS$DTsjIH;`GOG&dF$M9WV8e?&^3t<&PbJ!QO-#c{*OA)9g zvz?5wzcE&BTyGS7$%0_Mp+K-;uz70kg2jBk=-dN45vHa5wi_w-f8}E&-d7jS)f)Z^ z>83Q-5#OHgcXws@K?xi;$0&W@9Uyw1(fS;GdIAR0^HtK_aBIT}&6arpZVQnO9ju_F zl-insxIsAumWCD2-v6FQd-3i~ID$|B?Y~l*2C4o{b2`5r7w2)c(IqlqxDRET3(P3d z-aGX+YWV zn87S!;i^3?2ALl9OcZ>pDk~FPr-R@`7hDI;gPF^Cd8+P(h075Q@7D%t?(Z9eHPQFs z%Pky8n`c8{-!KY!1m;k5a`F|F)HU4_Zz2^!7z&S9$=h`J>SEIVEj?gX{7dzhDlT>f z7T{q>@K<)3mL+{ZT<-o-`-J;@*AE*CxVehPt&UN8iD*uUToPTj+SUfM@e4iiC~JpK zOx(4{X@*txjT3xJL`Ll;6yH(>FD^cwiZ%#gzrJMi-zDybfgQ_uNhvQOvL?4b06DF; zwiYBaHM`#^V=!m73fX~}dX%B3paTB>@|Kp9OBDdk3zIn4IY;8;m@FBiZg z#ZUy1emPu8*pWv{{?&!|QOk{~raR6WKW{iyN)D1Td=A!$0v23&beP!)UoN#CNbel$ z3UPzY_ICsfuGgn<`+kpdf@gbV%d=a?#y>)e;)0II$Jrh!)e&1Oleshw*Z;!-t;e5c zms3lssysy|)62T6BIOAy2(WC7oW#kTM37TVe*^mY{534BBR^?eK{;=EganaKQnDwm zeoRfJwn^w0rsj-u%vWp8dqEx$VvQn-694Zz9#m~IMv}0_)j3mpMpW0N)qeUfI1cYU zR{xM^46SlAo&DNnX)u0~D&HKB?%rl1N~a!PPmAce9S!&#AN z9rE`yzFo~|bqZ(QF-n66IH_XP&C(m9yqLrEaK>wF?NHpgPiJIW43%BWUNKJ_1{H3l zsX0srjZR5b`i$-D49VBxAu~0FB4H;7((*~?5a3dBwN%`8)AI*jMXgO!3s>DPb-vxt z`O3h|w9T#!yvBd&9-q3N@Y>nb_%hYlerdbbt;n|{OCwdqy2K%sG&J>1m7Kp$i}U^% z9gw}sMiP;s!0rZWVTzGG&MjSnW+y4E?&k%qe$;8Zm}$!20{Wg}3k@Q>j?tnM##;FD zQWZ;Nwzf>)$_jg>LHbY(bCNf>^UxxuPl*xcW*7lW5N;@HODmVr#1}@wk?t)z6jY^@ zJ97m~115IR;&c#It!YLv{yfQY^sO13Bx@611@$}5+}D&tiom4i%4pS00|jF%v|#9k!2<8erL8nwO7}nLwAW+zP%2cK>#(&Tv&e$MxOdbIQ3blDn|ildTaB)xiT z#qu=1r7`A0;z2*x-)cm8?`^(nl0ZJyeTk5;P7HO0bAyfA^6RPxbPRLZ|TY3H$%5|D|4~m1-|~GvHAp0Z0E* z#vs&A`LDr`NcKvk6fg7>Ru(kd&Mw8nBsZjz@}&C-ZfN-Ksa9x646+&Ere+tBI_3ZMNy|dMblyWCh3nt*TM4T%j+^N z<3TS;9UkQlloH|#ztC?l65m!Np2fI4kAs2CsXI`fU{H;{yVp=HPz?%qTH6|>U zQ-19wJnwgP>jKWsjy-DMeR0Oyae9Y@b8J6OoK6VK5vSyJ{4H)pPw0nNcAF`uHK?|v zvONs6U$g`bKfuO%BLZ zwuEQzt{?u1$d`mhu%U(NphXqf!)z1!7ug9XvM#hdF6affaz7KEL)2$|*WRDr4A6KJuWN3z%Gz0oED>P5AEj zW+086upW62n*gFyQRApa{fRAww-q0@<>@RrI2z-8CAp4AH)eViz5gpBQ5(Nl!;;En_ ziF13mXTG?Yn(Ge2z7a=i`*ZWlTvvIWgHynJKR;R@9hWH-!)d?h7Z!=So2%;voc2u& zEU-M3&3*wfvW}Q9|7+r+)%BOh*u;d5P?3ShB^IK>Jk{!t&X1PrJ*RqVS@YX zQ>9(ox?lujvfli7BN+1R*;)u6ZzX>9BgZ_M;kokXPM7+h;D1@tK8EwkqvvMXcoY8i zEiIqp1sd?`nc<1TiPu+i|^;1lz8zMcrZoT-ANkZ@jV^-NQF ztN)BnXED-IWb!XnR-rQ@*>Ta~W}*tQcF~ep0ml><3WMZqJ(b(5a&4I*TIo^HAQfnI z?v8wNx1AigvQz+|q3CZ~`Y8JmkDw}8`jFcls<+^v}QYHJ7I-KxZm#FK8t}S$@w2j|FXrfX> zQC0$@0mKd2yf7dYO_^tswizb5^LMjx7CN=2M%mh>XvF@vlXqN_Qf7GgdD8zhoKO(j zdL*<*&aAY+GP~+f@0C=UL;3B$kN%r2R3PGJJVd9rN>s#YWR5ul_6Y;rUdST_5geVF zX4`lRmq9i7Tb+9q>60SLjn>%~2{Cf8;=xhd1^10Q?yxo+*J1d zV)j$9+}Y?LSo*5D;Jvz$qK~ePzkk->GtKu`3y?p{sQs$B@Y!$6TRxJg$=BPkofj8Z zzn%E|=R6j8=P(RNGv*}^rb5cq5YunW2^LfTUO(kIX~;G&6Gjq4YSMIDZWWiBsw6t? zAsUIGUisiOdiy8}{~j@2!;H*tQ(xcMF~0LuK^JPPKpv|0+f^Ek5a^j!(hN(tfSX|b z-|eKxcCFH<|KHuO*OgqRw(5U>e12Qyv;FiSP1OdZ-}rjc;Hotfszv&@s%mN?E-=4C z+Uogna-JIo8IriaANI}GK^P&H)Pv5%J|#5GhpWPj-0ph;g^q~ zb38Fop0v6`O^+2xJIDc0Z03dwsdEhYTgb?ug|TpcYa4}V0KQCYY;53%tSv>Pmy`YtCot^Rm3B3qTVnzzMT5|u7A#SsR?wW3ZBw21~`K% z=`9E%6z-bPYBwe?Ixde6iHylcTPp1bM`&=XWA^>CCAo7KfegZ9KM}Pb2jaqMG)j(> zk4*dc+Lykcp)OM6L1vPHsrPQ(JvRklZE}Dh5BUjAH9xRv_fo1t?nU>N?aao-7SRaY zyj`}QpG}EcP&ES;tQ=xp?zWL zqF6)?A$j9YUkz7$VMNWK8o3E)G+X)U_$%_HNnJnomSyNfH!T>I&iecK{A|g8!i$WFqBL^X*(V#i<%4ECiSn%Xp12|k z%|)6RlhN1?l43vV-;~u#9n)GUaYX#sl-V|#7u3)FZki83^%Uq}Snp6e%CTrUi~}Zm zmNQK`p*sf+2gEp=|HL$Rj|dg5O4XBTxo{17<_8^fiIs^P1Kuy8EzFR3t0wQv#`s`m z_MXb1g(Tz5em=B#vhJkSM+qsTH!gDwsYkuio^YBg$99sF!Qoe4+i5VsGC4a>j#MYc zi+-W&UeZbm+YzMoZDeF5ujr(q6XF>J_WJr9`Xnk`mNApGl+4ZLade=^N|V)8sH&AeqMplN#V zZ>u&J;$XoN2fM)P4c85_pUB8TH3naC+Y$A>6JNGUqn)1=N2zxx!Fqlt?4}Z!yNL-? z(VYbTd}nIt8Y!;3-=S()b`Q1WlgL-HGenju6q(?fZ(&*pCOiz}Asb_})SddnGDjYy zLHYJ9?CV}S6RQUcor`lpAC1(A${xs>H74vzbUu9XJ@oC_q8nxfh37(KB`SXYeCaR~ z?x-5q+XGKd#@>E@dv2JU-JgHl-;<$G5;~WdWI6W_)AWUOiFwryHbJzaH!e)1_M)T3 zhML(JN=Ea$@9~-WrbYYt36sT%?YbHRWs7rV(Fi3kkiv?#i5lyKiL%jgwf^#7MVN2z@8AM`3UkO!n1veGhOFJqnf5%nyjj4=Pefp zn!3r%9OQ7&Vi2)Y#&HY3;D#wS{P@Velx1-aO(>j?*roeI9dABpanx}PBugnSbHvn_ ze9Yu;%b-B(j$LGYF_o(=&@4j8;7oeZtl)fy$%4*w3Srk9m_$(AW0shiDin>w+u6P7 z`?al}zDS^|2VI--X!{!u8O8r%gXtYql+IM1}7Z`{X_~0x@WiT9sJpZ6{?R8 zk)_LI4rE+JI9KK_PA+N=T9?@>K57u1YuQNdVIDj-9cV)QkZAOsNsCOsH_jecw4W}~ za;Tmyy}_LU8AVFU(hegY?be;0o#U@lv&0trbLaU(<&Mn%kzRN|kUgmhBdX^^A!8*; zAOgUx<+1Na35Qk%+=Z`I+ws` zH}q*c(7 zqd>b62}0Q{o9t6bKI*Y_oU~MGc+xcJowRfJLS6j49|1!G_*Ewxhh5nmgaL=;C|$jS zV2rnGXN!(2>l~fwQOaf2`(Qn1)4?`P*4KP@&_W~`ZsCQgwi&A9ywd#O;(YEw4!&-V zl8he52bJN{y}?fy<&N#FO3j@&5?-7eote#Dw1wl_-3c|ri{hu7<6N84JVSiDfdH6Z zpjGQy@a68Y?#h{BrJQ$19fqCBk|NJS22*!CI5ETA>9stqkXOft z@;4H#$!0uB;&SE#(=1njpt-o?D8FNfiCx7sM_qE(Btj*IbgO~ccjLDWu>NkNHA^hD)MB*$ai zx`UR|jzLfs10_d9tZ|af)d%WR43yDAV+}^W=>dY5N}e6Ba$5WX9*Q0xO7j zgAC+m-=_`pEw^?4wdQx+yTe=90Md>GJ#q#BzV1XOpo}9A9!VOw#~l|37pp;5!o!0c zR8x$+m9~R$5%_0eAXR@d~SN4)lMsvKVSk*@dq;6_Jt zs+`3QU0*ZMLfjN{Pyi&G=fsp z(@am-<{-CmYGj=A<-X}7>X;+DsHdc)q!_3EOfvL(sUNSn5f3{%U^w%XjKYX|%D?1yPK2kMD>&I^bhL@$CWYnB@PgzCf)tfip$9t(k0!`c5 z6koo6EiNOoDONREE=5g6g$oTKtco!gu3taE#l>GS8y-YUkbda|oj+{(hv zUWo=&PP9#3tIE$lhP`@~(@gi{B+KHI42#~1wA!9nQ@7uK*= zFVc5$HMG%lsQQfAn>6JJx3shv)_yE_Z=<r8<7$5A z&We4UoSbEao@`34tLS$77#>wiVRw=(&{J04Idu3GPtx9^I7u(ostDN!@82^g3O_;3 zEIKLhn{!^?DRy@DHS5>^BO=mxD=1i4LPkdBRcSmrKUnH9HlF+&0u}7nAI^@NpPRch zk)D}pKH4GmBS_R_Oy_gkI>t)FjcaLA1G8%ND#y~?kB z29*s4VYvT0gN*^$u6y~WJ$p)G)lxAj2UuC3Z#gJQ@o8xK{4FxptwrhyK2~^m3JH*A z)22;V?>gc(@0|}G6S!gs@^_EQbIjU{+pRT+B2<4-sorSTO@vbv zDw?DieG>^tSy}n;l}0hH+&T62=EeGUPl#f4G&MCZ`SCo1{ltCi=f1D5d!2)V zn4l65?%TIdD`>?x=Q+)Abarvu&)jjCZue$rVm@44tbMj=y3p&W7UMo@fe78?Fp8gC znYrreW+e1|eTxt)M>I0-1P{!Ab=l*4?AkI6cVEqi{67EHr%#`L`1tV_dV2BRU$IA& z;u!E*p&EFx-=v8VB{4hE_@(&4e_rj_V!D3+Na>~(z~Dh^kq*f9;_EM_*Sgcqe;EBN zqvC+~yhHf5b@;63)=*a;nNwe7KRa=Aabe!DE=gi-8Vn~1Ic#~Uma2HBy1E76MVS~+i!h!W6&9D3f`pU+4+<4&Ypw}$d``sHxxpfE9K z`di7Ws!6v_ryBo0EFbp5%thzB&nHx~oo{HadMwQ?^h4%Tpr7B&mo~b|W{K^C*hZQ8 z;K3u4S#KvrczL~OmalqC?Jd_&1_XUJbhA=ZQ$wR!z8|l_nzd_NYCdS&fuE3nvEk>> zTt`P7NTc*Ni0j{Vw5e6%z1Xu&2bySOw;=;x#738auC=+2q7-9eW0q`J=jZzc-U!@2 zV3WP@ObhRrvAcKnHD;fLEz-Cw4<9{h>Ftfqq8VYA3KZHEt9UV9Gg|;}mEpSYmEtw;bXPnA zTsHUgsQxMQef?VJZsz_PKI+WD%!Yvw&3L7++zs*f8)su;*s(*}_s4X55>irh>XP(| z4Iyh}UrGZ9qEKab0=x! zYhL0FWg)X~FZZ+HWj~D^kC2dWeNpFGove9+FxlwcOTnq ze%yX>|4lxcaeR*JZonSr{MIpWSU)DTV5N-Maf(%Mt*@xqVpUbqb{ngq71xxu%entu z8_f(lsZ1hvJDsSSw*Aiv_t3B9wPd0}D=FP6Bt);3XXz##@Ix&7`A$9Au-DYg?0UiT z?c(*ZF)^Nx_|U85hAhQz()b7TUx_iKvb*Nv&Gl%~;XfG^btSsBzn|{UAmjR_@sQnF zG*R>={p;pl`in7Y?5b)UHqVWX_U`{OdUl!d{&V;2CTex3rlvOS*m2&Op2LUVBv95V zlG-b1JHak&GjO=UNeOuK#%Yn`jnYosV}58I zQ zL74ssh@bv(ZM38G1(RqX-q8ETtS)uo!d1v!3Vwp0YJMzBv$d`5nX_}rY*8o4@swiw z;{sMg`^ciQ9_^q={+yo@S~rsMJ4tUV`Y(Cv=y&ffhL--2m>6==n^RiI0kMc+O#qzV z?W?(#G>BXI?!&eGl=aqiGW4S_TwQg5t>RZ^MCXQ^q4)x_`xKI7dgb zVH&Tu7kd>?s3hue>3rY$no~pHtN}*lSNP2d2?;XyjsJ#WV2Xeg164EqD{t9(t>J^M zkA1BuU)t9opg|h zLcC@G+AG@z27Uk-*JWST#%JBV(_iO>mGa?so4AmW5M(xgp#StPg=j?=fHKXdojWhg z&x~7-mhxM}+fh!swHXY<4gev|5VEgxXtlH?Z=yV8{_!$RkY3MS|(UG zhyIwU>FM^!^X3TB;h~{Z;g#iYPcL7#Y#Ctr$Ph2dS`_p#vFzLD1U~)}GgqErVGwpX zKyt7#``-EZvW+5Br}REtv--V(LExp66Ghx*w^y%u_Z_zdZivviC&=qZ%BaC-SIe_qJA|i`SehAH(2GZU0vUx8-_CbHQ2?;r)u9ERzFTg*0_>FHMJ7>X_v9ht*0+t16|B#aM z6?_GOXodq6(L85z_r>W4tIAVNw6M?q=FOWQsZuuQVch~Ljw5y%7#OCy!-J4FNq%_2 zDC`HQtxUV!c1HM#;A1ClVc~$hygY{GJ*|F0pI+`iyJq9Ya10&xd-F$@e+hB|)0zN9 ze9nx1oc5nd2C&Wo^vF%22z>;c6x=OFE!8#TyqjG3<-PPrHNOJ^z3%RpzHVfMrM(7( ziA)o22e2UD+*^(rK6B#DY;^pNfCN91Tvm$LI+uf;= z>o7ls9Pf+w!2+Ao?0gBe7hRZoFf?R(lWxr`(Swqn&2TW!iHpmHh|^KHxw*d;7k{p+ zJ0UGbBdAxCu%F+!VIK=iSVY)tJn2y0vURJo?QZEulA&ip%70?5hV-8ZaK)ILgHK)e zQ(0(;GxfJUI2fF0HzrZMj-RdhcGL2U8lM~=KX(oY*b9BcVj_d1$~iT&F5u-lu2R~$ z`S}kCFK1L_vz{*;ANtEcp6+-o8OohmV|-d!Rh6FAZtEEzT_YonE`Ar>V4BtN0asU7 zF&?)4fhNXW#t|M>l4@IKZ`iWm+45!GFt>Y<;a?!tJhq)xfvlXtMq${b;%#4DWTUIo zGBQTK?lCdNJW`+v^8HP6o@Hj91kzQ-Yc<`tSNF!oRM*iJ`>$-?w8;tI0gWSQCoMW( zb*o(USkr@9IFML)`qfd7E{C@{AI*6SI04|xX57(hwC>z{v!$8IVd@@OcUxE2Q{;Ov z@lHU5co`R>562W>`gP(<;oV{FXTf5WHrlX~Y^MT@at;qagf0A%RizMBz9RM+wR}b^ z(^s!jOEqqH;cq+@Qhrri`z(Rd+QdV6`|8_dmWR8$kBB|eVAZEjpJ+C2+^CvjScJPh zcbRET%EynbU~Itf?f8bFkr5E-`qvk`baqr;mXy4{FgMMkU-cB3;2N%qJc57L1F(3l z=fJRVceHy?cqS$BgkAD|*H8%&2IlyL0f%-1&OKP9Oz+(Jf{ZiKUvG}PXB4t>k_`Qf zj=MiT_#KkgL&RN7Z{Pley*#C*r5|r(`l01G?^VXO?vQlgd$2`J1#A2Rq}fg@Ve_6( z_T3c+XC?=wktMOceE~A)ZeIOkW`8ccd-u+>5HPh7FNRlCRCtcsWhu=hW~~N~xq%o| zh*DU4^5jX@D^cg54g_G6)fNVwv~)%BM=r#G|5mE#9p zYR!4A3B8Gk_iIx(9X%Kcv?MF4b)|Mh+J?1jueE%Bv|{z@%47qj6vNujC|C>P^*yx| z!(brUSbx1YlBp@)EIV`dY{&xAWOZ)fl zzXycv(0c=I4fazCyxYlhYt!1bYv<5o)?ROtd+@{wKeYci?>eqC)Mz_c4)T&>(u93n zY=@AeU`f=}*YB9I+1|-O&SSTk9FS5}q$kuonX35@E)P0$%&3kBY_Jp)^&;xddYg@q z0AD}eEJ^tA;Zsu+6QTeJGmW%dn`M36;8)E4!-o$`kGi_J6qJ>@p(nbzrR5&PCvNK8 zxpSs4#Km11itevmf63MP#fuwwX9roM70C=SJq;tn_k;y2?3eFBqFUC5W@g+A3k&$Y z=GN9T;Dj>K)pGzJ!}=5#yc&^UJ*tD6wxO93xY*h?YxW&H_^7%0Dvp<`O*Yt(dAGl{ zt2_iiw439dkmG_KqI9_v$STrqJC;h4e)V%?i{e{`559ak2hb37m=hQn7yxc=2FZe{ zSyT~vaV;I)L3Z{RaA-QZ{lsx2ot@`_j#wMPx7)sc`TBK)kb+)neCM?MCK83XI)tUB z{rDA#%X?VPFkRVIlb!;J;Y7di_TGUz|58x_uC=MJzkk<>JBNq5q&#))H^Ryj!%aVR zb0cgb$$;vLHTvOZ2|b|ZtDES;1;nCfp$Ui@fXu~o~2B{AU4HOFPQVyc|Kg)5sI<9Wo2aviNmdh=<8z#rh`9AIhy%| z3Xz5d&Hg+sZ-e);2A_bC>wpL=yM4R8uWb$#1KRZd)2C|=exU==!_D@=IfL9ZMXSp} z(>*8evM1|Tx1u571}rH+1#hl*ce?L`%i-F{7B_C*#7>i25Jh2q&aSRs3k#p1(2)o> z2%@RWJvi6!z-15rN5fifbqx(c=u|*_F&Bm+6gWb=i+hErsA#eG(V*T27$DIK*WS&avV+^nB=w357!na z2lD7`p)}cz(g7xmtAXM z=Rgm6_)VZFrlzJ>ae%kDo1^07zT?L|z%(~8F_rbzChih-$l`7U?phCKPvV2$0kP83 z(l%}1E@o5SGy12?`g`--C~>{ zB9aZWb6FnD#KR4%Zc*d*4n@SC)?B%2mEXe_40yrUua5ylaay^7;kUVuANLiw{Z97L zM?}0A>y>41Ee9JV6KLH&9~TwPwJV#nesk8w=7g60xYw5En@Uj%M{LHrXs)Kvt$f48P^vyBE#qVpV&ozb;}n^?aSCvS z4*m!vrORg{CkYQ0Stt#U;kMRR|OciRR zn>_+!4UvoV;Wc<&p2emRk%xs}nqtaT`1AgkhU&=FG{XlAmvy?UdOHI6m?-V@iX`}!eI9PgtKjhc!|575s3LBOzZL8DZ z^51Uw`}^;q(Cy*-ep^eE?HmpAwcf{4ob3eT`&~%LGdH)gQDwo>N$`I$zNXIG8^BG- z)r$ww=4U-M6ujkzj>-7d%bJ6yVPB&;XW22EoIbn)n}@1TA*8Z-z$Bc73)0esn0&+J z$rzPH@|?BWiApoOK~!2gI=7D&d)ni&%6u>wJWfp&@?tkcdbi zc)>0gmEbcgVI>)ks53G$It}ykj#={UShE}%P$}JE6&CqH4h|O#f&YBf1N46*FX&E> zv;*RP_GK6UIF^Gk3%%&gR|`{O_7G!`2F8aZQY6G{<2}_@*49U60jzphy@7=`ij#Ri zN9(Cns$sINva(NYlW6xit(zuZJNK2I<9W8}%u{dgx$dJ&Ce@eqQI~wVS?X!~w|{@6 z``G?O0B2d*EBQU^&%X4eet=zl7^=BB4NI2`deT3EP zImnc8Q;rmtn-Ep_BT}f=~vX1gJuZlz?z`6h>lsIAB1c`-~`~2 zM(|qOF<4k+A2X;q3LHBftQkSZAgb+4clUR8Ok1{$d@0n4fBQoM8T?ev1G#-#UP&e1 zM|H8`89W>!ckS%$Z=0LTf9-Uz%vPY=~}OygWdUO_>@4gVHD44@m{uo!sO*4gg2 z`>SmQFKT&R0%!Fst5-xK!)Cziq`OYuH4L1&FB)z8vWe>1 zVuKzgerjPy`wUDdD?y1oj=!Z0D?KEl?UUOs+0Bnr)w6B3gHQrnAD|zgd;!)tebK1E zi4)7*?$3F8dNMp{$l_ixRQq7`-Rr=>A77qrrBO~X+;#RbEmvJU+96{M%Z{Fn@RPSN zyMFy$5nn#9JuWJEw@*2^^J>~5!P3*=l}Aq7X@Z`jG_wul_cNk;?fUiFNLfUtfl9o3 z_39IH#K;$}z;@wpg9gRr<*zVL5J3;{PSLCHr^&iMPw%_!--$X#d*zql%3An?)~~T^ z0J3qjtXpSczR}?fF`j6J$op72HravosU|yYgwATU!&&tG9Rx8aCnuM)thNxMZe*zC zY)nkdC3=SyQ%EhNSzXtSY5VnPjm|K7+jE_JfP}Ej6eidK-v`05GM6Vik)T&Pc!a@d zp@lgD$RCEwK}mq}QFpU_J-IKHssK!fjrKk~e7Tt8JTNNj&5~&l3F7@$F4A-5jpt{f zAY~#IzWejX*L29d34CI^PxI1}^AII8udNKP*crYkWh0}|vD$EIuk-ujl!#rb0zT0Z zIS{~jp4Dapp8}NhlT}sD9p~Yx>eJ@b${}igbekkU>?o{_frfN#zPWkq^L5+I>>a$1 zl{mkx4pj_aBZH4t!`ItqKWheo(k=TlwOb|EA-gCAIrh4)ZXw=6H}9j_OHcn5-K8T{ z;lF=&&LV#j%EK~i*;n%li5Vv{$7p0KuKma~`Af|tSS~WnaWO|Cd8&;%tkSqVe_0S* zLisa&1U{W0)sQqOZ?PIr{fO@b&m_LprAwEBI}Rer7O;S!y*ou{3D0h++tO#($Wlf| z*&bTGs*aRj?Sz!!_fR!jF}4+?t$-``5GI74f|^vK>>8Wd2_tadOPHQ}Z`hni3A3Vr zGzWo(?Cj69pXGyPieeA(+efpA=@k{y9%7OQ^CuO5%&-@7o?ploD8X6jfSXHmCu3PX)4DJxj`q%s{&$hLstlG%-;}W>oIh0C#gsi!dTWHp4>8W}?-mv#M zCKX946n2&!s`x|+A3b_hpBh&RQ9}{H9)_?l1+aIn?A*jWw=czuwi9D~d82$By(BuvwMiaR zFx|J2N#w@NSoilp;XQy8RLf7h?B=DctKN|j;l-)phk_)rUqJ(la4+W-6t~c<{~)|VP)Ye*2YbbM%~G64suq#H?7JVYGdhVLBI|vGRB~9D)+Nsk!ED{1OeJ;= zh;T!Oh4awR&>3MWm?<1OPPm$V^{H+sP|Jr(ZbuO-F6kK8m^DADIIXY|*_9KV0B?!t zC4}jaZac{dkZ6I;Ov@-FP-adn0#Mdqpx2i#Uxtt(Ko|4TNr$qsYsKS3snnqe*^rtX z`;)|$1f`jS*$V&q5!$)95g?Gz5&%Q5LKM)pZrMV}F49#CE`Y)ZrEG$cSVhn|TNoH# zKpUdDsv*nT1ADLFHF}yx`$>(ELg+_-xFhB9TB0DbDyhbMS8rf=i)8`<{{-g5w?mZ= zRf>9Uw5qpxt{dQ~=aJby8S`+H^aII7Aum2GeOnB28yr~vT98dwsDJR~W{Bx#JSD1W z$DyxW83ZAtmLWiy4hh)NSW{h_gz?RI%gKmiFoH0XvyhX8s#2tFm5 zfV{_OX8U1*1OT%@JJA%hVK8@51Zte$rZ3rmIy5%+9x8-14nXn0W>@))Z(oMXg74`x zq}_%Al7C}^o}M1*CLmQ5Vx}VTL*h!GIz`#aa_KE9@YW(sPS934b0Zhw5`Dq%!V0O1 zQSm@=>M2a*V7d806aAIhtC4(T)YIJ|>5Ut+B-GUzP*CR4t9Xb<_Q7rJ5_Z5kB9Mu$ zu+?P#v1T`;G==9)KxqmXKq3uZb@d-R^ z1&IWpWyBOlUwa+>jUON@7$B5O3ZU6xU&9uv2$yDpPw+T9JA0%C6=e_fT$5P=oL%Qu zgriL;6qx5&FZC!js0lqKe8vsm0K+>4&EA)5V`4vJA%KVNL`zOYwLWe^42411_=*en zXdlhiZU&ipUII4^!dDoPv5%YkV_Nt>f#yVo;05%w@L>fQvv^*lhGTVcmEB18B7i}T zFyHpF&^qrlwF%A>CFifyH}1$jGHq)@BzH|qip#S;OedYdl-Ez4Oe@SGC zKLsd)&m_C{KK90dH%AN4L3U(m<+Hdhek(39Oh@#Gw-?}q_~Y61Uzm(q1z*l z9yLkS2yGXN$U!`~Anx&IFMwbb+?1^OiF#CT>iTX^r>{m^#?^Vh ziFt>R-R&};6xWTCCusmevzLg9ipm%u1CE(l=a0QCm)~3feR{EM0u_n2-rkb-5^pK` zquFNd&nu1|XJ$UPHg)}pP7KX4s4N1`2JzWnVRrq10kxCgn8Bzn>4<{ZbxlVHrc`j8 ze{JxGz%i09;ieGfvH2hIA=v*rIksK-8MK%9y?Pb;$$bs!9tSVJ_A&Z!t?MQxc|Inb z<)PKOOEX5jrG{J2WNo{2@$jQft!s(p3IPju6eiLq=Dy=QMID47KNRWPX{Kg+a`vbPb{On5Z2ec2ESxb1r(VdlLyZzV2jUMCe#z{_xkl$SaV)t zU)G)I1Qd}nJIp~O92wRuR0Z{ZXOPMz!AB%OkzodNcYsbGT0p*l4x_d~Y-yOdM`jlm zW=&A={)#Q~r@-!DgdLC>`ZqRkd=WFu9;_Pd@;Z&R>tzp5Pj(@fY3EL5b@^>)wjHc) z%e5a1f`R+bb~Md|ze7KP_$SspBBO4FUFZ zsR#;-zIpSe25kqy!NIVPh~o`rjwZsy=%2beI^5PHH$t2?$lOowyOM?`8(2B3oRIr= zt}H-}&kk*_C}=}XbHb```Tz0TLYcgSY<~i*NS46EzUZJmyncgb=G{_5X&DqOF_JF# zZ+c0JojT=IG+vuxv`01eHR@b@9@SF__+a2!+IEcd{!Y~0=*_9|4$ceYOH)Ks5`vpe zDNbQozo+N6n_8&d`0|@D;+Ijc-{gea#3Ue>w)B-XvMb)Jsy%hwNctb8#U>=RmZLy~mIw+wul++2F8M%d zidAoH>UY;_l#VGI7=@IZr$PK)#MDiEZA#J#@uOlsI(UOlm)d7V)8i z;-O7W0T@%^quSPe{(MHI@6gdsbG(F7QCT@WHpZitEn@JC9e&|Eg&#WJR9lLh$n!nu zlYsau`u_b7ZjlhDh={{mwrufSD2AEzXx;V*_4JQLcg?At5J!0-{M)~G*Qdr8rM$}t zLoJ+=gciw&vXs;CfCzLWbc*fhh`h?p6~$}KIv94W%2mm#gn$|-SZKZ!JjB9chCD$5 z+Fx?*uKDl}$_IwEI*(nv{_6$!c#vw&E(v5>CexT;^`^yRIer8xT$E*YbSCj17%xKW zAxoRFT*mrpJs^ikAq>HG3*rlNegjBTAS|~3+-9!GU$3*&o_fDdI=uOe(01GN)-fs=_mXE~* zp{;scW{g^OtP!_r#!$8?OEcTX3)*OBzgo5pFIE@$@=mL&pbS#M4K#-yu*qh;c=2NK zYYzWjYazDB)VIM0OWL5~pLls~hxJITeiWDX^q2LPxx&aDjv*WkS%-d-2QewDqr(z8 zDOaA^RerK(v}(89n&DP=^y&;N>|7SpaKnUV^OC{Vu}!kG02{`TXvO-#4gExYuh{d* zgV*ng^((fUtomUxqEofcv^Ry*BqqDL&hK_D0J|Q^;ECN zKE#M=PcCo)3A9qxYLD6&QEuM*Qn=$459+R5wTe~$4TI6EYsOjl?Migpp`_@VoXiUW z#O5xzXCOIPb;0_Yzz$p6Sq3I;UET9&qchu3+uk|;w~T)7G+LKo6rRD~k4#oLa?U^4 zu$RxmFfSub_wYk2?5d156Sni`&o|4Kbu77WWuN_^!tsn4c(7IdkB-PuVk1J2N3H)e z+6r+xtkduw8Zi!GVGX_8q<%zbVv<&PWxH~1pw{EJBH`pIZez$8(LJ+Ar)NXPs6^@ z*JmBd9sRe&t5^K(8>|C~waM@gy-ZKSMF59q-^=kK*ThZaqFb>lz0bDRn=HbBkAf)Z z7r3D4A58}ZlecBeZ++$VBz5R;-aL#Z=Rel8v8-V4D$H%WY}B-XsC^6Qz65deEbhAh z^u>!mU^B$bVxLA`5S3le(CNtXAdc7dv+BD13YR0Vp>M zL?skIX@~WYX4>{g5Vh@xXt{tdX>^)VcWQm+z5Of7j(p3(-lKs*qK6*;VirtxM0$4} znK?#v)>tx!pMI8vjnB#H3d48Hu3bgo>FHQ@NJO2`bm|#*p5-ns?7`4P%7sS2stTRE zculEvgID$9#+303Ovd{)<(7ksnD5DkK9CoStDW-^(V_G^+!`M z<2>_{6FRGs^yJYBo(5eCMaehogGwCfTn}H!2lpzdtMkLYg+6qSaKy}!^SY?Agos&QfhdiPPD)ORE*my$?;{q5ajh37M%kLsOP;ffSe`7>P!G?~5 z@jwt4!f3;wbzl=5?sXpPxpnb%^K>!Phu{Bc@4dsh?*ISqw{~f$vqeKnWwfIy?STd| zLP-mehSEt{r5!0FX(1ycBnd5Tp@>LmDN;10VPCgro#*d5zu)7yj_aT6&+Bt^e2&h_ z`~4cv=VRQ*#sRP|p~h&Ldi z@)}$0iYp1yUF%=0FcabG-!Ginx}z6BezU6DS*W@x$ep4;;YLOtttmmLVPMiA)8Ej1 zr0K;jLN7M%qx#0$T*j2l3$X{L3bA2-BMluZSv~-GGLk@6IU{(Tyd!CNe?2i zxU;Wo>LLFVKsBS+Jskyiv-n-YAKvHSAQatznH#H~3>RQBVP0S~DEZ#7uxZNde|}nq zJ`Wgx)v*|84(uh;EO~@@R}?Y^k-Abuk8`mP)t(=%v{NuQ&GRs8cVxpK%*z9~@-f1u zXyf>WP&n^7=W55jDymWvM5A|I^SqnfjYUQ1FQ0CG#OKBEb)1;R3oJ1ELv7is@MnL@g z_wBnup~I`z18daq`pKw&dq!|jeGroj9SNpd+S*`IJJGiZbRhBw+JTJ#(gMh)#4~<%x*X(5NPQsc^7sP;fQ#VpCc4zAiRJ{> zw+9&Jkn|qq>P+voAngks0-gr}MbTzyabwVs0{2e2a)lN^F8s`tapR6s*TYF6fAP;f z6GRpH8l-tOxDg`!o%~%d$85x)7CdBt6e&=|~QtURD!HTKI;o_VyQYe^OknwzNcO=w%ukL3Irh0c}S3 zKzxJYXBXb}qMe<0cV8#{HD2MjUK|Mv9pMUAECu6{Tt_^a@92y}?tOj~(h{cb!Kul@EAov3SRWjbxlsa$m{|5^HVTPU|{LOoz$gEI6ysR6L2cKPbij}-3kT-!SMH)o;RR3CWd(T(YC8Mym z2&!A{DDRl^QJ@yw8Cr%#EanbsR{q*|dFOs#8tD=VTzqQ}Azq@B^t-Dh#p0Ul=s1C8 zBo;jCF+IKq6~aw;0@0XBc^21qFRS=TPEJRuIx?-n2gFeZ7!d}5TJ0@|jfArj7B!{+ zA>)4)=2d;y4n8&I!8qseurO4qRQ;V$7WzTiQqCZ9^|P3~XvdE?IrYuWV-NQnJmczB zgSs=;XHFA7&zVCX~bn@7-e{J8seefMt-z@}ueDmP^>GxBTk*Yls0Hw{Jgj&MCCOM&xq{uDfbu0e{CU>vnr>;@d&U$a6e# z9HA>+n&x_nM(k19$Qks)H$pqu{>g23zAZZYIHbVlVVj~opShaz$;oqLjRZtLn5Pj{ zVDrr-Q97h%YWUZb&mp_Yo~(T`a&^k^UH4D@W}Z*WQZ4WF@BlF%qONYZHbhEr6R31M zBILK&v_S9Alla;SX((MGN$cT{oP}Ci)8h+OcQ86`GHhV`3!OgBJuvB!>q)yk!&jFz zO;EUVa1o%txb{CiUI^8ZXP@zh=BTa$9A33U^Y)s*RKO@^TOJrC>Zu>?LQACJ|Hk~?bfdMsS#NvuxaUluuux1 zmdM#MUmq^=ursmNZKtyDd%<1 zT4A2pH2wMsKN-PEP0sl2;~tM?+bi7h{XaCmXr6XzLtgf=?sFX~GyTbvo^9K<)zHxJ zth0wlqTB0k8>76Im6a6&7#0P7Q_o_rdBMYX{ThFm zZtdS2d_D0n)t#y7ajnlEKJ+LCqT~n27u?oKy~B3xl9^a>u-@RnGSBTD-(PzF&TyOL z+2<>(POLxJp?%$M$D-fw{hueV*Ky0Fex|Wc)*ZI{Wq$T?>8n@nrkoA_@ZoB`c}b>- zweL*!zGC)iL>C|?NvSLaxCKgj*x*T9FOAIngdEll(hNPVJ66W~I2x(X?#QtbgwdXiC6=>_=aj z$=kcw`D^dy#ffmIVwf4`c8LqSb?Z#ZqVnCL&CSiS^K82*n4ACi#dqI9mEkLyygenh zz{Y=C33xHL!8?aX8T@EOi~ghgPq6Mcs;u}@)TPx~S9Z&c?E2qD*a5ZM;}0tj?^&K? zI-J!?T4kYe{N%}Q)_rE!wZ9m2=z^R7;H-ht{*`*S>`vGmY;AvPx1;QT*Upi)Fv!BX zMoVK)H1*XiMuq|@Nvz)J;1G_~K|AS^LjI-1MBi!kvga2h5C5bLt@J-GAlXoNYnyfCxi1R(SE$44`em#=e|{Nd&yXFLO6z$I*h)50zLSg{ z9UWhN`m}KV{EjsCJQuNp&m8;D_w92NB%MmZQ*UFN^gDMBA3rW=ZFcL14I6}~jQtN^ z#>WKbTAxo!Dn}8DW3}hc_k8cP-$C`yTDrQcX4^HbV7tid>;FVCwh?V7u?OOTRHY{8 z)y=X`3p*}8XXJn0-q%}MnVAC>6mCWioV>lH>&)Pfm6c434Z-fJ&Dt(_{v4&>iPxGv z_`%u%|JkwT6UYI$y;yVgKPR2)%&>L7?DXl=+E=>HjO4UM9=F4$paaO7X8d;-=3FB_ z(%+~2{rPlJhmW*j1}gsDtc_!g9!3`IQ}`WcKP`q3(%bc)FnMS5Pyj^!ap=)OMfKL{ z_wI>MiQ10B_FhRzA71L<2fV3ZJT%>`r4{bzEd0;Y>3+r26KKfM;$pkiKXfOL7}1%K z0>Gk#Aq7%Zy)x({v6i!HTNSr(-`@Y{{qxz9g3y-%o+I`Hl^r^AZFeO3mXG1ypT zSoiwWVVT!a!Zh}82$(%$@Zh^jcMyB4n+_PGpdf0EKW~Gjqcr8Bx?CqnkUOLWe{GfZ zvu{S~Dho(EAmBe&p>(mVY_)InhYtnC1OQs=QdTaFm9oi&Fs-bvzw^)RBacD`Z6DuF zI;?v6z5xIK{Pg`~Lf9IG`ybc?+hdJ{bm-424xdzV`}WNCN$4gH)T`amsr))#o3&c= zvghl;qL={Cij$|?kA(%$!H6=H&Ut=Z}8$ibzTWJdmX1+SPD zUwEQb@t(>L^mpH0-E4{ERax&$EA|Z-bVlTil1KJ;ii=#?bMh0X;Nx6p$07#s(;?mx|ZJ}?Mm}os1aQd(4bT?HV-qmwu z%^Lq+{GBw2^Fbpfao5D7ec{ya)I zqy-qi@vYyH&sPLW1@j62{lR1ZV;8Wr#4f;@40mVQ-7;X9NjGAw_F%g{ce0f0ZOy_1 z3R7i9j{Uzw&%TPKHa5}vA$B8>%Y0EFGSft%Zt-s_Dsp2+VZb!A2HX2Bd}lOl|4-)C zuxgUu{&)W#cm2n?HkeHtf8x=A;9#XQ`+9fXziIBX(5|bVb-LHvOD_4&Rk^ob$M;u3 z@bp>mV1iAzz57Rh(hGeX*>2P9ZpMBoQX}>aNOAwLrRDRqslOaL4S)E=-TJL-_Sg9l zF)^QF%^XI4$&amIE}>kjgvWV#9eeKMpq2=hBU*(wA3xe1o@~~f2EH{gczC;=0~+4% zmn0A1H-CQRCs6I^CtlFWev~_u=|uFXES_K#Q(=EVHX(&TYRv-Ib&d zG<$a*c3@V!`7%xCW_|A2YP!syU%RY^sjBLjx4W=WdvL^ajkZ*!jh3@V5V6(*@qM$FrhEIgg%LtBFs- z$w4ow6W%9kd75U2-Dlz!&6F|k{luo~avV33v#;Go>3?si-HhS)GcrnP)ac&i9z1ew z_%+%z*64J|$M^4*`M|c~wnmK~A78atT>Gwy(wG@mf-X6eqI85-WK z%vTT4>IOs@Ulr|V53#MNMY$Rh7gK#}Nt){vAH~sI-syVeP)b0Chd?QDxSDD5dOLer zWo2dispoX4rRVtw#ihBI#gsA?1qRl8 z3jz}s7WRtj5F|wwXqgUjHRH!T8NGo(D=*P%5&Y*&BvG?Anu&W*(R%Poyoy~mlpl99 zGNNvMR_A0U+5ERf+rPY$q6{t*ZVZnunvqqNeiv{Li?(V1{+oq`$#F4@W4L6nQM;#r zF3XI=i;?x1B&=-Bf`SEVJAQm}ho4R_KF{WR#xeQIS6e?rR>1+t3`FP z#hp8MJ{GutqLp|Ry2}RM5X-Gy!6>WjzLXb+g$0pg0hnT|RQ#$;vX9yoME7uVa&j26 zm}Po`Y{@-+dyo}(2%U*Hw5{Lq@W`}yP?KyF#LJ>qP5J!u%z$=1>c?I$73MRhs1WaO zzj$HZ>SAkNUP#Y<|19evlYuvv8HX%2j0z&qjT|WqTfUh-itQ=Ue1F8o0VV_&*w`j{ zK6|zl(8N~FeFG7*rbokv59=f}0V*!%DjLnZw+eA?-MTdxnMUFJIrGaueKIdJ{JmnP zs(<~pMEve_i1;X7B?0>abA(@#pS-oBmJj{5XoB1^3U$!>Eu8R{pDLywpt$Hx&&qs( z`?yq70LpW#$)SX_fZ(N? zGq!V@#0-gL_Q|zs>2b>CK~uIL#qLEjB7AEQ`!Lq`*BIY}!r7~+g>kgIJ0CPqs~euE z7EQkOwX6q$aG_-3({H1I>3B#C3IW0!nVd{jj=q-h8Bqp-<>jx8VhV(23Fs8@s_5Df z3qol7`1!4_=}UVd)P8_TbHnvlAc=)+eZU6H$jb6fs~|Ijwn+)AuIJkmkOiGVRxyM~ zQ`dlu?gh?a_mqOBhi7heaG33**ni5lI|q8G3W5*YBT(j&>r=BXyQZe5B2OQvrN4W6 z#o5gptD2h;D7CvG^mp79V@ucc554g7jOO9%fX!eyNPxiq#vw~Mf^xdgluOEmv2=`y zCOF}kPIU%Ei2VxsDab6O)Zy3DkV+_O32P$tFV;c#Mu$W`qbwPhO_+G0CB>G1^lPYvL>)MWXp&2@0@Td=;Yv zeCvhIQ0HS|nATs4TCXV~PHMUwM|SWUSP{hzP{7TTkMZEQ#{>KRUZ$e#)Se7PWcDTOK;h_jIf9ncb zvIZ+O`#tODeQb6h!1Kd1d;E^QwF6o_6LI59N2U~>7IKk>24|+LtT?|QGSAAA|b1dz*S7zmILDa;t*nXs?~+cG$u7B|q+1NvOOdQ}2#FcN_DYVF$-1u9b+ z1cYb|u6`aUpkVKSwYH+H zY!tdCM(&9DF=gZSzMi%gtt+yzyX+>`KSPyrpl0DDG~5{creYXC(IvztbLCy`pj;9@ zO)l@wvu7unVJ44GYBK=2e!cLl5iy0C7y-FZ)W8vrlXq(v4OQsx@rA26-m zEHL2qU~=V2^gf8Yn?Ia*{jU~)@3#8lvN+z%u&k_1Ou*sO_MsYsD#EYT7nn$BSOwe) zlDqD_x2uL@by<7Xq9S|()+;dx?Qz1Yx#H!JSLZEUIPPhVU(=G)V8f+6Tx1CcA=3%W zDMZhHx6ve%}P1!R$KApr?zoW#{1#kK^7)a*sxDlp zBH)Vd+`TK?_sXT>8n_YRQ~dBUO&&A~?0Y7U74L-z;xJkspN$-JpPK-4#%r`a?~P!VaUp^z zr*wT$&6_1_3gejzBHV&}oHV@}pAW6C z0Q`;CuxrnrMm9mrzi=loY(jlr!A6a zD~a%mAtN)vFXz8`W3TSrnR#u6^zlAqYx~Zf+gRWO=fS1rf4GFFN7Myfw0ux$D&pq| zu!?~!nJDuOy6-Da$ooO{wY8hdGkY+VBNIBQ{MANWCDbW`#3oT)fDTGMhs?Sg+O_j5 zZZmM^VBe?v4jqc%0ntKj;v6ZsiMBWJme;b1bcTPhvZ<}x%B=S@8q$3Rj2?Z2O;7Mu z8aAwq&j<1}c>07z1nBN(y4oI34iWw+LR;Xj#?OD$oPaDh!=%ml9F>PtBK zMKmSwve@l)8~9S>@p3FKWOrqsp$1OT%7{hG0d{4wFJ{l4?OdHPl%3fEz7L?c{F@jL zgZowJ^~I-Q6A1n#H4D9C%9i)tL?AM`yhT~E+_iQvI%!Mzpf(5R+o;JgqK-ZJij#>f zi5m8@Hc7{kYYOs=jGsgJDR1PT>_2$$HdX^dgMgo%N>FPEDHVYPjrmoB6Tq=zM%EX% z=AUkDc5GdR5I=`9QIx6d6aT4h3|$e%ZWA0=;qr=p4kG~y8NauOjgS79H6Fx`x4b(& z1=i&PU!!klk?El74R{3Q#YZ1S%Prvzwc%OrK{ZLdRzKF5h9DTN$}GZl#}+3jq{Tw! zKrQ4Nx5ztX)ee*T;R6A9Pe8;m@tw7e+c2FKD-@V3+6}>)nCwNixnCl*zR+OwoeJ>r z{@Q~Ji-_|SZ<{&n8Yn~xfLlyI7A9?$!B|Emq-K)=85R|lug*zhcVE5?0yYyKf)}p! zc1|UTqM*E5a(td}NU+p0OZrcB^<@1|oH&u|$qm=(CE=FSnLt89WY&`p<6xu?2L6Ug?3)m3(sg#?1wXX?+dUrWIfk<4#|sTGG7IF-;k2%7>`^PnkH`bi&r z-SL?4A#<~LX~9u4-R}}CK`L<*4+f~3!k97ou3vh?UsBC^`uZ*o?-l5Y%^cp6;0V+? z!M?1WtE=m@P0LR)AO|co0vkJ2&$1Vb(j*DM!omdftM)v_m#lQ;ARP=95lrN{>f*WGn1 z?(|do-B^erS{P)q8aWig%EP65ht{GB)eiT8`1ZvaN5=exOh>egguB?>3tJ|gn(p51 z1_`XQ1iRPbg>N?Tl!c`ha1Kgz%(2=JjLbnN>Y=E`n1;;wT;QFr>=^1xrWA}m7Ww|%;DDn?!9^62P6$7f;+_aM*{o}pg z<=u8{F;{~0_*P+IFO0(m1_r6+c;67!cIe)AtWKLzAoC^|1%W4*VgMj4WR}!OC6Jgh zZrZsMFTNF71u@*|roXDOibf8Ut?%K(V#tMd5+}e97CgBGwO*UG>uWwz)2xztw&!)x z7ckuhq`~%b{RE~-g50-z_wMPBzB&aP#n6Bp@hH)4Xxk8`Xt4&|u9CpHLF>mSq2a>=CYlYP0dzzjHC;X)#YXY6=c>8ZzU zku+WoNa=JpF*0cV2_JghPCH8^0G>0W417+VvimY*pX;WlVv-8~=uzn0E-$uK4R;^o z_QKGAPUs4RG4>n#9H@`J?v2yJgPI_t1cO2A8>l+?9NmWV>u_I|y?t99@75SIr*f!R zi!(lUlUgsZkjOm%lc;+QO4H6JAx~gAkTh;xb^7MWktj4o!g@d{FFQO7)>!ne3&2*5qBWnmg?TN8F@n%sszz<_VpY#adF8pHX(un z0E+MyGj;pUdlD3&xoDk{(b1FMOMn;XW0{RpEcoVn4GG%GtMmW68ypPa6S?~)w9D$5S& z1$iaHK*p;QGzx_gyKyG^MeXozqg;c)E_MMJ_}4KkFFao}q9(oi-M4{1D+{vTefZ83 ziZj2KNsO}j;sjsf6%jjnYbPA3VkX!zMANiNBA+vDC$-Db`2{QIqb1Jun{%&tu3PrK zIx|oc?NfW3`i8tM$zReB?29t>6&i`^+dC=`=^->#`W~2YDau-&5Ia#f?&V12SGa3h zPIG-#t=4EZt;ZC_a|bTmBU+eB-5q-;#L=^$`ReGS#{CXIerj;mO?szp@`12{pB$f+ zMieeszwLS1r3$+a52RII=*jHrrT;!{izt1jN2)E>_j~scKN5bhK(e6J-H8_8-)nm+ z2g+Yoq{sqYWl9h*kWfoI4S9|UfiYw|a~o@J?xQ3`2qjAVY2lksA5HhG{yxzoYg@l( z4G-}?nGJIi@RJlOgu=V<=f5SBt`sF2N@ zzu8wA%huW2e7L#qG+B#P2WxY**vS5eqZYx(5|OwwYnM&6ylH9Ll2s-ZriJvp+Aa~g zO75>^bGJn-9lsdEbO7Oh6AXO5O;YaX-dA!mD~Hy#mA#jJR)q)=aj3_=VtLQyE!{;y zieprW_dcyWch4Z)r6zrZttaR9jP#dobh3WT9==zczNEz9qIW`L%?6KSfr0)`55EWX z>GSt|1+8wwO)rkR{1DOsL3@_8181U}#Z}>O^VAG;0_@UlY#QEf#`E0cwpw524|u5} zFWEh3hwTN`0|RIGE1WO0tN5QjQ+MuzhYzVTk1l^Ra%4&;UD|~)$((w}o~W(8n|7ya z`TjIqL%XF*-?tn@CYMy-@+?@PU0dgpsroW6@4}px&s6*~-&G)F6s_phs~Wr$Sxx7Z zlj*VtJO=t_OpTg)7I~Q8@sAA`&&GSW{@|@-xlL-Vqg7{DXRo6Y<01;_&70p41Wsx= z`A}Y-)^M7^3|z{jIad0bT|6JI9Dk1;b3hbhSmz%+c;Lu{yY~e#y(kd_swUD1jrsgD zb3{sqi0|pu$0ivWTxyhpQ4o`Wc#UcsUYvwU5wdq+2dSr+VN(xEjCkPEmo%^K3p<_Q zs#|Dh`h0Y>%E!e8F4~96*Oad=@SY6L@@~sz?ec_?-v0iEf!`koe6Puwt7QH;Sfk+m z%bf!>+HTp?Y&WdjZ$LY@&i|l%4vMH(0Z4>$*WA26g=Yj7YLpLs8m~8bZ(da+CD#~J zU1#x&NGOuBs-e8gtH?36D^*wWOke4nBrZuZjdebqWXCk9vhs3S28a4+rmdsN5`I*1 z5>u2*P2u!dBLpWgN!E+j#6?|SkhR^tT5a>@&G)?Jb0}16OZUptsEPqHu!xxL%m&@8 zy}UZpAx6b(&Y-jPCYWOBg~vXPE3i>@o*8^${(JB8sEmX&!&pm}X+!tAX_r|B~08bBxji!gfAY>ZTDKo zvQov{WaogZPiJ-hlSc+Iex*M;0nw5RzaGHw(G#C$HFv0gjI5;WZm;k0hpUzsJgF#) z>*%8SlJZOLxw(PCEIu!M=Yt5p_?#)`PgJV_8n#)E-B9DSBB=AE8DHfW2{1c<)BLq< zkyt2dA!In}^bj&JBRf0p%aXc$#qw*G@gwN~67w8(y}sLOu+~bRX7`>wHGjU>ioWGn zWn>7vFbKky_~;apeNX`Q@7d-w%Y6LON| z@MFa(51)4YX!Se-+;_E=Rn{sC@g#3Pe*Bk~&!hKS+DI=ty1FuD@lik<3MZ>ACp24o zX_osSBDJ)%WJ${D92v;o#wkUF7s|Q}-=V3_wPXI?@M3Vqmd=&FHerd~^e@g@xJ?W* z74tHX9%?nkB_uy>HQh1cAAmT2hv+8p^L4{-41Ok@%LJ7HYHEH0)p|}!olNp=;#M&(iOMlFy#$5m^jC>=w)7w3I@N-OZwTyGOr+JZ+rBL#O1ZqgzP{z% zn@e2c@_jh9V?)gZf4zdh^L570y&irj;p~XM?PA`g01Vy6a7D?0?R9O$7f+8Z4Z_gWA-RAp?JevAZe zZL{7pnu8rWS39o%;4GnwYc&nrSI2H_QZ}kjm2+V8Zu44i^_MrZYEF{qs-^7zbbX><86lLjrDGbYou`=F0=#uPiLElyvw z29%^@?@Px`uY~u~rYujk~(3V?L2}*Dd z?Y?;NqJBLgpF_@?(gzr7ZQXjQVOs-ZuF7&Kq79KFqN%MAdhYvgVjjO=f^7r4-PN!6 z`cx0o8#;8TC>td}lnNscx4E0RAg!)aRpKE@cC{>jJl1Q0@=NM_nt#CYW{x1R9c5Mz zE@?sQZJ1qaX4I%s&5V92Khq_j;Clp8!%}LwCg)fFV#e_?s!{R}dgDLo1(*bWy}dW* zi=*LMoCo-s7~J}9twqIyz?R)}))lB$X?XkweFTyz>RJmkbMwLg=nen5)H6`S z>4Nimump!m+e`9o?L4CjV^s)jx+?x6iggHfMa2t6U|_!S{F(Z514YdxsyJG1WFDEz zo2q+xT)zw)h^+7c2-=`Io}*H;>ogrPU3=_p2baWbpd`MQLN zhrrk$h)vAA6?St@^ixt%5re=e|4YltW?5TD-u#d&PzS)ouClWG36$K)U~ocgT^)$e zNPK&bTX(FXk=-Z;-?8y;Q%Pc!M#+3^X_JtHv+1dCg)d8>xEkAP_VKDlV;w`4KOOuv z-0GJD<0SxhMz6Tlit!87kB(fvaLX1o1_o5H!e0?m8#rGlEHYAj zQUbu6;B)rMyDqWpU&I8C&%yvpLoQ6=V%8+#12_hxWCf?=0l3K0i$|F{a9Ncf3>=Uq}NFEFhDR04I%i3V-wSvQOi%IEfk5iWxl`ek#|-@-MGj0?yg`sFL9W12NxS6<~88XBtgan%8s zf-lg))$BGgn2`4mLoZrgw5>g~d^qu@X*z6hnTrs@!#RTZl`+*nggquaw;;o3AK2G) znF=A41Eyt-!}O*qCdrhNyO- z>pRtUx4xnI{i{zO9VBoN>VS@5I-Ppjj=T5ZfhXk03R_zt&=DgE);&E;Ln4L)A2@KJ zqwCaOtxE3>u>4K^&rlbgBobGH%Ah%+rHoTm;O#?tjRLIKPp{`BD?n?(z%zC*%i=^} zpe)JOQ%?N=fW!qRRkK~hoM&DTx@~;^Rz~xSmq? z2CM_~PfhYC;R{JUH&6sZmMZODTvQ~Gc)^#^rV5yj+op#J6hl3EfMPzNhYO1nI&9su zlq2A$_E1McF-~{<3;n$CTyP{~({+rUM7*RHi*~I>r|5nK=E;e=DJWc*av}*bDgAt?3FB=x%(Z9#2su_HP82*7l`UXfU_jgLf zCi+y~dMc(Z+QV2Q6On(!#AI>Y1k-95x`Xm?2-Cy>8o1nh4AY7+Tn-;30wdUlaLO{U zLzHefb$tj$)cJkrtoAaX1$(E0x_Uv`1rS1TGhxC&Oq+n4i{4mv+`8VFmyY%t>bx!C z4)_xBoB0}g*jnc^*N(3}n*NK+kPB;$$`~DeNwmU((GVkd;NreOfrQ-yp?^C6z4}Y-=f0ev!x`*PbmSL+47`4HMs2~efd;aig`s(d= zo^xn`_|n0Rp5lcNCT9R}QP2TG7c5=xQLceuJ1p}ur9a1_ zQr&0eHo6|3ojpwVq-c{({b+4(5xkX2Uj&^fXqt298J$G3xc(y|j#RJ-@PfL6H!tL?MUnGGt zF>?mbJKS_+T+E<$Lm(4Y(5bXZjn^Sqv^Ze3PAG&NRHsf2LTf^oPZo|~hZl5MKlAJ7 z^$fUU9X^5z18gp9ZPR+XAydrF>X;&Twi zpNN5I!%_8Pzigv!?>t?`Cg7LOtlwl=h@6-$%U_5&91`YU#J!O#h+~y>Lzuu3g?GgC z33VHT)PpzL-}=T87hA;?DY{_cE}#r|0ytp8ycNO%1W8yGK^|hNqC21mGgehng8OUB zJ>gKZ&I{A>>i-fc1G|glGuPEslhmocO}nHV70OUF)}7|Up6fM26R!|30w z;jm#HA+s=O<5JUEW~?O>{SmNkB{m;n-{#o^Db8fVALY)`Ucud2i@w}jaC2tJEHj?TgHxKxM-yRhWn}CJQY_Gx1qVlshKS{URu*mSn^e$7#7V=xM28zCmkz4PlSG0Z^@E*+$?rOI3t$)Va5G0 zh^DdLEIcwAIG?G`ZrbOE{~*=>UPQO) z0+%gW0^!h_Z3ZyB659YXx|ub)dxk=DR(7@!l3|n9p4ig7*S}f-?G7ZBBz>p?v05m? z@+mrvGKpN4`)3aklCRR%e*-rHy9pICg%MG|(80elpStac;(j2qLI*>Y;f%tks3BLD z=ZJ_0@k;#>|KqERvonu~+R?Cn$;it{NffoBlcpZfsRKl^ejL$B%=s$$Ersws#BlSS zidyr03~sACe--nLw0t;YLeHyjPC)@B6Et$%kvEMdFnIjUJEHqCLsicF)R%~u9)#c^tZ;k2kuXK(GK|} zQ`^}X_J^-fY|*!Iy46F|iEWv;K)E1RE4@6{w

YcMixOHrnGi=Wf1{G^IFtbXNc$ zVX36s;Gp*zvO-x$x^%+-EA8YQQVozJM$HkS#f%>zRRc>dbroTf)I-%&C7WMeJNVNY zp_x3PSuk(gw#yo0g>TGjj>nwPBagipTts2Y%LrKPCEO~yO6(U(W1)~cA2~rI+(1Pf zR)92;N5D(kE7xTjnwX7WU(fzWO#EQ}1L+>SdhPhL-fu|{`{Oo|aGe~Lv$qjtHTUe^x0TVPB9`{|oMBG6`5l)*~M&pb0N zf(NsZEo^OdI8BP|a{J}Ww0qf$LvuGmmEgV?);$;%^{wkf?Ed#I=1lE_N($zwlY4Be zU2N-Q!UJbr^nBknIx0BW9fC77weNSgnt~@^cUvubIerQf#A`Xkc6MBnVR)~5iB|)v z2A&^&&j88c--HKhBmuNTETM3DOQr`fJ>u&N_BM`65xkrekHmXMmC15}t#vZGG$SN3 z!Q_$1HZjIs=)AaT&hl)<1EMzQg@Tp5Bj%ft1<-Tv;X*s*o6796nts(*LBt$GrYh6W z+@jk6o+IGjBkSNo?ZlR5HEzPj9azVXMOhyq)UtTV=6^9RHq(pdQ=WJfj!ftuj?kRIW$Wrv)Aw)rjSzLRtsxV)D%a$!@1{wEJ zi_nOfi-$dAd3F^Le(IN(v%+X8&d}G>jLC%S?`Q4~CRke6yjNEYQv;Bn3!ZarUfBNW zFUO9%3O*NnewlY=iBa<^sIk`+bZZGS{!ieO3EA~OrVT*yUD->(H^lW>=}2*$wEjc zTb4EQFU5e*w8kHOAd0AW+c7p9LvPm9rmtO47jWJ{D`XkfnrwZE814uKbbtCNa=19F zjzm$!IdG^|#AKvtu7+cgGm80`^m0^xLJP=I32hP+R)t~6P5k-qOhNj^GpYtB^B+!j$y*u_9=LtwxO)@r) zSwNvJ&I#ZlG2-~2agJO|lQPK!AX1R}ZHrK8P^HQsIE_c_LDMpaQXQ z2uKYz5v`du8j zMhwIgN0I;t2uzY%T*oDy+X1oOBk)3c12H-kpDr^b`vO6;IRrvv5c4oAG_AkDm4t~N zqydrSN!WBDa>717Z~pw%SZb>^p)YH|9RLOY9Q(pz6=nvZrG%Tv;q!%jOSg7=D(Q&Y z1Ao7m7)w6WSJ7t*{371dSeE zQ4yXy4DA+QW6<7FI%5QDK6Bp|?8rGQqs6KO>p(;+5okf8{% zRIu2k7M>1iJoj?W=&@sOXJ;>5C>0U3^egG*gqp9})Xm#jL6mWNX|68R?vM;|@1v0d z98^5zIBdl4^w~{beq`HmVj3VY@FAeMt1i47u^>qb9Dt?j#su6gsOc7=(gsJqjY-L! zOsiR2_LtGQCE_#`P?u_XX@uvc1mkdU3gJt~Qz#dE5PRs&4?QTvfRn)noEyHTBY9h@ z8DSc0Nr5Nkxi&S{Z$|CpG!?fdmPSU5u7-YUBehKeNr5IAOQAUAz}_M>I9S5JL6YGC z>dLlV#Q^APS46AW>y*xNNWf$$s-@F@ln!x5tx` z{Obk>-OGbCY`jBtGRNPZDiF$qF_y$aj)KKbtza%U7=W`uPc2 zz5uDJBw}0+`)@zJ6bzZY%~9k~;;NPQq%HP}!s;`o?0$MYhHnteDHA80Vp=|NpnaDvRxAc)4bF)(10fRA zbxYF(MR@4HD^CS^s_MUR9l^T?&M@^;eMs8 zr}NCs?TT*+#8DhMS6nQIR-bZ@x47o|l<&iObnkxH&+iU9>yfn@LSIhzokoCFb?Hbi z3S=h|G^nyTP>N$oD(p9D0TI9!>VzvkAXH%LhFP2xElbR8PPH9bn&zF-^0!4vPN=YD zp0yDfjSP$-xi;x1&O{#Aj@PedWw?u6Mxh}DxWKNP;Z~f?GE7{-o8z}!BUB6H3FYVO z#2n4B$CiP!E4K~2ed|_7^W?&SiZ^c-tH>OxFqf-1@8v{W+$wq9Wr~t2*op#!==IXl_*RD+GbQA^( z(Z?P3^}S6ySeElWF%{X%2ASTidqbX4JPxLJ62fDDl`E6dAD^A4C+Y$Z$WQJY9QSV^)AqDkZfRRp_qgV@uT0RyMQT4%pF^( z(ALm#wA}O2`F}}7oj(2#iD;BI!Bi|wA4UJl<>U@=V%M68McrE6Jp3DZIRSBmVoe*E zlfF%mJYWsPTTzN(n;DG=j{20uzkr4k_eU3mzLb|3Hy4ohgvAzHJ8UzvsZL)>Rt8QI zV`Ky&L$@#X4WE<9h&GP1LNT`HQ;bmz)y@j?o~ZU28rX*)7Pb&>eD--G8S`laXYUs< zlEF+Q$P<6&Wl$jyJx!PHiuy9dU+`7_7@u>UfE5QdQnRjb0&K^Kn|wV)Wi)l9^zV85Ec| zgdS`t0&I5fPv(bN6m*rOutFEIPf=L~?h>Eg^apX6Z3w z++Vj<;nrFz`B%>v$>eRpsiK89Ub5c78$*+?{!gXe8?0O=-uu)=oK5RRe`~nJ>RRQG z@Z**r5bns#d8*_p9MXql%29nnH4fVN;%#_P>VtqaxZIFxf97)2R?w$RG%pAj;RV?3p& zAFVkvY-fzFl5m59i-9>)eTefJNeE1)c5>-X(+Q_Sfd{1yxHSXk3jYC`E0!H$8JpN& zH|?f7PX7ntG?-~J(eL@QXDQCL7f!aAK6R`SrYz{-(E4{)xBQ)Bm&TW^d!LztB+-4k z><Bj*c8BwTOzUsA!el^xztn44J^6^~S+|1&$=f)}N zIMnMe7;Dsg_RlMgq9U3zweV-g*~Mv`c>RwYF>s7kzM;D9$~B+YEatFPKXKw1aTTY7 zn2H6`74FvDgvQ{kc9%ZiJ-wm|YEyL!#udCwH+)#X+<)tnpd1MEEDia_+mU~Cm#QD) z0fUsfAF!&kJTySVTRTFId8&%!8W7ouR+o4=08xJs;7wb%a++$!!LF*^JMdRCLVhi7 zy@}c<5=lDFMnPyIQ$Pm5K?ohF+XQsOdt7*S?7W9(^rNux+(Od{l6YjZnT+|yf3$W( zE?l}a;+w;QaQ*h(D|WXjD@>3F1EEt`{%MofLk)u{1HU46UgX+q4Z7z(i+uBCuU+GEH^UwIo>fXryF1Erb%5AH){5S$E&tE zeP`rxcd7NIX$J_RLx-kYY~6}Bx$pfaIoX^G!g@ylv5Uc98k0*v2Ez4~+g@CL@ulJX z6_%FF@<{4?E;}b@DBU9Y-|6ioMJ;>HO_Zk|&tAJlxTg(hNd5-|A9chucFx(yvYqVT zHCq>^MZ|V#=fFwB423P+_Pi$kQ$R=iDZ@vO%n4qfb6nYuF&?eE=Qs|F`KUAElF713 zr{Xfl>NIz(DV*b@NS#-{)y@2nasS4Itm6fy1@&)cztg#wZ+Rl1qeVbXP0HC^>$2AE zi1B7NxyG?Z_0N8YaT%CQZ{WP8RYP5{6JyPJw`Nz(reCW%bm$;-0nvtglvf2u+1Y?! zn8uFysTnt-v6f?Syn(!~>en0OGshooOwYuv*hn*Gg6fKI>=Ec9$q%4U>`$y zPTJgg@xr|G>VT6WjW5xVcBBOU2RI^%oKEd@w+m9(hYSIcnQk}zmv8Oo{*AvGLODVN zjg)#_ho8V6?#)-XK1Yt_KIYrWCu%N}c310ndAHnz`o(#O!#1AInMFHv4Giu8*OY6V zA8e@pd}mXalT^w2C4fmmSJVdO?EItTqhmyt)yZCFYL|3X@239Bs>|jvgvbBT&w(|A zSJ@;!WbZGtIVDk=@`=9Ri<%KkrEK>oodaH8E($$m)-lYABMwAWBF+$GqNPawMw4&Y zW%jnVIWdk(oH?q%v1_+{eZZ4|4B?>dsDTBtkFzS{=>o@08Yg}0VDuS-LBORHt)RPy zexDgC%T{x`w<+Uf(ZG3Tnl7WvWOg-oUa2NXs$Dkiq@`8An=l6AWJ}Yu3C4U5K4>vn z8%kYniV?62Fb9)PqFogdK$19|C+Z{hF%XP2(EwgBdf91Zwjd6l3+e_d`CAlEu&Ixye^fxrb%Xs)CokiJ2i;8^qS$jt<-#@RF*2E7OMjpxf6^SsB`v z_f+__>N@JkX8H+7ERsdm9zHj{3V17U& zDvCWSm`<1Me(N&#sr377@?&tLdVWs3__$)5Z{idKG@W0H&?}@;w!%Dtly#JV(qjkb zb%gJH4L+n!`RLzkO8&@k?UG&^XQG2b>^Se?6{PS8Bwu1;^h^u$(ZWKwf)Qpjqg+ai+diVXwQbT41wFIxxj(eN@Q)H3!U6 zR$Um9qH5l1q;s=%%C}Y1+zu%9bJnyxwj#UYWKQGB&8b$$3TvPJ9IBqAznufiGBY#t zX*2i6{ak)(yM;sid$@!0w{IiRs?+OcBs^cAY|93{?DQ?d+_AKEdgJ*?P|+cPNu0$t zo0d9Ccl;I35u<-D02nR66PZ5j8-LA2SM4=x*2qnDb>3Z63>fkl)lu}-Z0ck=PUxU{ zh$4vDc*{mAhlhtlxazyQUdP58PT;{ayG&b4D;FTi@AT<7`liYK52>$vstahw6n9^u zQ4Oj~PEOit!x;5*Mlql@WgkBd=e66+YI(yYcvgFfq@b*{Gz3l~isF%t7r=_WhzNpj zi=yQ2VVS3uCr%JJdNhLaL75XF$cnxkyC*J!g_fF|qyfHduD<&&C$t+o2o;GL>SdwIRSWM z!%M8=q@?bB`oxgeRVGYWLYU*E^S#&$G+e+?e>S>mX6NYFKByq-I#lLsQ8MRamMW(q zjcw{*pe~PBi&7z+0mV`D2~53yM5(LTSpO=6!aFbRyZ>BHtf$3`A@GZHLmyZsA`%Ft zo@xXt7WWJ2EiQnD&>FFocSEB6$esshqw#qRVbr~U|2Uq#_-vKo!wbOk5G*Rtb1IJ* z5jThPDL?NhxE6uLTX*TwlS1**sqX|`jyyBK8HDI58t9v_uoiryi^B-yE2gRT;g|pZ z90&e72mI$TM?DO@@;nZ6(_#U_z+MRbY3a=se4P3AkLtrg+K?}ZhmCtVk|h2PdNQAa zES?o;{OdvSx^aB_JRj=4Q6{lZ_R4Kvmdsh6;^&AIdh6H6asKHD_*qC}#z`y%n=z!x zv32m|QS0%_%S%i3LT%S-sG#6gQBu;SM_D!cezdk1$T@FL2d?bU?g4acss#^S56`xh zlK6k^EhBNaxlr=44$%<}t{NV$8DI;KdCmn0Vwp8+pkn;${d=())&lm44MDOIQd;Hl zgr$;Os2QJk_Vl)6fdnG^jcYz)>vEZ47JED&Q1VUnW{&Y+GAL)m77<5BFfP|xlM z7igvsu->7NC}h>2A?>L$8GnecmQjr1)+@`<@#{G|UuB;286gAB95eq{^7i%Dp8VJ-d3GCA@jGj~ z5{}8{SxSNc%9&_A;ra>%Ew{$+0pKCuDGQ^?F@(NcaU`1Ro5uKt4Th$s(I7`EbQND2 zZ{7TkFD8xnJhWV_r+0)mNcdMEA&@s7CCG$jtd71Y6V?^l% zbYjAfOi6_U?14x2{f^5IEgw^KsQP`}{tUEQIn=|{>cN%a67j#tJOE7xM47d9bv7WY zHYA8}7v##JJiKUfpxl_%`+)gF@OecdAWj(P^AdKp@ysS)#{YW^w%n?NE#+@LH zhC>YW=+!H0-8j_&1E!HTj0k1N)z+TjlcG{mo_4jll9Dp2Pala*d#UliFTep~(4|#F zwmNnCv7HIk=Sh96whE>8-`t+3Y??`(s=aXG6DVjhz%Vq|vuDkM#oS~#V&OJ?zb@Yk zj5#>aA8kcE>*GGB^^$sWsaRG0H*N3BGZX3nai#cGiKUr2Ie)h*Do;$rNmam@8IjY0 zwK~8i6Fmv<{NlN-8F#{P$&yGaM2#QcBoc!;H#&)noz^eGwQ-xjpC7>FJhFOP{3^Je z=x64-y1}?s!_S`0B5xpsy^I7oo}@EaQBjHUmqH%|?9wlt?WZznk|{A6^yc@&FR^ zA$#YRP{61$y5}0_T-Bjc?Pmu-$M{)8mcLlhFo+Wm1x|8^#_4|slWUF=WewOxS&6;7%p=7LqnId4xAwQbKgK zRcq;(hlQr_hm7ReUKWy8-q;+CZ@P`xBc>Cat|_hssqAsfPOFY1B5T<4s)Gj2gdoqQ zdLFC=gCp`F9z~U1B|bHfr?wmtG6{|Whui>g@4a%XQhj{7F-S=p3Z0_nvP=CXhAEYQ z{v6L(7f$%bK|T$LZ0myuBf4BP>Dxu(>FwS}JTdo4ui@Bz6uWfsRw)72iegC{7Cj-T z+C4o#-RB}Ek)n@VO=69b_=~*jq+~*44CtTV@#B^4QfAJa$&ORex{R3_eZ{a758oc^ z%ZQ1H*RNMD<6xJ2E!Hze&}3LoK4I>$j};ZhA(oel)*X#e?b=R~Kl|BpDRB{zgHCU& zRMrxDiI{aGm6i1XzWwbeg$}*sT==0{+wfU`t}_(`uA;K4YRs)4l(uV$m30u&TTmIO zc*kaJxD9U-P2qtLN_V&ZAc_0Xmj7qRSy%)sDo>emE%V2tM~}2it10hMm&A7{$+X(Z zHD9@IX&%7ZO7i?=(V<-{k_@V-sj4dE2Lc8 zi_0bMqh&U>6gQze7Xnm8Qc#Ry{#2Jy?s$ z8F^4ZDj$}cnr2QKB5{{Xx9K20Lz3T>4#Wsy_7<8q4r?>M5>%b1Na>MUrCGjaerB(W z8mdc^X=?VZn#!o?A{%b-VuNZ%g}@5}OYH zK1eYvtvjiUp!Xd+IvtNbI;Pz&6v0WTX|8>_CCyMU`^T9Sdbna{f-mR#`ASX(15$Z3ke{Q;>nUOly6k9e-I#ZEh^MMqA z`~SoYKHp+qt7pHzhX0%SPw?fpy}SLhP$ZHYhufw6-rW50o>_mg3BMhs_|FO@^eCi0 z`N1EF|9RfANvZ@#NSfj~H-di8{}QV+3J#g@8MV9Xlp>;8jPs)TLwt$4dc9}mPB#~$+^-uiw_y3v6_>=-33nSEXU~q4zS=dp`$cMz){z^*)}>ORQWOC?tG?X6tT?iw zgOA29@MbB{R2&xc@U!>HrU;EcdG#bGsUi~_jj4jt-`Dr{oh!DFMVLtl$6K5{q;8FG z%f(dGt?vCy7W!Ij+*Zak9;sF}SrVUA?!I3w+2l7%Ya(=f;u*$@EqVb4eEyOpD4)Fc z?+++-u1}c%{=k}r3HSWZt2ydc=)d2il!I9>{`-UMz5o9Y{{LC}HyZx0(9o&$q3NHV zPIYs4UlAbs&)edLF==gv$tWm>l;s7oM)kcLCYApak1sXDSTCvgu{3&c_Z94rb6whMNtfi|-{9|L1Kz(kc?u`9o7vC3llu zL|R*0dA z#Otv5=60S6gZXH&uG>mc^)f&Ezju&?+(GBOo!ik;jw*93os=;C;!vKl+b_Qx|L40% ztu?b>y}BT9_IHPYIK(mG-&yF<^ChUs$Hu`iKi*%1G5(1=iIx^WKG+xyr{r7a`0u3} z;8Lo{rS^Y3n|GazJ2525FDZ%0O8C!MQgM;7VER0|`y{b{e{H&(AxwIX z^V9#ljkTKqriG20J6Hd7J9c?vgZjX=Z^vQo3qix_(aIn{yMagYLSA*XIvN_bYXlm7Z;6_lM{w$>AhrJ(<{Z^@Nthkk&hY}9nDEOS$(!ZIS6x|lk8@ZV2Ylo zFPJh4gV=jN^*4J`xrOnQYe0OeQr=?oE3~7%67M3Tj__f3-Z;9NQ)I>W#7SNi_$;_C zFE4-7wr+5ov_16DD{0tI2&dqAAjgiz+`}5`CV!zEe}QtD30u_9P-DZ~fOzKUGW_jO zfbPZ>)Vs8%CVhGSEnh6ZPp%z@jU}@k5i7L|$%8kV{&(!BBcP{)Ejf1Ku{Ks!zodb*C&y2zP^?Ps{ld(W-N_zRxT z+l5abc(adEI0yRr<2nY|JT67w?EG;3yE*4)riq$cS;nDHZQ;fYcoj%(FJZPS1mIDR z95kJIIyyKk{(f)WSU5}Se{+z-adTQ&V5f)O?a!}(=w8#i=2e3%Zy%dY)Hyy|BK+$!_11I?!bjrN96w({ipooK5fZjuhUj1{KOY|&1$^`e*rIZB za&{C8i6uOa%TZMBt8DW-t`qJX4boXkv7DD%S))3QD{N;a)_#;rM(}S3Hg1Jk>+IWJ z&`Hp;!H~WCm2XIU*Km84sUOEjL7YqFN7%*JW#suP6ETuhl4-(ug!!w(`;vXC^$J!@ zkGN^Ya#e4Jsu25Ts9wxC#=i8+ELsF#jQVU;#Gk#|kR+V^R&G_vk)B1wYtp~o=I>^g zD`w3<%q+Py6~q~J;Vlc?N7iqjCNxf>?WrQNtC8_0aodWBii#%iITtq`_F7x)Ef3E& zW-HJyR*vcou1|d28!quuy-Lg&7ghVcs_5(2CllUhCr9hfO$Cr*qz|UNg{Yrg7|cye z6MoNS9b;*KuYLDdeXA^fNLz*7yfl+`m29VR+2mmDZDIO(nO9izkNnC?p3NAHOg``Xji_G+%hCt{_>XgXduEX6Czgg`Dk&{?qQ)$trGde7ya_yN6HgWRuY7~Pcu)kQ46Ny z`zCwd7nmeE_c26P6sPsM_ z9!pjU4{_ZLOt>qV=F^UT)#x=w=g#W^8$E0w6`s>~Y8u2LMHs~P$UAMS4^xpMWk>M?(4sK9K)@V?kVM!(3f@3SLVRH4hSbGMx}1p@B-i%U5vBTUsl)1MdDns)sz zciDPcq}QMoA#_@^-f*C&>wU7Pyj>0-bEgY0v&E<6)hDw+Ruyaxoo&gB{vJG7r2Zj_ zbfVWu#AIk{sWHjwX+o0=Ft96sckewVQDl7+NE*!NPspZhJFfCG$j4`_(f8UVtRRhD zolg&m3c_s*2j1NLE%xh`03mUxRhX8^OY<*7i}wBmewW)x`;ux)swi2+SbGL+e)W84 z<_KjML4$#yNW>x2K#qYmgz}w}oqcD*bs=dsoScekq{RE=`Me#Ez-BYrf~AdTt(KNn zg-JK@$!37i&^38}VG`I5*y#gueEKIP5LH{9uDzLxax$&1s@~x%!E{8T#esm z!>`OeXf$%w?t}_@J53u9pd(|AYr&+=j^8*&O5>#WnI{xEub=J1uok;ZgJZS!Ilp`2 z?Z5sWd6zZPo!-!(Yu$L5{Un(`&voaw+)^Jpjcala0J0xdMY4C4Hi+k4nA`de80F7NkjUKk8np@yL===%~3 z7OF5TB{@$jlK9tcwUc+Oq5V2;to!&8DP@p4bd|M;6yJ3kJGA0(EzZa4k9^!{lp(nw z`}+T_g8h1`TAv$vlWR3kXyZ8zHB%DDn}dvw;pwy)47&nVEUQYpmOath$;GNF4yB(C zm1RqDzwg*BvsA1Ydwn(OD_6_wf5STbhBf+$hV)(8tamYFGuhudOOGvxaH>qgeXk6t zJzG0ASX3CF>H4&X2jkCW`4ng#(>=fYcc<@u(vy{{aVv7?&;?gs*X>NZ+MnVq@pH$G zlkOV==Qa6Y!r5fJikFwy0YT5S)Q4Yq^kd=9#x1LtwmPUsp>E|sVmwUuVty&}>_axj z^2;6E^Sq6Lm27v&{>iUC=aon5X}$W|0RES~i>meX3b`(Zm3KwC%lfX0_}wU#R-z9J z7wTA%6@@_J%wpusvUnxJDf@V6UEAU@3GGc$CT^R;T&Z%)Fg3>SYC|7t)EX47lCU1z zoFGxZ{F?P?!rtEAl6uoobPS7r@z<|kZ9C?6T-ScqD#w`U4iU;hsd8JdUD*9@6tR^3 z-s;=Q!Bhz#%Dw&lWxpGG{m300Z!~%TJVS+a%r394Mj4Xudi>d>YZ5|T8}08;?S0P` zG5(n*xT;>PPaLU0j`*gnZm%$}rYvXaQ)dG!TKWt&g_{`kPt&4(kZY=(Bmh|s} zWtQ5uzlBs&6pk=~ z%a*wcBk|tx)S2GAoo0c0iJFW|cg<|qd|6#x-O$ibW_EV=70Qna^kx8X-F62g_oiRt zEdw)B)Yg6vAS2mxUsGV~^EItHhrEZ@lZ8C?U-htBSg|=dIC4u%6*n4>*G(GaQP+&d ztH#F0mIZKn9wa)e$I?Xk2YYcEZ#ug5Q%>NzbrGe1NL$5V_?U5UKUu{VO-}8r0hy9$ zI@xWN`=kjLEh1flvtAYaN-7OdxWX;JlyW%fJ9gjr&KCb)O28I|aryGzazP10ysX9A zSmnZtM0Mua;faYN2VQ|RYb!s)T;-f6OPzO9RJ^^L1o!gf^J;4~m4>k0&CDJ*G&GFW z*k&l@4e>-6X~rn!MFF^TGPlM@p=5)CZ{$B~9_+jzpJP}2np)HzQeMJ4uQBa7L=tELX7}h|%2Ca$qEHW! zu_Bc)>B;jSWhM(RWY_A7fq7LrEGcQmIJV4U2&V#_ZP@wBM@B~WZELn8`tj{3_>#R- z>A0eXAa48LJv`PVhT~N*SlC2#O_C^-jrk{qu2{6B#RwmNWghvv_Qg+dU6#qWRp>7> zxTkeRKceGO$s^;|`T9UQ90I0dD6t9>(Qgcy9~D`$ud`mfE^5!riZh~D!y!sMI6BzCtx05=h9tlg>&nE@n>Rb(AhDDysXP@cb*!$PPaa4$i%3X*m};?eVI4 z?r?~l-F{KLr3~tmT(v@tG&-3Wgg*@9aQ(DtG17?1YHycF;&-+Cv~d;cIfc+0Hw>L5 zvd#Ro*9Gr*)H#xPN4qGj z>bEgPC8uWBLk+tZ%538#SBNCm$NeeT$IgW&n_5WtQnflGEw3+g^79uG-B(NG3eB~p zkj!@dRf)~mtt2TKAh;9XXExR7>9&*=Tj73S#rg1|#bmu}9c zcg$|{Tf=~xvvxf7YjvJfS*F zh5q_nU2$Y*CSj16?(bJW{Qjo`WWpu{&J~%7=l!SE;>8R81&vl#W6cS_7AGGzEu$pr`}u_Q^l>c>|rzh+Wg5M!UiFcz&y3eO~W8*>TTRJB%c0< zlHUMS1Y-ihVCoF5^|hkcULlY+4xn>}m@|18~hjUl`SM zFIume#VyjVej*?sz-u=bnCx|AelmAgXyATHeL5oXAX|$+X5+YPVaLMEEH3H*$KWY8 zv6dvI&7^L9@Qr1$rh?g%;_w62>XYIle@~+Bfp5~4&1ot@WK#Or-5gPJ+7{2tBtQAr z#t&pg6S9e3xtnhn$Twgo9i(xcS10HbtBT9L=kga~gZ^10YADmGBL;2|Pp~{g*>dma zT$3kV7bqKczsVdGG#wSN%^H=)5i@EaBzWqe&-EwVkGj66>eT6eHJucm(BBV84!v}h z*sR6pl2)Zf^zYvHIdH>EP(g$?N;Bz0>4`&@7Z+>(a^Xz-Kx(J}cyi^y|H2)#g$X}k zmdO{aZ@=IkQ6C68&CL-_<0pG~y`Y;>_r)T9IZkiy_k__^GrjVRLruw@gpAFbL?IXb zYmDfvB*(>i>X*sHI-ar>0nzA=VN!k&UwBS;|0#JPO`mgwN&Ml0N{~FQ>bE2+D=Kn9 z_vsTjNCaf}l`Q4)?FtY_8urJYGsJc;@LPeT)6LRUsIKQKE)&Zv@LUS?vFsNQ3uNzP z3>T)M$%#VJeru8K&U)IDw8<{p>nhZ6Ct|?q$Inq zrlZ;B`B21?l9GbbB{ z&DhFLqDi?ABa8j;I*xVcA+icoaTPc5^H(vj?ojZONOOOy{~b4`oz4(&iK*)MGm6T@ z(h8+pYFDY!EfAFog)$`v$Yh`ygTzYZ^U?gA97(8Ah z(s$lLw#XKQPK5b9OY^RGf15cj4%`>C9c%zL)dp z^IbuZU;4N9UBC8dwjY^haZ(joHXnaGQH8$-&J{-(7|vko|op&sp-R ze$G)H`<5(x3=E9j0{s)|orS);p-?{v`1N_?3&dJPt%t_bKCO`EKTZ_dk_0WVV45awdvCs4Ouw*uK0fC`86 z`cK=A5r%teC3-~-?gtRl02f?;mTtLtWGe1KB}=udrC=g``GVw6x>z? zB#AY+R~I*(x-se1|0$bdd3p8Ug7L2oR{VK~89PgaN5NTNTvGny^18iaVRbs>T2XO* zI(3E^sC|vW(Lw5basES5WkZuQxfz_<`-K_dYLfQvDLFsO(LK$0B^udpsC4On)U>{j zQMXw&i$9-dA{)+|p>cQo4FQ4Kiky&Ow<(?!a?yM}6 zpQhihDFOuCAGa=m3bXUO7m`XnK_;qTGc1Q4=TUvXmS|v0m-j{b%%*w4rfnNOChDyaQUX&>*6E zSpFyz2b=*E7zu!Oa%&{J*8#p{){wejV7FzByT^L%D<2CcKuYz4C3+WbyD?Rm;geP` zN7pQ^O?;+u4uY6_oLt|R%^cfR_o%c3{=tED+%2DgNca-4N0}#Rl^F+7d29-M9(hQ2AWE#UTN$G%6zUYXi9kX{u>T*bR=7WUk0L`}4E>?RR=RIsEBv*sKwd-A!O zy_bw(O6s+NATH45**!n9K~k9GpH0J) z-l@M~2?+^z=4((de`Kus^G;G=NvfS!lciFb=kUOa;aA+Q(|H1##u6rBYi)x{ru$Ki`s_~!(yrkN z&j6gDw{IKLmagZvL?>|Y)Bfn^f?y8h)+e7{TtKOpmys`P=vRDJT63z`+EOU=9o}qF z&m*+Bb(KjoJ8eYbe!i1gfj=Hocv)DL5-m=a934fB<~h!smX;*3y<`Rjf313|*nzj` z)A^UeJy$sI7E`MS`1MczrS76Fqf*L>$P^OFngkNRhyD2 z`I@qONJh5tb^gqm>_}VD&Ny-J08IwWi$qwLYKse?#~^k~@f_G4Fr!d|8UIl%?Cr~A z7&Yw_OV-xbRMpjE5lj;v9)2(3=1aGmp*23Y34^3+@yY$uR2Z^U7&xz#U$n{d4+yCA zJa#g9K#GVPNV6np%=He zjO>zcp2{bc2d4Qqtr!T{O_VlY=Kn7Y+H0cfaq(IkvYE1zSL%?0b3LL1;kJ6aEAQXG zN66XA;y?x{=M7WL}e}as41`4uGr8l8q^ue6*|<{<)?+gVxPR_tamOS7w$UaLe05M>sE7s= z(MCW#UP||lG0{YbES2Z3A}}l^sP`zMux3?X=)EuBh89PwKh6WWk-V1qt0Ly9(=ha+ z4pDJQcilZacaVmO?x$_j>Ca22#?`6_gQV)dz@KdXI6f+iZf8d8!QE^+BnsaFad|II z$H@6P1OH-;M)<7R)=Zm)wRMg)Q8rGK^95852XuY_p|dpoEz@(ICptMyIjda3CwJ!mt$sNbGW?_d-=w)$-}_#wc);v&FU>`a^ex4yAwt*IJ`BV?R2dbIlks za&nNhbzb?<4B6ZpIu??YXmo)Kp^25bOfXu> z*8x0oRZ3T6^5W9`#Z>kTN=FFqKo@Q|sJUVmiP6~XygVsr37o5yNVC<#(o&#c`6jk# z!=ITDSp2$Q{^Z8vv8Qh{3`w*aJ!)YfdtLWS%m5|=lj)sr#6hv63_)OI*C3G=rPB{^ z|Cw9sAg?LuexFxh@xK1PYN4;{NkBr49MmE{cjL)Df+&8vTEKYG_RJYTVB`A$7pj{Pu6#z#%G&b z%(jOeO&&Dn0J3|}da*_tUjl_<75yWe3-T9j&VAl*+9PkN)H{xJ_HbRhVkHVFv2GCX zYh-h9&6+7{tE_!6ej;HKxRHp_IZbbA7N7TUT4i$FgLoF@-9Af^@!vo8qyRMJbVztv-IN-ith75pKGnga)9B%6wXYu;V z%3zvk002Oad#VJSL1H41P)9>p8goIJS^Ubkkyv4bmWv0M&3y+f3RH=KB_s5RbKa9#<55Lp4w9fF@GFjM1nSYRo z(UfkJr4#I5NYi0nnZ5u$uUP0XudNMlZhp|x)*k-(Q|G^#E!GO@^8;-Vgsx}G@asHi z{{rwsK*EFgo=XvkCVMh#BlL6AE6erPD1OnZGf#LwfuO$F(hO?l*!n)VEIxu)xiaj69hGbAG{ zpu_1)5J!xNe>EIgN>Us3JK>-o#V~0*so5_B(L{RrOiWBb3l{jpH;&!@Zgo^zPYLQe zPdFl=@!r${QchJFh$f&}1I=tBy}_|Dh7McM5Q+TLLZ$LIslcI8-E?B<=wD_@|0!J@KQ^B9}ON#B7jl&hW1Di=%FqQr>^N^31)6 z!U_?AU`BE-EB=+k^>r%{@MZ7VPku-(D3FmCJj@&^)-8a}AJP;oX*#W&beY8=3K5T% z&MNnkzxz%qKKtIN<6WjuZl~3_#+{@M=&DOa>bd;7#H3TBP(A6kVnR)hXkw^GNw*2F zSbqN?oGmpweP8$oj$`_is`FI543jE{3WX)3uC|r=j11GT8^74A*7Pb!4|h}xoIXT_ zl1sNS{&+Wt77o?`pIL6LdY96%@p0&po!91n)(8r~aL~284jq)vxfvO=g$wTP?j|Jd zn%!KU{TtqA?hPmV|_7wPPF z&2Pt@0DHY1ipstKX=^CRMDxa9Bb-4N>?{O&DAaxA%6H?A--%+;KT?v3x!2n}bn&ue z$O3Fv!abMA?LBWX2J>oMrHJsZwSh^anM00_FzCM&o4I!&LvsGO5eSsA<}+^@5M3UZ zYOMMU2ZV)%K}?|OVU)%Q-|)(U5T zLZ9>KozUUCZr+D4gKh%X>(TO}0ikecLR-<o3Y_6uEQ$io>Em)PG#% zeB0zHCu$+BsRcmaP#cgymbhg&ua;3)W`2w4Ei9@?wiO=%Dg-O0>VeM)v{j;rj^VK} z-gT1hGGon=OR)-L9}HhNLQ{5GQt0Td7hwLSXm!1T*$AOx7VpFEqfa*)Q=x2?>nZd7 zo<}EuhAq^rAW*`8l!u?h_jyRbZW*P6@MuE@t+RJ7%KoEe3=in3cevf>lm!&)kNx$D0?*@pbMPA= zYP-i&tRaa}jDYNILSUy1*RdA(pX8}TnrI&F<_Hx*WJAP)s;T$wpz%OJ;CQvX?(p~f z4jfvL3-QruyLojPM;-UR&_!Z`!H~qhD`esYtvXH*W(9fTR@2%?0jeCC9+M6U~1K8^jXrF9wM}~v6Mvs=&oASr4 zn{*9HEZ}at=IxHwti21A@;KI?-;WOVp&@a0&AkdHtD}+X#w^H0&ON8lUpd*+KdVHb z=0FF!jVpAYQ=k0P#{g(|NV`agp2nfE>A35_>9QD+Px%DL1=`1kqIqP3Q4B4<1(dR_ z3cQBEwbdGUmd$KAs(&c*8iuRzb9|O-qnr&caDtAX?6hk#$n=PuJTfw3`=03HyD)^a z-q_gu)%rkAIfR%=iJvNVmYY_9!h)Dd>vk(EVxVEg?#nm$Uimy0DF|jD(9+5X08s+2 z0Gb$5;dh+v1yf=-j=`jn&OrN>NUSG`PaTm1L0h}y!H9YnfB?8m&}=%wDFKjr(A!Z7 z<6GojUvz28ne`;1+;E1hGu)Y&^U5dZDUV7gPC6A{v;olZ+nuG@y`5sixRgZ$gfeSP zPbzwpeyV&5B9p#58#7atCXPN^pb6a?fQMjSt!gV+{p?GKXvVDf{CNSwBwYB5 z5h)L96BrUG*-b${v#_!n0SgibOh$WqJ6oT=`&y;j^sCDby_};6CX7sf^DB&NQUR1e zC@^0SKOTbF4Lo6x2(IDMN@qnPX*H2Z%)!ZNIW2%n=|Ozr;`n9O&hv$%=uiZC{@ap6 zL(T(Q-!u*#-27Lf*ZC6{ogM9(m94(34-~2LqC=gBa&d}2s__8lUJ?f+DP?y~n?+c? zk{@ckY-3Y5e~EQ7@$9R<;Y~#Qk3*u<7$hF0Je6~_{m36HA9} z`^h1Q62*Y%!3TAhV@fG6)B7mLTS;AgH16d2Na27eo`8c?x4?xs{_|=Nzy_=iB!hpR zKiu@lv;IEVnW)|1%FBr_K*jiHcs}~mTa%bBJ$h>&8Ad6kpKKgWJlU6+oK%+HI98;# zDOROvt>Lpr2ggf)#-^j#$87E=K?fJ2I2zzf{ z_D%)Dh2$~8ers4tkk>L`E2#tg1BIDn#{(>H;Ms7T@;q1qZ3y5HG(jxP%@vJ|W_i51 zMq@N|K+6ZE>*(s&Xqt<0hv)0Y*v-2_POJV7nr0uX)02gTuqcmoA!j?(PpP(r#HcY0 z=TrPNb7xC?Z6f`nqG-R6U1{wD%}Q=Vo8nKlsL=P)yo!r&LgP82i|fYv_;g5R2UTvp z%{|~??MAw<)8CBCHBHKY*b9P!h`1sIjutbF2n%D;|;=I#S zFHaC58mBilpO)rYd#-3dyF`FgNkp#k!8GuvLGtqhA=T*uTy~RP*n{a5MP zvm9J1{#@8f^3vYfTvHy(l$4Z6$G&fzC0&DYnfh#t+HrSrfbICot(Wo0wzknTq@V9@ zbi?r2!>(J-!@$eI;NQb`14V{*7$-}bL{&iLV(ksZc^Yv~$^@mDbJe&u-eR-=MZrB2 z@nPIjdY8wavD+*~W282bLV?=*%^hB4HIYyKclt6I8x~9g2p|K4VRaCZ0KxZaA5I&H zDrSW6LtR2rA~cutoawPhp$!KYhCI)yfiA!-DilZokZivKner{h}G`*E6zfZ8FwtwcwG=W zs|8%(Fet~>S=Dj&=i3gy=K|l=T-W`u zJzJBZJ%i}zUolA}s`S8B*VXj>v+%&Sbdg-lZ<9o`psZy}y>>NTLy6u@N_$Y(*5k?+ z@A1xO@6@AxZQJ38*1H8zQfM$h)+$ECMkJgJEWpn(ZuLtjUg&gIXcvqMVL#;YFZ8_l-)OyI6;GUBNTn|o+y~cL z=e8S<{5|Hk8{GoZJKBOvg2|aO=8n?3hL4F@-mLiD(EUXt<$sfoLfQWPnuXu%44(Mh zlvXIG(8wnZiP4be_9q-h`G^D@#rN#s)~JBe2o;9cZ8sNqge1u;^A>Pcyv&Q0&Z>ZZ zFo-V>yq*Ik)t1`Y)mEyE#LCLbgFGGQy)bada+*$oGK6{SC22TPMn2n8fFDw46OTiv zKkiMM_jl#94<)A_6}|JG^D>IB7qz}jAEhx^(Tu8BOkH)nqS=bs9W|ElqSw4^cw`RR zM@6;0;lE8NOa@~RJCU|@A}Rl8di%JbJ8qK~lsh@(K(v7YsW7OX+hjmTZQccStbT5k z%s&m%%}%&0z>?k7^1kpNqmz@xC7x@~(FvNdB@wPqD1X~wEkLlaSoy;=zK8FG( zxKpCL-O1?1gj;O})WKeJ6scWgOj2a_hG8;`DZ^pJgF>_@Y`FR6tl5)yMLeY1mSI(8 z=I)v14nOlAzA0udozsZo(UBqy@_qQ?JI&y2Mv)Wl@Qk*Q8wFtVDb*+h!pL|&o%g2@ zE1~|`o<6iq8aKMj7(voq{uMy2#!pppu#3_`n7-@h2@E?u=cTX<5mkWl@BI%@h`+H8^l0 z+eLAO<(LIeU7D;i>C8J{|>(ix4u?pfPbWeNH!*Q5*ZN6K$?jw=q`Ox0!p5PS)n zvD=ztQRPoar0KY@h{0ERXc32h346FXZS}slMDrV#OWUt=6)SFty%Je#)W;#IH{kHt z{M&hjG}ElN2Rf7E2KiY7ig!#TRB_C;nZl|P$YsGAcQn?WOcD6Rs?YTiAfOIPDDw0rN##A7JOtEde0zX{C0LBY2?fbZO6 z5iME~##iW#gF+SSKo7p@?>x)iYwEv`oPXK|Amxlnt0H%D@FHqRlf?h1+WVMmZ+AEJ z$5{>_2=EHN^Y{0!@ILbb_bw=|(b9BDf}UDPe;=IbjvxUNNTb*>4bflLUG-7$lg@og zr%*}}I-z!OqYJzgxleyYsQV$0YuK=(U2-ADXgr*mYz1iP`_s(|4m&*IEZNt%W!BGpI z7t-29yhHj5XB!KY8G6iePn+Iq&JS?nV0*rZ~cVcIiLCO%N(aZjOireIFG?cCCvRu`6k zJ^f88G5sH5dLc|AUx~fb?+Y1Ok)Nb=ahE)>Ti+N-fq3lio9A#VU(M`soQ3RnFoj9q zWy+e(P9RG+?eF|<#^TRjKxQ%ixBq4GM75;Eo8hi~)xmASmjE(AoPv(vwjsrGyQ411 zJQ|V_RKu_*FlkwtYEE@YrL(?$*)v4WhQO&0qyb89RU@2oG?cRoeO=$IM3h0ycfd2r z9^0L4$A|=n5PAw%4+K+#=;(HKasXD2_Rtdp`cj);B9=dE6sb=)13=Nwo)A|izOUA?gk(%ujhxk|5-BRBbLC{}U1+C;Gbo?7-af_;T^MeU^b|9-q54ucTrHT2;E_$^e$7Zp^A6f!nnVn_-N|B{ zQR{^;YOF*8;!wfxWIRr%)kA$gqO_KI>cIzD*_i@&xXp6?u(vE~SP8k~r0Hbo@?X6& z@dqPPwykM14Nuj*?!rrWk(Ti{ux~J{-Fn;ak3(*pP}t(T)QadPwiM7F)_{gcaNE=W z90gHlo;nzY<1yg-0zZyCs5Cwx@afzWD*i+R`N+hOR$&-@9CSKzRZJh%|S6@!_Eu5cL+4J}g&2^5|!=vR-rlSLx_ zVODISE(L`mj6jhK8FfNO{X+a1`Kb>Dv0K?MzB*F5CQCFJ$Z!?%zpoL4)%#!`#dp7J zXaTRVb*TIdC*!>P6xd@_V7xSUMmLqX>eco*g z;PH>X{EQ5vpIb`~T0lC7p<_HWJeZOkNaBwz`XJ0Kk9P2l?BE-7>5(s<8E*PzvdY;6;iTX^dwE|SA04!XYgE+! zzv4~_KRR!WfQ@+=Hl?;ztvDd5tR{4n&MQO!LXKM*?N7MOhSA~_bQqENBfd6>)_ll) zk?rV&m2A&22;*fXoF`p#tZL_p!AJIF{XNR&3Cz3&lWv{L*&q3-0sYgxvjQ5-Wr3u7 z@DbR45Avyd$b$vJmbS<<$a>rFLBXu-V3eT>wR#8nZ_*Ow>sTI}HI-ZJ9ia)>P~nzu zV_w9;#m(1X?Bb9^oN8Yac^J_yqtxSIN*9IBc7!@spIcjx0@Oad+W7E&uLVdAh)(?k z40|Ix)Y!M63uA>?v|&5arunVZfoNFO+mY3*@=O0lu~w(C64#Vh_31RrpxsHg{!A-PqsN$pYbwz%s~UVM z`%3amHHAI@prD&z_;>d5Uy0w^I5#1$N;DGSGi|AmtB-ST^NI$~1eTVNQ_3TN;$^2g z{dGhZKbe?1nGkRITE^H5`UmuABLw$LBM?U$^q16SWI`Cb6ViWNMBRZ}ay06FqF!6f zR|Y3{7C}CUoaMgZ(O{l{C|DKG`jX$WrmIofn&J zk5S6L-kLS}z1DIoXU7Fhv?rv@!{5I(g7x}%7;g(ll$Lr?l6p5_*mFSguNr4FYXM6r z1A&ClCUu@#t}3I7zIuU9;JW&K3R9h|i_B`ZI%<%1z?K6Fl+u43;{Qu8Qsd;}8g-YB zyHs=9`vS36lt1h9?HCo5ty`-aN4yUIITT@{c?VS^B5*kO4h+(Bai02zUFt*MzCHM5 z1cC&z*^xi|^3D4h27%J`r_ahY!D}0O zWqdu{a+5d0dLyEP6Wo^WwE8{m#l!A^TX7E)o#U?Pj8bYYc>cFNQ0#%k!cUvm=K%wp zO{?lfJg~PKe`Jq>MuZ$;>{$Ic8_ri@+M5u<3l__tiG3KN#jvI0!YAEk_Q&6rla8! z4p!DwIQ9mK7|vuUP+pKFIBzkD-AcnDfB1!?*G>LXIVK_{b=X$G5sk{~>OlkILI0Jh z=vfa>ni^A7^YDCW2Niia|2spHqwc1^-BA-P-2mM?<`mgnnP z-(*sNr0S$Q>MWW4ndyW0c-ei=o3C!;-+c5Ysf?B;FsogQnaNDmthQ=+#?joJdTp4w zYB;CCQq^~oAwpI05qcgbJwEZP4}MJen72vFB2Dg$8^_qMQ{P0R<&*l29lx>Q>M@-N zrtIpaUvhR{JB>n2V63rO?7vy4Rf)wMdldlM8xzt;?i;~C($nhe6WcJ;t(u>r6TFq? zAj9b~Egxf}Z{BRA^`;5F<>TWs6fS(he>UZe{e74i!`tk14>)l-kNY;iwYi#v;^Jiyg*$h9SYZR#^a@$^Pj`pPM>h8APo|DSV%4&I9 z>cDW7z}1M&C-D5GV!}$oYC9t~H#heI51l{}Wy71~0!IPr_uD>yo`zQ1%5LqRn}9zy zsZXQlu^Sc^WpBQ=mX^)mKekcP(HCk|0vBC$6|ZwAJ-JRyoDQcH871%?*@$WX`Si!C zWMLR@-@XkD4OQX8A|N(iyaD*9lJ4+a-*=RK!V1=IUQGkvOxjDCaiA0MDu z{bIZd{FA-v*KaYaD=GP~Kl_?0pCXtzAT#7wW57W0@9R*^)|Rd6#gCavYdB8wSXOqm z?D?VtFMP?TrInQtg8tV6S}1%dzrd|xHFy9(K7|#3pH{xH*Oe#VK29^P=ycIX4Kf=UoQX{;=RSh#Fp(pPW)*)I~FSO z?Ck7}6ZCYe)*Uo0H-v@x(%rqoAg0qh-xdV@)!CkScAHwAiI_0@{tqO=Vwr>=C&JUy zZ+U(5@d!SkJVcA__FG=Ifa|qdROV9#Ttx2>x^?T;9ze~3=dO3cBwm9*_0jc@8w4gc zHmo2i1>954)+wb(O{Z7q_^@tJJ&vqwRBY_jkYnPLyG|REVIXnOz*UpJ$_-sBeTKxA z&+FH0#$WJBurVq#6i~lBB~Kp}4Bz76Ax%q53k(ic;=}#-w#u}MG$5mmHj=WNIvn@C zj=X)7jg8=7(wzl~fKQ)9RwoTx}`K4Nhf17-F%_XNkfAKaT1wTYNeRK4gzHY#xZ9Qj$K{!0RI!W#4>Gg1vlrTZ*8khf{+#=hM%am_E~$^>`DS!66|H zSOlm|M2Qq+5<{&C;gN(%+`esBLsO*{P^XUh25Q66~L1PZGw~>)PA3m^_oWK!3aaUI! z#5$LmljFYM1VShYs{yJ#lyr6_R}i{x!O&H>6d|xrLU`@kaJZ=M=QSsAB~5OP#lC&} zYIXHRG-2h9X_zedZvs-%AaJtJ!g;Oljh=jPIP1#CiFKZ;;$mEJaq%x-zC02WLw~vN z?g%CqsDmu217@ryUDrcN*)awN2L4W?4LBn4{?BVp6t;q-lvL1YV?qKML@O;HA33$x zpR{L9gG-!hTl^b8E!4ANi9LIIM|@bQf+hr(h)>UpH5MvQ?+6$&@dYQ|yr5PbmW ze+H9T_WQRfswO?&T3GniXikND8PuL!%2#!9!xn90mCqaY<&t;Wp?+3IaT^j6*=q%sgEkuf~gxj<)DXL$z#01X_(kMP;@6$^E&#{T4kvW`o<_ zC!+`f|CyPY`{Bc89A=i5ZSa5vKVM&Th#G7XR+M$aUd*WN)G8^P{cl+~E_BiC?0PK? zCL~xfD=TJyTuLmI3uvh~F)t$i{61HJ%v;cK!3M(;GBu&0pTXQ70l-1;tz3-B-_wI8 zNraR;W|~e{nouanwvZ(L><-G8{5fibrx+}b zmQX{0xgD&BfhOpV#WUxvR;;t+7~$vVX9$7HaHp;`JpD6h5n+ohJ?Z-pS^<`x&X!`3o* z_@02Ayuj%;7K-95aM9`SFFfz&@;<>3y#}{m0AxiTKgI-_6b@A4a*Ef{J&;0P{`uq5 zx5b-;3&5`(9(@tE;jzGHW@XhLKEJP${@E6FGjmwVU7k`oLxpAy2x-*}st7z)oGAd9^H3;N&^=H~a%g=_LkBs)Y$LGqY}{&)*=F-ENl zOlVQIg7H#PHj$eEXp^X^>7AGRKd9c_m2U?_4=VtHpTPM)Xchf|6E<7W@`a;LRPq9Q z*HP14O@}x!%(}r~p`3-2T4K`DSV%*Ut8Qrri-q&PfX4ARa6c6LLUY$~c^C&qL>GNiaNT*1X{e{)mRfR*IG z`=CfIWNyyb*WdqW{<`OKJohQVz#0%eE(jo7aPq)^xa~IqlKcaT)k`?LFdK9?d2^M8 zp1v7snk_)7KD1HIa#O?o)gOOGn@$~jpMEaXEPs=f6c(%Jc121`%4NIru0V;Zii!cO z0*QcI#po$ST1I9jI#}c$cpY}@yX~JXc%R+{jlds@>ok0BzZpkvUS114b-};CUtx9P z;|(@8Hq^_r(~Yxs=#Zz;cgcAQ@CFkjh+-kdI~*QW(y^l@D~p}%GIIslL>)i^GfRwWyQRLxk1-f;ooGpiyIU6EJx=GV2h4p8^SJi)&7ohYQYc z?lNhz_o*u&H6(^Ks$P)Z4vMJ#+c|%hg0?1CU~gxqB5l6{g&yE_L>M{OCyUA%@bew) zhSH>ux0)otjz}L|dIQ-UCi%a`K4XC9&K(Tc^!|w3>7Qcnz*netUrez+{mo&+h9@3W zR6Re;)RSNH@a&NrCGuX*Jx^-J%AQmgl$H|QS1%UR(V;*%Psu2fS2y5(xSiK2wzs!Y zDDeFFw*Gnqot_;03#iE3x?8932db_0OGMC79`J~m0Q%rR(0|}RhVA_t0Vi-ObCdVs z{rguTgTu6MS-kL|MUJ+NhIZA|a2r2+)@oJl&Xgj$%;&I(-__N{KYlt?abya7>?s_$ z&?q;>k(QS3hX-yL8ykO^79WxV%t??Zc3pgN&kexee{UNf{c$9E(v!|`9=qEp1Hgo+mw^gIHvPW1?O z;!i6sga82G)v2**VIQ1ROR&cyf4Ca#Nx87pRl?#p3G3ca1$)@NqbIQP#|r>o0+0?a zzwh;j7`qI}SIohoVr(FA-Gy=CU)-zPMs8jIs;cUt2N=e_^!EDQmLlP_xK8CVeSsf3 zw1B$wI`p4kxgm^i<#sRgy`r)*8VWx6#PL`_MNJKQQp?NWHd&dN`dY?5>J|ZG*VH71 zapDsaUPK}L9&u;EksNg9*p-+P$BY%HzZ)CKXukpls5h;D9O;W#o!i8?N~)@eQ@l@k zfZtw_ie$AM<3Q>^ph|pkuk81^`W>ilC=So5c4z(afbJpcOb$5der;pZ$N26}^_q)r~8>ddz zoxw5W_3HCyvHHK;-AGjdkb9xxpq?9!_A=?e|NEY?`_G@*h=%d$c9%%N0|4*0uIuC@(4|IF)jzM%fgE{iM!kBHkQ*!#o}L0;r#mULAeXm;6EYCm z%Y$%?IwmA2B%~EiTY0q3^2Iz@j=O1F8~)>3^~@)~tLhU|wx@u_0FfZiXz918M6i?F z-txTT>TpbKI^R^XfP4Kq9?X^Jkpt1S34Zv_te>Vvhxv0yhtcMAi~4TJ&GfIo{=$?+ z15Ggi?V6sRUV#tm68@y~93Jd^K$L)z8pqvGA`X1#>66=ipAiho4f{|-e_4AUlcT1= zy=w9K6Fku;ZE(p3KDJ8zKk0X!=fRfwDS_;1_LKXly z1Z{8I^_2oybeWGUdWDEy)NdO>Rla!HX3KUO?G$ZDQ3=B5%j_n)Wq37Sj#s<{%)*yUooV zmr_NOGW-8UpB&)C0(CeXHK(Tb*t`JeR(>D)Iz#D(z5)&a$!E!~+2i)cCMFk9;Adpw z;NqgCqq_tTfnq%U(;@T}a=@Q?7VjXa?*^X(2|#RZPT+iQv%ji|5Dp+U7f=Xm_<0`8SH>p-IJn7dM1PhS>*)Plj#rc@uEqE!=iXg+)Y4U@?%|S4!{g?VY;S zU-~3`MGmkaxw^a8zB2@>A1HU@JUJa}V~hScl$pumMvYm&zO21;=~6%f{8s&JTwLK8 zLNtO5rhf3?`jg+gvtE+5At({qSXf48IoJ;JtqC-QE6^4RD*$RiQgU+lCYxsIkC+x= z4?iX;%SfGO&YSY1tgcRFz+>~Hqb4S7R}9mr_S6YUz#W&Y6Oq~3LLI5Hi{8C^cW}Ef zGgIgh$;*cq!YTg2tcSGR9JXAI0(kQZO-a+FwzrS;nHUP7|dmT_=60o6rTHwKG z5Y5eDPZjtQt=qjHTvUa_$aOt_2tZ~G*a#M01*Ye75B=+6T(x^nD9Qgr4pAs$%0wtd zaI}TOJW%SiG(kW$X0c!p8yeTNEG^Rqr_Ih~Wlfn=kaSWN+|I;AUoXPh2Un z>V?EEq^4#)X`xLUw(MH;A6|$;xh^6l#lk6W*icw}E5_#M_};e0J@{T@~UAPUD2MxUFq(Ul9Ekm^Yua_8;+43I3J+ykL}mARag8kglj9J6iZ4^ zkHH3hg&@!hbV&Y&3MNpI%E%Nsec$=sgm=3!jI9BGNcE{@(MrrbGneh^MQLUST2{$x zgy#F#$#zZpq#ZX6Il-X78Axb6QiT1t%uv2SP|*0qL{e(%J;ub>oY=~gJV~Zdn%I_5 zz;9ukaEH5bcfey{R|^Vl+a?H~;l?9AKI|)2Ts~@+HT&io#WYvOYwq|tIf;=lRWU^-Ossn_L-MVusp-ay z2YSZF&TB&T#L~HKf~IvUwAk1ggu&VLPq5=Vqu8o=WfC$%0wKXz;YjV;+qXB_Zp`D4 zrlTPQ);KHbC-49~DghfAS$IOwKI-r%+iO`_@$cHTi*4n~D@Qv#OAhv~55jA|I0^P4 zPH>xby?Q^2Q9?f8o30e5n2AbAxpA`RYo2!kEr*4@V0@K;Il|LP#L!heUAFIhPM0g# zhn@s&+7PS+yPqN`HkizL$@#!IwlFZ#wgWfp0^XOj5{d%Rp+e;7DnKllqFFtwo|a8P z!y)yHxuK5suY`rV^6_+=ty;K<&C5RzNue^u>n<|o`kTD)L$JyM0tvr<{t#Kab}=C3 zENW$PykA1`(9_dX_w`kv*D%?7@G7`?T2LkzC;y3NC~=$L`Qlyu%G7@y^*@LtJWdxX z)BtV+NfmXow!OVDHbhcNN|aUY(L0kzbN3copM3Iq&Up(TtJMBV7UQekWmDKy_=D7# zeCaJgvm4Qg$f#q=#?F3+N}nWX_m||wo?Pmtz-uA35?hO87f=^q=*W3C&Qv-@p)fVK zv}l|Wt;l^=O6p7ChKq;Fp2XpF{AkhojR4_+XMo>CGax_-FYl&`NRnXnXI+)Qv52}g zR{f4&Z0R5?~^BNb)=vJf$H1cM6h zwY6#BuLG0yCg^CVyyzfF1NeuW7(YKhN_@OIsayVmK!E>VZ#q`tr6jjq`lqy~=xv}% zG`cE)OIwz!8z0)`+6)OZ5vvCt@KLF8V7>KZo}%yfFK!-# z>^->f*$6LuX>-_}kd6++d30~wL2tDpwzL5DeG{ym)0oHe3d*brm(FBrKWPpwo&-6N zr}m@aov%G4+JQ2cyaf=)Qf*Mqc9WQmq1k{x`pccpWTnMfGx<& z8#6ZMN|;>{Q<{<4?b_PpOwuo2EV6Fh5;URcqHZJn27wj$8D6!+IND#^8T%pF%wpRw z*>_&`$E|PmQ)`5UHCxQ^<`>_IH5^Ia7GMRBwr8s_%?LVTiu#X45&i}|qM2dO^`fF>dkR+|Caqbs zW^w+1Vze8IRP&fMG_#b> z(nUu{6WV?B)Q|5o6W)M$kG^8zWpQw_-U?B-uKrIpJDHtZwFktEZai-UmXB0rP_$Z6 zMhG#{;j{$}WVVc`a9$TrR99C6Do*c z8U3&cuo&bGUpxeejXshe1s$D)v_#h_$z%HQMa-fP{0P2Je?$j?Livdp5cYv z- zm~r^r{W&JXXqn$iS-D~b(S7m?3L2r+0_inni9~cnGr0VS^n_pPd`{5S|! zf$bApp5e-9k4 z78||j+O_`s!X`kccJ2#7OW&t~X4RV>t2s%e4M&7U6MAvYGz* zHLQW<#Tg>x8?+GA7_``77a99YN=oq16K02_z_b^OrPFIP%+Gy3aZ6zrKp|$X#6j_j zTdl|n=|IcGByp!an`!@lL=A0!9#by-j8jWE#j`Ouj=*}tQ(`zD54@Rop|EardB}%y z=vm*~x5=k(D=ws^<==m-ch&fUroR3XMpnLiqiK{6UjJQ)s57EV@CnDBR>_bu4eSZw z;^F&ge$f=gjxc)ZlBnL}q7&lBfc^7|ie@~XV@Aao7)b7`w@a`LqGDop4I#98J9fPM zWT@@G@eew~TR^x3J-tRuOy@8Cd;=R@N{W1AKof-Mg1ITO>;q8~rr z_5MlOVl*JCqdq>9oP4-u?u%lID_zKTfn&{Y4HRfY?%1k>XKZY0I$WKtsr_s8D|Z5R zjj^}#1ytwiMn>^uCoM?E?Q&rBz%+L~eoXy)pd{D;&%kE~{doHP?(^Tj{0U`@&`%1$ z8!(O6p&1g~u%gN%1paJ^7#Hj?tBTPidW{g{s}5^I^A@w6ZQs69SoqT_)OgTtpulPC z>MjVCpeQ>7@4oYAdhJ@El55@IRHDP@@w`LQhoKC zGuwkft(aO^j6FFCKM5%;ZFJUB1!73G_~#c@;J#dwAF_;E+ta~8=BlUhD4rfh3XR(h{I8tJBfG%P&hFm* z`;F+Q#Y%;e00xo;jfXr4JV}X(Bga18hRuzOi!0z+*7@_1`pM#RQd1!1rn|NaYM62X zDwPOn^n`u1k^g%TOqYxQ8@32_J3l*3O4QAsLlgixTLjJkw7e5m7C-HHz5l($HEQkq zAX}ip4B?C=hMMK2lit`N;ng9hJsjE{z;kf_w47no*YAz@w5F z^3TygjhuA$?CY}72J{wsV{!z*GARyGt*cc_v(F{u9i(SBtzj)|q zE&uiezB|BCCcAe1yZA0mvzaQ3D9zad&s^&q3p>oPY?fZf?^G11oi; z-)KUAUy%HfO1ZhO9%W(PNXiy)CP3mRU&aT;kaDGKh95~CjL4lkcW6T3}a_31~myVXU8`?=fZPb;*UDXD642PeQNpvCS{~-nakM6wJ0U z)Dfg5YXUXicC&a`81;PirrrGSDWd@sxMg7S=%dOuM@Mi|7W3^w4rqUj8#3GKi@Ww4%?|HeJa^~u@k zSJqF5t>PpkCAF-r1+enSu_!$#p7jFkbBiB>Dc%*`{Z1Q537p@*auJM16_&(RaQ^(t zg`YzpuCE`K8YLAT>f6-wqJ9~ zlYalFdXrFx_k7U3c55sA{?Y#eE6tY&V(EB245sfdK9XL|!U#5HjfzTUnJ|TpYvK7yo_G+c-o`E=;147Tj>q<5>-v97?yhq|Ph=p=lQJ7Pl!=*nymEpq={NRKpcE1ZDsbXB zL5VS`q`emwBjm1-rWgOx+K&5BMd^T!0K{5wg)AJ5b3yy!*yw2)!*ZTJ+^PL*Cn_h? zt@Nh;$j%VQBuP$zE282Ro7EjqB3G_3g2(})TM*aDYk4}U3)l(=2VhT}ZtlOnl2798 za)i2Tge35lxZ??*eMOjhF-~42uN8`U6FhHSwf=`!irkaYKNAj7s=~n}WWhI++tpxS zg0DOh_ZF-=hu=QR`nFyh2eph%LwmU3xbkDR{Eio1+2Fw#7#NfSzeteDwns((9=Y2u z3dPbPYvGj*Z+I(C-HJWcBZ6Ym4mvARDFKoY8L$86Z+PR37EgYV(1quU5L6boFoJmL z(%SiXZC@8`l)y{i?03>qfxu8;@7eMlxXH_gTbc3+SA8!ciQ7 z9`kYVaE0YGW|(B7^Wn0i_TD4^e~^eGJ@<95iA{Yqsf?dkOhgZfjV2G|@xnYl=-WWgfazPi{|N z-^<+7YBl5Tpg{-_j%9zXD5^jHY15Wy&jn)%c&XSHI*eK(`H}FC z@sJ(;Yg@EXu3eK-;$sCsAmkC!Cgff0wgxcJdkOyo$dIafe6!024hFWb zcyqbAGR+lz7mwBsD+T{j!F>r+uN?8H3%`El*2b~}g7C=N(-XQ7&<#Fi$3{?TNf{Zj zz@2sQjv(u8Pq9v+%%ec=aUh0AOrGsmy#hl6$foMk9Dld{9CyZpH!~W>7mWKy+g+GL zX~OQ%)LSptU{m=aA|f&kSwa@k$I7P+fLRQ6dP&(ip7~==VM(Ar;mx5neXr` zvT4D0<79l7Sk+ZgJ?x3s0m=Pe5~x%vH$Q&~#uMY%{`K@w@`e>%bWle9cs~e*41^L! z>^qRE=pw$iwQg7ps*gl>2C^n}AiExc`; z&7=gE`huZFiI4c$a8E^xjY^x#!r7^q`0%DzkqX~c(5x3h)&$=mauH4ydP3G4A>rrn zc?O2>-**x--brNm@J3r(aq82$LhW17<$A72Fq4qV$RI?L7S|X;Uwvh5DGzGP&Y>ab zo65YFk1`aO2i6M^vIPnd_<~xgrR;Np4{!o!se^0AcHqog)E?bH_!5**3*_ot5$ZnB zY)jyQ5OCag>&0}bl$I$M%PKi~7&O%M^nCr0rZ#V02_ocTq_y^NJaI^&=HuWXk`F?u z7RboIR78&_N^pRRFCIHnH_~ETT~I3q{vgr?PEC`2$++S~0ZlIzw@e;MOy$=DxvIXA}-ZW*;7@8#<-a2RZj#-2TUQXGYae>d8P3qr?j zf{~FxZxU?9#73_?bE&W_fnOhGFC%1^2{T3ww$6b83g!Zdz{3fV3b=HlXG?9YL<~%@ zq$GG>aU0kgZ5%ovY{4Up&ZO(+zVP7uC$cjuJ(tqOD*Lw`GcYh9=n77@p)ZejV!wi6 zz+44r+1wwoUm@KHK%b=t_gE{+%|5q$rO13D79X7(YxFsE6ZoPLE1rK;CHyz|O&Bs+ zF-(CQEZc?qAgEBb5=EV8lrdByyq~PT>*?qyO70-AD!F~*1{?W|9v)KY@{f?T{?`8z zCgFu&rv9KRT@N1o zy{LKXSABrgftXbjOEgr77hWmX>iPKi;;=sI=bh@{*uoG0a{rx-uQERnlwZrq!rs8) z{=Z<3P9OAB|53!Wl*}q*F??PU(LFrg8_9I{&lfFh_76=Bbx z>eFQ$=K|h^qYc}P6mnpG2oZ$T@-`Lt_x52>5Ogbd!&F z&aaNw#iNOU*ZPegQCIL5ToCp*4(P?kRY@}ckOUY5Xkuftymt8dUy^`QQ*5K%%3%bO z2*Sn9A|DWe1DNC)WSOKU6#g?qcv=jk)Uh2Jf^762L>!y1l5K0aL3N_xpbjYPcNPw_NoLo3`l!KLK{_=I{sUE!)`h!&;aGeUvYd3KG}^ zEFZ8A6V0Sf4Cq9{9RPrUovZn947MwRuR*YY)dJP)>+Y$+#s*ChzojDRz?w1~sQOPZ z1gAON+fcKWYhf8F38 z0Hi%W=PXNorB(WCJ<=k|C2g2;aLz+86K)NDB50C>+eN5P8|=eRqXEeld4Os8^41XA zMJhiSGzdcouO@A7S3uKeQl$au(()E>zd$Of1~C*VU-c>SDY5+*njen@h<;DU@^ z{nb)T_;-_i_;M%@cpFqm)VSztyP4V9{)sc9!(Wb&VIe@58m_Jq_6`n*$5j!VP#_`l za}x_Rj3rNZ&q5$*#4MtCzyN5K2R23N=4!zF4`C1`$dim3adxW=)O9fKZ20+f?fAkL zcig9IV6YU{C>V=>=qB!5;MLXphlbu)@bmEv<$s2JRLY{3WRY0?D^}FR>ZK*W@ zz=Gg^yZiTQ%Dt)q`Nk*&$Hc6x@)$=ZM7e2=;GVOOg?dm`bBOI}t4#pA%0w(SR`xl!goQ$j@&3i`wNr||0|)o8&1 z`{}*Ag-OR0Eh}9>FId$D>kJ59S#U@&2ocK;p<0lo6?h+PdX(Gc3R7@#-WATSB6;3; z;z1XU){>oLCB!o}B;2Dwyb*V7P5#n!Tw^tX&e~wo$$3N*28c)h@dJvnkn;L zPFLGsw1*Hes;c$7-zGb)!k*m7!=h*&2Z9wbRR`F%AN>6dO$hmadA)z+Xs~>w3X|yc8||RLB#%XdV|H z*u%Rx#Ner3ASZ$f8AIZ_DtR|lNIkbp{rqT#nwqpUD~SMrMMNt>YXdp01GWA#x4w@{ z5@QeUN$6KSO_e~orf5zB<@V37-<{`LC_qCv-$KgDyr4hTtQeEX!ygEuzF!nWZGc-C z-wF?mv={0UI6Jv{kX?tJF^m>(SkXKYp9XvjVvR+)EBmvc&ql-Xr@(b}$|A^7S7_E-M}Kli@Xl=2WTiH|_~8IWhnx;$5r?V6?}-?$jZ^w6OV zpeT}dE%-z%TmZxkZybb_Q#C41~|K{O^*p3cE5Q8A! z3BFmkZi!6&7Y-an;F!~?si_kei!Waut!ZTgm%5I5#7ojk$w_ILIa50O!Ds)`m+mnx zwXZhqa|=LDEF|>$=GwXrc@@IwiHpxGMC!xT41f{%xsCJKav*+_)ihMp%K0 zTO`!EXyO?=ndlUF*{L)XDqa37p7_pNJ40Odi!_wkh%hHA(E0BA5p1a+ZoFu$T-cW* z%)cxd%MLmmTZ^FkfPes(+~M;Hk$pge#1&4)iweuhaex8eBetA0qZCp(sP1TH;~k3G0U%b|I8tDBET3mO}+~<1JU>wJpY$7K-a-> zm3Zb1ohjF03rFk@0BB9pyCkW|ZuJtctg{oI0kF2<*s2;fNV=A`yB zOQTRrH`YqGaJQ~OM%stY_Mt$mkr#EJan>W=j@e`W782>H>yoQ2PV>mp!7hhG3LXDK z{L!ZiCk~a>a%?wrf#RQ_*g^OcHHoNyh-ZfEQ-J8Fz;?mrnL^oL`Th7aV=FQ{x%=+}AMnB#&$4jUe z(i$?dzY$ty$hgcuv^k6)FHK|@tQ`szGnD7&71o|pEQICCvba;gWWWH{JuT? z$hPOZxAIzU`*cr)bc6f@Lr@8&AcoGfkmbgcBhX~AdT4dANBu+`wvCOA*N+<^ zpA*RxM;&xsbY~IsT2Y3sP|FH%Wo{TX}gOqx+CsH72 zTxfdnaj@^5?|QL!f#9DA#ftthcftb_12h{ye|(y}i)L)<|F`IYH)Os`uet)!<#Y9w|D;!?uvP`dE&>tZ|04FH*N z9RYJ3w&?Qo@MwmCvlA)+c$jBLj|v}LtIq-brZ>TRyH~sViL#~K*Q9$k*O>Ib*0f4q zz0Amy{O0*<&#CqiMn2ApH)fM~l)5#V5%gR;XRu3rs z$oRR@ag}TBwcxv>zk@ebwYhru9gh)zaFijw$W!6Tuxn}6x0hbScYjA4r_i}LS(-G>90HP}LI>nVx0%QWLTG+B5pLUqDtD$&kv=Jx{?u{6atJG!+alf6H)vh%>QQf2cQfsWrfCQg=APDGo5NW-FRd<( z&DLtH6~>~OQNjmIHrQ)cP?mHH4^mI9)B9Pxi7;GUqeGrkPg<&W$H6b91NF{OynES? zgn~8F(g|eMfC~I?K>sHW!ioOkRx}C$g$*AvKZGy=b{Hjz9lD)WuLl}y-x~FmlqmKI zT(Nrn#D%=dn$9<7o#S4)51#z`_~gUct~ZH?k2{Cya*MfrMdo#5{uAN*Ik zIhRkJaoS($v3B!jeZJC84^f`SjQ5u_EjgR{HT-c?4(+b5bZ!Hh1|cT*XpaP1Fh39X zTyr&1Jx7!+JyE&Em`|qEX@BX_eeHT>Lus`?f8ESY+Mcn&JuT_YPvzEC`ekFQMsrVp z=n}tFUHxY zw(fIN^5uNNml3}=mNngx-;h;z-iS5RP`IgFuIP$fbX@tQt<)PaDe98NE^DRY3{!d1 zzO47S>+rU?GId8}b3N0M>zwqjMa9kbh3s6BQ%I+Ia!G{~bAc9fL6h7;Vder&W?_wA zKZzbkoli}RvvBns3&JgGA92_D8aAd804wN*-A5v-q?9_-^KQtlDv4Yd6H1J+hYlZK zeKBx+9faYR)WzF6KHx@kAsT&c4KsV0W(6an7xVM;&&J-KT?&LE_2Zimb*9bxfFUny zO;q<7zkcrF9?dB|-X_kK9P1YA4o-8hy0sc8r*fxwcRJFJUY1*L;A9rgWp-9CkHx6! zahG|q(c=U9jAHVqbJU%SyXdZ*(MS*au=@Mw+tpJw>Vrq^_DMfZ+p@A-UaHPdab?!U zO>*Zh@uZb|Z$4;mpHOKmFSyOAMlWr%I7hY2d&f2dL)RD@t7+%mV=;SA?6$d{ealee zM0IE+^NLpt@BeR>SaTc$HlbFc79X^!+ zHjEZwfx+eGd#yS95*{+8HN45L?w!$Ldvp3OxspSxA#^1=RSUK6=WfRei1TL(80Wf6 zM98}seTlmyD^QlCwvEzE_RV&h(wVd>Hb)x+%tNkNuXw2Dj zoF4A!=Mv|2wmdxHxh8Z(tUzI(I!!}Ib4!o<`|@-8W)|JiF=pbXn={jP%Vp;0DQ&fT z@jhHp=tRzDlk<}mXVVSeoV4O#m^G6zmEGiWsd;UVvQ$oqrk26Em@7M0_&Ke=)RL7~ z>8z9xrY%g{t?=UWT=qoZEiJ0BiQx}o&p2>CSI*womy45=lcFswv0;PN_0IGBi!C`< zh>MH#DVcH+7m;H9JEK`>3kgsmUOqOEv8rsXl3Ln&TCkOLj)6QXl5!KV)Ge`K*}3hf zf@TgIW-#3iiYjw;Yj4TF!)3hua@VHJ#xy%lm$h|ISfe{`I}Vwx~nze0lK{+ih$FF)h7oa4>x;F^|dXH`q@5s-86VD{l5d zL3~%-g!x#T-hSTT643r(=u{t^y`fU=YynqzO|6Tv_EzY0OnrNWiyWHUlGje3{ylqo z7HzS$Qu>Qpy%$!A`Z0=&Vki5P3%IM1uJzoC$b-rK3yaPL%ErtpM zDXTYQyTlJJUBjfV&S}bNYQp)IgVp-6hVH&-7ONH6lES{`9hEhvqZQLWmXdwv)XP?ej3GuKnWQ+HyfcqLM zqqYH!p+YqLC+Mu-8&aFs3iBm)S>)LIT!`E-qvnyf=f&>+hf5{R&Aa;gpbc*3nqTEt ze)7-eQ1o$bwtt=~$j8?V+wz?%S7ngaPu4tDS#wI_cYx?EV_;xN8o2h0pVIouK;RyX zzlbi-m7>&zLeN+26mynxWq~4y35rT`vXl*nK(l{J~{L=hlz6bDf=S_Bb6Bd}XIvGV7eF>x8H38Ex8=Mj z2X%7MJ~+3&vS(u8z}4L99r&P)#W87jYUxCiTrRL#Noc4$OVoyYsncaQ_$B3M-zdAC zrDeL5{{*9QV11>Ve3WCYbZOWtcAd>zrf;w1U>bj>{=P)^7f(qh38O|Kfn6!V(C@9X! zN?o%0r-OLHS03`r?{XCE@4l}zj(pd+aYN<>b>}zQ%rZyCO{lRHdM9l9lFQGczB2MZ zFh3}8aUDT&Md!P^OkvEyJ-jp_REe>vsqI)$hHa5o+&UEwUDgz(3O6`nw9>_a%J}JN z?|Y?nmri|tyJMfU@$xHPvvJ?Voxa_OjyC+X=6t!`;L^2%zUJDyBVzh^vEzKp&GIEA zlh}J0&d!R?Zb~}0+tZ1Sb}H@ouF} zsdvXNo%0Fqk5Dw(I%%uKOwn@Vo7nWRR>b@4cQLa_$MRmcfxfY(Hsds)(w z$rPb^6XRxN#%1}qc`lTD0wu&eINva;gljC68w_Bk!vzypg7btjK>+Q6h zoH-{mW56^fOqbpt82wqGFJ;ui|Ex`S(FI4dv-h8Qxwp4CWz17nJ)8RF)zcV#a?yn_ zw@f}gJFkxB>U_Ocoug`ozf+?h($YrNoS7ZHqaVJAgZI99x#Bo^uE>MS?#sOufBa5? zbiZKAV|i6oF1&%qZqs)0-TckYZYs-3Pm9ELZU^nhgjVOuL&CzAZievR;$rZ2_*m38 z@*L>-dB%-D&}i*r6ik;iKRa7@ zs!C(HFv#}l<(WzQe*P8G8Z^E-As6+HX`Y$9w^|)Uxy;vmhV`Lws?uOaW7kDd<1bg8 zA7tL};C|)38ec9C=~{p68hD^j@vJk{YJ<-Np!Iqnb zNSEP2^vf@4&Izv?{J5`Yt`)ZQ{PW?jPYl!__kT$H;y`Kdax4A1BjVAoPOOV-xmqCT zaj9c&xsa2-x=wWXhGqEXSDqH1oz;FAB(aOT=7Z~@-A=SlVsiK8|6S=m{WJ7chA?UomN@>~mjZn*5G;asxXL3ZhdMejV0*xO?36dUk! zQ=FZ5e_?8vK1sXSm{(#ZHc#SQ30@?gd2sa!i5aVbj5?~sCkCk^S z+PsR`GRTmeMhrrL`8V<$6I^OE$v6!R!bwNG%3B)@te(wB-SOt+TvANesI+rN%Sv10 zcy7P0lS6z$qK#(0jiw2A&N@Riwk`#YkCD9-1(bqBmZ#H}RaRviLR=f~G^CQ}C84P6 zu#mIix060rLQXY2G3h)pbXOU>l^#2c+_p*AJ{BE!e*KD+%Gr{7{q2Vw-%Vyh3#GUo zqfnJ3SC#MpXXfVSdRcMDG`><1u2K54H74jd^;hGt1msIbJE%VU_-^`U|H-z}w`xk6 zyejpVjmf*K+&rGg+9ok`d@_YDy}8do+xL#Bse1HIO?;i$awC6F)8!3nNCj~%9=@zs zyl-wjg^&AP*QZe2qg6-2Q-rt5`;7-LqW#I|N$R2!0NO2L50sB8{OCN8uVL@PM^aB+ zTA@*LS!cr?AN0A|dU&wlg)=dRl?lXB#xxgVe2hnH%e_nSVOKc<-ucq4UEIwRyN@D{ z)APB?28q1aZq-v>KM(gWcDsub^h`8yUZQP6g{N&3Dd(fsFU^yfiL_JPTkTrd@7=p+ z+uc{JjCZBT9?tn7s=PREUzzyJ$grD9y1#ikwtdEa#68?3&gv)j@yK2dmxt** zr}tCDJw$i0zS+uX=0v-HynZ}t!;CWT{S{}O2W1!(STA0QP2O?2v$vPQs2ldG%qg$D zhUn0cY-ypq!aT`En|o_+mg}@?Q@KQBmjd_lsX2_?OB0P;d+q(t1Kb-Qv&NN&<>W;q zFIvYpzT;*7?_?9x^$rI0G3O}}gB**NZE|9YYC0Bl-c0JxN!zN(PAlc<+iU2o-M=55vYItvhBx5y)79##8$IoW zM6Zk{8j6=-61KK5`>j>mV~=|FYR4AZ8C*!{{~&QEphI&iFIo$c=JBDC9$V(VEtjpY zOxim>ZoGFXq8mwPaub^gAN{7)MZFF;?K8rWI%h`TZ!?sPBGuK3S|3i1gjWZ=ezd!pF4sRb+W~!M$9vI zloWMEonOD~MMyY~mpbyThNfH?DJjCk@@6ZS(nvf#dg!B_@C$P- zzIU>CYb4yJ8V)}B;q=y!hK+$;)j`~Pd`qmCy5@X=t|kHc-=p>2;+D*4uwJL`XQAQ8<66{p zqsX*1eyaf%z>B&qLMv@Y$uCp+NGZib;3y&I|d-ev$gM(WhjAM;#w$ z{NBi2{PRq>!T$MyXRiSemL+BH{b@3uvgUJ#jit^RQ5bkdpWAgRuZ@0oi+jlq*8;N} z)yA#nlNxcYhl($BzoWO_lHA;OimSu0D}16xZ+`=_H@;BjCS=Nfd@f@|y{4_}UJ*HI zMDm-$SsyRq4FU^=lrvT0;XZ!vHJC=?g-e|@xO808D><+qk{0#@?fFUjfX2q0>!Pe# z`cxmG_>$C!=lYCY^LKW?41mhOf@5I9s5A0N(wM$ z#=%YR4^FR1zah(4;dQAsL*DyZzq*3A=hn5hDxMB1p07IgabimZe6Zll38BJY+cwOIftSm>WyRi+xwlz1rQc4A{wsV+~XzqfW6PKYhK%D5ZQZev=x zY?^OkR1p%CqIT_uvs(IX64U$DtB52zDyRm5?5_{VeYEG4f9?Q{LSFE^`y< zVhn#GFT&SaJ%X7md3ANT_Wl9zDYsv+{uzYOIM`F15QbX47N=8!l=?E78&cB_)t}X?_Ik5LVz(3fhTip+n}8IvbMtrUC<*2E$OvZ} zuyK2D_FR8XbMIbm1tWNjKFg_YrABxUo36PbwG_@_N{hXOjLdc=zDNmXrZGCYw4=s& z7YCGkAG$R*mRK)BZdK}Yw^dOae%R)nq%UyXoOA8>-2v5-(HvQOH86iJRnh6lA0sa_3CHZ zM9IW3;73Ir*Iq9?(MBUqT*p54?%f@<=drOyxeV*>KJs)+h2q%FUuQVt?n?PCyX>vh zy`$J&Vp)6IvnHeCH3z9bu7xD1EqcTskM+u-n(6K*On~y{zJqy7Bn#)t*FF04RLP?2 zt{Np{M0C#;H(Og8IE97b=7N{s)XJ*Q&FF!V!iet#Nui-B5vMTG9 zck8RnUw!uPdxe3ScMlzJy6I6SnBnec7V%n4OqfP}As6Hp6dcq)tyRu*z~78X+f-YE z3j>K}80rU-#b}W_Km=~xKY!D0@462)Iedb@e;=HFvUS3%f7$3jtyoCunW4`fe62b| zUY*;VUs@EOdhXvmE%@m4tJT|9H@f_?*{1e0*LwbAn(6#hG`+6FSC!`%`j-9)z%U?+ z8hzuaJoF><3_ErZ=`1IG5EfFEXVyq(Or4lIesjE_(8SV`85{v<6b#nl26Wp}b^Q5{ zXNxu1h=X+q{}IVOU}FFCbf00&gFNSxwf15F9cC(TnLoJ=u5E9~V-6tVa5pK&l{Uaa zNE0A0f`3C#d)c=W7!!tpkYwHrpRz9#+|*i1e7Z_}cX0_-7(B2?`+VS~xkE0FMwNuL zDGV08v|YN%9|~veuemQ@zF?*Rxgb!<=MBpemRIw)x^itq42Eu3auYz`AjxGd1^7!}KjeMR;wN|7IurPRMS+>rKA; z3I-vLvo|hVw^r&34vs6Boeey<{PM|TEs;AX7Sih5%nO?3k8gg+W0Qypg&7q@oQ8R? z&hTC~n%m+a`0}D@iZ<~g4&0P|XRBiOs^f`5LgsX&ZI-}}x1yOFp0)%GJuE*a=Y3$M z*T-_grf?;i?7d=ZQ2))}c6Slu?YqyDXTld?Oj&GE98Ofe8S@#@qUclo&A=bh$pWnjxvnYs}CN1A6Pv^4V{qqa38_MWJldvI9y`0*cg zr+;Ssp3Az4QRUfgyw5P1hgwj;ObA2ITXW82@G^~pQO37lyZh@g{fx|p{z%@#&57%^ zr1^0u`1jA7xJ&mVI9FS^Luo<+R1z>Vj(ssJUjtlLQMl$~MVBiVX{q<_xAM0G1{a)d zSiJJ5e0ogo?c0KwXQYZtz5-Ri%<^Dsq}=)*Cr;WI0x%*+R!*+;lIYT+WvE!X(jA{jKQtZ~8A6r^S|U7X-qWF}a*dxW)B{@(eu3v!b9M zcQ^xNt|+Mc6ujDX^bfS zwZAbqzdryi&L1z!oLE8})ijQhI>bTpA{du1JbHR}8m42V1N|+xe?Gl!w=iGuQP3Ot zo49-UBN+!ubL8Y*c_XWD!&4`@xBYy#v+Oi&fPNPF!!2Y|?9QNcPR=1dhL#J>b`CeiN<4 z&L@78M`^{+H^HdEhQe&}J;;Yc6Z@r+{#6^6{hs3JO1ItG&~P&v{FE`vC9n0#L8*q8 zsS13eEH2NgmxuJf%-u}2bq`B;;K#eUZ%ksTv6vtr@xDJ8tQe>({Y-l@W_E5;9pCPV%kqEf1an-&q0c5GqXL^zhGxCi5lsEUf zy5>L5E;bqEBPebM`aP%;&QW`JT1kI#KB~a0Bek*#o~os4`M;Y4f3eXJ_jO0i4E}wi zK;YOKGF9=3V{^~vTbPgfFoQy}CYelu`?WGfp>)hf1(!ccZP!$?w;2a{8Ji@}lo+!@9+{J~lzcL@mRKMmR{e6VukhDuadB5X{K#Tn_|HxkjQPD6tR zJk^OB(hz_?Puvm7&Gi-?N6se>tv`0;!+Zq#3Z3?Eeo`6V)~0W9e($^0tWmVK`eD?G z@$ol?j${*~Q4n^}#ki_325u;l%xGx({n%q$5_ept5&GeCz>p95bnaTQk!qGt*0!RZ zh(M;#wn($ZKP7y9zX`LIOZV88jJvKKxUy@*|j|uzt}B2)jG#9kuq?N47tuOEnDe0f@PbnAS*=+VabZl~;a$ zP?Bbo=WAwJ9Cky9nGXCkmQqxRQ(^r?6 z$k}h$0%T8CdVuCKB{CJc5FcPEHb&@LRQSTgdQ10|5oq{%;p7Q{=HO z+kzsrwF?ifpYD`@DaKb5*{$TWIX+2WW;#*t$+NUPx5Y~*%L7=XT^27A{S{a-mA}tZOxaq5lQek1j5$NPl?fo!P$iP2N@>`TgGJwP9_S z;=A;hUXAKj>U&k;H@?Na@yJ6Xppbh;uPD9y*l(KIPQmWSh_2C@v?~Ev$`s)S2JYAXVb)R;GYp!7m4Ixu;$S~s@mz45uUW>O1r}T-oAC={*=-g^g zh3*Dc8PXQ`G|_I>GwTj_`pQ*!wTm^lSD5mj@7i_Q9>gJ1&&=rh(3)?NJ59LzhitnX z<)Sf3LWCpwqY=C1CW2`VyS4rO6$1kU5v3FAL`9rA7-(s&)YZB1UF`N2x*qQF_B+ld z+jKXe<8JgRE)oxp2tkbR-g1uf`qHVx`vaAeuj|oSkMBSo#N-MgRUK6kcC_-f?9J5d zD~1~8`Ek2`e^(MIN&Lfwtc|fZUeRpk)T{|*m<$oZH4dR!t4z_Bg!?!hTwR&4#Gq$m{}+dys^5GH86Ng_cbAQ|9-zEZn*DM6_iW6Xw4vD>$jOsIOnKNW!ZnH4ymFV?EjLg->kx$YyfV6eP~w4b{YA&5~v z>#7uY+u7t3Vd7~=xjm{Bbj~p-?9CrADYDy*g*><-Df^qVu}KP>MOa%@8kdd+ro4vU zvAw00Bi!h>JpxmZ@YYhVq^Z^xcIr_R56vu=@H&uP-xbw%X>Xh2$|^7C0qwWy%xf80 ze3!p{m`Ov^eN}ELoUE6GX-FS35B`*C&Xu*w8J$21f zRW8=@|Ln;0RkEX+XV_u$g=!ck)h>DD>+d6hGle$sX!7Aj`r$*nL$c2>6m!yh?eY8; zzgpJeuG6ZUYG0twpzJ!Cjf`9MWTeNAL3@sikGI39$ubW1pFe*R1eP+divQcy-ya2M zOJ?y-^8*Nii)heQ#Xxft9y%Y-w>8pa)TPuG*7ec^Z869{mS)Tq2UYsz^krEkPePW1 z!qdJF6G4*URuGUZ-5U4nZdeD$NP&CHt=i;tBF%oi{jvG@H<%RVEz zA}CF=XxpEV_#HV`%ilg7ve#@;&C7~okGa@ugd2*ZC1lQ-@_*u(HMf(|H(l}aK+K%i zZ%L1YS3)ae?{oe(nTP!b}MhWos`bI$MFb^mwWyO(uV>zvN^9p3kOpXc*@p3ldXnThb) z@{D7bdG)15y%6vPezu1}DGUzqS%{j){j7Q*FTOTAcJWR()TlnN;4L@juYI|7r|Zhp z2H(4ojh8_nnV#sakbtU4r1$`TZT-cOR}vGKn8-=N!f{_K#NYX7ZqGK0sW0paNl9}s zn9~h*NC_q_AB~7L5orB$Ufa5OE&BN9dV9k3yivtvwyUtmX8kL!@LKPVkJ>?$`n`Gf zH#t}x0DDK}N>d<|B|%?$53DBzHt#{gTEeF~KwI^^@U2rJU?<)M>z%xYvUaI<@`$q)N5>32yTVfNR8M>h>gbm$`@AI&_>?%zG)!YZq-oNRi>a zC&_W}&_>mV{J`=~OG7hNjfQZ5AS8#m%uAZtS+Bm#{W|k?kiBXko(~#*&nd}fMw`37 zvyM{K$p^>9LBa)OqMS;f%VG#%hb|eAHthUf=X~>d#ha$QvHP%^#ER+2FspT{x`}4w z59ShenLZtdNHXS*t5maL3EukZ3Ic*%JFJFb=N_^m4cz(C3qQrJL4|vuUO7(~9TQp8*j3 zW`S9)*b0*12$^^?8NiMF>@b|PbGlxaSrB6{1i+JyeJX3Dh`5dXY>4G2O1w3@wU#qy z2ITGXofD6PBmm6Vqrp>HJKGwqon}5s^DSo5H*2I_6tcA6Lh{xdwO$Xfa|9tP3h-y# z_-X9DGy967+~?Y{yp}I~Vg*R98sUsgwLEZ|9@+9~kE;!}g5$`aiUxZPE@6ITKURcn zIR555nNOz{W&z{*Ry#+EIXdyWG|irQ(P+Hr_Z|t_r2Bx4UU(BnQZ1}%0_4bVXVY=3 zG8+w|S2nO1HQ=KpR9?U-hzY*WWTJmgNzoi&sQBA@NF3Y^k;ds-{tzlaD!W-3#eMpnC`Agp+PF`M3VdmaI z1scUasBzWBS9~z1b7Fc{|E8@YxxsZ`D*+cp?IKIg?Acc=r;g`3WND8BA0<`tD*(UgYaXPClwoZCJX0Dt@c*xojZ|h_(SmZAJnm+n&o%~&wcU^<^QH8~E zg~dlp&&^q8tYGR?nL*6%IcDILv4fN&Q}ufz%i?Nz)8jnPg(b+cOX9;K&)tb-eoFgP z+-cEbZB<#4W1>!4Q86BP8$8OFSz&&m3p6&6n!tSHa(O2-cVWIhYZV&@soJSj;H9#q zW;nLjtpt0WfCb259YhLHUj3)){^}#-@xw4Qf>632AMX5e(TmcQ$?p0v^ni&z27Wd; z1r28HWx}1=R!-bhm05tNhJ7uSdXT&K4Bocnsh`XW-E}<+DT$sak3Dts9RV`EQD@ZK zt6w$LNR>yuwuH{BSzKiNIf?}lW^o+{U~`EbzG=XoX7G{Yh{n;VPxs5?^@Urhs!RcQ zva+%ol%<0Rv_l^gPY&z@vi@qUj0_-+(ZHs{Un9s(&QXyRO$&Hi33xPQo9WV@bEycm zlX0}ie6X=`7e8fd=l!n3=8bvf!qDb?Bi3V;e6Ixdq5(677<0jMySftfUSTN*gD_#T zRAE)-miN(T*=C0BeL6#PM;!90wQ-Z+Z~F|*B1whCymL->{h9iA3B`QuE}UFHL#Nmia)Y0LC2n`A#B25^lfjV<5wYM7FT0 zi5q4`H18yAzqqIpf%5Y0kteND;7)UV_bYNI1@c%uc+Oaq|ncR7%kxrN^&y{^Tx zB5iYAif7aB%Pt95GkolkQ`@RN;HGM9d}zD=o?Yg4)82ZyxAeQ(NL zPg@XS|4WAb@sU#$9Ca&Btq)RyL*#Gyt=ZMwPXACK=db0Y`N1$%O+7d+wP917$1u3D z#P;Ls-M3dduVj$CyNI%ktNge)d65eqE?-$$8P)xS144fZQHB*!4zf}$ ziXJ4X_%4_o&^)I1;mlFZqJ<&-HyzF|o&gz5*3(|%vypL9cgw5A<9gXHAM3lYizn>A zSf(zCV1*6BBy_JyI5KmD&+x{?;%9!cG?Px^XY{T~Q8Ug=ny^Y+)fVRE)@QlOr$2nJ zk1I}1(RGN$2vB98CR{mV#+sttAL4A#~1I))Qo!JZ^apXb5b6e zY$5+8WPY%CnvqEo(2bOZ4^M*^OA~-j0DPI-dKFD$%pCJzB+5#(N2vJqv4V(Hf#`P! z!1+YGA?RWN)^)8_Ls&dW>0^<R;s9k@m>Z`lNwZN*wC9jF~BMM`Q zkxx{7a+OM_l1OaGgnD1NaMWFoc=eP1_m957jM*xegYY=Ex3}@1k4%Tep>rN_h1ctz zw0K0}MKI>MPNG6*h8$$-P-#}c4nNBhebP?EPy)v7TG6R%L$S^S@Po)3J+hb(6#B222iIis|HBaC(+4Y z`ta7JzK*I#ZWcp#^60FNsO6pP2aBgTU}!}wK6Mpa{2V<8MsnK`5>0buJV|kC?uQ>W zZ3S*Ftaw?fcHS`OV#YHRcIr_A;*7%k!v)kB9b;3;Oj1Zs?ZL67$kyZc#&TJniV$#P z#L<-(lcnaj+z#YsOYvWoIs0}ZI24v9q>&Kuh;-S19$c$Zm?TquLF;5FOqwIEe*A$+)oABi z?&jiyQ~oNtFC4OYy|&3MDZOXLUE2Hw+V)x=_%@wTL1lA73z#|P+?JGK0%VM&YF|{? zarN2B6l&o#q~T)0qZ&$!au`b!Twfm7$O^_$5$cbkg$|#VF)M4$nB3b73$@SuWG=Om z93N5~%4w83e#fmb>doefRk_px+YLwgndmD!&-`0On5lmJSUk}a`fc(_@$OEDN;6o1 zK3lf_rf3O`Y0!?_13VRl8_}`O^yqd&;N%>sElCMa{^25N`7N)tJ!|ar+hutP%I6KY zQ+ATWK2!h)PQU8|j>31ZWPEt$djUi*qLEL>X6XnkWM^9sJ#J39J)i!QXK16%X==ph zo%>|Z8~>#Fze1!)D8CESS4xopRSGm^TMH({Yw zX?dZqt0hd0TN_U?8c5F>$d|e0U~KFYGgh&HZpJPt2@{St>>(+r^k-fGkx>wWL=e7r zC!KsjOA9aLVgP|el>Alkl7oq0Uj0^17v=#GV-gU^!SV4%E?^QU_7EAB_s$*k^Y>R9 zk_C&9#p68U%&2yQgd3PVFlhnP^<#Qb#uVS4);eu^Y86Uv@%3EhS>PG4J?ETt7q;AlX6u0pIfzP`ysG78-Q|@X;o#i|BX{ z9w0GVU|SG>LBu5iAVEP4gCpPxnPh+X{EHJ6=NQS2?=TUn?SP^qcJ}`jL7{p&eTNuy zp)3T>2+YUw?>s-L02ZdsQ7_zw{93b_G8|`tiqHdcM@WSZ@QDhoEL=?zVt}O`fcE0I z&y$RrdP)z5(FH;u_Ya>i>EZ;TWcHWITUp&sklRl>E!7Z7yw2yAdmeGP4!u{P2fe*G zl%;XYxg+98M#6uXg*)^S@w6yCGGHx)Igic)Oy|#vN?oHfQR;;uG3vM)&)#Y!H>WQ3 zbf&P(N-V8?`#lOKLe!iKVk7+dEWfinA|xf;D?r(y6RnBUjD)ZM`-AuQbQSn&sNUgk zb?@B6;8G#W(U;bGp=WS4tbnl~wlMmzk!l+FmIwhk^~}%!GuOs6`;I;Zh4cXa7GB+Q5hn zX5S@3?;CZa7ndpwngw^kk2O_z0o@ZqX=2$;_6x>iKv@tRqth<&WAHcr(1}4rL3ij2 z?_Re3D1{0ac%OIkWDOVb*9P~-X770fi3myaM@qgYP$>{?0{%RCJO=w%cW4I@ll$ZT z^FA=x(HE5Tm7@4z#M=A&W58tUo-2yMFLV`o;c&sJ+QKM-CnqBX7pfzu$eC%pt8SAc z+St@2EhiTZQZ8@aym^0ISe%S_?M@7pa=MqM93nj?kfVqXxQn3e2hukdW!O09+jfqK z?adi|9dTU!{TGh2ievuX!-Ip2&=X=x)Y{;sXQM(K0bE#-i@wp(-C*FIDBjNBs4HKd z17RQZ#nK82_2wupJnKW7c769JvIq!Kx$rMqN!$~HJoNB%Wr)}P3)E5HiwF%sHyTzh z+G4lA$>DGu@x&eQ=fyCR3r-j6GtI(1LVg5=I%qafol5=k?-f11#RLV#LqqXoM3c59 zt_>hE6uJDnchnet_a0y_+e^HGsZ&7MQfJjvNP>ADcxvtw`TnWT8>m7=H{zU+d4mq? zKac%pmYZi+h({JoN5HfH&-=KURcbU8qVb5-E2Vb1v6P96sqE5!_X`!Q$)UzUY{Icy zpcaIsQp5Gfzq}k5`$ZUVIFQZu|L0h1UFA&_QvH*2XQf!ZwKg(uJk<^YbexEj{$l1F|t=hu1$iHWueBoAW1} zfezxArAC!Q`)}&pcbe2=BnMx*IcT(l?#S2we%Il7LEH#?F=?lO)4uQCOGw5^*3n2~ev4`@a8=TS*CkVPnTgmz>}P zKo%$v8#x#gZ#OWA#Sgck4ai8IZ+o&d32phCCr7`U5jPQ(TYCS|M>iC98c5ISV1E~BHl&i4nt%4#S>>mZ*7PIpT@MTGS>Mvq$Lon4UIHG z3xeU3vk@YQfo(9zl0ldRQG@^d|5u-$xESjXbSGO*;@ctp_wBUv6I@Z4fvI(e?3luu zM&kO^&CO28@^b289rZU6lE9cR{>O`{IQGSGkxOeIr6?xWxnV6$_TNJXGqS zj6Z=MNHbYQai2eX0=kBj{UN#7p^u9v`SV<0!;ktytR`-FD6xPXjqW=+cH|&Za_(d4 z#10Y&*UQVx;Y`(xL=+51Gfplp^@|{fL~tfa<^W#g|8@|~ zZ|wLoe?9M!GjJ3zrt)$r7z}(A0IQZBt=fOKiUZm8w%`d_T_g4SavFHsM^!N9*8nsA z=cS6vTr$#nar6jSywzRA;2qnYT3}zx0R99NQu$8A-r7xj*P7hpa9`8H+$fjxBOYakXHbcf5Hn?cF;Wjfo z8ZjAxQ9DeIhm#C213Iy^V5Iw^QIdrjS7Z3!V?q#e&Lb#Z{6$+e^~8(6y!E>)WboRl zX~~Rn&b;U(`)4aqzT~mvh2}rd)9#$aFu{`viPXX^r(~f3@%P91>(0+#dBFPs34MGz zn&JBAAY;mb{+-B8?e~Uo;gSdHTrilvTXAtz$YcynLVCE9id^rIlEwSg%L z%nGOeGeL{Vkz}NNFDx{-9yEY{1Mx&O$cJ6`>(|wLLm&R#Ir9p!T6f_KR6$tpe>+D` zcc@@l5zgg#1?>kzSlT^F^Qx?4`cbhN9K;~QOdaJ7E)VJkY5#svkxTvi)YFy08&2dA z?f;%Y1ov-_ee0qY84Yo1 z+5;&(1KuN#@BHrGpCoH8)@K?0UWvbr0~2$x^$h*fBbV|wS}RuX8j8aR9ZZoU&cQZx z(h||}0R~qPQWLFZm{x3QVT*F%G8}=BD0_MT8;77Nf+wUfbL$H54DV*D>k`R$gs++y zCg+@J-v-*5FO17@-nz@($j;vXej|9hb$TY9nPA;>`OrW63@^$ShhwCUa{X-$nPqq% z6$W3{f&Je?IaOBcVt!sK)8L^YS3L$ZUcvdlJpSmz(|A$hAl}mVat^IWM)2D`M55u0r?Z=oV`pc#F*7FK`6BPi-uy*d ze}6W}-2l;c-}Eg$g_vrX#@1TW5x12r+D_H`=N{HNeF?qekrV5Dno=c@1%r?F=Gg}# zuyAJI29d9SuA;vDhFuk9Czdf$3m{Fd7Gc*vsjufJL=4$@b>f2Ct4$C9oquw5`HB8R z!<1KxOvyd4y2;cSxth;m#`{qv@*HK27ONy_<>CB^F(T#K~frIaIeEs%Q?cs**+=NqyG) z*Gq-*ElIYJ`A5KzZHJIvkZlNj%ZHSu~j-jF*&*s8bFk3gFA0k&e`Ou~AbH0UJ=-;c8+1d&}UhRz4c* zrt3t(&3YV+W~%X8@ICeec#a(Tp<83{mH&iKlcvkDUx(9~+{bXZ+-^DDn!~~QF^1w% zh~WSn=jRSGOE4S0S^dxJ3=lB}9zuY8NLVEenW^rv^lNAF*)R~ zj*rvPcD8MAD?s9+b@C*%B?gy73|MB+F<(R6EbyP-zU6HF^|eBXFL^XHId*9t-pX#$ zyh2uXHWG%S6Ik-u9&R!`aw3E_W+!yO)Ku%t&6){0Y~ zL#KQC`lzo0D?`rN@t>TiDYwYQzbuEHgF{+HCCOcm=G6vQy$oiYffMc{wSQr)gXXa1 zw<~Usg~ikR=quuv%v%}KXc>lFSZK^3#{8{=*jQvVgrvI=x1MM$KM}CUL<_e|y3cgg zw{=y6G1B6f^$~Ga>LB1`fEca!Z;HBvv>mrArc)*r-m3?Wg5Ar=0W~tYD9+S3x0po{KQkI47f|s(eCu| z49N_Z%k6&rN~IqgUUz%tdsaU*pDAWLU!+EL8*z(t()>DN#W}Jd?^`WA)3SdLlNHX8 zgDF{?Q-{30OFKDQ<2ILH`mB(LwaT3yL{)|C4|@0Yg#JQNN6x*^dU~LG#X@>|{rYvS z!*Mx(()!${M%^KElG$CAPD;$UtabZT6d>}*)E*Ix)$X5bpP3Q3`YrI zMZ;P2mfFdaJp&R+IqGAZKDLA|hrTwy@s3Zaaqa{Sg13Q;QkpJ9-IaNH&!lDh+D~@1 zJhXdRC}!Si?jfW^7E9qpB;Yl4!~M?Qi*ApME*^MI)#zX6VQ*_on&Ei#^1(M(H>`2kJvNU^GzkyH0N?FbReA8u`kd8WI1_?CH!P-T3l9R1?crCd@G!_P_akCa$(O7+Ha0epyDhSuTp9f6{B%7;z{D5U7B;;an=Rw*Gp04x%%fr`!SGq} zaSKjO)sTZQhH0-1eNpk|+tg-Afpd@;m-WgzzqQQT#~2J=kV;aJsn?jIQ&}-Om1}R4 zkzaSi{h^oLkV^oO9!?_^f{I+Ykm({cxdHV1-8DILqiFN^eX4vDBDsO%|5nIz5g|kF2c)`^&A#)gSJ< zUpBS$7ocp5sgC=dD<;I1$~dGcY|ch2VnlnuAO0z9!M64jW2Kw1pd0fVmn-uB%n)C? z{xE)D%(%rBn0?eCdoM;n|F~x{*be^n0xs6bKdjh8fv78meQ) z%oUhwLd{E4Nl2#m(N09zUU|+Me(WIsOYZHLX|cspg6zx$zFX31gV=X>Z50X&Gc~II zh`BoRj+Q3afSrv+lx-LNmr(xlW&F8^$h@K(#14@oOJiU3xrdQQE)KL|Y0-QV8dV`~ zng0HM5E*gY*G%?;*Es>{ug}tKr3w0~Bd+b0oa>$6uja*F?;1lG&)eI;y8Y8-h zOzJ$f1t6TPgXh9sODV6Vbx3J_e3%Y5uaUK`CwjSWd~|-Yp~O$o*=g9wrD9mh{Kb(& zq*L>udE(4v`Kucul&WVkv03`kX>YJ;gWkobHBXzC(BI2o93j`9ON`JsMQ$fZRh2?s zb8szWX3Ls4%5~yF$XNINgv8z`0fB72+~?`<8tqM!7)qBg7PPHWr^%+8^wngA1@TnQ z$-PUf=cHfXwHGU#(|OOK5vwjm(Rh# zkO;u!J|Eval%&CofFcf5he$SO`^mLkdE}0c1_$dlkI7+jU(Q_wctY~$3piWzuYPxl zX3~AW9s()`S!c4d%J(wTm~o2?F?8(f)ac%hDID=YMtDveGd`=?s>;giIAv96TMo&t$67_oco&p=&Ig+O7~v zjMyMk^$VHtHy!kqrQenf=L58ZJ~_#7qRYSh-kKc4cbO6~0<3lccTbLhRmDt>REMDr z9_=xqZ^VXZe!!R^wQRNj4Vus>?Y^k8v0ppYa5os3EJu%0On+NP(_(O#$cIRQauj$X z5i7;VCw7kj%@%9`A>KB&Pk3$t^4zkpiI4LfsUT`jGpr3G>NY|V@(M-PaKu9bO( zqH#|2?<#hVZ9Vj)FIt&D_w1QrUzXYd5dP_QfVVo>ej_-0WG}WFj_@+4S6fNErAQ3cD)ixSrd-|hk@))an@0vbV$>9sV zC_4<_h&$Q|F26DI3!19csCs23v*s#RJmXAtT4AurrvCdCdQn5au5FpB>34m>Cu^*f zUTHK~!czex!C&%VTpbND70ZR3Egla9<)Hk1)8Bwa2P$Hyju{F{cZq?-8e(M2`3J8>rKBuO zC9l-l4ml1*%$HC59()wX`Dw(pvxvd}U~J6&g2|gw82qV}``mnXo$=imL^FX31l+_v zW?ZvAPwpI_kYu{%HL>o4zi_g5Q~yzr=|ROTJ&RgzyMW&C(C*c%3;LgGr+;?dAe-XM zbiH(-ab706)Z=zEGgqnyPkhU$$5yk@ICX|2x@?HFNb(-e@c-1UfYU?5U0g!li6tRl zophflZ?erGru9{wBOS3YHnO?3H3vTE4@2R>%_5;|m;!G7v2b|Q<4fzR(5+r#^c#Kp z%O4t*(`(0IV(Y~VS~Nc$^6~r~bwIf5e(6EcW^Zqg*#2P<8b1Ybs=e(08uEy>#U@F; zuWJ(@*N_l}pDlC<63bTWzwiG{S(TZhMhizPQscT1krc54o2j;BAE~WXhvGb+oJZ+r zDFX*m4}<+4!*jwtUwwY)7he_IN{#AGyB-%MkY`GR39Bu9t3o@`?yJHXUv>~Pl~XQ& zkBg1M`E|WFk9w|suJd{TMRk{--QhVa-8asytCu)2N6G(W_6Ot7$+NtX)m2CuYGY#} zTy4kN#h7J8K_Z;i?})V6YxUbVlq4i2ZLePCL!~GrP^RB5b=xs{HLvdl6`-Rlx#h;< z>1!ZMEd-$lIGJ5_-!`F+gg6JC1O+$)e{CoK4zjqDoRhh-U7uD}a)kNJ3kfq*%i4&U zLM|1~j3=L^9Zsp9tz{$FsCV0_YXn+q8D_d3;ZpxN@In_-Mow<-iMsYxh*Oa0iAazZ z(|3O!GLXTDjnH+=N#B&gK6bV`!a7l-oK+W--mzfcDt}%Lm&rJ+S)+-g751Y&02#s2 zO@AM;Ezc*Di@XG_;*xkYoZ#)vh$>@9hTDlKw0$|f5MY}g6Liq*U*QNj(Ao*`45A7{ zb8Q~dpW?}E5lS+M!$@9s4%vAWm8DAbqbS94R_Qv(xp_=3LSm!<)>bff3+9<#E}_7N zzO82;5Wt?ULjnB-z&BvvYk43X`l+0Je9wTpv!}oMV>B;QC{OF^UAvw7%AkgqgWZla zWBBu>A!51KRuhHG1S8U)R$S4y#G_Lczc(4yXhsAx*y^g{G7I_=8#K;kI6~Xx^V^L$ zGPrA;KNA&sI^#+D%k{s#$u);G3O`}eFJYy7X$rWUdv)q6jdmaw>XS{*$syy#UtnP}j zQbW>ny~qVjTDGG{(c+oAad-}V*SlAqOeaCJAr>DC3ory|!ic~Ji;){2a@xJ=AO*Q94KS7|BBvOy~~OeANFGK%sGpO-NaBZ`0A5p0^j%h)10BlXFJ3 z-3@T_a63%q6k3t3K72eKRUI#Pwq6ZI91qc-MJuqA&#-Be(bN<7O`nS1~2)k}gsG{UTIqPD+j>nzGq&OR4 z(`fhVGWfY^*Y&j*xUBg0i_}F=af0^9Au>OTrQ*GN>q=*DMcA^6OX)<%oM~_OQ=~jl zbWZdy899juSH%K)p(uOzQTqDECCn5jgSZUTB60NzP=3wk3&`r!_=?F9fdGQ1k3T11 zrcgR9hB6U~q!Zpk{Yd52x+7|6)D4sm(2{Iicr_agmcJO-YcLdFT}T?*x@zz1%Zw=b zkuW1koJVzWAtjNJlA417zAnIhCHfm@rD1{}i7>=x-MKSeJsq=^9KT@ebTI2H7OM3o z2mAX=1rBI6lr|NID(7Gdo@lh|%VZf~vjz!#bWX~TUWPau_TT@hbCbMAOSncW+`D5v zByWkK(1v^#SH5I-S$g}ozYH5~ce&|TjjBT#G4Soj_{sVBPqkT`XT$k1Ri#7@uHGurUWZix^kKz4*qFVo*&TpXro}}sAr;Fi* zHw;-$5K!b%L>XzBfrB*!#&NnJ$4-RNl;6=Uq!env4S-SA>@!ZMuX2nxDZM(`zJ|@N zhP#9xpM&;77h0NHO&fyyMbt>}jgjp*ED-P@JI##GNHOKk=OJin&rP*BuQW>eHoR*z zGH6Paus+7h?XApza(C0Un3c9W->Q{I&r&=0xk)+gfe=&r%5#2|=N|E$C!1;!5X5sZ z4vW;B6xj?cRZ}3`oz>5zP81x<7`p*j^NIY$LQ5$yfsIrz^awtS^E>({SX}x_;-os+e}3!qpY%V>`Y4JC)SzWwmVNhkPWDz7xc#`4qksm^d<2 z2(k3_F(XTb-=+2O&v%v0Bc5VR^XdW)h+s3apW%w zawU2$t(TO{ZB2OfD1UnwVR9jq4G}!op~Z*?6a{%_Jv{$lt>INDeX8Gl;bXiQ1OiCx zJ1RpgE$gti>7}r*B(k5gzBBK?pX#%baXMaN#-=I0@Lqi3$L5%F_J<>$2k~)(!++J! zG~byTq#_Fs=FOq(itwJ3JHQ!lC8NyRCzbIVJAfXFxJw zCBsMvuhWyXrBe2giN4~OAbgb8uhcntec_Yw%7cxhEz#+3!GXO0q!cbW&!D2Nkqr9k z6a#$>C}sc(2mAqL=M$IW@K7WHFW@DAg3b0O9Fgl#!8{52EBhkx6acTsAb9EPkWS41 z{*EK%&WNhVB0{-JL*45C+WPp9$MgBpQU4BA$4EU(z3eJoc=E*s80S(JL8vD zjiI0oUlS}8kIkkxq@?waWUBs*GU_hvS0mn-hwqFzl^%VgcuRY|d$5q%MhV z(aClKxPPalL;?JVVGN9kI*JSR4~XDCEC3L&0CXX6?l^$+@amD{1P}}$L9C_On($e- zP8EjZE=1*NVeMEQou+{|U}&}=Gzk)tCKIu#h_2Ua9ox$Y)YKNsXo>t!Vg&;+{#a z%g0%}TxTO9D@E-XlCQjFhEwD5IvE-Dm@=VY*Y#?6W=jNf{`buXz z-}W|#@s1aGs-f194l6IQtzfF{mk#@xtV-y+Gq7pJb^baZ6$V8wi3J!vhSpV6EWUo0 zS`XT1|K?O+nT;2t6^0^(Q|lAStBsUi2RPdKVMuIt=*}-$z~te%K?KWats)3ApvDh~c84pa4+H{tInyyD@ZrkOjxt0JCpA@?ixb{)3KLD0n4 z?J-|pk;y1#@v^L@>a|RB8os?OT;uq2D;-{@EWw4DDsl)Af#WPzm^COr`EIBRU;Rss zsyWOBp9m6<_AUoSg=7=zuO1)VM=QAFCF9in#p)mw;@oi03iWE)^&l4fbNWRJgw%td z$h-n0IVt}6E8rp?g9I^bF<2~JXDyT;s%?M@0Y^w1=1;Ms2&4INp+}(Tcv_nc>^CEJm<$= zPsgdKyxLc-xeqd*TL<@?KghCS#vN5{ar^7cUAtiK(GLy6)MVxzn7xgMV;Dkji<@_x zI~v5uND$EuIjcT_W2J~ZN@}Z%3$&z}pg&)TgbjE#sG7 zjSm3kDsJ|GJcxVPDtg#RFBUjh^2vI<<@@1J%@31BftJr~)H}V;b*rj(UYEOX{FRaF z6y-rO3n`E5wTx#o9P8wpD8fmWKr;R&VT`#sfkLB7LoA0co{iyp6gu6NaR zJx#7+bsq{HE^C`4@63vjR$MdG!j&33)*R&2bLG@2;nZ1LnmV9S6%4(4Z%0i>F;=_Y z6DyQ|vV|w?+V!4;)T91Z_2m|$t#PqS#y$m!kE?iuie#YYyt>#!Srow7?5q6cmB#n`2385UKvltD{F!mOM4|v%3;O3e z_0>Be;-8dtu4SdoWiLD^apf&NRKduD3Q$g%s2*Ng_~ZhAU0L+5GW(ASpHQ9?_wE{& zG9JBr>dhY>qeq_bDSunoZqN;P9;%P{L<0EZ(-DzXoGitf(Ef zaJVBz!-{&&wjrQBT{1I(@3&K3z66zXqPBBcojIH-ZwqapYFJA-)KFjV4vXmgUMUHn zU}pXf8i}^MNKG#jHRIOT92Z!0sJ4Lxu#N~Sw$3;kY`}%ZDX#dJ8%bO*zlClur+;Mf zU?DCV`9S|tQPAmE7-*Dij*In-1}qUoW8-l6krJ2VVAOE)CKCd+wjr-ZkSes>mQ{>d zHKE?5>A%%yHvBn_#-fDyLj>9-AqCnjx^R#gWSeLtS)9(t5b}N4+`TCd5OKQ zG&Q{xG&f2ECZ#Q3ooxMtxe!p=BkS`SZ%``Z3ee`;@`9%p(3(qvzFd;&e2m=&Vji$+ z5}Q#GIkZF+D)E+MgH+oSkEW4o*!=T$oK{UW3Q#$J08U+6k<|GFpL zdS$GsSk?|BK~s#mpD)%^i!m%k9CI&z$(^b-U^^_jDLRz3^wI&D9an`a8ykq1(C)o5 ztpBONx3`S0Tjc}?&k^=iMw+;#q<+rN1nD%&U!J!-`dT^vuKafUhdpve_L_pb(caG3 z&_@t-9_ZcfKm)`m8X*wt_579mm>V32=a5p;`the5$LoLp+7*m%UjB8NhXVjH)cZ6< z5Mk5~8;wZk$%o?sy_F$B%bS+W6a_~y_5y{l`o8*?#72b&oQ7tvHk&}zA~PXlkd-Ni ztmb5d{7h2mY!WFHLpM@C*xsM9yG-cn3cvm^E$T+UvDMeq)jf_w8e^L&2Ng)d)h4`j zO`tsLQpYIT$wa4$N8eJ6zQsjfb0}rM0Fh*25Frh`nUyxI9siI&FYFW!l^<&wAs~&= z1JkZ`e$D|^rfABwP>dP|#($B|dI$9iymSF9JtsMjSt$Snrm|LCr1d zD}JS3wfsHC#Fz9fqvp(~N7td);Gzys*0|lS`l$e;Gr6hnj>us_`7yw1o2Y|I158T( z$4Pp2FrG})!1Z?kPYmK|aKS3nOBIF_V-{(59eJe`0c=saWR>q?k-G2nRu$+~zAp)( z<_Y4-pi|5=mUcaEb0yKW@_Xbo?t!hJmh!JXXX75?ez;yv6}CFRza15zX0$>%VG{iczV9g!fxiDs zQ3O!W08Nak2wialCe+yIO7_U**0YEAvN1rm`1mxtalfa(epyWXhvBbrPxEUtPPg!8 zu6nBs770Lmd4wG2A19faV|pYi_$7`ptWq5FD1Iq{;=*J4?fOe%3F;zmHL5ikSZMZ& zo^Kb}-ASNZEGc{|a-_Jr(N}ECjXxc#Xm1Rm#OB@s$^*o1z5Leefq#xRk#D$($ldAB zfE8L_SvmRxEJ1_-1c^p6aN960mzN#HzT6P%erbZDkM!opVq zPJVEp$;il%JT~PycUi?ao)0ao`?{9UJbq;^X4w3(c^?B?f5dXxZ?Z=R$-XNZ(TdcL zSAN)XW>g?gXJD3%;*ZR=`g5c?WLx+=)^{XzHB`6Q>}z0AjA!G}>^xbwG}D1ceTQBY zP(*2$ziU)wRoXAyzE5G(s+q)qNSn;y0le<~aUWM#DAr$BM?I{G zdYE=STZHCx@FGB$Le32}`L#`VVp6$K977O!xqAbv;fcxxW*`6{a9j?UqN=b9`7#(8 z_IZ7=I@?*LA;_9279SlmoEkB9-zGW75^BX>T$OLb+0xZLMJw$!$_~`@VFGJGi|YQL zBc$2r8c9X(hR3%XBL&Ef5W>reHFXd{@}RWcL0bIfH3AZF6V$qK7o>=(g|@5PG= z;7`Xcwey~8W#Bo+N!u-De5f7@ESBMHmRmHU>?X^dR6Sp-%mb>->7!r9k$FQx!5u%z zb(1jq&}K6%>87j2F{_1qEgY_?e>`m2Pcd<0@zp$7>28B!$8+L^0*Sv7+p(bpELrrR zou@4%jn{5vzOt`-yLUrWGLu9#@&@CV*!a@exMR3(B}~x`Z*!cjQCC+&q**q{$5`jU z%DjT=L#{!b0ZPJb`!y@rG@r6*o=A%4k4iqIg4-_MyT5%Ol|iNV=hUzv{*3SuJub#{ zo!C>ya4DK+EThPq44(1<>z4}jdjZUv-t=i*1;E~%<7mRg{ zQ=oL!IJp}s77sF9YM_p*a_8hjL)Xnz zXMSefe)DFIo1Z&VzOp~kYYrQz6T1)?cyRigSMcF_LP#7^bO2QxQKY`&Ipi7_yLIAJ z>c_ptAdJ)FGqMAG>Rfx^PFic<@^;521(T44h+&!7B931b>JV4=B`wd38FFe{@rrWe zCk-k3S@UzGgR;N6vc4Y3T7y?bVpD3xge4iwb{T!eD5Sxi??~kR)TC7Y7>jQKs$nz~ zg-I?47ynEjV40ANIV7#H9xD1oN5-&zKW#% z?2Qx~qf$N| zZJX+|iO>fj!d}ozTq4{>BGYq9792}XF35UV6S^iJN zb*#-I;gGSs5FN+Z$EPnv{oFEb?N@c=+k3G%%V*k0^8iCwa-W@`D_IQY193Z>2{~Xr z_*p&OVK6wq5h`%OM;h88W_0{gWpBmOG+D)|``p7g^hFvs%s7uVZ$Xhj zoa&W?2gg^WswKR(HRK7#4d0tt$We#gx!vk4ieJU^zk~o1;V5^Ibu0EwM zrNXjRsP7x;(3b5uy$r>^aDka-^5&yPYB&x8bH*TVCKh-^3Wc`CCp9qTsy0&Z-atnS zk$7dCIW8&lXNTYDrCd}-*Z+ThmuR>MrLgjLwhkfP(dkt_CD7M1zq92 z=zO_o7Tn7LpHK-0-ZMqCXC%n4^xI9TRm~MTkf&P|wfvgQY81CAIPT0L57aU&VDaos z!y-VNAut{`T|El93y9beW!pc#ImmN7fHn?C25M>gMzw@~AhhRi=AmrWgk9eCPu{5iD)p7%`xM4M6)9XHVP?1#f@E@YscWBt#F2oux zo2^To8SqWsDpv&`)gJA08fTlxZqAYuTAfT)q?{zqNM&W|?3?Y>A)qFytWp{sqMFk1 zg_A&OqR}f5!uf#!?PK5`2$t+?*Dz&i$o!<1w+G_)@mRd6N$_96d_)2caqNQ-O+|)U zsL)tA?H%*xW(3z~E~>kx>nVqufUW3#wLCnI0)dlbcA*NkO)9=3PuR_$!?}Eh!oW&h zLby;_6gb7U_fB^HL)thLkGqn-x?60jQZ%HdISj?&r*n*!8MKEf`Oh$XPTZ?Pl7b^$ zuQV+yJ_jg;Pk|L66d3%zVFp1XhxB2-A~9;9at8c(IsJofQI(Nth0Mf6D=5DQojK5# zL-Qj!qE1dupf3&5Jj4xa5jsT`PNK_Ha1f(t->!Lbfu8M$bgO~-X;+1;eyrW! zT_m1dMdbcQFg?9hDI_UUFYz}7+fh&jpb`ZXlT6b z#!U(bj=Yf(klq4q{QT0;w0{7p0qgQ!(<4x(mbJlnN3oiCIyLGfK-<`wwUGDm~a!d!_}AnoWLn0&0~Eq2@r{6`maaOF7Xt%xukW8morlg?<$*uFmvA$;rW$BOmeg5_ z@8_evGT&J=YJS+iOKKkjlhyd<^f7elYK)99V}#~tV1}ZjcF!YHm{ma}K{V*`Cy$2- zuS9F=qc^qk0s%=B61^+L-n^pl36&R?bO$UY7A6aP@#C$IKEvfr&L1wT0PhhpFd!=! zkWbw?$~b%@_9NKK%6xA!O4xMfTp{=rTSPtcwle`b4v>=SJcM}Y;&7X%4f;wr|RVz#R?MX9)xe10JKqDgYqTp$bg zo=dvQ3x!MJ9Ok_D8lm}mudBk%zH$GSzpP%JB&-?8h99p5pT|H#Tg3_3-Zx@T3UB(0 z!-JFdRqfGN*IZ)1@^WZ|S(B-;T>kQYKVBf{xPQ;m$<5L+%QD3RVY|aMcom*mB2h@e zQz$Y#;()DT^@v1@PJR`;&* zQ*oQ^i}!i84^V~F4}x^6tmGj8u=wx$VzygKA+hr{BisnKjz*0w?k46}&GD@JUcoy`~_!wcRhc#v; zpsWpC0ETJeokwx8T;R$3;>8QqA=%Au-(dN_5#E{)J`ks>Bq7L`0WU>~zlVV$okdMy z*6_;ozG0S2`%69Fmapz%>(}W1Qki$5G!N_TgikQl#z_bZj)~j9598ZxJ6jAHiAC{C zAbvwX3mO67_zNnZ9-FCKbe&(Mn|KVB&)ho$Yxp^PL`e(~aK_$ocNRVAyh?;~>xRCX z%T_6d$I3d~9rSXK3P9 z73;zJh7D9B%tJLi59)89xjR)_+BURp0h(L2VH$)e490bO-}?s4oA_x%E_7 zmc)tC-=nb&zrM6m)GCi*fj6$q(Z`|f8dGxS&tjck6PaR=_F>1+&Is4TI`Q{zUAm`K z-B>_~?dj?=P>8&hvT9 z9mSPmD43v;#K}9Jk>v3#xza_Mb{RS1fbRAW6D?wb(=CM}0v@TyGm0-AV^I-WQTn#^ zsX3i*!Q9bB)M17G3oDqse(9&sw<~Q60#6|N`F)-bxxdZV`F@{T)jP3a*{dTcL0NxB z_2V?s&1|$>+^c>4bZcI`tNk3Zk#2M9T28Abur6D5mQuECT(hIIV4d#Q8<#npUYSts zQ1fS@G7?PqWSC!Dzr_2fGP=6n(0`p`EF%6z!%B{Osk$)T=DmA9hg&q1eDRYnI|9va z&gfkju@tT2Sg@!OWeG19jzspYKIQCVt44Qw>Bnito0I)J8N|WvgNJC@zNUN4i}tH) zu5aG0F}vbm+r(|I+&6c1Df}j~#U2MYNlC&tr)^g7AMXQ5s%}c)A6nLBs*xs&@=jtR zQEz^d7v;Yvd|}yMnAiSQQB+7Z zmeX6h$2Q3=WZjhx4Ez@%;Ie3G1HG9U*Oh^zQj*(RV>X}?&!4H9C$PS{>CutfZp+R} zpgzRJo!p)n$}EWc-HI`m-EnKC?)l1F3Rb5KSNwexnx~VZ0Yu1GFPN-oovo`6Nzri6 zE%xc1&PmoRD`zKV?{Km$k3K3)jhlc#gz9UPrnaAzE%W#|-RCC!MylVNW zfPM6cjx2`48gn8H)^bvMn650gn+rUT@+zr~H7G*?$AbtLNoge&$ul$^Y_|Vev2%*P z>wQ0K_KGbni8H&m$K*Qq+b?CT{9@I~(R|y~+b%5ow8ZSH74t%tFk70o)bb@x)mK9O z#^=*rdu#0PPR*7{xK7@dW<2@qN#(ugZ+~96Az$osYU}=}Lp{pA+ z-OnO?@fq1$C*N&zwO~jXePfzlJ~G9%`T8y{u8IM>_iuO~8458(E{%Cg^+AtOa`gsaPPz05;7Ut&4 zW@hmmyXdK?6WJG0%r2TNrD(mf$>!qZEF0jtWz^@|9bhD56VH}i7ge519TJzIbwr!L zB*`#GK&YmkWl*PaSG45X^_kA4D>95iRd$A|?Q9Ku!$Z|yyeh0yusOymJF0z8{LD@TIe__*sL z;jg~OcT5z%R$cQT^yF9Na*k{A0i6Ec6v~5elLHB7coStfwkdcVwfkEOAbXr+gPGuB zib4S1f>JDair!b3+T6j$*5OFt?h_r_;#@i}l#Vcqt;%$IrLM|4T;N!=Kl!c}Ied9x`Z&#u$E*X#V{@~cj3j>$8NwdD8IM)^Lynf0ok(LX7F-*ojx zA;*Fh!FAOc7djbe(vRzgp6sdNFc=9up|3ge>;!Gtatejw<9ho2yzn9lgcidL5Ikq)A?$EhIo)=Z`Y*evz=&IC~EG!J!csbXl zl6%6!B~2&&n%?fWj{55+)-JF2IOE@E=P1Rg9kbfEQZ23Du3oK{NqpLnKCr4o$I4y9 z;PAKaN3tE#-Gg=BPAXY3;yEbqH3oL?0#pX zm!Ik8+@Ge)bJRnmma6dguH!B|0aBtvxis5agow4X5XHgp~t4n*h zwR+^h#X6fafmKnmg`Gvl_Nv$8J$~ME9*|dHvgk_=R%)YHmfRZGv#V(^#$L6?Q1`qc z3dww3SgFf<_Xl-nCT%T?I_Y`!>dEakcR%M#KbKS9v$+l>oX)>~*zeWO=z9{lex%W3 zWm4Au#Jn#u1_gex7e2)vVShYjn9Z>JU8bc*+OhN#Vxh`CYULck&pP<8$txNX?V$K% z%1Bdujy_O`M^mhxvFRt&%NQ0ag5$4v_G?WyPs!Y!czV) zd9NaaG%dN4Cr_5Vp6zs}nLWtbsWZaXtZ6kPH^IW>B6)gRp>oeKSF>J^%Hf-O;;EA2 z0T4n-8_sgSt2ak!@T^Z4BmjBNn(v=0PN&;1qUx6{x>)aFFTSrW<+)Y9+ScuXwJ*P4 z$}15XSUs_wlkuf+b9ER+u!d2+E2u{bJ6RwSH934K_WoCX$)7hT-}I(c^kya$_g0VZ zvZ>rPaYiHUMBQpVhso`nWIZY>)U~yD2Uj4sT+}IPZ7h|!wpU~1aA3QF2Ek^Wjooa>#94!a|GGwni;y(nCI z$QGtV@ zLdK};6#Nc_^5iId427~p(8?F?Z2Cj`le(AYEY6qj3{Z16u=o!u8B47g{2910d4K7K zC3iNK$JRG!#vB<)u6sJKB_*zCtLJMKpm#w2vazXcfuD?u*r!(vgJSf)LEUNQrfHn& za`~sOooI=Gox|?wXR~c-h=Wa|80xYyoL^=6+MmH4j=5**XEOCNiqD$R5}Ta@6)Ejc zI(wvQoh&=m0xozSjal*{hg#sMhnWIAa>jPZ*ln56C4n2+PiHfP_N2$JK3%ojC5fYI zS7cMfaVwMDkV)KtLg{8MUn!@Ro0~gR?I+H0Q3M`}UY%bOU%VQ7Volt{=2z6d8!Sd- z2dYL+Huj%6G46kmWv0biMOoiAtv}?bP30b!1d~9nyKdjkesvI;wjq1yvt}(WdPX6> zZeX2{5xUx-#aQ`}OHy?7%K^JvY<;fuYh1#jm{RdaKD0-zHt5UUvnu6R54j$3u2g2W zxYDO2DRoRynih51oRDzUHM*hdUu(ar1ip_uk#v zX1%klE$q_Mw)@jQHD&*b;D6wsrxz-3or~z~stx4j`=FE+l5|K%H{GGQ<>1emcXkOYqxKPr~UnTO$%H8=fe{R3-ssXv;S!2|JlgXSy(l3FXhF-~F>}BhSZfHbiZ`SUtkSf>u||V(w}fdZ&Ei#Px{tFhX1W$droDy-Mw?i*qQzf&$x*H3fMoEfCZHFXT|Jw*8P2HdQ}egzke^jzYTo| z|9oE4^08Bjx1mu;Yo=xJv-I>#r+yW3qlX`iL{V}n>^}Z@@p+#(h493#u2V^pN0$G2 zg3@AzPnH}@otI}h~rJr!m$S^4ksnVddtUV3fQclQDfzYA1H z{`&==KNsD!d9yY%^?{}T__y`J6_4J&Jj-@2|ECrs3Jb*-Fb-cbHHxcgYq&8z%M5)%>#boejX z=(gt*5J<|((g1;^;dhbh#UG^!A>RARlRe2=X-D)^n|?ZPGdOz}(O*!T9b7%%&#v3`F#0e+R)gT7!y#@k?%hY5xHR4j zPG~c)KCqH#_wO(QlMU3gw9b%S_!mv+atCA9@o9SBziSQCuxZn#gr`rHT=F~qx%z^+ zYqsLg?XXEIIpiA!x#ppgq+TH*d0YR_1t0&b5C1o-QF^KXdlnJFGSr%RqNSxpJI^VB zX!}1l;QXOOXlJHwZ=cq{## zJjjUt?^+vXx2dbC#X_fA;939Eil(>pxa22OFJXWe97U@OA*NqcN8R`THsaAR;(tEG zhVn#NcRoLfF;W_Se@!UE4U?riGDta4YoTZU%TG@mqW*m0(Ccjkkzf`tw4e?hdY;_j zRD_M=kwJ{hZ`1zRx-IMEA7MW%$kd4GN13N9HZu!3y!zkdxA;;+kyIVdAV+QFRDh`P z$n4pyDk*spJs|&@f~_HPP%240*g$`O+CPSoI%x^z^${L=CLVUu%~CtZF6x|kWa;fi zBj~G{hxxHRPQn06z~gxLAs5ThuF}whX4D@lWw!h=+<0j=Ykal1RxV7yRzqF=u4z?- zwUJu!A!zH}Aq{N~VNZ6m1n8{W^yh~r+=1)wDIe^O0Y7C05UH8|; z9ReuXaRrNvW2R4 z@0r(@D0yA~_m<4f&^=?~kzu(YzO zM~|;$Lmt5{;|nhyVydURM*1$Fn#Puvgd1A~EYOSluY#kKPbS*STemzrio-(x%0C`p zjXn>3J+yZu5d>DFhbugA%SL|dlhN>5KuFUi`6_s^s@N`U1;Bk-d!%73jc zdK>`9C>a~aAawl)t=%&UMc0#c#ag5{R;JgiJ62E$gQlhuXwKVn0!2Q0bQCrU`kwXI zDoSmO!n)fD?uo35M^CnYp_KI}7-hebD9nof>!O~v4M9QihrHs;|AyKWO6@QZe?GNe zeapsdSbO>s9^UlkN1qR--|c>Mi3R&{i+cg<-O@!}h z*fbNa;YZ>#lchGx@c)Oj3mo^vrYOAxaQf7lvL@kRP=+uSe!kWC79cNve$+T_gYFXF z(wAwmf#Z_oC)QeVt2XKjhSocZwBGgTiG|5qf+nmabm<;FQ@PzyE1%K42KxjtI|=#J z)Ia-(NI05TZQn5R-d{_IQ^)amyMxHuH8B_m$h5NmvuF5fX^;6eCiLS1_-R z7t4;3T<@BM8%XZF#W6c!Z% z{I>WESK$amvrDR1XwKZ#(K2-2Sxgz~SY_>zeR`~Py#mrzqI!3C^sfP6j&B*)2~U#5b-h% zH8lulDj^o+N9QtpVIhFugND-!%Mh4BKt<7qRLu51OyX4Bf{EJit4ltu@h{1lzxP-G zouBN+_14|gf>XOv@<~Zn_9}S_24A)kLye`i*GKel@nY@z|9F)@uSKuAr;b+v#Mn?v z`Z18f+PMyoU>sE1@G=8~gJ_;*oAB(J3YvF6Yw4`y0+uodF1;qTjr=0^a+Bg8w?d)F zzVoLK#xht~Sd3TA|Eik7F@R*!Ou2aS(AI}IZld+!$7_LcjKn)0rF5n`4JYy*vYh*N z7$LEvR4=c*Dk4A(Md)SrhVh5TlB+|e=FekN=)?opcPsHSsyjPp!YC!q%($N|=&a|j z<85eee#{wpP6Y?oRCyVhdAQKWbAZ?z00SKFV+$yAd_9I9yyOLGM8El*d;lf=WKTaW(7R}td;p$_6O@M*W1E;TX=YKtr+cA8&jL|nrJxRm7zxGkQn5HO8 z6SAG-=)q;#^6WH_w8+Sh0{v7H=gp(55(dhL1neC)NTiB7=Xynl7GLjNBb^5B@~BMhHcN76`ch;HT53^?gcbaaC^MTV7Z zY-}uaTwSv70q0Tv-SLTkyTA!zw>Dt z2#lf50-XS{$@^Hd48s=}ls!{?jUGRIcnE%eV0gIk-d-K)OwT{^UwrwZi4-G%G;VVg z%82K35DpI&u#IqVaNwADe-4Eb4Jms0ypCVwl24{fE5sjkJ_l_vIZ{G=__$;sL694TwWhezZYSBX=y15x6pg` zB;x6S8KJ+r*v(pgg%^8+@H#O$`EFHjT_~TWO8OSSaOgfQ)$&aD35!bnTX7mx8e?yi zjvl?7k~fgJD1FdEU1nM08`Xy5l0cP#_7Z3(iTm^=CgwF7OJ(gvT|oZCx_@$KIPrg-$eiqTrfW1d~7q%ZKBRH(D7E1HydqPuJD_F&z>#6iQ*I4~Xe_MD6k@ce4*Ajq`jCiW1tJqbt<_g*{P zhMyCA)^WBs{Nhb9bxqA+jID_ga{ThZWqGL*RvkXCp|&;}+p=u&B6P5=W4QwcVS20= z2Tuqs?!R$FZ-6lRaGp=X=Mwp(^&tFf_C0?nduNCF=eKtg%6?uK^X_41t%;Srvz)ni z)NLFSs1-3`S=Gg5(#INNhw)7_ea9pcF`zke@>k6nHFWjRK+!GY&Z_%4eZg`&h{cE7 z?Z@~(C;^NUsI9k^l?~`Ko8dOv#TGE(UZDNd@Vs1|8Ui-Cx}I(H4?C-Tt9n%(X0U%q^KxU3Dd2@+8f5(cPm0(?(kU^}#f;F|w3NoI1oON?)XZ7^I` z=t?{+2xOTUI4!~-W07#;QQX?W=m{8QW>GgKmVjeILPG4qXo++T2)z!Y(LKa)A~_Fs z6md2hv8%!C?$yacRu;-m9pZn>ea%U_&6@#cNVfO)$Ams`y?H$Vq{OdJG=Sb00g|~kn6Z6WYyvDDoDnkyI1q%L_W-t`IT_%^B1{(lEGT}4D(B^e! zcEme%mulRZPcJX$;VKXo=hr7$X3MX*iE`KR9_vn^&^-sR`)v;(EU*XAr-iuTB2}sF zBCYcy9iw|0Z&(16%;1cD3|wwPV&ZX4J?Fb$-iKQ{pTUFDZ|7jI1w}Q8f^FcbP=4!B z009eGCQw8DPRALiFH^8QM3TT0yQ4{$6J82BIfzNj^@FKJDT?R1Hj+Ww$If|C3Sd_O zY&gym9w0V9Uq>g~2E$mI_?mQ$LEB;Op0VjNn9FL5BOpfZCC*9iY>n>!(K7JVv9f zD>veT-qI6S? z_frf-56G*6w8TQy;cFQPiwkh%(H$M*GtW&s=waYW9-7F1o(NQf4CPec@|U@Y7XY3d z7_j*K(NK_7e!|qftTtZv>O9^5JLaloOl^$c>2o4C_}e?QzJ>p)4OCbuYlIH;ds@A|)^|ur5LXRB=!F9hk-K42#D5=SA)J zQ}_4S3G$x(ZbHy(cQ)lo@zn6;y|-m{u3L#eeK_+-vJw1N&4)Z!krdfVc=^74jLbKr z`Ou0SOfFEs;8f9kflXe2T*hm{9pljl1&XF`2n!4QcI>+?gK^^W1ObbC=D~dnor$y) zd;<0v3S^E+X7OUSaJMA64QYOBnjStiMxTJ)1aCP|&Kao&Sk?M|jla~^E_KU6E0RuM zvPkUbSA|V(zKXPqi>02X<{r8IhIV3}))R*u>%ATxwee_gE#`?DEf6V060ZQw?Acod zfWbg+A(E&MCML&+$jqGZT4WGIdCdd=fRunT$k+GZZ*lbc=3PMVNEo2kfo;g8^ROw$ zj~{oMXwV#FXPv&Xd7u7+*2c)kZquKG8>*`xk}hHyd_33^L`a)fU&fmDuvH0YAoc<0 zIDvl6ubv4r7u$Ums#CM;5AJyz$u0|ER6Fl6Ilrq>-_qWM!jt6?{OiUuGd-?+kz;}5 zXx2B7P@-e<`oiX8zE}NWJt}!C>)yAs4Bw9$IAPWN^f2k->WsI(shokA5~PFeDE?%3 z28H?B**4)8mX?`DCCiZj>W8hgYh9BHR|Ov00*P7Sb3dM<{lwGqDsac-^&vl8G! zcY=^E;X%CNjKeJmF*?xNA@4`mbw!W&&qT!+MHX9q7{$d z7@78H;gvl%a+9QW;MN=Aa9>~imYQP5)Cicafw#F$yV|U+b?-OR z&%e$_-om;)M>(}{X5dNytR!*?O=uS4HCt-%>oNhEU0q!nRj*MdRQv`~x)Cwl$#m0% z=g)P^O;ix{KRbPq0O4fqN6aEFXE3!f54O>-y=nm&V#+6WZTp?_`fh4JW2w=wIARv_ z@`NkHMKoc~nHqWzYyi9ihq=3arN4;YRgI%DWr!7S0W|I2ySHInCFQlzSIlK2SBCTY zn_HQl>W$PC7=58x4tYDj14IHL|=1&zF4d4y_42? zyyPL~mE$4~Jy(FdVR1~-!#fUmA>VlyL8iU^=t)*ENw2BPuTY&%Z{f9U+~fKEPGmj& zX$Hm?>v>Kz#JJca2{8Z!F*9A|or1O=T3i}W=*Kl1}@00t;X{q57LXqHXYPOT-}(W zmvrsg>RFtWR&{lqI-A{s+!t!Ec5k?PW_D%*>SQKFYV0T_2dE_VQ-h^mEp0SV{N_E^ z>pc!bhw9C>t(;(kT#J5&;{oB4&b~jfDqoko05dF9fnN!egeCxEYf;|izt~jTL@=x} z4uo)r`(QFA9@F3D4_Aoa%&q&F_~rkgMtt+hj>mHCz5Vj2 zCAoDT*#OJEdU#WHuZ8YTk|OpK53WW14xL^a&rlC13P>_HGc$j%`0e3XK!Nes?ARq#-e z(zNHT(;%%p7<{8D!vq3UOyaYFpYdNs;Ib4erg=uKK(OJ9WVC^5z@vOt<1S>LX!AR~ zIwgK|wrxIfa8dD(Qu?)9Rgv~QV($yW2k`OoKF0GyFk&1E5skwOB&MV& zz-_RM+Mhms8ZSrh+Fc6HY#e=YPcpy0l;J(^MWP<#T9?Cz&!db``tz46)f=bV%?8nF z_?8j9*)IXxPSGSuG0u>==`9srq7US}D>--HGha-(?pB}=i^?};=gL#diQFoz1CsZv zD1%6G!`{g*7zl}CZD4)kQBh~hhw78V0xt_NYxr4<6&BX!gX^p5gH)0PO9M|v;{Z1y zjo5{UvGz=N#{#m@tX&35iBS%I4N-D}ilU>J$TWjKJRbc-R?$SVZNJWkna0Q2TsN%S zdo5mEScbgd`=@Q_dK3EkjI?5$_uT7etTdc;24h#R8FVcqFlt;6U%GBD!wMh>cS>px z+THT&XhY7A(maI%<(z*lP6DSzoVCJo6p@TwMXk3B}hr|2Q!LqknUURiWN2Z@E#x^l6L5_@QD}`Q_aC%?{ z{22}g1qTZlwgI6NWMy6#mynb5BV!1IZ3oLF<_P8Jgux$u6$W$9P#Oww`Vf5-JgVm) z7KF6}n#1X3Y1%<0KK4$x?zJ5b6?-8Vx5~PeL29NH&AF3sg5APVFpS^27Wfv322%na zp|)ohod7ctV%}@*jhC2B0JDw&O2wH^A-U)q`n2~W2rPn^2N2)9N9&=j_s_PA1N!5s zKMO6JxINJ@4Ln|iP5w|;{Uj<&(f!1r4kixxBq%&Q8JWBR!Uen^JWFjBYwtbm7nQZ%7u;%2prPt{OF&w4zN<_Dk<s=B7{dkaw`Eqzh%Wb0Pj^f)PmxXoM zp&0Q5Yz4EhlMKei)q{ZE-$xIy4WJCtz)n!~vE8H$X}?DTLxhtyxt}-VffGOkDvD3X z>Yp1uiiWk0+Ng#)nf(*Ctsl)g)nL(V3a3rwLwRLWi{|oJJja!ZXcJEhDNV`gTJ1SI zXwc+ZIK~WftO#Bp6_TVfbZ*4sL!D;Pj5-#8Tqp>v0EAh`6Z5aCPwXp*MVKCYuW+EK z8$+;In_>dQ6T@r^PononFbClfLoHKkU_~-aD;Ya5bRCJ=>QwJp%MOg1#|F=!jgEI? zm7}29#_YDCd-WdcCllf$YB4S2BoIR%araeTlLv{1N1h^KHqv8Qr~|w>xTHMvY2-Wo zmKG6SI^NYfamQ7FFVKSHF|4yPAJCZ+jo6Y|e|=n$V0~3;gvteK>pa*a`1nD6IE}&UD+C^RkK+tnz67#Br)Iww*H;>l&^pigjB^z}Q z(@`yVMpQ@QZ-{t4p)Cj?0wH^2a;S}zPCG&qQ17U$s2DJZ?k&p5faP`H6yZfkEURK{ z977@y6pu(*Hl;McV%bBCj}*-`qypRQ0QlcOkvr(!i7W=WBrzlqww)8L=K$n_K+WPC zqxHE4nA)I+W?(qFFw@?(jAUjboQ*V&hFTe+LVMA>Es{lNb-p^eQnLLkI~17 zL_MdPqX}8_pIGM(OU%>+@OsWTp%sVcTcl00tlP$+)Jjzn^UsN4MFD86zJYmPRla#B zaT623bOV7WxN9bw3{nwyObj*!xQU9id5JO_>mLZImlx=W#iaPd1b-4~xO{|d;fc_) zK8i3L`#3MBn=IZ~j}}_S7z`8&cyy44MHCfh#asQtwteB8n|OM5S~Ib-qDaNMb2>&M zjF0oBhTk%Z@$iQTTYic0Vo`aNMs>QhS+m=uW3cr^Gg{@ym+-s; z`LpP!7lfE^dx*qzxuQw{7~1L}6DW~OaUmR^z>rJ6kaa6>dQ=qKgxj{;Jhu5m{HnD+ zO%v$S9k{C;lOgy5n1l{IOhyuQo_Bi)aRbXm=g`SI3{`e}_Uz%kQ{H19S%;btZ8_O5 z*EVsz7aArV3*$KIMyA3hCMK4&7Qw#A%YK0ns|LXIHV2uA!*?WlH2!|^;cH}vm@-oU>dmymE#er8HTYGInN zL^Co9r;Z=cOw|{A*a1^_P(Yw*+`Yhb&t?(hHp$WgxN)_1GV#sFIuhU=&w(cX_uao* zeYpPV9ITYU_7KvFyDG=F2+7fqz;|GkW=%OZFgzVfof}A9UTT5+A({)tQ|{TfPoR4= z$2@eTP&4oy#EhnS{;sAz!?-@8-*gmgXS7&-fwV6FI!}m~Ad^n?>_{l{{rPKcFJXys zbBvG@`8Y~?V8wBaAqaBYJq(`}hDzu5bh9cSPw%m?5BCG#p;kttNK}|C=otz@#?Gmq7uaif<~KZY4OdX>98VMF>%HPhhp%niw@s_ zIoVQehALhm#BFsp*)$fc-D@g%7x^5;Ij{knEnD?K7a@yXW2-Vm}U=KIY=stBxdU**1DYoKt)nj4M|(*^!u)p zH}%_RhYNq&pkRZ_?JLZ~Z4Q{+;{$q=mdMzW{3|lH!L3!F?E0eoSX4w=B$Bj@)9!mA zja||26vr}HSq7ybOg( zdfdTW6K+UUksJ%|+6NV?^)cqo>)X}=)kGn6-^18vvoMG9N^t$s@lCQot7=3$(a zNqT|D*_@1w@h4_K{bN}J8t*qr)OCRqn)4CAg9>D##l#Dc{?!_z>;(&Fcz$#HPf#ow z_nX;ofRK_R#67oVZuuW=CE*i~yecSvb<~9;*XXC)`HIJX5nYL|D(I`CpZP^~YX#Z~ zH?)x607#D}{cKwcJf@zOO{B(qr_Aj8NNnQ_k%{LAHZJfR&OB8ywCS^h=)Yk1yY=YKu*Ym znIyh1JJUcT*px%JM~mmo{M_|tvx9Y0sp&;vVh{i1*2((n?<}i;Y}x~DmH5b}!Mhco zg^jKK4l>+W{<*leo9f zK>Xu2*CK!$H5J?Fu>vqFz_GE50#MG6qKx$tW{C1(cy=*S)137CB8OBEDUCpW9!20Z z*FF<}wcGw14AAjFAm^#IEse0T9I}Y_gu3StdLpz`L2?ig_zJ5n13;HTC!d*=KeUz{ z@)lL#GQu&(>-^|tR0B~=9*#}Z2vKz3(9ipfTUc4C;UWNOq`(|Z zejV?MbDL3NPgNpl9W9KLr$`{7Oaxh(d*Ihe7)MMCIcJk`re+&hK7mZ>84rYR-~b)< z$L26&sRr``7u4bwzDeX2C})bW`%C_ zRLfVi%Zix%dqJ(#kpx-A;%$fwpm8<{_q<(V>4Y6ofLGk)!Fls#3o+AUS}r?IyjAjL29 zqHIM^)?+j7sM$avU$Q}w*Q=obw33QPGlWF`^8Rt}Va$B>YZnK%zUb!-lli!~9iX?@ z-rvPv-&;`BJfUPy-PG%Mu(oOTT-o!vCVs{n5&Y*pxkt9t`XQmI_3D2XrU-W*SXr!v zgblK+BxU38?ZZdSD*gnGZ3sO{%p{VI2qy`T8Ck`dFm>vF(;)L?mn*OzhTIyF=!?Kj zXT)(yv9VGhWt30}T?n9o{I_NE>H9MyS)MX|lD5Q2Xok zMkIwMUUn#@mV(gITL?K(&N6|%juvyjrV}0|kPKYx@OzfEy^K>b;|9N&hPO@TW(eKB zG3jAX%ovx!^xKoAb{5`W1I$r#oCoH@Pt4|V$XfQA4|4>_A?&Bl|Ii<}+suK#;^o?4 zw*lMk`ldOnDOO1Nhu2EhH%h6#)XhP)8RcoTQV%5`)pJ9lA>3Oinmew#f)57 zN!NW#oZ64w*>A1kreQh1O@tET<>T80>I$J8f=p5gim)2l&d}EQoE$B9+SQkjz-3+J zj&*i%89-F00WhYN{bI-kMMReHGTP9uTj|?o0;Z_@6~|j*L12dQvJ^IlqfrDfS{^ZYjn0`-*saorDP|0`UYf1-n%*j>2!q zh8k*|kT*Q=cx_}=aH3hYH=QHSj1p{*F}`O=B!l1dv-|Axk3G6Rsr%q>^AY<=HX3q-X5+j2Hhd^-oHE* zTu$W2KYF7SeU!k&x z#$k5GS+Brd9btS`@Rc05(P(I=ZqNN|(HULbGGODkZ+gx!j5f(ulfQgCi>?PI8Wa`k z>gk~l==|apiMH)Iqe`|T5`7VSPk7$Fbmz{U=;&ytu`iY9JX+{|qY#X|$g@2HZCrB$ zO(RJ}3Q`LxM;g(2Xc724RVk@UqN1WK^zo-R_Fpg+1r0KEK5}15ZQs~C({x6DtH*8G zwu7iFoWA)X*OBvs7lYfcg<@T7m`hEDx#~oJ-Lc-P$R-2=>dD%CM~@wAdtQU&`4ddz z>qClT=93@m_l8gX{Rt4ZouZ<;tmnR+&vWXJ_L`kB2kstdPK!BZY`jKK|I3@(>;M+` z7B60WJi|;1#6-lo@3MpynC{Fdav2I$h!ju8Sy?*sZzKBfy7xE`j=S=ICP64%)sqPw ztv~_I6x}qTBA_Oeh^d@A_k3cn#dWN0(vi!nadgPTP}IxI>-+e)nuSH8*W9$3PPO-dlyp5RYcP!Dusz3iCXFX4&9mMzp2y zar0N!RU^@{qGDp3wrokN2;RpfF5dY?3r~)hk44#@9!kliCbDfhwBdO{fF%V51(`U0 zMT?%srSV6NB)l*8cjRYtn15|fj>r#71hkB+(!-mq4;o+41#;?!(`1UDLHU1_M zi{j!#D2D1st%ruTb|{>!#@EkB@?1w!;N{8j^W%z&n#gx$qSOFE)qE`^X8hg3sy^^H zHJ4UxtWP&ngdD14n_IJOBi*Nl_tMbN5ON6oL1T`6H!U4q{F^s26MZ!}(O)R+)JImC zmXI#%w2rd@<(Q~( zs1%Uwu~$=SFFid1AtLp#v9TOCSj4npZ^_s2z~p3BxVWb_Ikd8P$&wRl+0gJWRgtNf z6On)v$v{nvA8M2SL(~mLD`-C+FTyK1Pm#g97;U$??Eh=X3 zA1I$X6}?;I$zwdr@jQ_d3%uz-V{({wmQ@030(T1vYJn}UMKyhbj}N8t{{9keTLdP2 zcxO_D3De<@99a+c4N<91WX)5fl568sWPgCGEK$*7QUCZhDChW$3|^3Ia-?Dy^+*1G zol>*GO z)(@}PUWS99cDINz2{Ku`eFrnA3`O8^&UiQ zb6ria^vQ1^~6|gm__gV@Wwpp0G4EA%a5al5vdF&*|VM=leL(S zneRHn{e8#t(a}*xVW-F3dU>%>0`ee`9#Z(nYw~6t-fHK0E`8mOK_@NdfjLJHpX+F`@$5g$yp%o5Y4dA~epn0msct7p&QZix)G^ zs#w-C3#*a5E)2&6GC4arIHUlL=i^b+D5f^MfB$}x=_3mJ>XnrIeV)TWcFIUMWS}_H zdAPmBeR$SuZZ%T<(V#DPadRs$FffoqN?EoaQZPCTdt7N6;QKyY#1dtY?&N5T-KQhq zEIddB`*JG!hhiR+TEWce_mS@)3?j?|gi#VjD232SKAUzyPn5h)4Q(9x3}1t(HqxkL zsJXm`juZn!4HbcG>u<41awMpgaUD;pIv7@YTtxHRPZfn4 zPCd0))*H!B6?6|CXxIMz%CK>oP#z{`>bH*>R?%fzj5wb*{lL7`ZFZXCY}LbMOVfGh z{A~67q5y%4ha{t2pQz47%Bem3gk8TjN8zYZB1$1h{B!l5`O8$r0{00g%xZZQAFmS} zxtJo#_^WgUg}UqOSKXfM%|5kcbs>&AP0Y)fUYH!%lvBRbP;uP5xVzGdKgquP^={3S z2Z&2myD~rSP0=q%#7>=ccTY4b@#Wa|_I`I+fF-H*bL_n-f7aAA4plYm5)ws6rf{&a znZ|qBVxNmSxw#3txei3t{PXkk2^xTEix5>aO%E|y$|5u)@o}{G)2ArHYz4+5E74|^ zsEuO2GuYMD)YOeA0pG{U8d*!Vaei5+$B5Vj9w*X!E?0gU^>?ud-V-3orJcP?DBr$m zNv)wUy(%xi`a)3DK|w*`JBrPn=y!Ji=w`inXnw^n*T>2+zBrlS3aZ1spR^HK|W~)bTC(;Vk0BFPWV_#>Bjw@^Sy?fq_I==DR<} zzAmHm+Z;Jn6MYm5OR=MoeoiSqOx2-R)z~$Vth@bd;c$-6g4d-`MA)zy)Teqn8^cAi znQI$aaFF2PJ zrv~L;k77J*v%B|o>Z7Nr$Vv@$_{@<5R9t+|6rdrk3k)8kSc`m=>3N zC`S&)Qg^{Ye2@|dYO%T(A0Ho6a+u+ESXh!j)xK6{CR8vex(@%?&B=KzB_+kd<$#bd zN6@0-;bDvBZ^QGXAeq7#>D>q3u z5~f$BrAOiXH4Yu}`TLDxEB=b6CQV2gQOSk7L!M`zBc*U4M2_%HF_LF@nwy*Bzbx8w z(qbfc-NQbGpz1qGbL6&x2izkllR!T|KMU+Zv@m+E!HfmnyQlHCMvRfBZEo)nx3F+t z5IdJHY=+5!5E23$bE)k5VQagw*n0^{_OGyab=55KU3;4U4&Cb*NxVogo)m6Q-OlbQ zA_``ht(7wp#iQWt}N`?f{r^V}H8MQ>^UuN$5(B1{#upLlc=Gqb@Tqur!nQ$o51 z##H!=ApJx0Mao2- zLP(~bgc;a*=Y9-12}z-R?E*L_mBnyQ@tDu6S5s4ifCW`7GyUJdPRdxo-yRd%t|KfCB(*zPelO@m8d;FZ=m%!5N2y zge-e)htT2%laLCaGAW6$?m`C6|7A(ZXXq|=cw*#(0mS_1wbRqzKhF%=dUF{V7+~8U z1A8(`c%3UeUk^`GZgRkUer}eSMiiQEQ&d!3wqgYrKfeZ`O@-zZ@JfBIquKP#%v&e` z3i|3%2|Ixod24c@KfOx)4u|?#BRyq?-bFE{; z{MVNBP3zaQAsA?QtSrec?f-O#*zny451xQ=;@Z0P5KPhPRjX5}x9N|9#&+)&a} zF?K`;^|7)Wq0tJ^Uq(T@heSVE#N06_vL6(7cI<^Ie=WQ|Zr9b_O^WcHzcwqAFmr57 z_4?+$2>F6W^iy2pK}wVjp$GVQb7(HXL!Z05 z+4t?+SNiJJnW_k}?Kj!6riv1?865o}S#Fn`)RK_&{Vs(tijpX47(+gfxM5l`xKBw% zCGbIbxO(BavpBj@ZpE*&;x5hFr+wy z#iCV4%Cbo;2yd$a3%Fet2(Jcc&>3Y)$-23>=-U%fs#wC@h;w*h!qwNz8M-m#8GZ`2$m=4MMlUUX;wfY zi>X#SN5?x(uD3jh^pOfm7!PtrF;vVWEAY-8=dM?)2B#rp3ridkkpgu5`0&N$p!c(J zLM#QbOl!T6eU}so{qRI}2vp!G36j_D#%Kd|*iqnAA?T$%;`3V6#q*x2-kO`22ZF_m z=G+&6dtWlw2nJIA;tHC3s3s$9CfOmFIC7ik1qFOS+I&{cN7jL&oUe68}(4cqw6^cq zL1KcV+RGCkPwnm~^4w$s)?lV%#ETQkOQ@DbixvULD&dVLUTsvAnW>u6URRMuimp&t z!pLLjGcz@kiq;_J;P4Q^)yzh8jw4h)(JidFhcFNNBI~#DMx* zR`Flwt74xDqDFuh6$&K&ko2V@7vO_|$pnYtF*V$P;W{V33gRaF0G&vA3(Sp*oSZ)+ zpM{CzY;@Kt%63CakqVb)3NIA%26Tn-gZF$vOv$3}3lN65>7QEt5NBPDEq z{Ti#HQJ+V$+f?R2#5hhwL}@Wh|a zG`Ob9iBqRe;W|*v%&+7mB3ro|B;NWxGi3e~7D48~+}u==PKC$Bz-gHSE?=9C#^g8{ zxVgEdA*eS{zo->}6SwWROt6b_56i5KVHA8h*hNL#;p==W)1oB(7z6!5Ls*7<7Qx1! zHSD-tYD4c!C_21!yaIEW*@Mtfi=6!YEr43mD8VtJclCB%g*lKQ`qI!1B+PvdGx2a0 z5FmGF3OZ9gXP?b(@imf?mc~B-;ax27ANJMV!bL`t^-}jIA{e1TS^+%tNj2ZL&o!>dnd7kH- zX^Qc*Jia@c!@5&#vcjxojJNzBD%;OqhH{jb4+(&h%X~aT8qMlA5Z6R0f(T| zF658HjFKx`&EulPj|{g)w__QWAs_K4<7+&Hoc}{gzKz`$F9m1Za@Hb8@+w!Obp218oBWPm$d@7S7%Q}vz%u9-id5>rrbmK$UHw$_P!=87? z<8G27gXn|zM1{T@w|x2X?xLA1xf?hBx_@Q3G%bxOHcN?kWRJ>3JG;>P)I4nf!%1vz z{1RRbn2ckgjl2xE{2zhMzT8xU1_`AG6v;1s0yT-99CO~E08}8b2X%*%)ZWSAd|lDg zw~Qq&>mM9+#OG>#z`!`dyEl>u5BzNK@{R0DQ$*G5u3Z>btsi}z!aA&%0UF z%xA{ypx&^Wb8u1c8owiThI&{yRMx|DkhSHvJkL#_VJC_0s-k|C1zyRW5j}T+yl&pS zX%;?F;MZ{NBedfV(aB6-`BnFb$p5P?Fk#P#Rz*&pisK^+6~E&TzrfpsTyDIx7JS76 zDUS!9$HCwKGQ}$Jm?%gp3d16k7SsC=y^}v+}#oP+SV{BrgU%cnK)h}G@ zqZncLhh9L}c3FDc={mWU9$#HuZmx>~OU`=cJ*6=p z3w*XO$x<0k(q9kIrb#*THSlp(p)$2Sf1Z8xs1oqMOEjRTJN%&)Gz<5v?vwn2=i2k< zXLok)v^%%Vo?8NW);2X)#D+*S7A_;o-aBe^!nU zY>ImFQ^7mUnNCZ9X0z4>sQn^3eI4e&gT>{T2g;}w#(=~|PP3)Q%GwiC@~_M;_1Y8l z<(b%N2nx~-fTn}fLY@UkXO6g+LlJ*w*1HHO8W8FfK1iHqCD6t`)LLRK-@e+wgdL`5 zVc}NQC~LF7J>|jx%W__!3u3gE;3Lc)Na}YgAJYk}I+KG|Ex|F2&J;eMbw2oyN+ zxm<26PSm>nEQXhfL%cIS;fRTO#|IF?gZ3HNHHD^{T+>e&RbrewX|N$hU6T-c=XSRE`Qs z;Ls5P%9C%wNDRgR`quJ_E;|)pCq5buVm&a!P=}&*ROKY(LZC0EBdQ*{W10xq_R`-O zV`mq6g%<&r$SI1hz|q6QBONBYtKJkiNFL(e(>q#Qcz$(bHvb{*K{&|i`G8X=?kKEA zQDIjB5&FjQX}1{qvYydj_Q4+22AAgWa8P%E;by6OwzB$SrjgM_D}kDhuI>gfkwD?5 z?cgZ%Se0AZOgC(Bxm{~ui;e~i%B1=8nxN=u9e4!>8-JLgU|cdwh?9pvg(R2@UV&{| z3~n@;)~z5VBi+6#sO{_99eMch+wsv{a}Y@jEl(J*^oChuV`FU)EkHDk1EJRR15@A> z%kz5I*@wF;`(y49&r+INdik{w)x%oL(mS^UMXC$k@WRJa)TWYMj%X)6z#8a{$}?t6 zreFd)c&D8xA9=wqQ^7;_=4+U8TnH;?VjT$n(3A1;@i0kw%?~Pviwu>B+FNSFkiPu) z86|ulMT-_t#eV~6P6b?YU7EcTV;!^S%uz>c1T6Mi762XBlDK@}OX_YAYSizPl$KVb zgMNTE4_MD8u&1H&=&Xf3uC>%9;+6OaJD-XR2T4W(lfncWjunfvc;wyjU07pCggqdb zp0TlmMaV#mR4OHZ|KY<5C}Q4Fgcun?3& zTr9j$hqUC9WrkacM3I25YBt7|?W46V)HF0wV`J55h>4(4V_p5NrXfv8g=i_$5f)vw z((|~mSN+?q9W%IWa5D7;!F!^*CtySRTY_PZv=V1Hj?wT6kUQCkBQi2Wri(j&{ye$S zW*2XLnCt~r4xMV;nzd`Q2i1#V2qXcCk0pn=sSI9q9K3uKdp%n|1bIYWcwF?SZxPj9 z%vb;-;dosq8d!ePzwkk+BqjqpaPdEQYf_2}lzYiOyYTRES`h>| z=!9n>OiV%vf+7TR3-M{)u2qr0Lw3ZE7z-9GppnS)VI%39OZ~Et2s4ooy6ST?jlQ^c z0c^#BwXhv2%27D_}gMqD^Ojo6^X^;+3oxBgFa;wa5$A|VvK#ayE;MjH{ z9SuIIvTqdce4A{ayg~Cb|CE63BUF7#Udr`(U|3nja{3gx9f+EruHyJXcc$ZUCse2J zP@w*q)KJ`*rM_X*>_iNiWMKE|blr9>UyOA10E1`gZ0s~4L2olmDttbrx4BeoDq7ovAv`Du!L!)$e4&B{d zXWu;U`+VOy|IaTKX70GIYwx|*+H316^IVjeh@1$8LJ>a`dm@KI5q?9VPLQ8I20t0- ziLrq{m@GwJSiUwjvoqGwwM2>PV05srEOp+{YTME3TUwg&va_2Rzrt8rnHaOZHZ{3) z_W>meb^N7)!VAm){v1UBm$40PP?9q3dwQ{mq}k;Mot^K?TLv=K`oZmuqQ_ad?>s0v zP5XUJ25*m(m^;rv;dbbt_e_@SdY2WO2;0rPUEPU>!k|loyqCYv$VnZup|fI0z8%Tc z8|{u}IMzc>qp9=bvuX>G>2#PMg~l&NvF%gykAHB#fBfZ7C}SBt?K7f>#$NUBpI>5r zctSy3pLN|s!4Nh`m#yDfe%iP;|F3*^wi#gB&BMtQQ(F;_G zow`%<6T=Y;eD#vLl9Z-F(~Fm6+{ho9+>F2_bh}|s53ByA%GX~M$v^8f{`v#s@SdD| zOIeot`uGTcBd+!AUr#YFi46759J#A3SK5Up9p(gw+3J*T-)FsBiXhe8u6PNApyDlfw8acWz(^KzxDXn z@coBBHXR0^#3sL(&OR^C5c)2sqLI*3|0!e6(>LiXk|`Wn=G-$GIokb9WBm6=HR;-Z z+GbGt96LKo{)+l)4a=gt>3w2Clbr?JCvGnezbqqsgjAcytTgjXvF>4v;c*8!rLda4 zrMyi#0dz8D!2s2?`NBZ~JJ+KW~swABm)K4QKROWo;J?$QQ zA1(f@>f!5K*yw`$39ESa`DLpbJ|#n!;)+Kr8J;#At5j{1Ttj30+b<#qWbSDX&%93- ztKp+ia%hV5vEtf2fvLI_5-cQI*eES+p2b}>Z)?CYCQ5$1(>`S&nbc>hO|JBIBmVFH znoW#f4E@%8`Uq9dA=&Et;g-3nXwzi3n!{lEsFja>Yj!FEy1bG}PL#YUZhy+goi<&z zzq>VbNto48d`cyo#6Rie;h=2Nq%680PF3>Ux4dpibx=QZH0ZUDbGq-HdqjVH0w;$g zP2@{n?rkw<(=^=Px|4G()o|Y2V###a@KV`|lg;VHbtTm{#{t5K5;oO~jvQIZ=g>o4 zX|XP57>O)NqGGnUnH#H~Qu5!HV}JZzpZUAi<;v3=dzIq+d*1tK%F==5evYkE5sNa1 zo9Y+WP$*Z_vnLM~Y&GZlZ5&Az{~Ve}-xguIN!03pQ%bg%j?kC-%zFBe+!excJHm&) z89zUkoQk1Kof7}bOnC0>wbSHGZ1-+nin?emq9Q{4G1C32;roic;*i%KHTdAuHBt+c z`=XkhdX1qE8!caXoJ2(S539R11r|KU$U_hToBEEn)SDu$z( zkBV*Py-Tx=dJ6EpY^WhsS{#9}%+iC8n<_U3UlcoTAMUywHmTUN`uxA2$uk@NQ}LNB zEQY&`v$hLks23K~wQ^d$;Cs=kT`K{~?qi4#8%p?MZHndB)wj2B1gI4f9vTglYpCVc z((q)2OYy6}9y|lKufN_DNmNSNspo8>6tHi<J>AN{ znY8onByplbf}d*hVA;Dash}<3MG#=*2Uj-ySdPd6^-#v$6eL0 zl90$3*{=`({m>M`V_Nq1#PL(-+g%S*3l?}CHj=*|><%7wo>m*KD*klYyRwZ4rMuCd zAdfccY*&5!;k-tkS!Am$JgiYys?*Mzff4EM)^52cNdSv-XSdT_cY3e354FHT!J?qU ziA9YJ@^(g8wO?y!mxH~ltg7)(9yBDHEss<*H_MP(&$LgcAb00g2!p;40 zKkL0qEfL7pVP?00$LT7$iDnKuu6ijB#{_E1)ud_^)X#lpFOKhl6Q)MW#is0;sKT(Z zoXg>%tDL53!aCoT7E$!Ji7h6E$F|?9tD>qZqzB^3pILEcz+o|)xp1S`C^5?SWx&Ud z=4L-jil#UO!~pX%FJBLeEsfA*QiShuldLmEOy21_$e-RrC^S6 zEtmalUDDk8;yt(N9&Uy;zENon{qn!hFp5yik9A%|6O@X9x!2@_fYdDxGA{iEw z&vTDkN^6Kqm@XCXE)>Y2SyQZLJK>j^x};|?xbdsfrq%l0zayFH^&l!TiAb66C-v$_ zd514{r$2U&67|U;i?y4_1&&QP`QTULB$W5NW4AS`zTykh>yR=l#Jfs$rD~+`);eJgcmSU{+&G9PlF(}jkpg7YxERWj;SN|uYB<+ zTC=S!;bSOuBb{1*gXW)ZMPqRh&TtP19o1;DueZW&NA|W?86>`+J9{=$Q94O27voMu znmW?vcVJm#CA|2NV6)#QA~23&5jHJRF^N~giD_uI<%x^^K#T;L=%0Iz3t!a)3;e(1 zbdFv(L$+#?nV41TdUc4H0d+Cn z(UFz_m5Tlr{O8Y~iTa?`u9AanlfIn8b*;m3UUkh(T`wYu?{`!nmz*VI>n01*I+1s< zGy8#0)!)opZL4sA!d26?D;yS!^a6JAbh(b!HSM_kDsEOa*lFxo z_1Bg0Iu^C!t&z{XS^^Fm#@)YPxvg>PtDQml^8NG1*{hRH7ia_vAGs63k}Lg`TadeK zLG^}Z<~DUa-X!ON{n`{~6Tijod~VWLs3hm9`R_k?(4$$_G9)du{{}O{bcz}Gz}d4e zf(^IPjDB#tkcqJ$9!KQ!RmI=Q8U;BSF|QLIy@qGZ%7RJ*3ET7Y=S=j_8*W4A4OJ6n z-7n;5W;D7ZaY(wUDU7cx*Hnv2a{Q^ohy5NpWx;|s9rxM})|w;2-$Z!}B{?4MZ!#++ z@{m;??C+kzX600MNG7pTA=XPn5A_sLsACj0#3X|xRqx< ziqzIgLx4Zb0DEXlR0?gE*SoY9zZkJC;3mVpD0mhIiumr`y9Yb4%V$4G#3^FZ!@>*RULsron0AyCKt z7$k1qyjkDJ`0d-bu$1E{-=w2E{DOMeC_Is?tmR|{6?!5^&C$_OPR=jW3bG?9@{H1! zvz-mstM|CAW)v85VdG`&rLBIH2! zQLCrW&LZ-Wd+2ukyMo1H2dHhIOooSt_n1*ATHm85X_)KD{7lBaAZfrx&V$*5M^078 z$qh@9>|N&h?`Nd6wSRHE092Cfs|4T^7EyI`gsZ>A}M%U)dk6SAlO ztk)p@ty_z5WVpGlA*b~h*p$qs7Qku5XBo83bR^9#W;Q{L)m&cf=Z-;>^nGVlyL$b4 zf?_>!ZhO0eUK9#7_Rm3-T@V)+=NOi8HRqLze@ohzbu<0nV{n^+ zp@PU%R#rBxXd~FK4~qX_wo1Nb0tYO}d*&DEUX%229*)lA2Pk_fOIOLrcuWWQ8FB#$ zkD78DbtcQ|_T`yJA)lpyQ&;)~dmJ^U_UTnkO^v6gCy{|T2A1idK+4$I*wL|&BZPUW zpBp9YN{2)pr^TuX05Wk*OH0dO-|gQJ0!*3aN$_-A$gb|0R(Vs2WB6tqp$z-*8-v%Rz}8&Ljt!HtrBMl^G>bFW2mxMQ_Yd$m?nYEP{=GO+~hZDL30n5 zrqoB+Hpa6k)WuTq?{^Z$VoMrNz@mj8?v@-{Aiq|{8ujO|!^OnAZYeWetPgiscwo`g zfCGMoZ-%m|E`d?$W%m7R>4Xh9R`z8PIZ@)=99L?HAG(d5Bz%B8-OnHAI+B#rN)GoI zmzS3ZT@IbF*o;g$U0eiSTU$FTzsXxuLzCO^Y8by=D-LzNkg|wNOCl{*S<@~?Izmu4 zA9x0Wg9`VE{3tGtAuHjk&CyQh!+#m}dg;5budl!VShBy0rZ{E?uh`)0dvWq@@-F0^ z3sk&oeWoQ3$i{53EJHz=Gw2}$y-k3RX<8*vSIC&;#v1t+fwfq|q04UHWm?4=?++(P zqpO=?cUj9Tcratu% ze|7p8w|?_aMycQ{cU~;Pt*zJ!?DwS4D_2CGgQL-6U9!8tmsGCOkqMdN!RNhEYrT@g zgIzTYE(Y*PzU#)~UmKf-{`y_ij^=g`Uf}TSkHc5<;5G ze%+mwjI)`*Qg{?Jp`0#{R`u#Pq>F&!vWDVz47z{JbN)T)^l=_p!{@k)nmSpLLY z8vr2zGR3A4-#ni?2(OtI@`!3LK|U_n;BlNYRJD!EXKRR0W0CSHeCFfW#-z|8PBMsN zv1oIkN$7BIJWz|-;l~PO=fua%dt=|E7XTtw(YWCK`%dkIccPPw=2C}?t&`PpSTc4^ zuJK#XLuGz%Peu9ECv$lGssq4|7O-7<+41Gmr(Q^I07C=r0VH~p*u%4fw`gM84Kl2C zBN95n!Qrzh_~HF~$Aj%jhmE-w{hz=abic-FG|NI{eb49wX5w#m<-MlkvPfpNSqQ$+ zW(b}{e!JLdH;b-`fA!0Xk6+4$Hc(06*dZOkfl_>!wS=+m^w(V)Het+qmcur+Vv0#h z=r-M1sN_p_#zn@xZEo0kImpEMT!1>~6ATTbnE9P{vWTqA>QyVX4pssUI}&>&?$Gnl zRv*<3hRtswm2KqZ?3#t$DomNx)zz07#D5gk&)CssIuEl%^0pG^aiKXo8%{B@#nC-Uj$%;D;caab`V&1M2I(U^75IY=5w7Jl4 z#I7(SADSswMD_16sM#Oes36nQw}%qjC~ja7;k2PrU_B3eX*24@1G}ft!R08ONxW8+ zoJ3#`wJ=$v_6!xDb=G(0iUg@~LaC%em%{^t>u1UbdO3ER;pOGsUw^ir`E(LCt}UNKxBeO{vw!4EUY7XVclBSCXjc%4 zBmk=qxiyvHkH_m$yX+V%rT_7W)3_VflW#RUP|v1SY>YhcflVnI6ZA8tc7SI-Uv@Ps z`utl(?L0x&>HqtITU$-DQngABdh{Y#cwXL1V;-MpE#08v;Q$SwpdFU)BgA`5Hrdnc657v4Hg0I^3x`U{2g;mvZdu7}k%hy#t z;&Q4!D)Q2$OP%@bg-dS}=A7Cl8ap5t&AZRHZ96{p-2cg>T0pJFj---Se#@F)b*d6g z5kjWLlR0*)y1T7iS}y&|0zBFjsCNLUPTz(i*4lc!70^`jl~*pSPvqp};B;L1beV*N zj*gB+IdzWveV&HRd~Y^{grN0YcYsvv;4!)HzgsH+ttiA{`ty6=D^9{H6|HxwL1jwo zyn5%w&@?OgV~=yV`J6t%t)X}OyPHX>IPAFO;NDy&+UP2--#u$>Q6)kB8FsMP$zgLr z@r1*QC71TrAc5UPkRGOFe`9J&-$a>0v6I#J0Hqh)C1n(-D0N0Wq0(?(>u^W8Cqt*e zW|5kVEUuH=q_;iK{B@VsiFlRF*z>{6chvJ_&NSFt#TA)qa?ei-vR`>swTT)}3#Riq|PxN`KffhLath(IR4K&d!kT(ZC4CN0E7 z$Fw=qteB!|1rlRwNqNdU7hr8H7g*#PgVA;A?K2^9QVtJfyxE+9QkwK;;ih9l+OM0) zK5SHww^x4GsXDQVhg-eW^)x}v9f6h07i);!UbaR*>+EX9{;-q!C@`%-2T)Evbax`e zw0;hNtWigz4oLNVsQVyopa|T@t`;JTW89NLa{$l$_6BPfABLKHRpXZ6ykuqlQ2q}DV;#kot>f+In_glja4|M$s)qNAg;^jrRv=jb*BXB%~S+d!uf3xx%RiUTMY zG}f7Iq&y&X40W0i-WwHq`SRs@lU#2qz7@=6lrSxV;fJ2;>&N?r2-1cD5U(bNkCiG~ z1Kf*nIj|F@<^eg4A@|ZeAh3D zqN*EpH97c^@_b@Zv`N*5G0p*J9SCPFTcDGc#m!X zyl%A8%Lo>`u?0xNbsCyQ{?7opk-dB~2;XZhad8=Ud-(1o+<}#pU=HxjY*(5KuydHLX+jj?UF2YeK*nnUvGf#;qZvShMt@gfD@Y>-ZLv&+pxTd>x*ca?Vq&%o zR~?flV^cS~N>I&*1kGG`rk;CyW~;=u!S!EnQYBJbE4 zNU)aSA}BjTSa4q*Se$7*ZWRD*C{TiW!fLwuuv};%OurNA8@slUz5ZWYgl*q`!;_#e)Y6IFrT8xEKA>3X|C&!M2p{siUe1S2j zLA!yIfYy}g!i6q;93AnkO;hzDT5pLB)V64qR@H_i?it=aO?qqk3&8Z#HJ!&;dO zXuap5y?|tqjF&*0$oBxtJ%DR%efzmq)1IMI7lO%8u$*p%{3B0@?X2c?$q6AgREoer zc9SuM>%qQDpSYpNV3R8AvKJ|zK!TiQ*g}z~PYt=5m}=}g1uUeF+4X~_Y<1aXdz@_Y ztz+5z_D$HI6UhFY;Ip1<9x~nCm~SNXWfdf;1JMfU2f_J?06qtO7IO6gY#l2Ef>mc7 z5qjLBpy##e#!%Ti`B+IN#l&{l9?mZ8DEWF74Q~K%B*+!2AOP6Cx25LG9<*5WL?RQ(@|d$gaCZ)XW2!fj$wlMt;_>IudFA zS47YwX#h|OVOt2b6aFP-I8i=g9RLX$_Nq>jLRw(G-Id@t*FE!*ayW|B%q|-}dZ#W> zCwq=o`6Rtv2@js>N*e?+Bge_jWwU^1R!qz?>Fca72J}$tM#`du&(Qg7P%eK#!-)F6 z87&uA))UXmAj}4S9{}}VNk_iy8dRs(J^~Xj)+#AX!*T}zy}eVcp$zoD@5P+HOMAZ)<9@LNoL@i+kVEZGpMr>-o^eE0R# z7p243e?5qSt#rH>Oa*|U>+xfBI)na?B;B)n z&oH7s)EzHWXl^y0xSoUQPkg1H$eNy~Awu`sozlTG{y2F>u)!>AAfSukFq?s(VCRAa zXa@`JuYF6nNI_ww9sW#E=`>g7#I5NpcAkFAZ%nz}4pXY~MT%AaERy3;NbSTiN~S3y zA1=@+@!L*@+0<8en`yKx^$>Txo0vXrtL+!!aX@nGIVC_9U|f$MJxawWSjg=5etP82 z@eB$~3V$2)S;i&T)t5)zPEpHEcX1lZ1#7jE^vRwFGRhKpGi~6eA+gX)0mMkXMJivj^zeFf9TRlLIiFcEg*&@ zus&R%0HhP17#4{0qxGxU72pX%8!17-W<-E6nWpVS67qh-0J-a+pQ*qJQ3%w36VZ`X zqmiKLpr1B9mE!FgHlzw`AWm{Y*Q(L+YY|G$(m= zIoC)&d-#Sq>`p#)?DMdlQ6C}QtYLFxEgqWp7wT|1l+>Re3P!+DMrp)Y> zf3b-NF>MW069Zv0#RXi@Bt?ZRH3>-+K`C@l;N`evLuAz3pVXZDl-yedna1`R#yeJU zXNoTD3TF{^T-^OCRSgLC@!8O!k8f_0$_qoEdUz^YHtH!5%g%hH>TJVf2y|>_#p!mI zC6DK`Yi`Jf$*w5#1alc=00@86#HT;A`&ju8#D4On$dy-ECFh&RO0$nDyPHsr6ySwO zIEzoVhd~1e8BehWs{0!IA+#HUK=61uL@uVT{7kCkuM!*&NYL?1@Um@j($IsLvl(;> zOb=^sZf?#o>4V01kX+v1|%REgoB<8H|N*6AjEX;%I|(pxxKq~m3U?ZK5!~aA8d{KoV69hc<;)d zy?W>O0?uHNMIruYr329HG%X?dDFYHrRG`si&RiUHo~Tx(GB*cZ2K^lp7OkZllHZMn zhit@vP*$V4*&?H7X;@!`mgbuh0@WbjFg&O|z&9r1Bg!lV0qH73df2w+ZE2UCZ&(R1 zgFp#4B0`tnfr6V+>(3;we%!N9QLasEr3LyT2#iojkkiPwY+>%adGA6blkE!z5aMis z{&Fo9Emu+i%z0ojQLk|5r&+L1P9)0g7Hcs1)1mmq2@CnQL zPmiBDbH?1<9AIDs2n|4!x7OOEXSZ_oTOPghxJ38#cCQY5HJm?5H{Sj-xl#}^Pg3zy^85=h%1hne8>T9_>h&g8b# zp*@-0jI^QM!`%K=b~F|*zyGGmVWu`Y=6KRHS~PK|fv%q2oaLtdQS;&J*RQHs zaAzoktm=7Yz(t~-dfCq;#QER8k{I^aMXNozlfzU!^uGCs6-bS66vozgO!$|}Nf1%y zm+AUUhnCa2qPz=;trN>aCOqs>62Awrgx5!5JiYvM`9@?uZ`MXkiUYeM1 z-C*#6+a+01aOvNDU3o5|rlBo7pTj7~MuItObE@U9J!^EIlfr<~oboF$w=Ci&saLb! zWPG4ni%2CDk>5T3P4JXE3VZqJ)lQwKY+k}ZNo^#&_=f8?h%>uz;<>zO?rFczd`b|M4_1BG_setm$-lMEgS-B z7#SIPL13-J}i@qSZz|VC%KU;+R@fz@8AT(1&Z}od4``o?KY}T4dS#%6*ovfnV{iu86wv zrVS7vpY75RkOprG9`D7%aZ0FJxj$Y2+{|fOOWN&aR^@6+$kCvm~qFwEK z17!2|-=+@KWKa)ZMnUJ!&a1KF?TNF11iJ6^A08|o&N!;1H`qUyo0Qe#q~O7~a&Qz@ zUWDK_oYxrB;eChPi?N1Jn%fnRs0nZ64Gj&UH7CejzyBR^_BH=}2s_XiNKK1^F0#Pk z-m1l9qoQtGGu|<`!P!RSKbI|6KUwQc{xm+j(}V9#nj<1-U1f{Pq}qf#$HzzkhT{{t=dJ&3rjWR=&L>D$-thySTn zgF5@`sFi6K+W5KAyYXwIe`BDP5kntxQS#=CT3-6e5kG!x39N90Jq!~KlL~7S!YZQj zW)RjQRQsNXcnkJX`}OOns3;I|NzYMAzZz$S1h0T~0MH(GcIAE;Sr}CqT^Lgsdsw#6 zwLZ{^5IH!Hs9u9?m(GIdq<7r!mG39cUcHT*PP2GO9k)7SOX=Nx5@mM`@{?J|SX|r$ zC~`mY*cfMzw-$o4^pGt z8pJWsol~d*{U}tC09E}Ed4yCD$7EiDB&i5!lM#q^*PXE1uz!Ee0TN3lM;}DQ&yreW zP(Y{uZ>bDiMh1`x+s;8T_5S$LOzGHvo~as41_-la%z=ss)*9==5JHsiEG#GUWdLefNJ9H2i5|VnuA*Da0Xz!aK6$0p&`Gh*x`60CO0n!||Zf4GzYi?gj^~9W+G2o0f08{A(3FuVbg- zR1p?zZEf9(aFmN$h5nKc1rHlP|K7U`g5A_>(5}9sv)+ZHt)9|GytQ@gC6rgM#(s_l zngXx_1Z%%l4lt#?hGjgh8OW{$+D(qfD41!McGhR1jSxX(3lEV4;@R}u>A{jikkdvA z!%?U%q-?$Q*Y1PeM-xSWCJ#6*?44!lJ4o8^Jv@Lw=z?VO?Afy;wMmbjMa)AaTYJnZ($*I4iq`SYN`%{hXu?wM|#5BLae*6f& zBSw09t$ zBH8czY$x4wAreRij#?aV>j2_&@qhC6wmx5)7UKd+8JG*P-zS)qoydxz;|x{#0Z~7u z!la=z-Fe?$Ll(ql@VU9CCcS@8NSqNC7^X+h^Fp2dBs>9}P1m7cZrL89fFv6UY^`w~ zUa;$+>L|TJP%1nIM40rl6t2{=Kx*#%1-%14U8oF(4F_f6Mx;*B zGcsf>N^{UA2Fb7~6zy13`E=frb^22O zhf|*b*yQEUtNXq?7-D2eBq>o5z@RScK_rYe2v}gk) zpMw+z{xPq7gcA$>Al_R(wdx}+*q5dJ(bJPjB_rDIR6VR1GjJzhS6f~XdfPYlUDEbA2VxM-+xmt-PkH|$Ik_tIgFyFzTMy(9 zdr(MjL%;9TxobaPDnZ0Tqa%#hO57a;LUv#0Cee0d@Tm{L?Ias?8c%{+KNTVi0#0sbsbDVntEn8PeGFCM z_;s7^?beD5M&klFxO$y{XdeNA4qbisBM2jJA(WSP^7KZCLtlqDPN1waI5eY z*SHnoZ~p%NEE+{K6ze@dH;JT*3?cB~0Gu{Gt$VbY2lPl@^-7Tjm5e|Kl)IF%PQW_g zn^*W7`?|^-)Gq@-cL_m%OQBkFhvL3X|urUK%Pw}F3!h*C;X%Y-Z6S3Uq78<$arG#9h=}$)AaGsGDt*3L}xefxSOLZB)zf!^-FW1I zV)?nbbHJ355LC5Ko@S)MX`& zcR-BjaOFeOoi>mO38ogp&-v5Yo!AL*x*yF@W*8G$? zPFzE{fZFtUtR)mhD}_w$FL7R~0ZvMHK~k5=F;=1a1TPsEE1G~EuQfpI?}s~GC3EWn z>v*(^ot8aB0GxjB>zs@otL7U6j}j+~R{zlR=;T0d+?Z;4OtT!}xZ-Ki>=dA1(q4ox z#h&fe$wBa6)m*nLmB+<}{!9{6ev~1B}oDF4u1)EjgwL>!~Y(d5iEN-kjQ6yOOka!e};GK`A_k?t_-)^{L$x9NJm zAASfRrrdnXCCs(?_6|U1%pyqY(Lv-A}VpO#IS*4mM)0qO$1=q2zv;25v6 zRND5&JCWg)%qTxVm*Fat+#B%21G4zdgxef&K&yc}nbQb8l`xrFQ@h*RzE-LPX*@cb zUb@N-G_sw&4)eAw!4;{q8|Q6%`Ph>kFu*G8;XrdmpFVSDy1!tP1~;i29!nx>2kp%r zFk(4#?t=Z?fae=0BuK2obD2P}8!O~n8l14DVqq0<-1<$2Q(13FjyeqAp@qhxf?!Jp zX!GRm1BiGi^FV1`Lbuu4s@sS1!HBgQhG)L0$$Q6pA?U+hfv{r^bSk}{n!;98ZpaJm zMb#PC_%U?4T7kG)qq4n!hL#2(ys+7F5I!1GE99dsNHAO{AydR$AC!RCfsKFWH7VCN z_%;5Xk>O5m`={#evvy8To{1YFX$ zRUi&$z4;cFG9c^D_umcS(}_~dS_6FAt_o8RK~+SL!nqC8=5pSS-miu>i58p`7%2$u z0VHamG#jjv^sp;jjWi<|9}T#C$5(3IEVL=~LDao9U~N{Epi8_`HCw~a57-Uw2;>4j zM(jrf&ft*n;a~a4770}Y^vU$a!qw*+Z$m50ON>A(#w_9z)Iab(*bjTZ5&AQ|*gGKq zRdLY9!R{iNSkny^aSSXouRe^h$Pl)sBLhK9T)FqamT1IjWM079B?Sn^X#ZG_17_yS zEZd9Zrx4f?eB%jkN58!Bv{RLHcmo2W&i9zX2-FGzf=gO1P+sCsg3rV~FzuPaIgJ$z6W&c>zR7U#Y4?$`jZ z_5cQjJex($aY|CdD40!wHt=$Wh;%>-QtC5=b%8jL3)pAPuuMn=aa5pJyT66>dG)ds zr1;KYDYHaOR8=bObePF!y6n$tH6#~3bZF8j@Q)eW0G&60T}xB6W8VBbRJ#C}rVtNc zMjXf4bsOOhy?jV33J4%Ny3-bn3pd!<5G4z=OuOX@vIys$Y4`$I4n`tBP`8!^@!4Rw z--cp;lHb!B$%px)59hA?gOj{|MMZ7(a6)gI*ngsb~jPe1bBcXY08x-rf zLsb95+gE5muaqr3Q!Xi`9=!xqw14EqT@v8~5EER7{5rHoI#1UWR#2PO?J!`ZYgl=C zc{w=bJ_C442V)E35CkL#M+jP;3eYQtNxB8fNQann7lBeKAiWfV<0tcq)#SDdp_w(I z_~94tgqwhgLMAjqK|42w@jvo^q(V`_<;x0l_>D4|wGL)rcR7mE2hf89FnUHr-y|1W zI0$Ua_z*u~-8Qg0r>gZqL$sq%4GZ}O)XV;sC{Zc&DG1?Z@}w|eO`G$jCOO7Ea@mF*z=r~vk%QfVnBSb~FoJr{d(b({%i77Oumav|Vc6E6oUi^65@)lk=M4eJQbB?q%#r7) zc-!l2RXYk1!}lJ@62R#%S^~rJj|ucgh5x9cLOR`tRc#4D?_l1*8MxXJJA^j)+(6MT z7|BBan$fa&QwzYnS^?OM_rET4{m(hG=0CT0(3j9fD9Mf#%}1e$^V1w;#|bmQ5^%vje!G0c$_ z__Q1}4<#U`k!equa+!>$Trz|#2ElUtv~@A!@k{9tkCow=p66CqJ^$Ydr7C8)lr~RoG|~ zev-0J{O@J$Ei|7A7b6hvr|tzr#hqAR06HD)kHKD~06qV59XQp)&c6N9+6%4Hxu!(c z#^09HavFE@jSpTLOGuRL1L2K+3W{EP?;ybiOS`F?Eiu2&GCJ_sx)mbsuChiVQ-}l* z!qj0(4j1*y95?zP<|i_h$H231#dg|0|L%XkRhhs0b-w%icjrrnS5lvHQA$fn?ot2u zQS)COR5P3!6M?f`x;QNL_}BaQ@4LIZr>3T07RjrQs)^}D090LOToFhFjVB&TlXO(*nS6NC`WyOA)$Jy3%evn5#(6AX$6Tvw4}Ilx+A^aF)Ge)Ka$+;oNUWsnRvB0gZHFnhLF zP_$%6YGFTkrc>f4#4y3ltt^PrrvmSQat`$KYXyJlx6Zkm`6wSjB4XlkJr@`!`v|L6 zN(xR)N3cL#=}sPt?T+;WE8_hm@bSGv1U>byzP>+8JHf~P@#AT!`Y^s+72W{8e}Da^ z6=$KRlLL%+CXGW4L?ZCNPbb41T;q`!&r|RcRD%Jo$50?(&?+)=f!kT>B0OMJ=RfuRT?kH(qC&oJyof&BOuNgtxb3w(s& zkqqZoae)))nd*ioHU;yonz8ZR$4hk3L6%F9V<4tpQ*L9H#eL^hh9Ms0#8sD<=X7a0 zu#$>Nbp-gT4VwV{CMM^~gIQEfyYT>MBaT4#gSlNxD(T6%Y9eoA2Z}ZVS(#MYoU(v3 zrhp+kE=eE`U(-(2L zr`NS)4O9WRofnNzF(gtLbgqKY2IE?=67@hHhFS?zqZ^=gC^2eo}9;06bF zZ-9-$@X5lRqDri8l(IRCU ziCh8U4Mv;>6Vp`C6qhcg!vTaN0If6yOaVc)D8$vp=)$U;_WIX5ATe~t%Z`HWB~?DI z5gZeo%6p)kfUt>-a?f_Ap#79Q55i!IJYK~f%Jm69fQ3e?@20C@W*Mf`WckS7AnHlN zbqaeBYaqENyA{N0IWAX#Y6b4@j{H?l5QA7d7!^`mO0vHjHFS5suu=?w4K^up*U=k9 zAF6G%+Od;D2*`nb3-o&)gVu5di{xx@KLw+W5Xz6Mm@xyH9V`P*oGI_NTP4_o4ESJLr2i7EL#Jc|bNV{7u8=<;j*S}mg`WLB`}$iWOZ{=GF+fN9{ZPixrUQ8Av(Ilm z>he>xfOZ7$iNs1CGs`ixOO$UXq`6!yDxetN?wtFSZj-%q?8aEMpblk?H zTuIyAh{Np&SVRD0B4q|2TrA_&;B<1m+eif&B&~2o9P9&D<1dt_VW7C3$3elOxfR&5 z>N=^870T+iB|miK!1{WHDJ2Hw+lAnzDWqkQw+DR(KGBgNmDlzs&T!_0gLSXdNf!Ezkp zPF1!x7|n0e*jxk5>V>*`XwW*AnW`U*HtIk+{dbZtFG8>728*i(DKyK{*%Wk4=c71N zd-SKF50{Kg<|VPwGw_Vh18kTt&IrxEf?7fT9~r`^JN*_CQZ&mhaH36%)|DU(QYiF2 z;>KbLvII4XVax&!jKO;Q8igSFi;zL_oJ`Z|dnSJMHQ#Q5gpR083To6AYMeI0OpRQVymVG`;SjP6Uf%+I15?ur6mcaI`292hAfPKO=4yUbi?f0v{g<~u@7#4UOoSP!}K&o;7b;3n)cHSnXK7Ax84Y_;(%z4hkj8^gKTUE zu3Mnm1}CC{ng@|gjw|ry$K8gU^(wZAGu;G|D(qZMtHeXZYc~HJdLj|f`T)DwG#3+R zh=}(ht_ZZ@fs)Bi@H6kuGJx+x3G6=WRfqS8QDZj{_M7#-NNgKRD?Cp5qH_(iDG%HbVi0$W3C}5981gPn3|uh6HOuT7?coJO$*v&G0lp z|6Gn;A6>u~kb2=d`G(cL>Cx+oNx4|30~P6gzi#cks|vX@MK;QVmmlDcks8>iz>~<; zwv(suh_lTa!xPtpZ3u^MNEV3nRpn91=8Lgi4?HwFYp)Y%3%T=n~!M=jVr7 z-_oLol`l1F`Q`2xa=CaVeA7l^MwOh;Iyufp;wp=hF-YJWHWEPVRI9+t@K29UrmebL z!nW@7bC_9UyTr8ewGLPtU;lnFlwW^m^OU~O;mDjTs&6qJo%;mrKZw6CUPOa?g5%r2bmW-1>{bAbK*CAec7EAOlaD3nV*mhjeW{R8EMUzwoRU3Lo^B zwxE_Iye^C+6m|wjF*86rV(b{TojX{S+fmsI|7|?fhL?+tH z*aDVLreQg9t|MR^L=n(%A$rEub)(WHVBClg9820E`EP)FpzIuiPx-oFB*M{HqRx?t*)!od?41UfOw>4&A1U5V zpI6-k(u9nynf)Ki-aHV??Ts3KOexBcDPvM1LPDk#kp_{e%!x>b5RwdqQc?<$A!9{I z$V}!`qC`q$NFo%OB4y}Zx9XfY{oe2W{yZJe^Xz-ydtdvy*0t8!eqL466Ri%AoO_`M zef5Pp-9|t=n)d938;8<{hL-#n!HZ}x$JIW~hxNnF|0SM$zPm1=#P+5Ei%qala+FZ7 z;#(Lr5Q3*j8T%7`*feJeQ}-#PMZ)yQ|;H8-CD6A9T;oo&L~cG=XUn zRzG|A->=z&ujwVqGmVK>?(YZv0|MZ0bEX2oM_Ai|(=*3=eLHVvXV@z0ZL53R@Zuci z2~GSQ6Do-wRsNi^)+77<3~$k-Ce_F`Nt3G0uqM1Yn+7iv?VjS#D@3W!{6kL}ZfJQe z6)(Ih|MQW^=_GaG>nZea=RU4-m?CJ17{TY0?DzoA>~)3cT*Ieg-$k3ogoSWv!eA9dv|%F!JkRZOpBPd3OEZBc;H`Ko%!QLq;l4CDwrP zJ+CQOsyq-*0BIiCc6y~-rw`I$7+vWf$2tbF;WgkK%;_7*_&Pb}aDiRm-M=uz_`}-p zttrhD5VFV$BZbH&zR_Z|$;e?{HsVjJb1v%cZw9VFhBgz-eWh`G^a@pnhD;l8im ztD&*~!k7h#G)iy}I|KR~Z$ntqyl3SW&q+*!0{AmYEEMh&0|sTMW`IT#R&ijYiyuch zYzX+w<8$GT9>do*kGI*?nyoFK`S$$u1bYYg5}IIXpiGmtZ<|Czi6HZ+e?v0@tXxf0 zgP0~BITyjP-Jp`qDG-mLQQc~Pe-KeA>Qqmd-Z}b}_BDVQhrzdv>IYlWPg*^C^T{m0 zilAq2=xI9Z*L+QQdZ`1gUyVZbf&zj)C(N7=4+`|Me1{(P*SsD7lp zgcXE{LXmKwDNgl90*J=K9=HQsj1d7T=*iX}-}X{v6XkqJWXR7>WYu7w>ARx+ub(PRsO3 z`Js2ujykESoi@}yZ^9%8aALM#-%3)@{kf434-W%OiQp7_1m5oViNQPG7Um(9VKi7t zZa^Ar<1>D3?p4q9?8dB-%|E*?z16APKWW@Y7wN3mMp^6lFu^*p@x3v&P0aX4wsPXod zk#xkc5EX)c)#4EOGzl^QqA6#@0akMLDPST*&Jq!E#7aOy;_A$2qM-e92on9kx8uQz zpkG|KFL-w@CnpDjeood$m$?ZxQAiI^_N>@z_w?=RVim5-UF9wk-L-n+8u6+Ku| zv!&`-jNbnJ*quRdo*1gCo;$|!aRR)F>_dzC_k=iqV5Oz&0^sSrO%Y+j+ktN77A_h; z;A7M2uEpqquGxg#V7Hpu-QKncRK<7f?uf4wj(UW+4W^xcZes-wPc%sPI9t6q6mH_m z?!m@Sr@hX_SW{C`$X|*>+X|8GmhXCkl?ICicJ4iKTiP}4>s$#(E~LR%KA)Z0X?Q0y zGl=ep%K+Q4rff+qXsctBvKc> zAkN<5Wnu2zifg`q9dckQ!x&%2zipm^Nh8o7TCwMQ+XiHE50K_pSi^$54(pI z>UFjmC5QDLy{|ngGK}X5`MO_#n&dr6QG@s8nGH*c{evacd-lZ0<(`RqTlnhbl31XC zb#Ys_iiixtoah#72tVE1YZiencC#N>a|g|Sd**Nobr`Sn%@`-=%m*D06WVMlADQQU zd!=V8W&Oee(Ml>w{+On{%SWJJ8R_YpG}u>|((nrj2}Pl|HTtbO^KBvOlrL9KPajfJ zQqt0DKmN+^je96Vlsaw3KxRwOXtc7~PuR7P7x3UGh)Z zyXD8Uv)ti8f&d86!S*B1`j&f#c1)ZNA*c;ew&^Fwo=HC&GJpIo;9?p8uISy4&hMd; zCQ_0{GRx@U{1vVdhKKk9C|5jLHI~oc@>S%v`t`%JdAAZV*@v%7a%r2R`d-J47c(<( z1Ev}w?fLxoUHZ2@>Ob5!2`fSImq1}``%MNSC|50^cO4*IJqpMIGCjs|0opY(!otF~ z!_*GLmLzZOpL;@cP_|R3W2sk`!`m$rRFx2Fj-UfYK&_uP*fy=7V5r5>wz1vv6q`I< zxS7=P<@^c??QI2M2jcxrKt@B5Qd+{{LbD2Dy=_9l3hHYlB%DzfrM16j+RbauK(@+E3w&O&?E(8HyNKLZi?Z!jSL7wrc^bVS_hcu*Un+sMF*F@KOth zDK`2pk%+Uko8Gh8=SWUIwqHa{@vpFhDOOG;b%~r)%sWXve;7Mi6pJ6yRBtjZ4<{qh zko7DgkxG?vdv`CZGFtC#H%2?}*A686xLp(tI?6TwkAtH&jBG+_dNiIa{(_&~d(yn0 z7&?1Vx?WK+?-9-br0>h5LUEyPgDHwKWz)TmYklxR!hskVAsd4Aw?m{ zM9F)SC6Z5qjvkn|B<_ZeN8mbyUAv~5(Zu9)er88MfvW8#J#5J| zJ0oTMh|Irv+4)DMmq>Jqp66T`XIF+AZ7@^A`@f00Tz9bH&N!uJ^yHpB_%mv}uD}b= zgG9+gjTFt)g05Yg*h*?vmZzLr!w1CWP+X(YUXmqb0?ut~*QyMhQ$A#>N}^U;8>?Kj zSks=2N{v*kIQPestt)2ydy`i@|C%JnF}0CgX7R?NbLxWm-oE^#1BzYw%I|H&GBcCi zz|sf{3)A9DOHIw1@aO(#q`pgOueY?c+&bE|A=R0phgGx7aS7aW9AE9zn;Ed$dXqCd z_9ACfhUwmXHlyBfC;Bp2(4lg9df5Sv0LZPrb&vfZyYQAS@J>m2b*4nC+njFeC>O`q|+RtzV`%V)bp zp9hgJqmt8$|Mv4OQ9u`WGA*D^-?d}8(vE>Y$!X93+c z4$i>WF)zo1aO8tYaXHQ?$2ZouV}S93m+TI`NlS|ViRG6k6#%ocp>}C6@sOSx3DZ09 z?V;Ey#s=QyW!w#E6N)YyUU(vy0~bN4Pg5{IAL=h6UD-^v>%DGOJjeNl*85_2SW0Xe z%at<4nKfVm!lioLKE91SAdTNYB7I=_Z3-;SFV_fzk0Zx2J;5D;5oYy~=nZC-EPBR_ z9WATr*hZx&#R$G8k_3aF#ek}LZgKH6Y)NlKRMx2$GtvH-?%jGOo`>CTFg@q42pF?Fn^(KDlxlqA1T_uXQ6nmM$oJP^Y z?huIhvsBO1`q5Xk)m>g^*#W->tLS5@NbOLA9Qtxe1_faL3!{N8vt>sS@i@T&0!`{0NST0j1E>B*ZB;(6Hbll(f|Z}IyAy3+~{3tzeC(ruMl*H^EE%@ z20I#$*qiZ=w378Ctz0i8l+ZR%e0}`V3QwCtzDp1MxO}fX@ax*(4z`Z3eMkLOSEgj+ zFX`J!)D`Fa)Jv58!>+`f)ezGY76Q1I+dgDS>B!(F!+d$U<0aY}b?WtMs3A9fA0d1+ zo2A@HOS?q3e2=7kTZAD&MK^rxV!12&)Zp3t6@eBfQDPCveETpv7BGOHn-ZMW zphpJgXZpaLPE(cecm(}h-lCe}&8J7w{?TF<_BlD(?+LTIy;>vhHfwhw(K-njBH5z9 z=`N>b8#Ym-h)OZj7)5Y#+nEQx=v4>PUE1r%PK48S0zYC_S&Qh;$Di_=JO5Lzd3;mm3x8M?Ig!_zc;&zu6?LVARSy| z*6+*ILB{fZ(gK|Vtxpl@>;HL+jrY?Fx&lx}UAnZ?+3I|osnJ&}7Dyv`GYHj(tXZ_oJ zB6OQgSI3uV%n%%YLwdF>+x*)5b*pnTVOp@eC{1$2P2j-i3Nxh^)7^xmNnvtC1MT3fV0{WdODV)>9hzSET1T`n#v zD9ydt)EA})CQeWIF}DPX6!3^>QQr-nk7eJtwF6*Zm+-kYe+U3U(xs5AS08lbf-wE@ zT3p;-_R0{SzT7rA=Lm2Otk`vNrq3>N2C&f9{ja<{ZBI_2We2iODNqNFYBX5_%Z{BU z>b&Q1Whk(UzJN+1R`NxAVyh!@Q(0kI(=jEKGVn_V$vo{-T64>S}?=c0;=sA!8ZJVtnp9^0+ z;s*>E78`r2PPSKb3M!-BiQXfw_h}8{SGhgCpSx)_>_B-FyU|S1+P*FS*!U|wa8*i+ zilRyqn`Sj+oXQ^f!dvd5{gVyVv#aaDEeIMfp+I<~Stm_Bl%Bg}%hEE&NAI@LRorfB z^?N!feyM}CXTPn4&oQ17+g0$4WB+$qzUIdb7mtt}SRbXTF+Wg`CyKU-2X!}SX0k>& zBgd{~6l}Tb?;SpfLO788lKnmOBR3ghASi;}L^wAp`ungBfN6jQ9 zTZB^6SK83)r>e4@l&kDzbbrLO{vf__$-m#Yo{Yrz@0U@OF7>|lZw7O435kL1RqQFn zLMo=ojU>a$1jkVCL&lo+a^7%Ur_}ZMPS(S^r?ZxHWXV6zM!E*qJKcTz*dM=p75iCAU$O`;4mEN_T@bJE?*r(Qlcu#zOxn?i z-v2K0j)HrltDLPDg(l5kztPbVy^&kDZ|j`2()Dnu$0Co8=Caj`=g_qG=>oB10OH@4 z@Fg}0uC`#a`ObUDPQoDu3_W&s_5@A;R0Vhb7FCg+o}Q+3MJZ&ORQ-}p?|{oom>wWd zr1x6hS)s%P9}v zEFs0Oo%f)VD+t!fNgQDVnmb%wT?Lu5T*+z3dsrn$$HrjR-q_gqB=~=Q7J-bq(T;HN z1RH&1Glhb;6D>z~A&OgWti9T`^YgrJMz zb23XGC)%~RSAo|wN$=AVl6TF#IcFe@y>$l_zz1t$QZ$Hf^L+yM)ar0p;aMw?ku?8^ z4a6FSee$)`5`=O?RA|H(~e1;rWw& zFtG#2zyTedu_~s$@tuu}1oPv~CM@0k@TW}k{#0f|xcjBHHe;Jr=TqUCotk=s^^=D; zb_`X3qiJ1j?HPPx*}P9oFF){696h{bFSNp#6|{y^XtA_2$9kY81TIidF>mjcW(tq5 z=+<;`h0CVkiw>#cn zwU&Cxe>;f2<6LuHmSHtgphp>E9?TBiwK<{~P1mw{<4&Ix8DBxyb+@QUj+tiJiVeK$ z)?vqK2#$Br2ucUO8?&SydE_Z8FMr)rR!ZtPSfWXH$Vle&^EQpu%U^$7wcHXL!;nn^q9^p0x zd~pmVp4H*QuAiC$UvlII*{z;orSa>a(#ACa63;$@5qa0PpIuN|gz>B8+Kvb@kjwI+ zLxo0V^^T-R-QC^O)1IFWP?8p}7QQv5{W}4{vO2f}jmB3NFt)w7-*L;6>gqnyjauMJ zX|=@H%>?z-qLF*gUW%mnU^UMRuYZz4#81bANPoDiw%oq`HN+3~&cvtJVqoA`D-&D2 zqXcrNuim=b5*XASfL|ULQNZ!Z-&N*(sB|;jJiw4kN=o7=jgE~aE_Xo)Ugnb)^jYoC zbs@pm6&U8e<^>pRD*aZdSVDKx>G#wKaAsL(6fJw|_NFf9XHjJ7RS~r9g*%iZm(#Ute;eQ6Nm( zy1Kgi_wP3_C5JcKi}((Pofsvq7V{%Ml*JxRi_Iea(V zgO<$eitr1|I5#atv!LuGg`#NIwj!~A(p$ue1A<~=ahr}tJ@$RRzBRepNSAu*97~J1 zp2ww+A3vh0wtwHgNKUeqSuZw+UQZ9A-!fcIQR*4_WD};hVaNWRUlad0@*(t5}ggifv?3 z3#;?bzZdsxF(_8bBV(XnILU54yCwCAzoeg=zasMqOL_d~BE@Ll1>h(Yb<6w1c;` zi_*ZFr$+tI(^4+tKS};8|MT;QL?@qiEz1%)6%_U%0Xte_?#J~O{`e%Haq;-j+qeTT zCyK4C+!pFCzGHvXd8fu$M{MJh5Q`HLfYM-9d-(4ZX6~4epe+U6Mn{`n@(9B|x3oIt z6gDH`LGyVJPV|5@-B8EA(PFVDyZ5Bhf_e3(xY=n`>?Y11R$RPUF1~M9hM%9G;JEqR zyJlrTN>L@T@V$Cw`Z}QhAF4~Jt)Y6?>AUqBpeF{aLJXFcju<5C!a>?6M}RxV%^wCG z5o~S(u75#a?3}jPxw(1vAunC3=*hQWig_!6sSBnsv$6dsi46##`R6A%h@W6s_!Er! z+ATTOI=M^!zy7Z3DoxPE$p9jq8i@fR|8l`0r+?rgBH2>foC1+T29kyijBjO0q<(+- zwew=;ugq%KLr+$fxM7wN;%q_M#L#%^*EK*+#97OC!T<7 z;S-eU>gjzQXt~P2+*vz8&*pY^leD)WpYSu~LMk$Bi(?BnEQ$JSoAX|Gce$SBt5fQg zzzM^Nmu8~m5=^W!@=C&W1VV{yF{YQ>2Ak4J-pLC?YB@44T2LD{Zrq6I$ItR_%EenW z_h!g^@@S4m{F`;r+OLA|?ZOozcJHnMZ&E)vJSyr9V6e2b^|o6Xj?XQ`&U%17 zD7c|KtglPZlS^W?6(A|D4`P`gr8^Hnq#vrGdYP*w;qt)1fTp0uAmxqAMBriN`X>Xk z?yVQ**14F=MB-&#xP^v+lF}u$_=6LUK1J8bMI+unKV9t%xaCNJ1owk*GJmFp<1c{T zS6X;{qlCnWU5Jd*+&X3k6fF_T$!)Zkf@FSnL8v52qxw6TctBNkQLOrMfuD=mchl0T zT+WgJJ07qb{__*Em?9^qjr=S$F-^|As&gMvf`J}Sj&t8DcXASg{KAi@tN>MlKa99K z!kxToF%f1&jvxx0ajgSg;;sORbWeG~hE_a_3DDM#lsR@|oYJ3>2(Cu;Zs0m1{jB0# zxRu+UUYE{LZhyb4FAOSurS)^+iJXdv6eJkK)8VhRmKngH|J_Sm|b54~7BV+rIG2S0C7|aL#mOzljOq2>B6d@$_n9 zMAny1m`(_HAV^mK=QFe&Y6|CejO2l%G+KcSG2j;eLDjif&Qex7pjC{zvIuEt(8YyM zFMJ9gJVWG-bbi|)9Nf8kH!#_&J2l8z=guyX|B=+G1TWZ2j^{F79zs)VLM;y)5A0Lz zl-EdJg3nS`&P9hW%KtmH<2|=NYSiH7QHlM<^a(KYyyLQU0 zij8IOawRfnm11#I9=Je`^?+yhp|=-k)jbEbq{PH=ST$I@CW~k9N{CoxKfk;X_9W6s zLlADibm0pEab)Kdm^MS!vFBSGp1D|sVs8O1xPc~%l zk6dL>U8C**4Rz(aS~RXR&WJIgSr2-&%&Dd4`3Cr^F@Cv7vU=iwIB z?HxDdnx)gKFBiT!gflGz#H-ZQnzj{^RgDtLZFHg6JLV^R9gOr3mmZU!SHTr4k{u(+ z;#=<0haY`({)@%CA+sM(*f#w06&p-Tfqg1`&oaoX2qzo%cN0A9-#WhvqY`Q;_Lr{S zWdF~HR+J8`C$co0@&A1W@~|W6$kWs*N4`8|$VUwzeb_XQ$pMhoV!ppjVwLf*-$i`8 z((iAdi13m%CUQI8%YPXRw{wLRE55AD|F+e+0&XHb6Cj2XB3Vy$#DE?_~l^7TJ&j_;aR6rK`i^TY~Dy0sBJkJMrPnDg3K=zl#C zE7#M~&45SV$fAnE693yk%YC$l!O@Qh*?r&u54Yx*Td(JGQLf*^RwOfB6u*k$zi({v zAk|xN@B~vfk3E$jnn?A#GJqBfj>|CYeU8_wX|F^eTP{_~;#dUp5~}}^9$umNJ#NLh zF#F$k#z4?fLv;f#Ui@)j@AmCfyA|kuy$z!c#PczZXyR2qn2(rU(}j9U_b7QH4|Uhi zwJs7tMB~3KAzoiMZL*~X66>%bL?Zl$xJceU>(4J=_>CjC$X8??*2dEQl`>Ko(D5(W z+l#w)QEjkzc8hrR2l+~!Nu)(tT)XE_M0FP|sWUfO@7}jB>=;+9?o%tD6O~pW^u**< zkYVz;ePtEe5+?tAq|PErZqo2mq7dfXxdSpKYYRp-?F0(BDIL8|_TLl8Mc!8{@Ys$N z&G4juLEtGrzNFeLl{8E`8U{*90HymrbjLn7+@w}p^Wjz&Slc+jUKo7h^rrqjwE$8q zfdh(ovCDG1scg7?altBl&94|r&699aA<*QSOhh*4Lkd9Ag=O zZ*v5L(Z_3SQo3U?Xb`EYpqpLJj{l{HzgMGHig3O>n=fh!eK0bavX z_e%P7RbzRX)swCa!Tv@M_2TvDCZd<$fNY{@%X40v-$917ZMOE*U=ymB5-(Zvcvr>U zMJ`fZZz|X;^3V9Iv9v!eOn(qIr_cpw*U5bXVGN$VRq&Tt!|z?hacuBl z#f!H?tv+l6c>!M)Gxz|`-ty52b5J1jy2M%mOR}(4At|jrrbLuOGULoh^!d2Kf&>iW%v=J)9oT#Bk zz94fo_7O6^PZyFEZzkO{x~;62x#uBkU}@X5>HM{gJ$kY_bD z-$8ybm_lAi+)hU;S`ZIcRf3?2OY~%E8e75R7{v{{E5egg%WBZ{-*sECB}i(u1%#pZ z@vf}myj;!AyC6~*5*Ge3a^-Y=jOLHE$BA_4-C89ICC-%OWWsQR&Zk2xr|I~{4=_FEHR*l0}wh`%&@?RhWXmy$Q5 zAjXn*sVM1otU1DaZ~UmF6$|P)de1u`1k9Becg9t8 zJ%`#ODYHhsH|3+j!)o(!8>hBAV z8}5BcU5}VH@gAZE_=>Ag6Wk2MzumGIa?fu|fU&b2u05e27dSJ%XqF!Ke9~WUToeUM zKk!>YiK6segd zYS;$*EG_wa8aRAR?NomsfK86&ezHNIURU=k(xm?_OjQY*_DsY~4wH&(UyI72ne+Hb z`;W12#=CZ1C=4#Slauo$KsbG}edv_c7R&zfQ^X=pJe!*Nyf-<gUg`-ew4b;aH^ zu9+9$3>|H4eez6C0pd*%_jSY7{p6QEt)|Edx%yMY)ww`+fXgZ1N<~*(Lmjpho&DQs zghfH3>gdUjWgr-jwXU99`K$f5tqK^04){Q+r)oN|@rxkm1Z%jA9&AdhtFgzy|omdREw+~GuUPkXnrj6Les}bp*PWRBfW;k?i(~>Z9 z!ka2Lnk-l!5T&}ChQ{TC!EEZkx2rOVjde$W>FV1Q>k9sM=+bHNkcJA-MP0imq8^U6 z(`J`Ws9xb|M-C1zbARTO4JyCloD`*_**gCzDJQugU)#T@AGbO=dbr_>D_!D+-Pk0w zs9D*MTb-jYul-C}*YA{OEq6iY`l=ZYS?-+`Qh!grv>gLS={AGml#-I-=3XF1aP7fX zZpZE337SXHb3k7eMWxi1t+7|u{#tzMa*k#O{}01k0h%E^HSY2+bvy*lG7KjrW<8_V zwhcWV`{z-2QH!o;RQliH4S5{1@y%jx-4yuhmf(K&rtee*_dtJ%n!wp|Z6;fH!olY5 z7^n2Fgh0CRWw~D>U*G@SzdmmT9Zpv1xcEQW&YgLG<^2i&$&Xw=@LJ>{dr%xQfoebZ z)CH<5SWB3La4{KfwZWzLmNaz-OKYSqkHsP$%)Hkqm z&ql31q9486XPR?&RO$6jqOke!lOu-gv?h?^{?t9&EB+aEBhS(J!sS1N%N>Z2=r1b;H^!t^^ z44a|HKxN`pLB%F%{o)pqHmE&MWcGjM5j+->OiU?s@7t}1Lcjm`V12@YZlYx?OQO!p zICcM%P6JChRLs^MTFm6+GM4i-IW_)`uh1p`ZFPrQPC&^C?}~b6lhZTfFf!SSTG(KU z;PvA|4rHYeybR$Msqc_?rHtU1mP`Ds?C$Hd*DZy4HXWBpoS)$IAa0B{5t)8RfBN7L zZD5EKIR~W1rP$j!kG4Y^size=G@gwxm0n^><`j&hQyt z?z`f8cv)9t1}+fg*Ge_;-?ny}#tCk}J0pFdJ3Id*L#C_o-e|ifYVsW%v_>-iFydVg zv^4hB<9OJ+<=d^SEW!~SA>+`{v!_o7;EV}(@O3-2e!!q*+Tt~(pKOsZ&0`ni{rd^H zlluCpAy^B2!-uCx=uuK{ZgGWcKt{$?g=cSQg-zu}X z5P{Nd-4rmw?H2|iQoE4?m7aJ_Dab+X#~yRLTp)NzA1q*RBE_@C;Olt0KPxJJ$jl~@ zT7{&5$JZ3tWQ$He(6O7Zai4S8xJ$`3TWa}A;mxlzd6ai@Hnt-xJG*xdLp5;IweJ$0 z#=BRKmI>yIO;lE?WtkjIMg4oS+GFg_--O&C%EY zGC>?)oP&0TjwRFq)i3Sa9>8zB`bP0%kL+eK5fRHlJgFzL)IirLF0n;BNgzh-d$m_#blXt97?cU^E z_)wNqT6uF&S4Yny28ovxPkPUr3bNeLRxs`Q?NjJ7V}~yg4U)CAVm0dZe%2aw3SZkm z5smR2M1r;HL}oTu!%CLXPw4l4CGI-kaFBF#iQ2YMHDxQlZkN|uZsI&%#$iUMPMtFT zv*((wcJOvv)XPKG(vR1UwnF^U10Tbi7PxC&aS*mMd6Z%ktG8>@w7Jyh@VL|VyhayZ zH^x(>iBL)=*&0&ZFw3s#Rea)AxT4QqiWthv-s6cG~R|T)EPQ7KZ z_nB;rn{`2I5vxOOX{jbHH{o_ZotsNjt#EF=KtO<=L(+fZT=h^}P-AeT*Spja(Hds8Ix0${5*6E^)){`b8}d*Is)97V@!>!VS&6&Ul|6ROPXqe7?t-fA_p>erK#i zwpDsd-0Hz&;BfDc{M=XezSnr--j!E@^qGNIUbQsx_K)A{kdne}XFkeahrfzC@3o=@5`K%gzT-VI z>t-mPt8UbPqYJEaC1TC_Z8d?Z*XWLGF53;3($99b#k=i=Pn^tNSnE>jBujc|5__qk zZvE;lGf^*h8W^-dK(}ij8Z*|o%m+xujd&r!?xh@ZOsj6+zg&57r0;!No8Tn@etxZ$ z?txeTU{wH>DhO+pA1YR+?rwgG%36ae(%J6Dd)(pz8ggUZoz$riim;)z54HwJM&hQd z${P{ii5$~EWy7AEFXGom212IqGyQW zH=nF(ba=HiMYVBT;v5Z5XjPB2P#!`{#nvI9qqz#cV$x4`N9V~pBfdpDTGBm zJw2?G>V(QW_X?Grd;Nb;?1XnhTXOup*oia0cjR5wX1`_fs7MnHHcG4JU@Ja&_NdJC zs?*JO4G!;3Li~$E6j8oGd-)X5J919-)`)YPp_GT3du&OepvBxCE#SDarLHEhQiir) zCHm|i%!qWgdLO;Qh7r)2oUpp#FNRA4Hi?Nnm)fLtfVg=N6!?;!H?|olH+MX{whY3M zOZLc|+o1S4qh9t^(JWMZu?O8NxNp1SawnX6IW@B#Tm#v?nuL@P?|WdE=7&#j*d_fd z_oy;O?b{uPIy({zbLH$X_432DAD8%T`?5Mks)p>G+t{5p!30o-?(S;8`Q*q4>&~

-## Launch - -The `ekf_localizer` starts with the default parameters with the following command. - -```sh -roslaunch ekf_localizer ekf_localizer.launch -``` - -The parameters and input topic names can be set in the `ekf_localizer.launch` file. - ## Node ### Subscribed Topics -- measured_pose_with_covariance (geometry_msgs/PoseWithCovarianceStamped) - - Input pose source with the measurement covariance matrix. - -- measured_twist_with_covariance (geometry_msgs/TwistWithCovarianceStamped) - - Input twist source with the measurement covariance matrix. - -- initialpose (geometry_msgs/PoseWithCovarianceStamped) - - Initial pose for EKF. The estimated pose is initialized with zeros at the start. It is initialized with this message whenever published. +| Name | Type | Description | +| -------------------------------- | ------------------------------------------------ | ---------------------------------------------------------------------------------------------------------------------------------------- | +| `measured_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input pose source with the measurement covariance matrix. | +| `measured_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | Input twist source with the measurement covariance matrix. | +| `initialpose` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Initial pose for EKF. The estimated pose is initialized with zeros at the start. It is initialized with this message whenever published. | ### Published Topics -- ekf_odom (nav_msgs/Odometry) - - Estimated odometry. - -- ekf_pose (geometry_msgs/PoseStamped) - - Estimated pose. - -- ekf_pose_with_covariance (geometry_msgs/PoseWithCovarianceStamped) - - Estimated pose with covariance. - -- ekf_biased_pose (geometry_msgs/PoseStamped) - - Estimated pose including the yaw bias - -- ekf_biased_pose_with_covariance (geometry_msgs/PoseWithCovarianceStamped) - - Estimated pose with covariance including the yaw bias - -- ekf_twist (geometry_msgs/TwistStamped) - - Estimated twist. - -- ekf_twist_with_covariance (geometry_msgs/TwistWithCovarianceStamped) - - The estimated twist with covariance. - -- diagnostics (diagnostic_msgs/DiagnosticArray) - - The diagnostic information. +| Name | Type | Description | +| --------------------------------- | ------------------------------------------------ | ----------------------------------------------------- | +| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. | +| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. | +| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. | +| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias | +| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias | +| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. | +| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. | +| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. | ### Published TF - base_link - - TF from "map" coordinate to estimated pose. + TF from `map` coordinate to estimated pose. ## Functions @@ -205,7 +167,9 @@ Increasing the number will improve the smoothness of the estimation, but may hav -where `b_k` is the yawbias. +where, $\theta_k$ represents the vehicle's heading angle, including the mounting angle bias. +$b_k$ is a correction term for the yaw bias, and it is modeled so that $(\theta_k+b_k)$ becomes the heading angle of the base_link. +The pose_estimator is expected to publish the base_link in the map coordinate system. However, the yaw angle may be offset due to calibration errors. This model compensates this error and improves estimation accuracy. ### time delay model @@ -240,7 +204,7 @@ Note that, although the dimension gets larger since the analytical expansion can ## Known issues -- In the presence of multiple inputs with yaw estimation, yaw bias `b_k` in the current EKF state would not make any sense, since it is intended to capture the extrinsic parameter's calibration error of a sensor. Thus, future work includes introducing yaw bias for each sensor with yaw estimation. +- If multiple pose_estimators are used, the input to the EKF will include multiple yaw biases corresponding to each source. However, the current EKF assumes the existence of only one yaw bias. Therefore, yaw bias `b_k` in the current EKF state would not make any sense and cannot correctly handle these multiple yaw biases. Thus, future work includes introducing yaw bias for each sensor with yaw estimation. ## reference diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp index 573472fe2dabf..8977d82f34138 100644 --- a/localization/ekf_localizer/src/ekf_module.cpp +++ b/localization/ekf_localizer/src/ekf_module.cpp @@ -87,9 +87,15 @@ geometry_msgs::msg::PoseStamped EKFModule::getCurrentPose( { const double x = kalman_filter_.getXelement(IDX::X); const double y = kalman_filter_.getXelement(IDX::Y); + /* + getXelement(IDX::YAW) is surely `biased_yaw`. + Please note how `yaw` and `yaw_bias` are used in the state transition model and + how the observed pose is handled in the measurement pose update. + */ const double biased_yaw = kalman_filter_.getXelement(IDX::YAW); const double yaw_bias = kalman_filter_.getXelement(IDX::YAWB); const double yaw = biased_yaw + yaw_bias; + Pose current_ekf_pose; current_ekf_pose.header.frame_id = params_.pose_frame_id; current_ekf_pose.header.stamp = current_time; @@ -224,7 +230,9 @@ bool EKFModule::measurementUpdatePose( return false; } - /* Set yaw */ + /* Since the kalman filter cannot handle the rotation angle directly, + offset the yaw angle so that the difference from the yaw angle that ekf holds internally is less + than 2 pi. */ double yaw = tf2::getYaw(pose.pose.pose.orientation); const double ekf_yaw = kalman_filter_.getXelement(delay_step * dim_x_ + IDX::YAW); const double yaw_error = normalizeYaw(yaw - ekf_yaw); // normalize the error not to exceed 2 pi From 216f6015378b7f3a50cbd9d711abcc5ce1b28aac Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 9 Jan 2024 11:10:00 +0900 Subject: [PATCH 196/276] refactor(dynamic_avoidance): separate dynamic avoidance module (#6019) * refactor(dynamic_avoidance): separate dynamic avoidance module Signed-off-by: Takayuki Murooka * move figures Signed-off-by: Takayuki Murooka * update .pages Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- planning/.pages | 2 +- .../CMakeLists.txt | 25 ++++ .../README.md} | 6 +- .../config}/dynamic_avoidance.param.yaml | 0 .../drivable_area_extraction_width.drawio.svg | 0 .../image}/opposite_directional_object.svg | 0 .../image}/same_directional_object.svg | 0 .../manager.hpp | 8 +- .../scene.hpp} | 9 +- .../package.xml | 42 ++++++ .../plugins.xml | 2 +- .../src}/manager.cpp | 2 +- .../src/scene.cpp} | 2 +- ...t_behavior_path_planner_node_interface.cpp | 123 ++++++++++++++++++ planning/behavior_path_planner/CMakeLists.txt | 4 - planning/behavior_path_planner/README.md | 2 +- ...t_behavior_path_planner_node_interface.cpp | 15 +-- 17 files changed, 211 insertions(+), 31 deletions(-) create mode 100644 planning/behavior_path_dynamic_avoidance_module/CMakeLists.txt rename planning/{behavior_path_planner/docs/behavior_path_planner_dynamic_avoidance_design.md => behavior_path_dynamic_avoidance_module/README.md} (94%) rename planning/{behavior_path_planner/config/dynamic_avoidance => behavior_path_dynamic_avoidance_module/config}/dynamic_avoidance.param.yaml (100%) rename planning/{behavior_path_planner/image/dynamic_avoidance => behavior_path_dynamic_avoidance_module/image}/drivable_area_extraction_width.drawio.svg (100%) rename planning/{behavior_path_planner/image/dynamic_avoidance => behavior_path_dynamic_avoidance_module/image}/opposite_directional_object.svg (100%) rename planning/{behavior_path_planner/image/dynamic_avoidance => behavior_path_dynamic_avoidance_module/image}/same_directional_object.svg (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance => behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module}/manager.hpp (82%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp => behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp} (97%) create mode 100644 planning/behavior_path_dynamic_avoidance_module/package.xml rename planning/{behavior_path_planner => behavior_path_dynamic_avoidance_module}/plugins.xml (72%) rename planning/{behavior_path_planner/src/scene_module/dynamic_avoidance => behavior_path_dynamic_avoidance_module/src}/manager.cpp (99%) rename planning/{behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp => behavior_path_dynamic_avoidance_module/src/scene.cpp} (99%) create mode 100644 planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp diff --git a/planning/.pages b/planning/.pages index c41a1cc8c6603..e244f1d1ea25d 100644 --- a/planning/.pages +++ b/planning/.pages @@ -12,7 +12,7 @@ nav: - 'Scene Module': - 'Avoidance': planning/behavior_path_avoidance_module - 'Avoidance by Lane Change': planning/behavior_path_avoidance_by_lane_change_module - - 'Dynamic Avoidance': planning/behavior_path_planner/docs/behavior_path_planner_dynamic_avoidance_design + - 'Dynamic Avoidance': planning/behavior_path_dynamic_avoidance_module - 'Goal Planner': planning/behavior_path_goal_planner_module - 'Lane Change': planning/behavior_path_lane_change_module - 'Side Shift': planning/behavior_path_side_shift_module diff --git a/planning/behavior_path_dynamic_avoidance_module/CMakeLists.txt b/planning/behavior_path_dynamic_avoidance_module/CMakeLists.txt new file mode 100644 index 0000000000000..98874b8923324 --- /dev/null +++ b/planning/behavior_path_dynamic_avoidance_module/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_dynamic_avoidance_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/scene.cpp + src/manager.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_behavior_path_planner_node_interface.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_dynamic_avoidance_design.md b/planning/behavior_path_dynamic_avoidance_module/README.md similarity index 94% rename from planning/behavior_path_planner/docs/behavior_path_planner_dynamic_avoidance_design.md rename to planning/behavior_path_dynamic_avoidance_module/README.md index f303937bd0f78..5e8be9136886c 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_dynamic_avoidance_design.md +++ b/planning/behavior_path_dynamic_avoidance_module/README.md @@ -32,16 +32,16 @@ First, a maximum lateral offset to avoid is calculated as follows. The polygon's width to extract from the drivable area is the obstacle width and double `drivable_area_generation.lat_offset_from_obstacle`. We can limit the lateral shift offset by `drivable_area_generation.max_lat_offset_to_avoid`. -![drivable_area_extraction_width](../image/dynamic_avoidance/drivable_area_extraction_width.drawio.svg) +![drivable_area_extraction_width](./image/drivable_area_extraction_width.drawio.svg) Then, extracting the same directional and opposite directional obstacles from the drivable area will work as follows considering TTC (time to collision). Regarding the same directional obstacles, obstacles whose TTC is negative will be ignored (e.g. The obstacle is in front of the ego, and the obstacle's velocity is larger than the ego's velocity.). Same directional obstacles -![same_directional_object](../image/dynamic_avoidance/same_directional_object.svg) +![same_directional_object](./image/same_directional_object.svg) Opposite directional obstacles -![opposite_directional_object](../image/dynamic_avoidance/opposite_directional_object.svg) +![opposite_directional_object](./image/opposite_directional_object.svg) ## Parameters diff --git a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml b/planning/behavior_path_dynamic_avoidance_module/config/dynamic_avoidance.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml rename to planning/behavior_path_dynamic_avoidance_module/config/dynamic_avoidance.param.yaml diff --git a/planning/behavior_path_planner/image/dynamic_avoidance/drivable_area_extraction_width.drawio.svg b/planning/behavior_path_dynamic_avoidance_module/image/drivable_area_extraction_width.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/dynamic_avoidance/drivable_area_extraction_width.drawio.svg rename to planning/behavior_path_dynamic_avoidance_module/image/drivable_area_extraction_width.drawio.svg diff --git a/planning/behavior_path_planner/image/dynamic_avoidance/opposite_directional_object.svg b/planning/behavior_path_dynamic_avoidance_module/image/opposite_directional_object.svg similarity index 100% rename from planning/behavior_path_planner/image/dynamic_avoidance/opposite_directional_object.svg rename to planning/behavior_path_dynamic_avoidance_module/image/opposite_directional_object.svg diff --git a/planning/behavior_path_planner/image/dynamic_avoidance/same_directional_object.svg b/planning/behavior_path_dynamic_avoidance_module/image/same_directional_object.svg similarity index 100% rename from planning/behavior_path_planner/image/dynamic_avoidance/same_directional_object.svg rename to planning/behavior_path_dynamic_avoidance_module/image/same_directional_object.svg diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp b/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/manager.hpp similarity index 82% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp rename to planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/manager.hpp index 9e08f309a78b3..c2c17c4e55c1e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp +++ b/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/manager.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__DYNAMIC_AVOIDANCE__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__DYNAMIC_AVOIDANCE__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp" +#include "behavior_path_dynamic_avoidance_module/scene.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" #include @@ -52,4 +52,4 @@ class DynamicAvoidanceModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__DYNAMIC_AVOIDANCE__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp similarity index 97% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp rename to planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp index 50f5b61e15169..d2f9cd95066d9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__DYNAMIC_AVOIDANCE__DYNAMIC_AVOIDANCE_MODULE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__DYNAMIC_AVOIDANCE__DYNAMIC_AVOIDANCE_MODULE_HPP_ +#ifndef BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__SCENE_HPP_ #include "behavior_path_planner_common/interface/scene_module_interface.hpp" @@ -23,9 +23,6 @@ #include #include #include -#include -#include -#include #include #include @@ -413,4 +410,4 @@ class DynamicAvoidanceModule : public SceneModuleInterface }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__DYNAMIC_AVOIDANCE__DYNAMIC_AVOIDANCE_MODULE_HPP_ +#endif // BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_dynamic_avoidance_module/package.xml b/planning/behavior_path_dynamic_avoidance_module/package.xml new file mode 100644 index 0000000000000..11792a15b2cd2 --- /dev/null +++ b/planning/behavior_path_dynamic_avoidance_module/package.xml @@ -0,0 +1,42 @@ + + + + behavior_path_dynamic_avoidance_module + 0.1.0 + The behavior_path_dynamic_avoidance_module package + + Takayuki Murooka + Yuki Takagi + Satoshi Ota + Kosuke Takeuchi + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + autoware_auto_perception_msgs + autoware_auto_planning_msgs + autoware_auto_vehicle_msgs + behavior_path_planner + behavior_path_planner_common + geometry_msgs + lanelet2_core + lanelet2_extension + motion_utils + object_recognition_utils + pluginlib + rclcpp + signal_processing + tier4_autoware_utils + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_planner/plugins.xml b/planning/behavior_path_dynamic_avoidance_module/plugins.xml similarity index 72% rename from planning/behavior_path_planner/plugins.xml rename to planning/behavior_path_dynamic_avoidance_module/plugins.xml index a16f3dd7bddee..fd2e1bc4137b7 100644 --- a/planning/behavior_path_planner/plugins.xml +++ b/planning/behavior_path_dynamic_avoidance_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp rename to planning/behavior_path_dynamic_avoidance_module/src/manager.cpp index f39727246d722..569c6a17b5b32 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp" +#include "behavior_path_dynamic_avoidance_module/manager.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp rename to planning/behavior_path_dynamic_avoidance_module/src/scene.cpp index 01635d7a6cb70..ca58bbf0adcaa 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp" +#include "behavior_path_dynamic_avoidance_module/scene.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/utils.hpp" diff --git a/planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..16b4ffbc688ae --- /dev/null +++ b/planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,123 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "behavior_path_planner/behavior_path_planner_node.hpp" + +#include +#include +#include + +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, + {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_dynamic_avoidance_module") + + "/config/dynamic_avoidance.param.yaml"}); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index f3727f35a492f..54b4bf122da00 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -7,13 +7,9 @@ autoware_package() find_package(OpenCV REQUIRED) find_package(magic_enum CONFIG REQUIRED) -pluginlib_export_plugin_description_file(${PROJECT_NAME} plugins.xml) - ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/planner_manager.cpp src/behavior_path_planner_node.cpp - src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp - src/scene_module/dynamic_avoidance/manager.cpp ) target_include_directories(${PROJECT_NAME}_lib SYSTEM PUBLIC diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 6f462e17248f0..03f8c8d2a5696 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -28,7 +28,7 @@ Behavior Path Planner has following scene modules | :----------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :----------------------------------------------------------------- | | Lane Following | this module generates reference path from lanelet centerline. | LINK | | Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](../behavior_path_avoidance_module/README.md) | -| Dynamic Avoidance | WIP | LINK | +| Dynamic Avoidance | WIP | [LINK](../behavior_path_dynamic_avoidance_module/README.md) | | Avoidance By Lane Change | this module generates lane change path when there is objects that should be avoid. | [LINK](../behavior_path_avoidance_by_lane_change_module/README.md) | | Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](../behavior_path_lane_change_module/README.md) | | External Lane Change | WIP | LINK | diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index 28ee6d31e80dc..7ba934e873a8d 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -50,21 +50,18 @@ std::shared_ptr generateNode() ament_index_cpp::get_package_share_directory("behavior_path_planner"); std::vector module_names; - module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); std::vector params; params.emplace_back("launch_modules", module_names); node_options.parameter_overrides(params); test_utils::updateNodeOptions( - node_options, - {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", - behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", - behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", - behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml"}); + node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml"}); return std::make_shared(node_options); } From 9e1005b35df951fef07f4b986acbefcd93c6b398 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 9 Jan 2024 11:11:13 +0900 Subject: [PATCH 197/276] feat(probabilistic_occupancy_grid_map): add grid map fusion node (#5993) * add synchronized ogm fusion node Signed-off-by: yoshiri * add launch test for grid map fusion node Signed-off-by: yoshiri * fix test cases input msg error Signed-off-by: yoshiri * change default fusion parameter Signed-off-by: yoshiri * rename parameter for ogm fusion Signed-off-by: yoshiri * feat: add multi_lidar_ogm generation method Signed-off-by: yoshiri * enable ogm creation launcher in tier4_perception_launch to call multi_lidar ogm creation Signed-off-by: yoshiri * fix: change ogm fusion node pub policy to reliable Signed-off-by: yoshiri * chore: remove files outof scope with divied PR Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- ...robabilistic_occupancy_grid_map.launch.xml | 16 +- .../CMakeLists.txt | 27 ++ .../README.md | 17 + ...nchronized_grid_map_fusion_node.param.yaml | 20 + .../synchronized_grid_map_fusion.drawio.svg | 290 +++++++++++ .../include/cost_value.hpp | 33 +- .../fusion/single_frame_fusion_policy.hpp | 66 +++ .../synchronized_grid_map_fusion_node.hpp | 127 +++++ ...grid_map_log_odds_bayes_filter_updater.hpp | 48 ++ .../include/utils/utils.hpp | 3 + ...nized_occupancy_grid_map_fusion.launch.xml | 10 + .../src/fusion/single_frame_fusion_policy.cpp | 322 ++++++++++++ .../synchronized_grid_map_fusion_node.cpp | 458 ++++++++++++++++++ ...grid_map_log_odds_bayes_filter_updater.cpp | 69 +++ .../src/utils/utils.cpp | 16 + .../synchronized_grid_map_fusion.md | 168 +++++++ .../test/cost_value_test.cpp | 47 ++ .../test/fusion_policy_test.cpp | 75 +++ .../test_synchronized_grid_map_fusion_node.py | 255 ++++++++++ 19 files changed, 2064 insertions(+), 3 deletions(-) create mode 100644 perception/probabilistic_occupancy_grid_map/config/synchronized_grid_map_fusion_node.param.yaml create mode 100644 perception/probabilistic_occupancy_grid_map/image/synchronized_grid_map_fusion.drawio.svg create mode 100644 perception/probabilistic_occupancy_grid_map/include/fusion/single_frame_fusion_policy.hpp create mode 100644 perception/probabilistic_occupancy_grid_map/include/fusion/synchronized_grid_map_fusion_node.hpp create mode 100644 perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp create mode 100644 perception/probabilistic_occupancy_grid_map/launch/synchronized_occupancy_grid_map_fusion.launch.xml create mode 100644 perception/probabilistic_occupancy_grid_map/src/fusion/single_frame_fusion_policy.cpp create mode 100644 perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp create mode 100644 perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_log_odds_bayes_filter_updater.cpp create mode 100644 perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md create mode 100644 perception/probabilistic_occupancy_grid_map/test/cost_value_test.cpp create mode 100644 perception/probabilistic_occupancy_grid_map/test/fusion_policy_test.cpp create mode 100644 perception/probabilistic_occupancy_grid_map/test/test_synchronized_grid_map_fusion_node.py diff --git a/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml b/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml index 751eeea66c7b6..281a52a85af71 100644 --- a/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml +++ b/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml @@ -8,7 +8,7 @@ - + @@ -48,4 +48,18 @@ + + + + + + + + + + + + + + diff --git a/perception/probabilistic_occupancy_grid_map/CMakeLists.txt b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt index 035845772ce53..928532f928e38 100644 --- a/perception/probabilistic_occupancy_grid_map/CMakeLists.txt +++ b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt @@ -55,6 +55,24 @@ rclcpp_components_register_node(laserscan_based_occupancy_grid_map EXECUTABLE laserscan_based_occupancy_grid_map_node ) +# GridMapFusionNode +ament_auto_add_library(synchronized_grid_map_fusion SHARED + src/fusion/synchronized_grid_map_fusion_node.cpp + src/fusion/single_frame_fusion_policy.cpp + src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp + src/updater/occupancy_grid_map_log_odds_bayes_filter_updater.cpp + src/utils/utils.cpp +) + +target_link_libraries(synchronized_grid_map_fusion + ${PCL_LIBRARIES} +) + +rclcpp_components_register_node(synchronized_grid_map_fusion + PLUGIN "synchronized_grid_map_fusion::GridMapFusionNode" + EXECUTABLE synchronized_grid_map_fusion_node +) + ament_auto_package( INSTALL_TO_SHARE launch @@ -66,13 +84,22 @@ if(BUILD_TESTING) # launch_testing find_package(launch_testing_ament_cmake REQUIRED) add_launch_test(test/test_pointcloud_based_method.py) + add_launch_test(test/test_synchronized_grid_map_fusion_node.py) # gtest ament_add_gtest(test_utils test/test_utils.cpp ) + ament_add_gtest(costmap_unit_tests + test/cost_value_test.cpp) + ament_add_gtest(fusion_policy_unit_tests + test/fusion_policy_test.cpp + src/fusion/single_frame_fusion_policy.cpp + ) target_link_libraries(test_utils ${PCL_LIBRARIES} ${PROJECT_NAME}_common ) + target_include_directories(costmap_unit_tests PRIVATE "include") + target_include_directories(fusion_policy_unit_tests PRIVATE "include") endif() diff --git a/perception/probabilistic_occupancy_grid_map/README.md b/perception/probabilistic_occupancy_grid_map/README.md index 962bcdc6f154f..084c55d80d629 100644 --- a/perception/probabilistic_occupancy_grid_map/README.md +++ b/perception/probabilistic_occupancy_grid_map/README.md @@ -9,6 +9,7 @@ This package outputs the probability of having an obstacle as occupancy grid map - [Pointcloud based occupancy grid map](pointcloud-based-occupancy-grid-map.md) - [Laserscan based occupancy grid map](laserscan-based-occupancy-grid-map.md) +- [Grid map fusion](synchronized_grid_map_fusion.md) ## Settings @@ -70,3 +71,19 @@ Additional argument is shown below: | `container_name` | `occupancy_grid_map_container` | | | `input_obstacle_pointcloud` | `false` | only for laserscan based method. If true, the node subscribe obstacle pointcloud | | `input_obstacle_and_raw_pointcloud` | `true` | only for laserscan based method. If true, the node subscribe both obstacle and raw pointcloud | + +### Test + +This package provides unit tests using `gtest`. +You can run the test by the following command. + +```bash +colcon test --packages-select probabilistic_occupancy_grid_map --event-handlers console_direct+ +``` + +Test contains the following. + +- Unit test for cost value conversion function +- Unit test for utility functions +- Unit test for occupancy grid map fusion functions +- Input/Output test for pointcloud based occupancy grid map diff --git a/perception/probabilistic_occupancy_grid_map/config/synchronized_grid_map_fusion_node.param.yaml b/perception/probabilistic_occupancy_grid_map/config/synchronized_grid_map_fusion_node.param.yaml new file mode 100644 index 0000000000000..f8a2dc2fbc7de --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/config/synchronized_grid_map_fusion_node.param.yaml @@ -0,0 +1,20 @@ +/**: + ros__parameters: + # 1. fusion parameters + fusion_input_ogm_topics: ["topic1", "topic2"] + input_ogm_reliabilities: [0.8, 0.2] + fusion_method: "overwrite" # choose from ["overwrite", "log-odds", "dempster-shafer"] + + # 2. synchronization settings + match_threshold_sec: 0.01 # 10ms + timeout_sec: 0.1 # 100ms + input_offset_sec: [0.0, 0.0] # no offset + + # 3. settings for fused fusion map + # remember resolution and map size should be same with input maps + map_frame_: "map" + base_link_frame_: "base_link" + grid_map_origin_frame_: "base_link" + fusion_map_length_x: 100.0 + fusion_map_length_y: 100.0 + fusion_map_resolution: 0.5 diff --git a/perception/probabilistic_occupancy_grid_map/image/synchronized_grid_map_fusion.drawio.svg b/perception/probabilistic_occupancy_grid_map/image/synchronized_grid_map_fusion.drawio.svg new file mode 100644 index 0000000000000..6bf5ed98e4edf --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/image/synchronized_grid_map_fusion.drawio.svg @@ -0,0 +1,290 @@ + + + + + + + + + + +
+
+
+ OGM1 +
+
+
+
+ OGM1 +
+
+ + + + + + +
+
+
+ OGM2 +
+
+
+
+ OGM2 +
+
+ + + + + + +
+
+
+ OGM3 +
+
+
+
+ OGM3 +
+
+ + + + + + +
+
+
+ Fused +
+ OGM +
+
+
+
+ Fused... +
+
+ + + + + + +
+
+
+ Fused +
+ OGM +
+ (Single Frame) +
+
+
+
+ Fused... +
+
+ + + + + + +
+
+
+ + Single Frame +
+ Fusion +
+
+
+
+
+ Single Frame... +
+
+ + + + + + +
+
+
+ + Multi Frame +
+ Fusion +
+
+
+
+
+ Multi Frame... +
+
+ + + + + + +
+
+
+ Fused +
+ OGM +
+
+
+
+ Fused... +
+
+ + + + +
+
+
`t=t_n`
+
+
+
+ `t=t_n` +
+
+ + + + +
+
+
`t=t_{n-1}`
+
+
+
+ `t=t_{n-1}` +
+
+ + + + +
+
+
`t=t_n`
+
+
+
+ `t=t_n` +
+
+ + + + +
+
+
+ Publish +
+
+
+
+ Publish +
+
+ + + + +
+
+
+ input topics +
+
+
+
+ input topics +
+
+ + + + +
+
+
+ output topics +
+
+
+
+ output topics +
+
+ + + + +
+
+
+ grid_map_fusion::GridMapFusionNode +
+
+
+
+ grid_map_fusion::GridMapFusionNode +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/perception/probabilistic_occupancy_grid_map/include/cost_value.hpp b/perception/probabilistic_occupancy_grid_map/include/cost_value.hpp index e9667ccf65577..e0f18cedcdff1 100644 --- a/perception/probabilistic_occupancy_grid_map/include/cost_value.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/cost_value.hpp @@ -59,19 +59,48 @@ static const unsigned char NO_INFORMATION = 128; // 0.5 * 255 static const unsigned char LETHAL_OBSTACLE = 255; static const unsigned char FREE_SPACE = 0; +static const unsigned char OCCUPIED_THRESHOLD = 180; +static const unsigned char FREE_THRESHOLD = 50; + struct CostTranslationTable { CostTranslationTable() { for (int i = 0; i < 256; i++) { - const auto value = static_cast(static_cast(i) * 100.f / 255.f); - data[i] = std::max(std::min(value, static_cast(99)), static_cast(1)); + const auto value = + static_cast(static_cast(i) * 100.f / 255.f); // 0-255 to 0-100 + data[i] = + std::max(std::min(value, static_cast(99)), static_cast(1)); // 0-100 to 1-99 } } char operator[](unsigned char n) const { return data[n]; } char data[256]; }; +struct InverseCostTranslationTable +{ + InverseCostTranslationTable() + { + // 0-100 to 0-255 + for (int i = 0; i < 100; i++) { + data[i] = static_cast(i * 255 / 99); + } + } + unsigned char operator[](char n) const + { + if (n > 99) { + return data[99]; + } else if (n < 1) { + return data[1]; + } else { + const unsigned char u_n = static_cast(n); + return data[u_n]; + } + } + unsigned char data[100]; +}; + static const CostTranslationTable cost_translation_table; +static const InverseCostTranslationTable inverse_cost_translation_table; } // namespace occupancy_cost_value #endif // COST_VALUE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/fusion/single_frame_fusion_policy.hpp b/perception/probabilistic_occupancy_grid_map/include/fusion/single_frame_fusion_policy.hpp new file mode 100644 index 0000000000000..13829b4910d96 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/include/fusion/single_frame_fusion_policy.hpp @@ -0,0 +1,66 @@ +// 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 FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_ +#define FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_ + +#include "cost_value.hpp" + +#include +#include +#include +#include + +/*min and max prob threshold to prevent log-odds to diverge*/ +#define EPSILON_PROB 0.03 + +namespace fusion_policy +{ +enum class FusionMethod { OVERWRITE, LOG_ODDS, DEMPSTER_SHAFER }; + +unsigned char convertProbabilityToChar(const double & probability); +double convertCharToProbability(const unsigned char & occupancy); +std::vector convertProbabilityToChar(const std::vector & probabilities); +std::vector convertCharToProbability(const std::vector & occupancies); + +namespace overwrite_fusion +{ +enum State : unsigned char { UNKNOWN = 0U, FREE = 1U, OCCUPIED = 2U }; +State getApproximateState(const unsigned char & occupancy); +unsigned char overwriteFusion(const std::vector & occupancies); +} // namespace overwrite_fusion + +namespace log_odds_fusion +{ +double logOddsFusion(const std::vector & probabilities); +double logOddsFusion( + const std::vector & probabilities, const std::vector & weights); +} // namespace log_odds_fusion + +namespace dempster_shafer_fusion +{ +struct dempsterShaferOccupancy; +double dempsterShaferFusion(const std::vector & probability); +double dempsterShaferFusion( + const std::vector & probability, const std::vector & reliability); +} // namespace dempster_shafer_fusion + +unsigned char singleFrameOccupancyFusion( + const std::vector & occupancy, FusionMethod method); +unsigned char singleFrameOccupancyFusion( + const std::vector & occupancy, FusionMethod method, + const std::vector & reliability); +} // namespace fusion_policy + +#endif // FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/fusion/synchronized_grid_map_fusion_node.hpp b/perception/probabilistic_occupancy_grid_map/include/fusion/synchronized_grid_map_fusion_node.hpp new file mode 100644 index 0000000000000..6bea5b2a16f72 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/include/fusion/synchronized_grid_map_fusion_node.hpp @@ -0,0 +1,127 @@ +// 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 FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_ +#define FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_ + +#include "fusion/single_frame_fusion_policy.hpp" +#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp" +#include "updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp" +#include "updater/occupancy_grid_map_updater_interface.hpp" + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace synchronized_grid_map_fusion +{ + +using costmap_2d::OccupancyGridMapFixedBlindSpot; +using costmap_2d::OccupancyGridMapLOBFUpdater; +using costmap_2d::OccupancyGridMapUpdaterInterface; +using geometry_msgs::msg::Pose; + +class GridMapFusionNode : public rclcpp::Node +{ +public: + explicit GridMapFusionNode(const rclcpp::NodeOptions & node_options); + +private: + void onGridMap( + const nav_msgs::msg::OccupancyGrid::ConstSharedPtr & occupancy_grid_msg, + const std::string & input_topic); + nav_msgs::msg::OccupancyGrid::UniquePtr OccupancyGridMapToMsgPtr( + 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(); + +private: + // Publisher and Subscribers + rclcpp::Publisher::SharedPtr fused_map_pub_; + rclcpp::Publisher::SharedPtr single_frame_pub_; + std::vector::SharedPtr> grid_map_subs_; + std::unique_ptr> stop_watch_ptr_{}; + std::unique_ptr debug_publisher_ptr_{}; + + // Topics manager + std::size_t num_input_topics_{1}; + std::vector input_topics_; + std::vector input_offset_sec_; + std::vector input_topic_weights_; + std::map input_topic_weights_map_; + + // TF + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + + // Timer to manage the timeout of the occupancy grid map + rclcpp::TimerBase::SharedPtr timer_; + double timeout_sec_{}; + double match_threshold_sec_{}; + + // cache for fusion + std::mutex mutex_; + std::shared_ptr + occupancy_grid_map_updater_ptr_; // contains fused grid map + std::map + gridmap_dict_; // temporary cache for grid map message + std::map + gridmap_dict_tmp_; // second cache for grid map message + std::map offset_map_; // time offset for each grid map + + // grid map parameters + std::string map_frame_; + std::string base_link_frame_; + std::string gridmap_origin_frame_; + float fusion_map_length_x_; + float fusion_map_length_y_; + float fusion_map_resolution_; + fusion_policy::FusionMethod fusion_method_; +}; + +} // namespace synchronized_grid_map_fusion + +#endif // FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp b/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp new file mode 100644 index 0000000000000..306f8988acab7 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp @@ -0,0 +1,48 @@ +// 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 UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_ +#define UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_ + +#include "fusion/single_frame_fusion_policy.hpp" +#include "updater/occupancy_grid_map_updater_interface.hpp" +#include "utils/utils.hpp" + +#include +#include + +// LOBF means: Log Odds Bayes Filter + +namespace costmap_2d +{ +class OccupancyGridMapLOBFUpdater : public OccupancyGridMapUpdaterInterface +{ +public: + enum Index : size_t { OCCUPIED = 0U, FREE = 1U }; + OccupancyGridMapLOBFUpdater( + const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) + : OccupancyGridMapUpdaterInterface(cells_size_x, cells_size_y, resolution) + { + } + bool update(const Costmap2D & single_frame_occupancy_grid_map) override; + void initRosParam(rclcpp::Node & node) override; + +private: + inline unsigned char applyLOBF(const unsigned char & z, const unsigned char & o); + Eigen::Matrix2f probability_matrix_; +}; + +} // namespace costmap_2d + +#endif // UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp b/perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp index 047b747c2861f..46bd14b843dae 100644 --- a/perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp @@ -15,6 +15,8 @@ #ifndef UTILS__UTILS_HPP_ #define UTILS__UTILS_HPP_ +#include "cost_value.hpp" + #include #include #include @@ -114,6 +116,7 @@ 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 #endif // UTILS__UTILS_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/launch/synchronized_occupancy_grid_map_fusion.launch.xml b/perception/probabilistic_occupancy_grid_map/launch/synchronized_occupancy_grid_map_fusion.launch.xml new file mode 100644 index 0000000000000..c2391141e9fa0 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/launch/synchronized_occupancy_grid_map_fusion.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/perception/probabilistic_occupancy_grid_map/src/fusion/single_frame_fusion_policy.cpp b/perception/probabilistic_occupancy_grid_map/src/fusion/single_frame_fusion_policy.cpp new file mode 100644 index 0000000000000..75e8791a04bca --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/src/fusion/single_frame_fusion_policy.cpp @@ -0,0 +1,322 @@ +// 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 "fusion/single_frame_fusion_policy.hpp" + +namespace fusion_policy +{ + +//// utils //// + +// convert [0, 1] to [0, 255] +unsigned char convertProbabilityToChar(const double & probability) +{ + return static_cast(probability * 255); +} +// convert [0, 255] to [0, 1] +double convertCharToProbability(const unsigned char & occupancy) +{ + return static_cast(occupancy) / 255.0; +} + +// convert [0, 1] to [0, 255] vectors +std::vector convertProbabilityToChar(const std::vector & probabilities) +{ + std::vector occupancies; + for (auto & probability : probabilities) { + occupancies.push_back(convertProbabilityToChar(probability)); + } + return occupancies; +} +// convert [0, 255] to [0, 1] vectors +std::vector convertCharToProbability(const std::vector & occupancies) +{ + std::vector probabilities; + for (auto & occupancy : occupancies) { + probabilities.push_back(convertCharToProbability(occupancy)); + } + return probabilities; +} + +/// @brief fusion with overwrite policy +namespace overwrite_fusion +{ + +/** + * @brief convert char value to occupancy state + * + * @param occupancy [0, 255] + * @return State + */ +State getApproximateState(const unsigned char & occupancy) +{ + if (occupancy >= occupancy_cost_value::OCCUPIED_THRESHOLD) { + return State::OCCUPIED; + } else if (occupancy <= occupancy_cost_value::FREE_THRESHOLD) { + return State::FREE; + } else { + return State::UNKNOWN; + } +} + +/** + * @brief override fusion + * + * @param occupancies : occupancies to be fused + * @return unsigned char + */ +unsigned char overwriteFusion(const std::vector & occupancies) +{ + if (occupancies.size() == 0) { + throw std::runtime_error("occupancies size is 0"); + } else if (occupancies.size() == 1) { + return occupancies[0]; + } + + auto fusion_occupancy = 128; // unknown + auto fusion_state = getApproximateState(fusion_occupancy); + for (auto & cell : occupancies) { + auto state = getApproximateState(cell); + if (state > fusion_state) { + fusion_state = state; + fusion_occupancy = cell; + } else if (state < fusion_state) { + continue; + } else { + fusion_occupancy = (fusion_occupancy / 2 + cell / 2); + } + } + return fusion_occupancy; +} +} // namespace overwrite_fusion + +/// @brief fusion with log-odds policy +namespace log_odds_fusion +{ +/** + * @brief log-odds fusion + * + * @param probabilities : probabilities of occupancy [0, 1] + * @return double + */ +double logOddsFusion(const std::vector & probabilities) +{ + double log_odds = 0.0; + for (auto & probability : probabilities) { + const double p = std::max(EPSILON_PROB, std::min(1.0 - EPSILON_PROB, probability)); + log_odds += std::log(p / (1.0 - p)); + } + return 1.0 / (1.0 + std::exp(-log_odds)); +} + +/** + * @brief weighted log-odds fusion + * + * @param probabilities : probabilities of occupancy [0, 1] + * @param weights : weights of probabilities + * @return double + */ +double logOddsFusion(const std::vector & probabilities, const std::vector & weights) +{ + // check if the size of probabilities and weights are the same + if (probabilities.size() != weights.size()) { + // warning and return normal log-odds fusion + std::cout + << "The size of probabilities and weights are not the same. Return normal log-odds fusion." + << std::endl; + return logOddsFusion(probabilities); + } + + double log_odds = 0.0; + for (size_t i = 0; i < probabilities.size(); i++) { + const double p = std::max(EPSILON_PROB, std::min(1.0 - EPSILON_PROB, probabilities[i])); + log_odds += weights[i] * std::log(p / (1.0 - p)); + } + return 1.0 / (1.0 + std::exp(-log_odds)); +} +} // namespace log_odds_fusion + +/// @brief fusion with Dempster-Shafer Theory +namespace dempster_shafer_fusion +{ +/** + * @brief conflict modified Dempster-Shafer Theory Data structure + * see https://www.diva-portal.org/smash/get/diva2:852457/FULLTEXT01.pdf + * + */ +struct dempsterShaferOccupancy +{ + double occupied; + double empty; + double unknown; + double conflict_threshold = 0.9; + + // initialize without args + dempsterShaferOccupancy() + { + occupied = 0.0; + empty = 0.0; + unknown = 1.0; + } + + // initialize with probability + dempsterShaferOccupancy(double occupied_probability) + { + // confine to [0, 1] + double p = std::max(0.0, std::min(1.0, occupied_probability)); + occupied = p; + empty = 1.0 - p; + unknown = 0.0; + } + + // initialize with probability and reliability + dempsterShaferOccupancy(double occupied_probability, double reliability) + { + // confine to [0, 1] + double p = std::max(0.0, std::min(1.0, occupied_probability)); + occupied = p * reliability; + empty = (1.0 - p) * reliability; + unknown = 1.0 - occupied - empty; + } + + // normalize + void normalize() + { + double sum = occupied + empty + unknown; + occupied /= sum; + empty /= sum; + unknown /= sum; + } + + // calc conflict factor K + double calcK(const dempsterShaferOccupancy & other) + { + return (occupied * other.empty + empty * other.occupied); + } + // calc sum of occupied probability mass + double calcOccupied(const dempsterShaferOccupancy & other) + { + return occupied * other.occupied + occupied * other.unknown + unknown * other.occupied; + } + // calc sum of empty probability mass + double calcEmpty(const dempsterShaferOccupancy & other) + { + return empty * other.empty + empty * other.unknown + unknown * other.empty; + } + + // Dempster-Shafer fusion + dempsterShaferOccupancy operator+(const dempsterShaferOccupancy & other) + { + dempsterShaferOccupancy result; + double K = calcK(other); + double O = calcOccupied(other); + double E = calcEmpty(other); + + if (K > conflict_threshold) { + // highly conflict + result.occupied = O; + result.empty = E; + result.unknown = 1 - O - E; + } else { + // low conflict + result.occupied = O / (1.0 - K); + result.empty = E / (1.0 - K); + result.unknown = 1 - result.occupied - result.empty; + } + return result; + } + + // get occupancy probability via Pignistic Probability + double getPignisticProbability() { return occupied + unknown / 2.0; } +}; + +/** + * @brief Dempster-Shafer fusion + * + * @param probability + * @return double + */ +double dempsterShaferFusion(const std::vector & probability) +{ + dempsterShaferOccupancy result; // init with unknown + for (auto & p : probability) { + result = result + dempsterShaferOccupancy(p); + } + return result.getPignisticProbability(); +} + +/** + * @brief Dempster-Shafer fusion with reliability + * + * @param probability + * @param reliability + * @return double + */ +double dempsterShaferFusion( + const std::vector & probability, const std::vector & reliability) +{ + // check if the size of probabilities and weights are the same + if (probability.size() != reliability.size()) { + // warning and return normal dempster-shafer fusion probability + std::cout << "The size of probabilities and reliability are not the same. Return normal " + "dempster-shafer fusion." + << std::endl; + return dempsterShaferFusion(probability); + } + + dempsterShaferOccupancy result; // init with unknown + for (size_t i = 0; i < probability.size(); i++) { + result = result + dempsterShaferOccupancy(probability[i], reliability[i]); + } + return result.getPignisticProbability(); +} +} // namespace dempster_shafer_fusion + +unsigned char singleFrameOccupancyFusion( + const std::vector & occupancy, FusionMethod method) +{ + if (method == FusionMethod::OVERWRITE) { + return overwrite_fusion::overwriteFusion(occupancy); + } else if (method == FusionMethod::LOG_ODDS) { + auto probability = convertCharToProbability(occupancy); + return convertProbabilityToChar(log_odds_fusion::logOddsFusion(probability)); + } else if (method == FusionMethod::DEMPSTER_SHAFER) { + auto probability = convertCharToProbability(occupancy); + return convertProbabilityToChar(dempster_shafer_fusion::dempsterShaferFusion(probability)); + } else { + std::cout << "Unknown fusion method: " << std::endl; + return 128; + } +} + +unsigned char singleFrameOccupancyFusion( + const std::vector & occupancy, FusionMethod method, + const std::vector & reliability) +{ + if (method == FusionMethod::OVERWRITE) { + return overwrite_fusion::overwriteFusion(occupancy); + } else if (method == FusionMethod::LOG_ODDS) { + auto probability = convertCharToProbability(occupancy); + return convertProbabilityToChar(log_odds_fusion::logOddsFusion(probability, reliability)); + } else if (method == FusionMethod::DEMPSTER_SHAFER) { + auto probability = convertCharToProbability(occupancy); + return convertProbabilityToChar( + dempster_shafer_fusion::dempsterShaferFusion(probability, reliability)); + } else { + std::cout << "Unknown fusion method: " << std::endl; + return 128; + } +} + +} // namespace fusion_policy diff --git a/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp b/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp new file mode 100644 index 0000000000000..6738286ae5592 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp @@ -0,0 +1,458 @@ +// 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 "fusion/synchronized_grid_map_fusion_node.hpp" + +#include "cost_value.hpp" +#include "utils/utils.hpp" + +namespace synchronized_grid_map_fusion +{ +using costmap_2d::OccupancyGridMapFixedBlindSpot; +using costmap_2d::OccupancyGridMapLOBFUpdater; +using geometry_msgs::msg::Pose; +using nav_msgs::msg::OccupancyGrid; + +GridMapFusionNode::GridMapFusionNode(const rclcpp::NodeOptions & node_options) +: Node("synchronized_occupancy_grid_map_fusion", node_options), + tf_buffer_(this->get_clock()), + tf_listener_(tf_buffer_) +{ + /* load input parameters */ + { + // get input topics + declare_parameter("fusion_input_ogm_topics", std::vector{}); + input_topics_ = get_parameter("fusion_input_ogm_topics").as_string_array(); + if (input_topics_.empty()) { + throw std::runtime_error("The number of input topics must larger than 0."); + } + num_input_topics_ = input_topics_.size(); + if (num_input_topics_ < 1) { + RCLCPP_WARN( + this->get_logger(), "minimum num_input_topics_ is 1. current num_input_topics_ is %zu", + num_input_topics_); + num_input_topics_ = 1; + } + if (num_input_topics_ > 12) { + RCLCPP_WARN( + this->get_logger(), "maximum num_input_topics_ is 12. current num_input_topics_ is %zu", + num_input_topics_); + num_input_topics_ = 12; + } + // get input topic reliabilities + declare_parameter("input_ogm_reliabilities", std::vector{}); + input_topic_weights_ = get_parameter("input_ogm_reliabilities").as_double_array(); + + if (input_topic_weights_.empty()) { // no topic weight is set + // set equal weight + for (std::size_t topic_i = 0; topic_i < num_input_topics_; ++topic_i) { + input_topic_weights_map_[input_topics_.at(topic_i)] = 1.0 / num_input_topics_; + } + } else if (num_input_topics_ == input_topic_weights_.size()) { + // set weight to map + for (std::size_t topic_i = 0; topic_i < num_input_topics_; ++topic_i) { + input_topic_weights_map_[input_topics_.at(topic_i)] = input_topic_weights_.at(topic_i); + } + } else { + throw std::runtime_error("The number of weights does not match the number of topics."); + } + } + + // Set fusion timing parameters + match_threshold_sec_ = declare_parameter("match_threshold_sec", 0.01); + timeout_sec_ = declare_parameter("timeout_sec", 0.1); + input_offset_sec_ = declare_parameter("input_offset_sec", std::vector{}); + if (!input_offset_sec_.empty() && num_input_topics_ != input_offset_sec_.size()) { + throw std::runtime_error("The number of offsets does not match the number of topics."); + } else if (input_offset_sec_.empty()) { + // if there are not input offset, set 0.0 + for (std::size_t topic_i = 0; topic_i < num_input_topics_; ++topic_i) { + input_offset_sec_.push_back(0.0); + } + } + // Set fusion map parameters + map_frame_ = declare_parameter("map_frame_", "map"); + base_link_frame_ = declare_parameter("base_link_frame_", "base_link"); + gridmap_origin_frame_ = declare_parameter("grid_map_origin_frame_", "base_link"); + fusion_map_length_x_ = declare_parameter("fusion_map_length_x", 100.0); + fusion_map_length_y_ = declare_parameter("fusion_map_length_y", 100.0); + fusion_map_resolution_ = declare_parameter("fusion_map_resolution", 0.5); + + // set fusion method + std::string fusion_method_str = declare_parameter("fusion_method", "overwrite"); + if (fusion_method_str == "overwrite") { + fusion_method_ = fusion_policy::FusionMethod::OVERWRITE; + } else if (fusion_method_str == "log-odds") { + fusion_method_ = fusion_policy::FusionMethod::LOG_ODDS; + } else if (fusion_method_str == "dempster-shafer") { + fusion_method_ = fusion_policy::FusionMethod::DEMPSTER_SHAFER; + } else { + throw std::runtime_error("The fusion method is not supported."); + } + + // sub grid_map + grid_map_subs_.resize(num_input_topics_); + for (std::size_t topic_i = 0; topic_i < num_input_topics_; ++topic_i) { + std::function fnc = std::bind( + &GridMapFusionNode::onGridMap, this, std::placeholders::_1, input_topics_.at(topic_i)); + grid_map_subs_.at(topic_i) = this->create_subscription( + input_topics_.at(topic_i), rclcpp::QoS{1}.best_effort(), fnc); + } + + // pub grid_map + fused_map_pub_ = this->create_publisher( + "~/output/occupancy_grid_map", rclcpp::QoS{1}.reliable()); + single_frame_pub_ = this->create_publisher( + "~/debug/single_frame_map", rclcpp::QoS{1}.reliable()); + + // updater + occupancy_grid_map_updater_ptr_ = std::make_shared( + fusion_map_length_x_ / fusion_map_resolution_, fusion_map_length_y_ / fusion_map_resolution_, + fusion_map_resolution_); + + // Set timer + const auto period_ns = std::chrono::duration_cast( + std::chrono::duration(timeout_sec_)); + timer_ = rclcpp::create_timer( + this, get_clock(), period_ns, std::bind(&GridMapFusionNode::timer_callback, this)); + + // set offset map + for (size_t i = 0; i < input_offset_sec_.size(); ++i) { + offset_map_[input_topics_[i]] = input_offset_sec_[i]; + } + + // init dict + for (size_t i = 0; i < input_topics_.size(); ++i) { + gridmap_dict_[input_topics_[i]] = nullptr; + gridmap_dict_tmp_[input_topics_[i]] = nullptr; + } + + // debug tools + { + using tier4_autoware_utils::DebugPublisher; + using tier4_autoware_utils::StopWatch; + stop_watch_ptr_ = std::make_unique>(); + debug_publisher_ptr_ = std::make_unique(this, "synchronized_grid_map_fusion"); + stop_watch_ptr_->tic("cyclic_time"); + stop_watch_ptr_->tic("processing_time"); + } +} + +/** + * @brief Set the period of the timer + * + * @param new_period + */ +void GridMapFusionNode::setPeriod(const int64_t new_period) +{ + if (!timer_) { + return; + } + int64_t old_period = 0; + rcl_ret_t ret = rcl_timer_get_period(timer_->get_timer_handle().get(), &old_period); + if (ret != RCL_RET_OK) { + rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't get old period"); + } + ret = rcl_timer_exchange_period(timer_->get_timer_handle().get(), new_period, &old_period); + if (ret != RCL_RET_OK) { + rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't exchange_period"); + } +} + +/** + * @brief Callback function for the grid map message add data to buffer + * + * @param occupancy_grid_msg + * @param topic_name + */ +void GridMapFusionNode::onGridMap( + const nav_msgs::msg::OccupancyGrid::ConstSharedPtr & occupancy_grid_msg, + const std::string & topic_name) +{ + 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( + std::begin(gridmap_dict_tmp_), std::end(gridmap_dict_tmp_), + [](const auto & e) { return e.second != nullptr; }); + + // already subscribed + if (is_already_subscribed_this) { + gridmap_dict_tmp_[topic_name] = occupancy_grid_msg; + + if (!is_already_subscribed_tmp) { + auto period = std::chrono::duration_cast( + std::chrono::duration(timeout_sec_)); + try { + setPeriod(period.count()); + } catch (rclcpp::exceptions::RCLError & ex) { + RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what()); + } + timer_->reset(); + } + // first time to subscribe in this period + } else { + gridmap_dict_[topic_name] = occupancy_grid_msg; // add to buffer + + // check if all topics are subscribed + bool is_subscribed_all = std::all_of( + std::begin(gridmap_dict_), std::end(gridmap_dict_), + [](const auto & e) { return e.second != nullptr; }); + // Then, go to publish + if (is_subscribed_all) { + for (const auto & e : gridmap_dict_tmp_) { + if (e.second != nullptr) { + gridmap_dict_[e.first] = e.second; + } + } + std::for_each(std::begin(gridmap_dict_tmp_), std::end(gridmap_dict_tmp_), [](auto & e) { + e.second = nullptr; + }); + + timer_->cancel(); + publish(); + // if not all topics are subscribed, set timer + } else if (offset_map_.size() > 0) { + timer_->cancel(); + auto period = std::chrono::duration_cast( + std::chrono::duration(timeout_sec_ - offset_map_[topic_name])); + try { + setPeriod(period.count()); + } catch (rclcpp::exceptions::RCLError & ex) { + RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what()); + } + timer_->reset(); + } + } +} + +/** + * @brief Timer callback function + * + */ +void GridMapFusionNode::timer_callback() +{ + using std::chrono_literals::operator""ms; + timer_->cancel(); + if (mutex_.try_lock()) { + publish(); + mutex_.unlock(); + } else { + try { + std::chrono::nanoseconds period = 10ms; + setPeriod(period.count()); + } catch (rclcpp::exceptions::RCLError & ex) { + RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what()); + } + timer_->reset(); + } +} + +/** + * @brief Publisher function + * + */ +void GridMapFusionNode::publish() +{ + stop_watch_ptr_->toc("processing_time", true); + builtin_interfaces::msg::Time latest_stamp = get_clock()->now(); + double height = 0.0; + + // 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; + } + } + + // return if empty + if (subscribed_maps.empty()) { + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 5000, + "No grid map is subscribed. Please check the topic name and the topic type."); + return; + } + + // fusion map + // single frame gridmap fusion + auto fused_map = SingleFrameOccupancyFusion(subscribed_maps, latest_stamp, weights); + // multi frame gridmap fusion + occupancy_grid_map_updater_ptr_->update(fused_map); + + // publish + fused_map_pub_->publish( + OccupancyGridMapToMsgPtr(map_frame_, latest_stamp, height, *occupancy_grid_map_updater_ptr_)); + single_frame_pub_->publish(OccupancyGridMapToMsgPtr(map_frame_, latest_stamp, height, fused_map)); + + // copy 2nd temp to temp buffer + gridmap_dict_ = gridmap_dict_tmp_; + std::for_each(std::begin(gridmap_dict_tmp_), std::end(gridmap_dict_tmp_), [](auto & e) { + e.second = nullptr; + }); + + // add processing time for debug + if (debug_publisher_ptr_ && stop_watch_ptr_) { + const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); + const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); + debug_publisher_ptr_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + debug_publisher_ptr_->publish( + "debug/processing_time_ms", processing_time_ms); + } +} + +OccupancyGridMapFixedBlindSpot GridMapFusionNode::SingleFrameOccupancyFusion( + std::vector & occupancy_grid_maps, + const builtin_interfaces::msg::Time latest_stamp, const std::vector & weights) +{ + // if only single map + if (occupancy_grid_maps.size() == 1) { + return occupancy_grid_maps[0]; + } + + // get map to gridmap_origin_frame_ transform + Pose gridmap_origin{}; + try { + gridmap_origin = utils::getPose(latest_stamp, tf_buffer_, gridmap_origin_frame_, map_frame_); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_STREAM(get_logger(), ex.what()); + 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()); + } + + // 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 max cost to fused map + fused_map.setCost(x, y, fused_cost); + } + } + + 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, occupancy_cost_value::inverse_cost_translation_table[occupancy_grid_map.data[index]]); + } + } + + return costmap2d; +} + +OccupancyGridMapFixedBlindSpot GridMapFusionNode::OccupancyGridMsgToGridMap( + const nav_msgs::msg::OccupancyGrid & occupancy_grid_map) +{ + OccupancyGridMapFixedBlindSpot gridmap( + occupancy_grid_map.info.width, occupancy_grid_map.info.height, + occupancy_grid_map.info.resolution); + gridmap.updateOrigin( + occupancy_grid_map.info.origin.position.x, occupancy_grid_map.info.origin.position.y); + + 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; + gridmap.setCost( + i, j, occupancy_cost_value::inverse_cost_translation_table[occupancy_grid_map.data[index]]); + } + } + return gridmap; +} + +nav_msgs::msg::OccupancyGrid::UniquePtr GridMapFusionNode::OccupancyGridMapToMsgPtr( + const std::string & frame_id, const builtin_interfaces::msg::Time & stamp, + const float & robot_pose_z, const nav2_costmap_2d::Costmap2D & occupancy_grid_map) +{ + auto msg_ptr = std::make_unique(); + + msg_ptr->header.frame_id = frame_id; + msg_ptr->header.stamp = stamp; + msg_ptr->info.resolution = occupancy_grid_map.getResolution(); + + msg_ptr->info.width = occupancy_grid_map.getSizeInCellsX(); + msg_ptr->info.height = occupancy_grid_map.getSizeInCellsY(); + + double wx{}; + double wy{}; + occupancy_grid_map.mapToWorld(0, 0, wx, wy); + msg_ptr->info.origin.position.x = occupancy_grid_map.getOriginX(); + msg_ptr->info.origin.position.y = occupancy_grid_map.getOriginY(); + msg_ptr->info.origin.position.z = robot_pose_z; + msg_ptr->info.origin.orientation.w = 1.0; + + msg_ptr->data.resize(msg_ptr->info.width * msg_ptr->info.height); + + unsigned char * data = occupancy_grid_map.getCharMap(); + for (unsigned int i = 0; i < msg_ptr->data.size(); ++i) { + msg_ptr->data[i] = occupancy_cost_value::cost_translation_table[data[i]]; + } + return msg_ptr; +} + +} // namespace synchronized_grid_map_fusion + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(synchronized_grid_map_fusion::GridMapFusionNode) diff --git a/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_log_odds_bayes_filter_updater.cpp b/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_log_odds_bayes_filter_updater.cpp new file mode 100644 index 0000000000000..e45f3d0686fbc --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_log_odds_bayes_filter_updater.cpp @@ -0,0 +1,69 @@ +// 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 "updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp" + +#include "cost_value.hpp" + +#include + +namespace costmap_2d +{ + +void OccupancyGridMapLOBFUpdater::initRosParam(rclcpp::Node & /*node*/) +{ + // nothing to load +} + +inline unsigned char OccupancyGridMapLOBFUpdater::applyLOBF( + const unsigned char & z, const unsigned char & o) +{ + using fusion_policy::convertCharToProbability; + using fusion_policy::convertProbabilityToChar; + using fusion_policy::log_odds_fusion::logOddsFusion; + + constexpr unsigned char unknown = occupancy_cost_value::NO_INFORMATION; + constexpr unsigned char unknown_margin = 1; + /* Tau and ST decides how fast the observation decay to the unknown status*/ + constexpr double tau = 0.75; + constexpr double sample_time = 0.1; + + // if the observation is unknown, decay the estimation + if (z >= unknown - unknown_margin && z <= unknown + unknown_margin) { + char diff = static_cast(o) - static_cast(unknown); + const double decay = std::exp(-sample_time / tau); + const double fused = static_cast(unknown) + static_cast(diff) * decay; + return static_cast(fused); + } else { + // else, do the log-odds fusion + const std::vector probability = { + convertCharToProbability(z), convertCharToProbability(o)}; + const unsigned char fused = convertProbabilityToChar(logOddsFusion(probability)); + return fused; + } +} + +bool OccupancyGridMapLOBFUpdater::update(const Costmap2D & single_frame_occupancy_grid_map) +{ + updateOrigin( + single_frame_occupancy_grid_map.getOriginX(), single_frame_occupancy_grid_map.getOriginY()); + for (unsigned int x = 0; x < getSizeInCellsX(); x++) { + for (unsigned int y = 0; y < getSizeInCellsY(); y++) { + unsigned int index = getIndex(x, y); + costmap_[index] = applyLOBF(single_frame_occupancy_grid_map.getCost(x, y), costmap_[index]); + } + } + return true; +} +} // namespace costmap_2d diff --git a/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp b/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp index 0060754cd875c..b876004d89b0a 100644 --- a/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp @@ -182,4 +182,20 @@ 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 >= occupancy_cost_value::OCCUPIED_THRESHOLD) { + return occupancy_cost_value::LETHAL_OBSTACLE; + } else if (value <= occupancy_cost_value::FREE_THRESHOLD) { + return occupancy_cost_value::FREE_SPACE; + } else { + return occupancy_cost_value::NO_INFORMATION; + } +} + } // namespace utils diff --git a/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md b/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md new file mode 100644 index 0000000000000..e1046fa24719d --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md @@ -0,0 +1,168 @@ +# synchronized OGM fusion + +> For simplicity, we use OGM as the meaning of the occupancy grid map. + +This package is used to fuse the OGMs from synchronized sensors. Especially for the lidar. + +Here shows the example OGM for the this synchronized OGM fusion. + +| left lidar OGM | right lidar OGM | top lidar OGM | +| --------------------------------- | ----------------------------------- | ------------------------------- | +| ![left](image/left_lidar_ogm.png) | ![right](image/right_lidar_ogm.png) | ![top](image/top_lidar_ogm.png) | + +OGM fusion with asynchronous sensor outputs is not suitable for this package. Asynchronous OGM fusion is under construction. + +## Processing flow + +The processing flow of this package is shown in the following figure. + +![data_flow](image/synchronized_grid_map_fusion.drawio.svg) + +- Single Frame Fusion + - Single frame fusion means that the OGMs from synchronized sensors are fused in a certain time frame $t=t_n$. +- Multi Frame Fusion + - In the multi frame fusion process, current fused single frame OGM in $t_n$ is fused with the previous fused single frame OGM in $t_{n-1}$. + +## I/O + +| Input topic name | Type | Description | +| ------------------ | ------------------------------------ | --------------------------------------------------------------------------------- | +| `input_ogm_topics` | list of nav_msgs::msg::OccupancyGrid | List of input topics for Occupancy Grid Maps. This parameter is given in list, so | + +| Output topic name | Type | Description | +| ----------------------------- | ---------------------------- | ----------------------------------------------------------------------------- | +| `~/output/occupancy_grid_map` | nav_msgs::msg::OccupancyGrid | Output topic name of the fused Occupancy Grid Map. | +| `~/debug/single_frame_map` | nav_msgs::msg::OccupancyGrid | (debug topic) Output topic name of the single frame fused Occupancy Grid Map. | + +## Parameters + +Synchronized OGM fusion node parameters are shown in the following table. Main parameters to be considered in the fusion node is shown as bold. + +| Ros param name | Sample value | Description | +| --------------------------- | -------------------- | ------------------------------------------------------------- | +| **input_ogm_topics** | ["topic1", "topic2"] | List of input topics for Occupancy Grid Maps | +| **input_ogm_reliabilities** | [0.8, 0.2] | Weights for the reliability of each input topic | +| **fusion_method** | "overwrite" | Method of fusion ("overwrite", "log-odds", "dempster-shafer") | +| match_threshold_sec | 0.01 | Matching threshold in milliseconds | +| timeout_sec | 0.1 | Timeout duration in seconds | +| input_offset_sec | [0.0, 0.0] | Offset time in seconds for each input topic | +| map*frame* | "map" | Frame name for the fused map | +| base*link_frame* | "base_link" | Frame name for the base link | +| grid*map_origin_frame* | "base_link" | Frame name for the origin of the grid map | +| fusion_map_length_x | 100.0 | Length of the fused map along the X-axis | +| fusion_map_length_y | 100.0 | Length of the fused map along the Y-axis | +| fusion_map_resolution | 0.5 | Resolution of the fused map | + +Since this node assumes that the OGMs from synchronized sensors are generated in the same time, we need to tune the `match_threshold_sec`, `timeout_sec` and `input_offset_sec` parameters to successfully fuse the OGMs. + +## Fusion methods + +For the single frame fusion, the following fusion methods are supported. + +| Fusion Method in parameter | Description | +| -------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `overwrite` | The value of the cell in the fused OGM is overwritten by the value of the cell in the OGM with the highest priority.
We set priority as `Occupied` > `Free` > `Unknown`. | +| `log-odds` | The value of the cell in the fused OGM is calculated by the log-odds ratio method, which is known as a Bayesian fusion method.
The log-odds of a probability $p$ can be written as $l_p = \log(\frac{p}{1-p})$.
And the fused log-odds is calculated by the sum of log-odds. $l_f = \Sigma l_p$ | +| `dempster-shafer` | The value of the cell in the fused OGM is calculated by the Dempster-Shafer theory[1]. This is also popular method to handle multiple evidences. This package applied conflict escape logic in [2] for the performance. See references for the algorithm details. | + +For the multi frame fusion, currently only supporting `log-odds` fusion method. + +## How to use + +### launch fusion node + +The minimum node launch will be like the following. + +```xml + + + + + + + + + + +``` + +### (Optional) Generate OGMs in each sensor frame + +You need to generate OGMs in each sensor frame before achieving grid map fusion. + +`probabilistic_occupancy_grid_map` package supports to generate OGMs for the each from the point cloud data. + +
+ Example launch.xml (click to expand) + +```xml + + + + + + + + + + + + + + + +The minimum parameter for the OGM generation in each frame is shown in the following table. + +|Parameter|Description| +|--|--| +|`input/obstacle_pointcloud`| The input point cloud data for the OGM generation. This point cloud data should be the point cloud data which is segmented as the obstacle.| +|`input/raw_pointcloud`| The input point cloud data for the OGM generation. This point cloud data should be the point cloud data which is not segmented as the obstacle. | +|`output`| The output topic of the OGM. | +|`map_frame`| The tf frame for the OGM center origin. | +|`scan_origin`| The tf frame for the sensor origin. | +|`method`| The method for the OGM generation. Currently we support `pointcloud_based_occupancy_grid_map` and `laser_scan_based_occupancy_grid_map`. The pointcloud based method is recommended. | +|`param_file`| The parameter file for the OGM generation. See [example parameter file](config/pointcloud_based_occupancy_grid_map_for_fusion.param.yaml) | + +``` + +
+ +
+ +We recommend to use same `map_frame`, size and resolutions for the OGMs from synchronized sensors. +Also, remember to set `enable_single_frame_mode` and `filter_obstacle_pointcloud_by_raw_pointcloud` to `true` in the `probabilistic_occupancy_grid_map` package (you do not need to set these parameters if you use the above example config file). + +
+ +### Run both OGM generation node and fusion node + +We prepared the launch file to run both OGM generation node and fusion node in [`grid_map_fusion_with_synchronized_pointclouds.launch.py`](launch/grid_map_fusion_with_synchronized_pointclouds.launch.py) + +You can include this launch file like the following. + +```xml + + + + + + + + + + +``` + +The minimum parameter for the launch file is shown in the following table. + +| Parameter | Description | +| -------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| `output` | The output topic of the finally fused OGM. | +| `method` | The method for the OGM generation. Currently we support `pointcloud_based_occupancy_grid_map` and `laser_scan_based_occupancy_grid_map`. The pointcloud based method is recommended. | +| `fusion_config_file` | The parameter file for the grid map fusion. See [example parameter file](config/grid_map_fusion.param.yaml) | +| `ogm_config_file` | The parameter file for the OGM generation. See [example parameter file](config/pointcloud_based_occupancy_grid_map_for_fusion.param.yaml) | + +## References + +- [1] Dempster, A. P., Laird, N. M., & Rubin, D. B. (1977). Maximum likelihood from incomplete data via the EM algorithm. Journal of the Royal Statistical Society. Series B (Methodological), 39(1), 1-38. +- [2] diff --git a/perception/probabilistic_occupancy_grid_map/test/cost_value_test.cpp b/perception/probabilistic_occupancy_grid_map/test/cost_value_test.cpp new file mode 100644 index 0000000000000..baf94fabfd2a1 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/test/cost_value_test.cpp @@ -0,0 +1,47 @@ +// 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 "cost_value.hpp" + +#include "gtest/gtest.h" + +// Test the CostTranslationTable and InverseCostTranslationTable functions +using occupancy_cost_value::cost_translation_table; +using occupancy_cost_value::inverse_cost_translation_table; + +TEST(CostTranslationTableTest, TestRange) +{ + // Test the value range of CostTranslationTable + for (int i = 0; i < 256; i++) { + EXPECT_GE(cost_translation_table[i], 1); + EXPECT_LE(cost_translation_table[i], 99); + } + + // Test the value range of InverseCostTranslationTable + for (int i = 1; i < 100; i++) { + EXPECT_GE(inverse_cost_translation_table[i], 0); + EXPECT_LE(inverse_cost_translation_table[i], 255); + } +} + +TEST(CostTranslationTableTest, TestConversion) +{ + // Test the forward and inverse conversion of 0, 128, and 255 + EXPECT_EQ(cost_translation_table[0], 1); + EXPECT_EQ(cost_translation_table[128], 50); + EXPECT_EQ(cost_translation_table[255], 99); + EXPECT_EQ(inverse_cost_translation_table[1], 2); + EXPECT_EQ(inverse_cost_translation_table[50], 128); + EXPECT_EQ(inverse_cost_translation_table[99], 255); +} diff --git a/perception/probabilistic_occupancy_grid_map/test/fusion_policy_test.cpp b/perception/probabilistic_occupancy_grid_map/test/fusion_policy_test.cpp new file mode 100644 index 0000000000000..2501a361fba58 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/test/fusion_policy_test.cpp @@ -0,0 +1,75 @@ +// 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 "cost_value.hpp" +#include "fusion/single_frame_fusion_policy.hpp" +#include "gtest/gtest.h" + +// Test the log-odds update rule +TEST(FusionPolicyTest, TestLogOddsUpdateRule) +{ + using fusion_policy::log_odds_fusion::logOddsFusion; + const double MARGIN = 0.03; + const double OCCUPIED = 1.0 - MARGIN; + const double FREE = 0.0 + MARGIN; + const double UNKNOWN = 0.5; + const double EPSILON = 1e-3; + + // same case + std::vector case1_1 = {OCCUPIED, OCCUPIED}; + std::vector case1_2 = {FREE, FREE}; + std::vector case1_3 = {UNKNOWN, UNKNOWN}; + EXPECT_GE(logOddsFusion(case1_1), OCCUPIED); + EXPECT_LE(logOddsFusion(case1_2), FREE); + EXPECT_NEAR(logOddsFusion(case1_3), UNKNOWN, EPSILON); + + // with unknown + std::vector case2_1 = {OCCUPIED, UNKNOWN}; + std::vector case2_2 = {FREE, UNKNOWN}; + EXPECT_NEAR(logOddsFusion(case2_1), OCCUPIED, EPSILON); + EXPECT_NEAR(logOddsFusion(case2_2), FREE, EPSILON); + + // with conflict + std::vector case3_1 = {OCCUPIED, FREE}; + EXPECT_NEAR(logOddsFusion(case3_1), UNKNOWN, EPSILON); +} + +// Test the dempster-shafer update rule +TEST(FusionPolicyTest, TestDempsterShaferUpdateRule) +{ + using fusion_policy::dempster_shafer_fusion::dempsterShaferFusion; + const double MARGIN = 0.03; + const double OCCUPIED = 1.0 - MARGIN; + const double FREE = 0.0 + MARGIN; + const double UNKNOWN = 0.5; + const double EPSILON = 1e-3; + + // same case + std::vector case1_1 = {OCCUPIED, OCCUPIED}; + std::vector case1_2 = {FREE, FREE}; + std::vector case1_3 = {UNKNOWN, UNKNOWN}; + EXPECT_GE(dempsterShaferFusion(case1_1), OCCUPIED); + EXPECT_LE(dempsterShaferFusion(case1_2), FREE); + EXPECT_NEAR(dempsterShaferFusion(case1_3), UNKNOWN, EPSILON); + + // with unknown + std::vector case2_1 = {OCCUPIED, UNKNOWN}; + std::vector case2_2 = {FREE, UNKNOWN}; + EXPECT_NEAR(dempsterShaferFusion(case2_1), OCCUPIED, EPSILON); + EXPECT_NEAR(dempsterShaferFusion(case2_2), FREE, EPSILON); + + // with conflict + std::vector case3_1 = {OCCUPIED, FREE}; + EXPECT_NEAR(dempsterShaferFusion(case3_1), UNKNOWN, EPSILON); +} diff --git a/perception/probabilistic_occupancy_grid_map/test/test_synchronized_grid_map_fusion_node.py b/perception/probabilistic_occupancy_grid_map/test/test_synchronized_grid_map_fusion_node.py new file mode 100644 index 0000000000000..c15daaf886b6f --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/test/test_synchronized_grid_map_fusion_node.py @@ -0,0 +1,255 @@ +# Copyright 2021 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import time +import unittest + +from geometry_msgs.msg import TransformStamped +import launch +import launch.actions +from launch_ros.substitutions import FindPackageShare +import launch_testing +import launch_testing.actions +import launch_testing.asserts +import launch_testing.markers +import launch_testing.tools +from nav_msgs.msg import OccupancyGrid +import numpy as np +import pytest +import rclpy +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSHistoryPolicy +from rclpy.qos import QoSProfile +from rclpy.qos import QoSReliabilityPolicy +from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster + +PACKAGE_NAME = "probabilistic_occupancy_grid_map" +INPUT_TOPICS = ["/topic1", "/topic2"] +DEBUG_OUTPUT_TOPIC = "/synchronized_grid_map_fusion_node/debug/single_frame_map" +OUTPUT_TOPIC = "/synchronized_grid_map_fusion_node/output/occupancy_grid_map" + +FREE_VALUE = 1 +UNKNOWN_VALUE = 50 +OCCUPIED_VALUE = 99 + + +# test launcher to launch grid map fusion node +@pytest.mark.launch_test +def generate_test_description(): + """Launch file test description. + + Returns: + _type_: launch.LaunchDescription + """ + # get launch file path + launch_file_path = ( + FindPackageShare(PACKAGE_NAME).find(PACKAGE_NAME) + + "/launch/synchronized_occupancy_grid_map_fusion.launch.xml" + ) + # use default launch arguments and parms + launch_args = [] + # action to include launch file + test_launch_file = launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.AnyLaunchDescriptionSource(launch_file_path), + launch_arguments=launch_args, + ) + + return launch.LaunchDescription( + [ + test_launch_file, + launch_testing.actions.ReadyToTest(), + ] + ) + + +# util functions +def create_nav_msgs_occupancy_grid_msg(fill_value: int = 0, stamp: rclpy.time.Time = None): + """Create nav_msgs occupancy grid message. + + Args: + fill_value (int, optional): fill value. Defaults to 0. + + Returns: + OccupancyGrid: nav_msgs occupancy grid message + """ + msg = OccupancyGrid() + msg.header.stamp = rclpy.clock.Clock().now().to_msg() if stamp is None else stamp.to_msg() + msg.header.frame_id = "map" + msg.info.resolution = 0.5 # 0.5m x 0.5m + msg.info.width = 200 # 100m x 100m + msg.info.height = 200 + msg.info.origin.position.x = -msg.info.width * msg.info.resolution / 2.0 + msg.info.origin.position.y = -msg.info.height * msg.info.resolution / 2.0 + msg.info.origin.position.z = 0.0 + msg.info.origin.orientation.x = 0.0 + msg.info.origin.orientation.y = 0.0 + msg.info.origin.orientation.z = 0.0 + msg.info.origin.orientation.w = 1.0 + msg.data = [fill_value] * msg.info.width * msg.info.height + return msg + + +def parse_ogm_msg(msg: OccupancyGrid): + """Parse nav_msgs occupancy grid message. + + Args: + msg (OccupancyGrid): nav_msgs occupancy grid message + + Returns: + np.ndarray: occupancy grid map + """ + ogm = np.array(msg.data).reshape((msg.info.height, msg.info.width)) + return ogm + + +# dummy tf broadcaster +def generate_static_transform_msg(stamp: rclpy.time.Time = None): + """Generate static transform message from base_link to map. + + Returns: + TransformStamped: static transform message + """ + msg = TransformStamped() + if stamp is None: + msg.header.stamp = rclpy.clock.Clock().now().to_msg() + else: + msg.header.stamp = stamp.to_msg() + msg.header.frame_id = "map" + msg.child_frame_id = "base_link" + msg.transform.translation.x = 0.0 + msg.transform.translation.y = 0.0 + msg.transform.translation.z = 0.0 + msg.transform.rotation.x = 0.0 + msg.transform.rotation.y = 0.0 + msg.transform.rotation.z = 0.0 + msg.transform.rotation.w = 1.0 + return msg + + +# --- TestSynchronizedOGMFusion --- +# 1. test free ogm and free ogm input fusion +# 2. test occupied ogm and occupied ogm input fusion +# 3. test unknown ogm and free ogm input fusion +# 4. test unknown ogm and occupied ogm input fusion +# 5. test free ogm and occupied ogm input fusion +class TestSynchronizedOGMFusion(unittest.TestCase): + @classmethod + def setUpClass(cls): + # init ROS at once + rclpy.init() + + @classmethod + def tearDownClass(cls): + # shutdown ROS at once + rclpy.shutdown() + + def setUp(self): + # called when each test started + self.node = rclpy.create_node("grid_map_fusion_node_test_node") + # send static transform from map to base_link + tf_msg = generate_static_transform_msg() + self.tf_broadcaster = StaticTransformBroadcaster(self.node) + self.tf_broadcaster.sendTransform(tf_msg) + + def tearDown(self): + # called when each test finished + self.node.destroy_node() + + def callback(self, msg: OccupancyGrid): + self.msg_buffer.append(msg) + print("callback", len(self.msg_buffer)) + + def get_newest_ogm_value(self): + return np.mean(self.msg_buffer[-1].data) + + # util functions test 1~3 + def create_pub_sub(self): + # create publisher + pub1 = self.node.create_publisher(OccupancyGrid, INPUT_TOPICS[0], 10) + pub2 = self.node.create_publisher(OccupancyGrid, INPUT_TOPICS[1], 10) + + # create subscriber for debug output + sensor_qos = QoSProfile( + history=QoSHistoryPolicy.KEEP_LAST, + depth=10, + reliability=QoSReliabilityPolicy.BEST_EFFORT, + durability=QoSDurabilityPolicy.VOLATILE, + ) + self.msg_buffer = [] + # subscribe to occupancy grid with buffer + sub = self.node.create_subscription( + OccupancyGrid, DEBUG_OUTPUT_TOPIC, self.callback, qos_profile=sensor_qos + ) + return [pub1, pub2], sub + + # test functions + def test_same_ogm_fusion(self): + """Test 1~3. + + Expected output: same ogm. + """ + # wait for the node to be ready + time.sleep(3) + pubs, sub = self.create_pub_sub() # pubs have two publishers + + fill_values = [FREE_VALUE, OCCUPIED_VALUE, UNKNOWN_VALUE] + + for fill_value in fill_values: + # create free/occupied/unknown ogm + ogm = create_nav_msgs_occupancy_grid_msg(fill_value=fill_value) + # publish free/occupied/unknown ogm + pubs[0].publish(ogm) + pubs[1].publish(ogm) + + # try to subscribe output pointcloud once + rclpy.spin_once(self.node, timeout_sec=2.0) + fused_mean = self.get_newest_ogm_value() + print("same ogm test: ", fill_value, fused_mean) + # assert almost equal + self.assertAlmostEqual(fused_mean, fill_value, delta=3.0) + + def test_unknown_fusion(self): + """Test unknown ogm and free ogm input fusion. + + Expected output: free, occupied, unknown. + """ + # wait for the node to be ready + time.sleep(3) + pubs, sub = self.create_pub_sub() + + fill_values = [FREE_VALUE, OCCUPIED_VALUE, UNKNOWN_VALUE] + now = rclpy.clock.Clock().now() + unknown_ogm = create_nav_msgs_occupancy_grid_msg(fill_value=UNKNOWN_VALUE, stamp=now) + + for fill_value in fill_values: + # publish unknown ogm + pubs[0].publish(unknown_ogm) + # create free/occupied/unknown ogm + ogm = create_nav_msgs_occupancy_grid_msg(fill_value=fill_value, stamp=now) + # publish ogm + pubs[1].publish(ogm) + + # try to subscribe output pointcloud once + rclpy.spin_once(self.node, timeout_sec=2.0) + fused_mean = self.get_newest_ogm_value() + print("unknown ogm test: ", fill_value, fused_mean) + # assert almost equal + self.assertAlmostEqual(fused_mean, fill_value, delta=3.0) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # check exit code + launch_testing.asserts.assertExitCodes(proc_info) From 0f1b5e88e35e6155b1b459cd18d0f5ccf2fdb9bd Mon Sep 17 00:00:00 2001 From: Tao Zhong <55872497+tzhong518@users.noreply.github.com> Date: Tue, 9 Jan 2024 11:31:08 +0900 Subject: [PATCH 198/276] feat(traffic_light): output undetected traffic light as unknown (#5934) * fix: output undetected traffic light as unknown Signed-off-by: tzhong518 * Update perception/traffic_light_classifier/src/nodelet.cpp Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * Update perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * style(pre-commit): autofix * fix: unnecessary count Signed-off-by: tzhong518 * style(pre-commit): autofix * fix: improve readability Signed-off-by: tzhong518 * fix: index error Signed-off-by: tzhong518 * fix: append the undetected rois at the end so that the order can be easily kept Signed-off-by: tzhong518 * fix: false occlusion ratio for undetected signals Signed-off-by: tzhong518 --------- Signed-off-by: tzhong518 Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../traffic_light_classifier/src/nodelet.cpp | 30 +++++++++++++++---- .../src/nodelet.cpp | 28 ++++++++++++----- .../src/nodelet.cpp | 14 ++++++++- .../src/occlusion_predictor.cpp | 6 +++- 4 files changed, 63 insertions(+), 15 deletions(-) diff --git a/perception/traffic_light_classifier/src/nodelet.cpp b/perception/traffic_light_classifier/src/nodelet.cpp index 3a00bb013d867..1ebc14c4e6f93 100644 --- a/perception/traffic_light_classifier/src/nodelet.cpp +++ b/perception/traffic_light_classifier/src/nodelet.cpp @@ -13,6 +13,8 @@ // limitations under the License. #include "traffic_light_classifier/nodelet.hpp" +#include + #include #include #include @@ -98,16 +100,18 @@ void TrafficLightClassifierNodelet::imageRoiCallback( output_msg.signals.resize(input_rois_msg->rois.size()); std::vector images; - size_t num_valid_roi = 0; std::vector backlight_indices; for (size_t i = 0; i < input_rois_msg->rois.size(); i++) { - // skip if not the expected type of roi + // skip if the roi is not detected + if (input_rois_msg->rois.at(i).roi.height == 0) { + break; + } if (input_rois_msg->rois.at(i).traffic_light_type != classify_traffic_light_type_) { continue; } - output_msg.signals[num_valid_roi].traffic_light_id = + output_msg.signals[images.size()].traffic_light_id = input_rois_msg->rois.at(i).traffic_light_id; - output_msg.signals[num_valid_roi].traffic_light_type = + output_msg.signals[images.size()].traffic_light_type = input_rois_msg->rois.at(i).traffic_light_type; const sensor_msgs::msg::RegionOfInterest & roi = input_rois_msg->rois.at(i).roi; @@ -116,15 +120,29 @@ void TrafficLightClassifierNodelet::imageRoiCallback( backlight_indices.emplace_back(i); } images.emplace_back(roi_img); - num_valid_roi++; } - output_msg.signals.resize(num_valid_roi); + output_msg.signals.resize(images.size()); if (!classifier_ptr_->getTrafficSignals(images, output_msg)) { RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback"); return; } + // append the undetected rois as unknown + for (const auto & input_roi : input_rois_msg->rois) { + if (input_roi.roi.height == 0 && input_roi.traffic_light_type == classify_traffic_light_type_) { + tier4_perception_msgs::msg::TrafficSignal tlr_sig; + tlr_sig.traffic_light_id = input_roi.traffic_light_id; + tlr_sig.traffic_light_type = input_roi.traffic_light_type; + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + element.shape = tier4_perception_msgs::msg::TrafficLightElement::CIRCLE; + element.confidence = 0.0; + tlr_sig.elements.push_back(element); + output_msg.signals.push_back(tlr_sig); + } + } + for (const auto & idx : backlight_indices) { auto & elements = output_msg.signals.at(idx).elements; for (auto & element : elements) { diff --git a/perception/traffic_light_fine_detector/src/nodelet.cpp b/perception/traffic_light_fine_detector/src/nodelet.cpp index 257e9fc7ea99d..8037dc5472fbe 100644 --- a/perception/traffic_light_fine_detector/src/nodelet.cpp +++ b/perception/traffic_light_fine_detector/src/nodelet.cpp @@ -272,14 +272,28 @@ void TrafficLightFineDetectorNodelet::detectionMatch( } out_rois.rois.clear(); - for (const auto & p : bestDetections) { + std::vector invalid_roi_id; + for (const auto & [tlr_id, roi] : id2expectRoi) { + // if matches, update the roi info + if (!bestDetections.count(tlr_id)) { + invalid_roi_id.emplace_back(tlr_id); + continue; + } + TrafficLightRoi tlr; + tlr.traffic_light_id = tlr_id; + const auto & object = bestDetections.at(tlr_id); + tlr.traffic_light_type = roi.traffic_light_type; + tlr.roi.x_offset = object.x_offset; + tlr.roi.y_offset = object.y_offset; + tlr.roi.width = object.width; + tlr.roi.height = object.height; + out_rois.rois.push_back(tlr); + } + // append undetected rois at the end + for (const auto & id : invalid_roi_id) { TrafficLightRoi tlr; - tlr.traffic_light_id = p.first; - tlr.traffic_light_type = id2expectRoi[p.first].traffic_light_type; - tlr.roi.x_offset = p.second.x_offset; - tlr.roi.y_offset = p.second.y_offset; - tlr.roi.width = p.second.width; - tlr.roi.height = p.second.height; + tlr.traffic_light_id = id; + tlr.traffic_light_type = id2expectRoi[id].traffic_light_type; out_rois.rois.push_back(tlr); } } diff --git a/perception/traffic_light_occlusion_predictor/src/nodelet.cpp b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp index 97fa98ab18a72..6429640ff44c1 100644 --- a/perception/traffic_light_occlusion_predictor/src/nodelet.cpp +++ b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp @@ -129,12 +129,18 @@ void TrafficLightOcclusionPredictorNodelet::syncCallback( const uint8_t traffic_light_type) { std::vector occlusion_ratios; + size_t not_detected_roi = 0; if (in_cloud_msg == nullptr || in_cam_info_msg == nullptr || in_roi_msg == nullptr) { occlusion_ratios.resize(in_signal_msg->signals.size(), 0); } else { tier4_perception_msgs::msg::TrafficLightRoiArray selected_roi_msg; selected_roi_msg.rois.reserve(in_roi_msg->rois.size()); for (size_t i = 0; i < in_roi_msg->rois.size(); ++i) { + // not detected roi + if (in_roi_msg->rois[i].roi.height == 0) { + not_detected_roi++; + continue; + } if (in_roi_msg->rois.at(i).traffic_light_type == traffic_light_type) { selected_roi_msg.rois.push_back(in_roi_msg->rois.at(i)); } @@ -142,7 +148,7 @@ void TrafficLightOcclusionPredictorNodelet::syncCallback( tier4_perception_msgs::msg::TrafficSignalArray out_msg = *in_signal_msg; - if (selected_roi_msg.rois.size() != in_signal_msg->signals.size()) { + if (selected_roi_msg.rois.size() != in_signal_msg->signals.size() - not_detected_roi) { occlusion_ratios.resize(in_signal_msg->signals.size(), 0); } else { auto selected_roi_msg_ptr = @@ -162,6 +168,12 @@ void TrafficLightOcclusionPredictorNodelet::syncCallback( traffic_light_utils::setSignalUnknown(out_msg_.signals.at(predicted_num + i), 0.0); } } + + // push back not detected rois + for (size_t i = occlusion_ratios.size(); i < in_signal_msg->signals.size(); ++i) { + out_msg_.signals.push_back(in_signal_msg->signals[i]); + } + subscribed_.at(traffic_light_type) = true; if (std::all_of(subscribed_.begin(), subscribed_.end(), [](bool v) { return v; })) { diff --git a/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp b/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp index 7daa0849abe5e..6f96913420bad 100644 --- a/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp +++ b/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp @@ -88,6 +88,10 @@ void CloudOcclusionPredictor::predict( image_geometry::PinholeCameraModel pinhole_model; pinhole_model.fromCameraInfo(*camera_info_msg); for (size_t i = 0; i < rois_msg->rois.size(); i++) { + // skip if no detection + if (rois_msg->rois[i].roi.height == 0) { + continue; + } calcRoiVector3D( rois_msg->rois[i], pinhole_model, traffic_light_position_map, tf_camera2map, roi_tls[i], roi_brs[i]); @@ -107,7 +111,7 @@ void CloudOcclusionPredictor::predict( lidar_rays_[static_cast(ray.azimuth)][static_cast(ray.elevation)].push_back(ray); } for (size_t i = 0; i < roi_tls.size(); i++) { - occlusion_ratios[i] = predict(roi_tls[i], roi_brs[i]); + occlusion_ratios[i] = rois_msg->rois[i].roi.height == 0 ? 0 : predict(roi_tls[i], roi_brs[i]); } } From 1a598f9943e620fed50e35b55ee6c50c714c0670 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 9 Jan 2024 12:55:27 +0900 Subject: [PATCH 199/276] refactor(ndt_scan_matcher, map_loader): remove map_module (#5873) * Removed use_dynamic_map_loading Signed-off-by: Shintaro SAKODA * Removed enable_differential_load option Signed-off-by: Shintaro SAKODA * style(pre-commit): autofix * Fixed title Signed-off-by: Shintaro Sakoda * Emphasized lock scope Signed-off-by: Shintaro Sakoda * Removed pointcloud_map and input_ekf_odom Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro SAKODA Signed-off-by: Shintaro Sakoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/ndt_scan_matcher/CMakeLists.txt | 1 - localization/ndt_scan_matcher/README.md | 38 +++++--------- .../config/ndt_scan_matcher.param.yaml | 3 -- .../include/ndt_scan_matcher/map_module.hpp | 49 ------------------- .../ndt_scan_matcher_core.hpp | 4 -- .../launch/ndt_scan_matcher.launch.xml | 2 - .../ndt_scan_matcher/src/map_module.cpp | 49 ------------------- .../src/map_update_module.cpp | 5 +- .../src/ndt_scan_matcher_core.cpp | 17 ++----- map/map_loader/README.md | 5 +- .../config/pointcloud_map_loader.param.yaml | 1 - .../pointcloud_map_loader_node.cpp | 30 +++++------- 12 files changed, 29 insertions(+), 175 deletions(-) delete mode 100644 localization/ndt_scan_matcher/include/ndt_scan_matcher/map_module.hpp delete mode 100644 localization/ndt_scan_matcher/src/map_module.cpp diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index 2ad4a47b833d1..b4d656cb1810b 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -30,7 +30,6 @@ ament_auto_add_executable(ndt_scan_matcher src/particle.cpp src/ndt_scan_matcher_node.cpp src/ndt_scan_matcher_core.cpp - src/map_module.cpp src/map_update_module.cpp ) diff --git a/localization/ndt_scan_matcher/README.md b/localization/ndt_scan_matcher/README.md index d7a7b1c5c37f3..95a7cebdc01c8 100644 --- a/localization/ndt_scan_matcher/README.md +++ b/localization/ndt_scan_matcher/README.md @@ -18,7 +18,6 @@ One optional function is regularization. Please see the regularization chapter i | Name | Type | Description | | ----------------------------------- | ----------------------------------------------- | ------------------------------------- | | `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | initial pose | -| `pointcloud_map` | `sensor_msgs::msg::PointCloud2` | map pointcloud | | `points_raw` | `sensor_msgs::msg::PointCloud2` | sensor pointcloud | | `sensing/gnss/pose_with_covariance` | `sensor_msgs::msg::PoseWithCovarianceStamped` | base position for regularization term | @@ -193,12 +192,6 @@ Using the feature, `ndt_scan_matcher` can theoretically handle any large size ma ### Additional interfaces -#### Additional inputs - -| Name | Type | Description | -| ---------------- | ------------------------- | ----------------------------------------------------------- | -| `input_ekf_odom` | `nav_msgs::msg::Odometry` | Vehicle localization results (used for map update decision) | - #### Additional outputs | Name | Type | Description | @@ -213,20 +206,15 @@ Using the feature, `ndt_scan_matcher` can theoretically handle any large size ma ### Parameters -| Name | Type | Description | -| ------------------------------------- | ------ | -------------------------------------------------------------------- | -| `use_dynamic_map_loading` | bool | Flag to enable dynamic map loading feature for NDT (TRUE by default) | -| `dynamic_map_loading_update_distance` | double | Distance traveled to load new map(s) | -| `dynamic_map_loading_map_radius` | double | Map loading radius for every update | -| `lidar_radius` | double | LiDAR radius used for localization (only used for diagnosis) | - -### Enabling the dynamic map loading feature +| Name | Type | Description | +| ------------------------------------- | ------ | ------------------------------------------------------------ | +| `dynamic_map_loading_update_distance` | double | Distance traveled to load new map(s) | +| `dynamic_map_loading_map_radius` | double | Map loading radius for every update | +| `lidar_radius` | double | LiDAR radius used for localization (only used for diagnosis) | -To use dynamic map loading feature for `ndt_scan_matcher`, you also need to appropriately configure some other settings outside of this node. -Follow the next two instructions. +### Notes for dynamic map loading -1. enable dynamic map loading interface in `pointcloud_map_loader` (by setting `enable_differential_load` to true in the package) -2. split the PCD files into grids (recommended size: 20[m] x 20[m]) +To use dynamic map loading feature for `ndt_scan_matcher`, you also need to split the PCD files into grids (recommended size: 20[m] x 20[m]) Note that the dynamic map loading may FAIL if the map is split into two or more large size map (e.g. 1000[m] x 1000[m]). Please provide either of @@ -235,14 +223,10 @@ Note that the dynamic map loading may FAIL if the map is split into two or more Here is a split PCD map for `sample-map-rosbag` from Autoware tutorial: [`sample-map-rosbag_split.zip`](https://github.com/autowarefoundation/autoware.universe/files/10349104/sample-map-rosbag_split.zip) -| PCD files | `use_dynamic_map_loading` | `enable_differential_load` | How NDT loads map(s) | -| :------------: | :-----------------------: | :------------------------: | :------------------: | -| single file | true | true | at once (standard) | -| single file | true | false | **does NOT work** | -| single file | false | true/false | at once (standard) | -| multiple files | true | true | dynamically | -| multiple files | true | false | **does NOT work** | -| multiple files | false | true/false | at once (standard) | +| PCD files | How NDT loads map(s) | +| :------------: | :------------------: | +| single file | at once (standard) | +| multiple files | dynamically | ## Scan matching score based on de-grounded LiDAR scan diff --git a/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml b/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml index 1a6c26cd9c351..9bc62d3f919c6 100644 --- a/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml +++ b/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml @@ -1,8 +1,5 @@ /**: ros__parameters: - # Use dynamic map loading - use_dynamic_map_loading: true - # Vehicle reference frame base_frame: "base_link" diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_module.hpp deleted file mode 100644 index 79454e89b9ed0..0000000000000 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_module.hpp +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef NDT_SCAN_MATCHER__MAP_MODULE_HPP_ -#define NDT_SCAN_MATCHER__MAP_MODULE_HPP_ - -#include - -#include - -#include -#include -#include - -#include - -class MapModule -{ - using PointSource = pcl::PointXYZ; - using PointTarget = pcl::PointXYZ; - using NormalDistributionsTransform = - pclomp::MultiGridNormalDistributionsTransform; - -public: - MapModule( - rclcpp::Node * node, std::mutex * ndt_ptr_mutex, - std::shared_ptr ndt_ptr, - rclcpp::CallbackGroup::SharedPtr map_callback_group); - -private: - void callback_map_points(sensor_msgs::msg::PointCloud2::ConstSharedPtr map_points_msg_ptr); - - rclcpp::Subscription::SharedPtr map_points_sub_; - std::shared_ptr ndt_ptr_; - std::mutex * ndt_ptr_mutex_; -}; - -#endif // NDT_SCAN_MATCHER__MAP_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 b8792c20c323e..e9aa265c78f34 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 @@ -18,7 +18,6 @@ #define FMT_HEADER_ONLY #include "localization_util/smart_pose_buffer.hpp" -#include "ndt_scan_matcher/map_module.hpp" #include "ndt_scan_matcher/map_update_module.hpp" #include @@ -216,7 +215,6 @@ class NDTScanMatcher : public rclcpp::Node std::unique_ptr regularization_pose_buffer_; std::atomic is_activated_; - std::unique_ptr map_module_; std::unique_ptr map_update_module_; std::unique_ptr logger_configure_; @@ -224,8 +222,6 @@ class NDTScanMatcher : public rclcpp::Node bool estimate_scores_for_degrounded_scan_; double z_margin_for_ground_removal_; - bool use_dynamic_map_loading_; - // The execution time which means probably NDT cannot matches scans properly int64_t critical_upper_bound_exe_time_ms_; }; diff --git a/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml b/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml index 655aa8e17ccd9..891d172aaf8fd 100644 --- a/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml +++ b/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml @@ -4,7 +4,6 @@ - @@ -19,7 +18,6 @@ - diff --git a/localization/ndt_scan_matcher/src/map_module.cpp b/localization/ndt_scan_matcher/src/map_module.cpp deleted file mode 100644 index d6088a1b14949..0000000000000 --- a/localization/ndt_scan_matcher/src/map_module.cpp +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "ndt_scan_matcher/map_module.hpp" - -MapModule::MapModule( - rclcpp::Node * node, std::mutex * ndt_ptr_mutex, - std::shared_ptr ndt_ptr, - rclcpp::CallbackGroup::SharedPtr map_callback_group) -: ndt_ptr_(std::move(ndt_ptr)), ndt_ptr_mutex_(ndt_ptr_mutex) -{ - auto map_sub_opt = rclcpp::SubscriptionOptions(); - map_sub_opt.callback_group = map_callback_group; - - map_points_sub_ = node->create_subscription( - "pointcloud_map", rclcpp::QoS{1}.transient_local(), - std::bind(&MapModule::callback_map_points, this, std::placeholders::_1), map_sub_opt); -} - -void MapModule::callback_map_points( - sensor_msgs::msg::PointCloud2::ConstSharedPtr map_points_msg_ptr) -{ - NormalDistributionsTransform new_ndt; - new_ndt.setParams(ndt_ptr_->getParams()); - - pcl::shared_ptr> map_points_ptr(new pcl::PointCloud); - pcl::fromROSMsg(*map_points_msg_ptr, *map_points_ptr); - new_ndt.setInputTarget(map_points_ptr); - // create Thread - // detach - auto output_cloud = std::make_shared>(); - new_ndt.align(*output_cloud); - - // swap - ndt_ptr_mutex_->lock(); - *ndt_ptr_ = new_ndt; - ndt_ptr_mutex_->unlock(); -} diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 446f926a1d3f7..39b92fe248660 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -57,10 +57,7 @@ void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position) request->cached_ids = ndt_ptr_->getCurrentMapIDs(); while (!pcd_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) { - RCLCPP_INFO( - logger_, - "Waiting for pcd loader service. Check if the enable_differential_load in " - "pointcloud_map_loader is set `true`."); + RCLCPP_INFO(logger_, "Waiting for pcd loader service. Check the pointcloud_map_loader."); } // send a request to map_loader 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 7108dca20d8d7..0f6fdbc15db26 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -264,12 +264,7 @@ NDTScanMatcher::NDTScanMatcher() &NDTScanMatcher::service_trigger_node, this, std::placeholders::_1, std::placeholders::_2), rclcpp::ServicesQoS().get_rmw_qos_profile(), sensor_callback_group); - use_dynamic_map_loading_ = this->declare_parameter("use_dynamic_map_loading"); - if (use_dynamic_map_loading_) { - map_update_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_); - } else { - map_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_, sensor_callback_group); - } + map_update_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_); logger_configure_ = std::make_unique(this); } @@ -347,9 +342,6 @@ void NDTScanMatcher::callback_timer() if (!is_activated_) { return; } - if (!use_dynamic_map_loading_) { - return; - } std::lock_guard lock(latest_ekf_position_mtx_); if (latest_ekf_position_ == std::nullopt) { RCLCPP_ERROR_STREAM_THROTTLE( @@ -380,7 +372,8 @@ void NDTScanMatcher::callback_initial_pose( << ". Please check the frame_id in the input topic and ensure it is correct."); } - if (use_dynamic_map_loading_) { + { + // latest_ekf_position_ is also used by callback_timer, so it is necessary to acquire the lock std::lock_guard lock(latest_ekf_position_mtx_); latest_ekf_position_ = initial_pose_msg_ptr->pose.pose.position; } @@ -898,9 +891,7 @@ void NDTScanMatcher::service_ndt_align( // transform pose_frame to map_frame const auto initial_pose_msg_in_map_frame = transform(req->pose_with_covariance, transform_s2t); - if (use_dynamic_map_loading_) { - map_update_module_->update_map(initial_pose_msg_in_map_frame.pose.pose.position); - } + map_update_module_->update_map(initial_pose_msg_in_map_frame.pose.pose.position); // mutex Map std::lock_guard lock(ndt_ptr_mtx_); diff --git a/map/map_loader/README.md b/map/map_loader/README.md index 65d9594cb7415..fbe019096a3e7 100644 --- a/map/map_loader/README.md +++ b/map/map_loader/README.md @@ -20,7 +20,7 @@ NOTE: **We strongly recommend to use divided maps when using large pointcloud ma #### Prerequisites on pointcloud map file(s) -You may provide either a single .pcd file or multiple .pcd files. If you are using multiple PCD data and either of `enable_partial_load`, `enable_differential_load` or `enable_selected_load` are set true, it MUST obey the following rules: +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). 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. @@ -29,8 +29,6 @@ You may provide either a single .pcd file or multiple .pcd files. If you are usi 5. **All the split maps should not overlap with each other.** 6. **Metadata file should also be provided.** The metadata structure description is provided below. -Note that these rules are not applicable when `enable_partial_load`, `enable_differential_load` and `enable_selected_load` are all set false. In this case, however, you also need to disable dynamic map loading mode for other nodes as well ([ndt_scan_matcher](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/ndt_scan_matcher) and [compare_map_segmentation](https://github.com/autowarefoundation/autoware.universe/tree/main/perception/compare_map_segmentation) as of June 2023). - #### Metadata structure The metadata should look like this: @@ -118,7 +116,6 @@ Please see [the description of `GetSelectedPointCloudMap.srv`](https://github.co | enable_whole_load | bool | A flag to enable raw pointcloud map publishing | true | | enable_downsampled_whole_load | bool | A flag to enable downsampled pointcloud map publishing | false | | enable_partial_load | bool | A flag to enable partial pointcloud map server | false | -| enable_differential_load | bool | A flag to enable differential pointcloud map server | false | | enable_selected_load | bool | A flag to enable selected pointcloud map server | false | | leaf_size | float | Downsampling leaf size (only used when enable_downsampled_whole_load is set true) | 3.0 | | pcd_paths_or_directory | std::string | Path(s) to pointcloud map file or directory | | diff --git a/map/map_loader/config/pointcloud_map_loader.param.yaml b/map/map_loader/config/pointcloud_map_loader.param.yaml index ba4c032d3e514..b4efbec9706b4 100644 --- a/map/map_loader/config/pointcloud_map_loader.param.yaml +++ b/map/map_loader/config/pointcloud_map_loader.param.yaml @@ -3,7 +3,6 @@ enable_whole_load: true enable_downsampled_whole_load: false enable_partial_load: true - enable_differential_load: true enable_selected_load: false # only used when downsample_whole_load enabled diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp b/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp index a2d9307084545..5f4b3e311e6e9 100644 --- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp +++ b/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp @@ -53,7 +53,6 @@ PointCloudMapLoaderNode::PointCloudMapLoaderNode(const rclcpp::NodeOptions & opt bool enable_whole_load = declare_parameter("enable_whole_load"); bool enable_downsample_whole_load = declare_parameter("enable_downsampled_whole_load"); bool enable_partial_load = declare_parameter("enable_partial_load"); - bool enable_differential_load = declare_parameter("enable_differential_load"); bool enable_selected_load = declare_parameter("enable_selected_load"); if (enable_whole_load) { @@ -68,26 +67,21 @@ PointCloudMapLoaderNode::PointCloudMapLoaderNode(const rclcpp::NodeOptions & opt std::make_unique(this, pcd_paths, publisher_name, true); } - if (enable_partial_load || enable_differential_load || enable_selected_load) { - std::map pcd_metadata_dict; - try { - pcd_metadata_dict = getPCDMetadata(pcd_metadata_path, pcd_paths); - } catch (std::runtime_error & e) { - RCLCPP_ERROR_STREAM(get_logger(), e.what()); - } + std::map pcd_metadata_dict; + try { + pcd_metadata_dict = getPCDMetadata(pcd_metadata_path, pcd_paths); + } catch (std::runtime_error & e) { + RCLCPP_ERROR_STREAM(get_logger(), e.what()); + } - if (enable_partial_load) { - partial_map_loader_ = std::make_unique(this, pcd_metadata_dict); - } + if (enable_partial_load) { + partial_map_loader_ = std::make_unique(this, pcd_metadata_dict); + } - if (enable_differential_load) { - differential_map_loader_ = - std::make_unique(this, pcd_metadata_dict); - } + differential_map_loader_ = std::make_unique(this, pcd_metadata_dict); - if (enable_selected_load) { - selected_map_loader_ = std::make_unique(this, pcd_metadata_dict); - } + if (enable_selected_load) { + selected_map_loader_ = std::make_unique(this, pcd_metadata_dict); } } From 1712379c2e957037f73957fab5bbca3230186113 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 9 Jan 2024 13:11:36 +0900 Subject: [PATCH 200/276] refactor(behavior_velocity_planner): output path's interval can be designated by yaml (#6023) Signed-off-by: Takayuki Murooka --- .../config/behavior_velocity_planner.param.yaml | 1 + planning/behavior_velocity_planner/src/node.cpp | 4 +++- planning/behavior_velocity_planner/src/node.hpp | 1 + .../utilization/path_utilization.hpp | 3 +-- 4 files changed, 6 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml b/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml index aa51c38b55742..b31506918a2db 100644 --- a/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml +++ b/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml @@ -2,6 +2,7 @@ ros__parameters: forward_path_length: 1000.0 backward_path_length: 5.0 + behavior_output_path_interval: 1.0 stop_line_extend_length: 5.0 max_accel: -2.8 max_jerk: -5.0 diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index 5da8df9e70c35..8ecad4d9c1548 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -138,6 +138,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio // Parameters forward_path_length_ = declare_parameter("forward_path_length"); backward_path_length_ = declare_parameter("backward_path_length"); + behavior_output_path_interval_ = declare_parameter("behavior_output_path_interval"); planner_data_.stop_line_extend_length = declare_parameter("stop_line_extend_length"); // nearest search @@ -409,7 +410,8 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath const auto filtered_path = filterLitterPathPoint(to_path(velocity_planned_path)); // interpolation - const auto interpolated_path_msg = interpolatePath(filtered_path, forward_path_length_); + const auto interpolated_path_msg = + interpolatePath(filtered_path, forward_path_length_, behavior_output_path_interval_); // check stop point output_path_msg = filterStopPathPoint(interpolated_path_msg); diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/src/node.hpp index ded1d08700a1d..a345f1200f721 100644 --- a/planning/behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/src/node.hpp @@ -102,6 +102,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node // parameter double forward_path_length_; double backward_path_length_; + double behavior_output_path_interval_; // member PlannerData planner_data_; diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/path_utilization.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/path_utilization.hpp index 591ef8667b81b..667c915ac1d7f 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/path_utilization.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/path_utilization.hpp @@ -28,8 +28,7 @@ bool splineInterpolate( const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, autoware_auto_planning_msgs::msg::PathWithLaneId & output, const rclcpp::Logger logger); autoware_auto_planning_msgs::msg::Path interpolatePath( - const autoware_auto_planning_msgs::msg::Path & path, const double length, - const double interval = 1.0); + const autoware_auto_planning_msgs::msg::Path & path, const double length, const double interval); autoware_auto_planning_msgs::msg::Path filterLitterPathPoint( const autoware_auto_planning_msgs::msg::Path & path); autoware_auto_planning_msgs::msg::Path filterStopPathPoint( From 245768e6e9f36b952776507883f0744208610a41 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 9 Jan 2024 13:12:42 +0900 Subject: [PATCH 201/276] fix(avoidance, lane_change): modules handle unknown traffic signal in the same way as red signal (#6013) * fix(avoidance, lane_change): modules handle unknown traffic signal in the same way as red signal Signed-off-by: satoshi-ota * feat(traffic_light_utils): add util functions Signed-off-by: satoshi-ota * refactor(bpp): use traffic light utils Signed-off-by: satoshi-ota * refactor(bvp): use traffic light utils Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../traffic_light_utils.hpp | 44 ++++++++++++++ common/traffic_light_utils/package.xml | 2 + .../src/traffic_light_utils.cpp | 57 +++++++++++++++++++ .../utils/traffic_light_utils.hpp | 37 ------------ .../behavior_path_planner_common/package.xml | 1 + .../src/utils/traffic_light_utils.cpp | 56 +----------------- .../package.xml | 1 + .../src/scene.cpp | 54 +----------------- .../src/scene.hpp | 6 -- 9 files changed, 110 insertions(+), 148 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 081eab28e8833..6ce95acc4ef1d 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 @@ -15,10 +15,13 @@ #ifndef TRAFFIC_LIGHT_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ #define TRAFFIC_LIGHT_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ +#include "autoware_perception_msgs/msg/traffic_signal.hpp" +#include "autoware_perception_msgs/msg/traffic_signal_element.hpp" #include "tier4_perception_msgs/msg/traffic_light_element.hpp" #include "tier4_perception_msgs/msg/traffic_light_roi.hpp" #include "tier4_perception_msgs/msg/traffic_signal.hpp" +#include #include #include #include @@ -36,6 +39,47 @@ bool isSignalUnknown(const tier4_perception_msgs::msg::TrafficSignal & signal); void setSignalUnknown(tier4_perception_msgs::msg::TrafficSignal & signal, float confidence = -1); +/** + * @brief Checks if a traffic light state includes a circle-shaped light with the specified color. + * + * Iterates through the traffic light elements to find a circle-shaped light that matches the given + * color. + * + * @param tl_state The traffic light state to check. + * @param lamp_color The color to look for in the traffic light's circle-shaped lamps. + * @return True if a circle-shaped light with the specified color is found, false otherwise. + */ +bool hasTrafficLightCircleColor( + const autoware_perception_msgs::msg::TrafficSignal & tl_state, const uint8_t & lamp_color); + +/** + * @brief Checks if a traffic light state includes a light with the specified shape. + * + * Searches through the traffic light elements to find a light that matches the given shape. + * + * @param tl_state The traffic light state to check. + * @param shape The shape to look for in the traffic light's lights. + * @return True if a light with the specified shape is found, false otherwise. + */ +bool hasTrafficLightShape( + const autoware_perception_msgs::msg::TrafficSignal & tl_state, const uint8_t & lamp_shape); + +/** + * @brief Determines if a traffic signal indicates a stop for the given lanelet. + * + * Evaluates the current state of the traffic light, considering if it's green or unknown, + * which would not necessitate a stop. Then, it checks the turn direction attribute of the lanelet + * against the traffic light's arrow shapes to determine whether a vehicle must stop or if it can + * proceed based on allowed turn directions. + * + * @param lanelet The lanelet to check for a stop signal at its traffic light. + * @param tl_state The current state of the traffic light associated with the lanelet. + * @return True if the traffic signal indicates a stop is required, false otherwise. + */ +bool isTrafficSignalStop( + const lanelet::ConstLanelet & lanelet, + const autoware_perception_msgs::msg::TrafficSignal & tl_state); + tf2::Vector3 getTrafficLightTopLeft(const lanelet::ConstLineString3d & traffic_light); tf2::Vector3 getTrafficLightBottomRight(const lanelet::ConstLineString3d & traffic_light); diff --git a/common/traffic_light_utils/package.xml b/common/traffic_light_utils/package.xml index de05355eafd66..37b4d46ce356a 100644 --- a/common/traffic_light_utils/package.xml +++ b/common/traffic_light_utils/package.xml @@ -6,6 +6,7 @@ The traffic_light_utils package Mingyu Li Shunsuke Miura + Satoshi Ota Apache License 2.0 ament_cmake_auto @@ -15,6 +16,7 @@ ament_lint_auto autoware_lint_common + autoware_perception_msgs lanelet2_extension tier4_perception_msgs diff --git a/common/traffic_light_utils/src/traffic_light_utils.cpp b/common/traffic_light_utils/src/traffic_light_utils.cpp index e02798bb41767..c8f2ca85b2089 100644 --- a/common/traffic_light_utils/src/traffic_light_utils.cpp +++ b/common/traffic_light_utils/src/traffic_light_utils.cpp @@ -51,6 +51,63 @@ void setSignalUnknown(tier4_perception_msgs::msg::TrafficSignal & signal, float } } +bool hasTrafficLightCircleColor( + const autoware_perception_msgs::msg::TrafficSignal & tl_state, const uint8_t & lamp_color) +{ + const auto it_lamp = + std::find_if(tl_state.elements.begin(), tl_state.elements.end(), [&lamp_color](const auto & x) { + return x.shape == autoware_perception_msgs::msg::TrafficSignalElement::CIRCLE && + x.color == lamp_color; + }); + + return it_lamp != tl_state.elements.end(); +} + +bool hasTrafficLightShape( + const autoware_perception_msgs::msg::TrafficSignal & tl_state, const uint8_t & lamp_shape) +{ + const auto it_lamp = std::find_if( + tl_state.elements.begin(), tl_state.elements.end(), + [&lamp_shape](const auto & x) { return x.shape == lamp_shape; }); + + return it_lamp != tl_state.elements.end(); +} + +bool isTrafficSignalStop( + const lanelet::ConstLanelet & lanelet, + const autoware_perception_msgs::msg::TrafficSignal & tl_state) +{ + if (hasTrafficLightCircleColor( + tl_state, autoware_perception_msgs::msg::TrafficSignalElement::GREEN)) { + return false; + } + + const std::string turn_direction = lanelet.attributeOr("turn_direction", "else"); + + if (turn_direction == "else") { + return true; + } + if ( + turn_direction == "right" && + hasTrafficLightShape( + tl_state, autoware_perception_msgs::msg::TrafficSignalElement::RIGHT_ARROW)) { + return false; + } + if ( + turn_direction == "left" && + hasTrafficLightShape( + tl_state, autoware_perception_msgs::msg::TrafficSignalElement::LEFT_ARROW)) { + return false; + } + if ( + turn_direction == "straight" && + hasTrafficLightShape(tl_state, autoware_perception_msgs::msg::TrafficSignalElement::UP_ARROW)) { + return false; + } + + return true; +} + tf2::Vector3 getTrafficLightTopLeft(const lanelet::ConstLineString3d & traffic_light) { const auto & tl_bl = traffic_light.front(); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/traffic_light_utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/traffic_light_utils.hpp index bf48252a01dcd..6380830806c33 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/traffic_light_utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/traffic_light_utils.hpp @@ -37,43 +37,6 @@ using autoware_perception_msgs::msg::TrafficSignal; using autoware_perception_msgs::msg::TrafficSignalElement; using geometry_msgs::msg::Pose; -/** - * @brief Checks if a traffic light state includes a circle-shaped light with the specified color. - * - * Iterates through the traffic light elements to find a circle-shaped light that matches the given - * color. - * - * @param tl_state The traffic light state to check. - * @param lamp_color The color to look for in the traffic light's circle-shaped lamps. - * @return True if a circle-shaped light with the specified color is found, false otherwise. - */ -bool hasTrafficLightCircleColor(const TrafficSignal & tl_state, const uint8_t & lamp_color); - -/** - * @brief Checks if a traffic light state includes a light with the specified shape. - * - * Searches through the traffic light elements to find a light that matches the given shape. - * - * @param tl_state The traffic light state to check. - * @param shape The shape to look for in the traffic light's lights. - * @return True if a light with the specified shape is found, false otherwise. - */ -bool hasTrafficLightShape(const TrafficSignal & tl_state, const uint8_t & lamp_shape); - -/** - * @brief Determines if a traffic signal indicates a stop for the given lanelet. - * - * Evaluates the current state of the traffic light, considering if it's green or unknown, - * which would not necessitate a stop. Then, it checks the turn direction attribute of the lanelet - * against the traffic light's arrow shapes to determine whether a vehicle must stop or if it can - * proceed based on allowed turn directions. - * - * @param lanelet The lanelet to check for a stop signal at its traffic light. - * @param tl_state The current state of the traffic light associated with the lanelet. - * @return True if the traffic signal indicates a stop is required, false otherwise. - */ -bool isTrafficSignalStop(const lanelet::ConstLanelet & lanelet, const TrafficSignal & tl_state); - /** * @brief Computes the distance from the current position to the next traffic light along a set of * lanelets. diff --git a/planning/behavior_path_planner_common/package.xml b/planning/behavior_path_planner_common/package.xml index 83e9c39e24dd6..db5dc51150e55 100644 --- a/planning/behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner_common/package.xml @@ -60,6 +60,7 @@ tf2 tier4_autoware_utils tier4_planning_msgs + traffic_light_utils vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/behavior_path_planner_common/src/utils/traffic_light_utils.cpp b/planning/behavior_path_planner_common/src/utils/traffic_light_utils.cpp index 850919f539e59..f77fafb42d829 100644 --- a/planning/behavior_path_planner_common/src/utils/traffic_light_utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/traffic_light_utils.cpp @@ -14,63 +14,12 @@ #include #include +#include namespace behavior_path_planner::utils::traffic_light { using motion_utils::calcSignedArcLength; -bool hasTrafficLightCircleColor(const TrafficSignal & tl_state, const uint8_t & lamp_color) -{ - const auto it_lamp = - std::find_if(tl_state.elements.begin(), tl_state.elements.end(), [&lamp_color](const auto & x) { - return x.shape == TrafficSignalElement::CIRCLE && x.color == lamp_color; - }); - - return it_lamp != tl_state.elements.end(); -} - -bool hasTrafficLightShape(const TrafficSignal & tl_state, const uint8_t & lamp_shape) -{ - const auto it_lamp = std::find_if( - tl_state.elements.begin(), tl_state.elements.end(), - [&lamp_shape](const auto & x) { return x.shape == lamp_shape; }); - - return it_lamp != tl_state.elements.end(); -} - -bool isTrafficSignalStop(const lanelet::ConstLanelet & lanelet, const TrafficSignal & tl_state) -{ - if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::GREEN)) { - return false; - } - - if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::UNKNOWN)) { - return false; - } - - const std::string turn_direction = lanelet.attributeOr("turn_direction", "else"); - - if (turn_direction == "else") { - return true; - } - if ( - turn_direction == "right" && - hasTrafficLightShape(tl_state, TrafficSignalElement::RIGHT_ARROW)) { - return false; - } - if ( - turn_direction == "left" && hasTrafficLightShape(tl_state, TrafficSignalElement::LEFT_ARROW)) { - return false; - } - if ( - turn_direction == "straight" && - hasTrafficLightShape(tl_state, TrafficSignalElement::UP_ARROW)) { - return false; - } - - return true; -} - double getDistanceToNextTrafficLight( const Pose & current_pose, const lanelet::ConstLanelets & lanelets) { @@ -138,7 +87,8 @@ std::optional calcDistanceToRedTrafficLight( continue; } - if (!isTrafficSignalStop(lanelet, traffic_signal_stamped.value().signal)) { + if (!traffic_light_utils::isTrafficSignalStop( + lanelet, traffic_signal_stamped.value().signal)) { continue; } diff --git a/planning/behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_traffic_light_module/package.xml index 39c454e59dcb2..33bb471e5920c 100644 --- a/planning/behavior_velocity_traffic_light_module/package.xml +++ b/planning/behavior_velocity_traffic_light_module/package.xml @@ -33,6 +33,7 @@ tf2_geometry_msgs tier4_autoware_utils tier4_planning_msgs + traffic_light_utils visualization_msgs ament_lint_auto diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp index 35d44a22f6cf0..a17fc43b86f23 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp @@ -16,6 +16,7 @@ #include #include +#include #include #include @@ -287,7 +288,7 @@ bool TrafficLightModule::isStopSignal() return true; } - return isTrafficSignalStop(looking_tl_state_); + return traffic_light_utils::isTrafficSignalStop(lane_, looking_tl_state_); } void TrafficLightModule::updateTrafficSignal() @@ -349,36 +350,6 @@ bool TrafficLightModule::isPassthrough(const double & signed_arc_length) const } } -bool TrafficLightModule::isTrafficSignalStop( - const autoware_perception_msgs::msg::TrafficSignal & tl_state) const -{ - if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::GREEN)) { - return false; - } - - const std::string turn_direction = lane_.attributeOr("turn_direction", "else"); - - if (turn_direction == "else") { - return true; - } - if ( - turn_direction == "right" && - hasTrafficLightShape(tl_state, TrafficSignalElement::RIGHT_ARROW)) { - return false; - } - if ( - turn_direction == "left" && hasTrafficLightShape(tl_state, TrafficSignalElement::LEFT_ARROW)) { - return false; - } - if ( - turn_direction == "straight" && - hasTrafficLightShape(tl_state, TrafficSignalElement::UP_ARROW)) { - return false; - } - - return true; -} - bool TrafficLightModule::findValidTrafficSignal(TrafficSignalStamped & valid_traffic_signal) const { // get traffic signal associated with the regulatory element id @@ -452,25 +423,4 @@ autoware_auto_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopP return modified_path; } -bool TrafficLightModule::hasTrafficLightCircleColor( - const autoware_perception_msgs::msg::TrafficSignal & tl_state, const uint8_t & lamp_color) const -{ - const auto it_lamp = - std::find_if(tl_state.elements.begin(), tl_state.elements.end(), [&lamp_color](const auto & x) { - return x.shape == TrafficSignalElement::CIRCLE && x.color == lamp_color; - }); - - return it_lamp != tl_state.elements.end(); -} - -bool TrafficLightModule::hasTrafficLightShape( - const autoware_perception_msgs::msg::TrafficSignal & tl_state, const uint8_t & lamp_shape) const -{ - const auto it_lamp = std::find_if( - tl_state.elements.begin(), tl_state.elements.end(), - [&lamp_shape](const auto & x) { return x.shape == lamp_shape; }); - - return it_lamp != tl_state.elements.end(); -} - } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_traffic_light_module/src/scene.hpp index c7b2472289bf5..102ddbe2e9fa8 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.hpp @@ -88,8 +88,6 @@ class TrafficLightModule : public SceneModuleInterface private: bool isStopSignal(); - bool isTrafficSignalStop(const TrafficSignal & tl_state) const; - autoware_auto_planning_msgs::msg::PathWithLaneId insertStopPose( const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const size_t & insert_target_point_idx, const Eigen::Vector2d & target_point, @@ -97,10 +95,6 @@ class TrafficLightModule : public SceneModuleInterface bool isPassthrough(const double & signed_arc_length) const; - bool hasTrafficLightCircleColor(const TrafficSignal & tl_state, const uint8_t & lamp_color) const; - - bool hasTrafficLightShape(const TrafficSignal & tl_state, const uint8_t & lamp_shape) const; - bool findValidTrafficSignal(TrafficSignalStamped & valid_traffic_signal) const; bool isTrafficSignalTimedOut() const; From 55fe7ffb8e05cbcd252b3f2b6ff8223336ee852d Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 9 Jan 2024 13:17:40 +0900 Subject: [PATCH 202/276] fix(crosswalk): stopping besides the stop line (#6015) * stopping besides the stop line Signed-off-by: Yuki Takagi --- .../src/scene_crosswalk.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index d10fc35a5a6f4..0dc7b78b6fe46 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -393,7 +393,7 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( return {}; } - // Check if the ego should stop beyond the stop line. + // Check if the ego should stop at the stop line or the other points. const bool stop_at_stop_line = dist_ego_to_stop < nearest_stop_info->second && nearest_stop_info->second < dist_ego_to_stop + planner_param_.far_object_threshold; @@ -404,9 +404,9 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( return createStopFactor(*default_stop_pose, stop_factor_points); } } else { - // Stop beyond the stop line const auto stop_pose = calcLongitudinalOffsetPose( - ego_path.points, nearest_stop_info->first, planner_param_.stop_distance_from_object); + ego_path.points, nearest_stop_info->first, + -base_link2front - planner_param_.stop_distance_from_object); if (stop_pose) { return createStopFactor(*stop_pose, stop_factor_points); } From c67b03235266ca41f52e0877e70ca2e237027b47 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Tue, 9 Jan 2024 05:06:58 +0000 Subject: [PATCH 203/276] fix(autoware_auto_common): move headers to a separate directory (#5919) * fix(autoware_auto_common): move headers to a separate directory Signed-off-by: Esteve Fernandez * style(pre-commit): autofix --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- common/autoware_auto_common/design/comparisons.md | 4 ++-- .../{ => autoware_auto_common}/common/type_traits.hpp | 10 +++++----- .../{ => autoware_auto_common}/common/types.hpp | 10 +++++----- .../common/visibility_control.hpp | 6 +++--- .../helper_functions/angle_utils.hpp | 6 +++--- .../helper_functions/bool_comparisons.hpp | 8 ++++---- .../helper_functions/byte_reader.hpp | 6 +++--- .../helper_functions/crtp.hpp | 6 +++--- .../helper_functions/float_comparisons.hpp | 6 +++--- .../helper_functions/mahalanobis_distance.hpp | 6 +++--- .../helper_functions/message_adapters.hpp | 6 +++--- .../helper_functions/template_utils.hpp | 8 ++++---- .../helper_functions/type_name.hpp | 8 ++++---- common/autoware_auto_common/test/test_angle_utils.cpp | 4 ++-- .../test/test_bool_comparisons.cpp | 2 +- common/autoware_auto_common/test/test_byte_reader.cpp | 7 ++++--- .../test/test_float_comparisons.cpp | 2 +- .../test/test_mahalanobis_distance.cpp | 4 ++-- .../test/test_message_field_adapters.cpp | 2 +- .../autoware_auto_common/test/test_template_utils.cpp | 2 +- common/autoware_auto_common/test/test_type_name.cpp | 4 ++-- common/autoware_auto_common/test/test_type_traits.cpp | 4 ++-- .../include/autoware_auto_geometry/common_2d.hpp | 2 +- .../include/autoware_auto_geometry/convex_hull.hpp | 2 +- .../include/autoware_auto_geometry/hull_pockets.hpp | 2 +- .../include/autoware_auto_geometry/interval.hpp | 4 ++-- .../include/autoware_auto_geometry/lookup_table.hpp | 3 ++- .../include/autoware_auto_geometry/spatial_hash.hpp | 2 +- .../autoware_auto_geometry/spatial_hash_config.hpp | 4 ++-- .../autoware_auto_geometry/test/src/lookup_table.cpp | 2 +- .../object_detection/object_polygon_display_base.hpp | 4 ++-- .../src/common/color_alpha_property.cpp | 2 +- .../autoware_auto_tf2/tf2_autoware_auto_msgs.hpp | 2 +- common/fake_test_node/test/test_fake_test_node.cpp | 2 +- .../src/frenet_planner/frenet_planner.cpp | 2 +- .../sim_model_delay_steer_map_acc_geared.hpp | 2 +- 36 files changed, 79 insertions(+), 77 deletions(-) rename common/autoware_auto_common/include/{ => autoware_auto_common}/common/type_traits.hpp (96%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/common/types.hpp (93%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/common/visibility_control.hpp (88%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/helper_functions/angle_utils.hpp (89%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/helper_functions/bool_comparisons.hpp (85%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/helper_functions/byte_reader.hpp (90%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/helper_functions/crtp.hpp (88%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/helper_functions/float_comparisons.hpp (95%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/helper_functions/mahalanobis_distance.hpp (92%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/helper_functions/message_adapters.hpp (94%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/helper_functions/template_utils.hpp (91%) rename common/autoware_auto_common/include/{ => autoware_auto_common}/helper_functions/type_name.hpp (84%) diff --git a/common/autoware_auto_common/design/comparisons.md b/common/autoware_auto_common/design/comparisons.md index f3a7eb5e58429..3d00f77c1b0c3 100644 --- a/common/autoware_auto_common/design/comparisons.md +++ b/common/autoware_auto_common/design/comparisons.md @@ -22,8 +22,8 @@ The `exclusive_or` function will test whether two values cast to different boole ## Example Usage ```c++ -#include "common/bool_comparisons.hpp" -#include "common/float_comparisons.hpp" +#include "autoware_auto_common/common/bool_comparisons.hpp" +#include "autoware_auto_common/common/float_comparisons.hpp" #include diff --git a/common/autoware_auto_common/include/common/type_traits.hpp b/common/autoware_auto_common/include/autoware_auto_common/common/type_traits.hpp similarity index 96% rename from common/autoware_auto_common/include/common/type_traits.hpp rename to common/autoware_auto_common/include/autoware_auto_common/common/type_traits.hpp index 7087ed1e81181..66f382f081b33 100644 --- a/common/autoware_auto_common/include/common/type_traits.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/common/type_traits.hpp @@ -14,15 +14,15 @@ // // Developed by Apex.AI, Inc. -#include -#include +#include "autoware_auto_common/common/types.hpp" +#include "autoware_auto_common/common/visibility_control.hpp" #include #include #include -#ifndef COMMON__TYPE_TRAITS_HPP_ -#define COMMON__TYPE_TRAITS_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__COMMON__TYPE_TRAITS_HPP_ +#define AUTOWARE_AUTO_COMMON__COMMON__TYPE_TRAITS_HPP_ namespace autoware { @@ -219,4 +219,4 @@ struct intersect } // namespace common } // namespace autoware -#endif // COMMON__TYPE_TRAITS_HPP_ +#endif // AUTOWARE_AUTO_COMMON__COMMON__TYPE_TRAITS_HPP_ diff --git a/common/autoware_auto_common/include/common/types.hpp b/common/autoware_auto_common/include/autoware_auto_common/common/types.hpp similarity index 93% rename from common/autoware_auto_common/include/common/types.hpp rename to common/autoware_auto_common/include/autoware_auto_common/common/types.hpp index 3f3e444c1aa8c..1c7dfe48c7ec8 100644 --- a/common/autoware_auto_common/include/common/types.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/common/types.hpp @@ -16,11 +16,11 @@ /// \file /// \brief This file includes common type definition -#ifndef COMMON__TYPES_HPP_ -#define COMMON__TYPES_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__COMMON__TYPES_HPP_ +#define AUTOWARE_AUTO_COMMON__COMMON__TYPES_HPP_ -#include "common/visibility_control.hpp" -#include "helper_functions/float_comparisons.hpp" +#include "autoware_auto_common/common/visibility_control.hpp" +#include "autoware_auto_common/helper_functions/float_comparisons.hpp" #include #include @@ -122,4 +122,4 @@ using void_t = void; } // namespace common } // namespace autoware -#endif // COMMON__TYPES_HPP_ +#endif // AUTOWARE_AUTO_COMMON__COMMON__TYPES_HPP_ diff --git a/common/autoware_auto_common/include/common/visibility_control.hpp b/common/autoware_auto_common/include/autoware_auto_common/common/visibility_control.hpp similarity index 88% rename from common/autoware_auto_common/include/common/visibility_control.hpp rename to common/autoware_auto_common/include/autoware_auto_common/common/visibility_control.hpp index 0a988d6407dfa..33834fd9ccfed 100644 --- a/common/autoware_auto_common/include/common/visibility_control.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/common/visibility_control.hpp @@ -14,8 +14,8 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#ifndef COMMON__VISIBILITY_CONTROL_HPP_ -#define COMMON__VISIBILITY_CONTROL_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__COMMON__VISIBILITY_CONTROL_HPP_ +#define AUTOWARE_AUTO_COMMON__COMMON__VISIBILITY_CONTROL_HPP_ #if defined(_MSC_VER) && defined(_WIN64) #if defined(COMMON_BUILDING_DLL) || defined(COMMON_EXPORTS) @@ -35,4 +35,4 @@ #error "Unsupported Build Configuration" #endif // _MSC_VER -#endif // COMMON__VISIBILITY_CONTROL_HPP_ +#endif // AUTOWARE_AUTO_COMMON__COMMON__VISIBILITY_CONTROL_HPP_ diff --git a/common/autoware_auto_common/include/helper_functions/angle_utils.hpp b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/angle_utils.hpp similarity index 89% rename from common/autoware_auto_common/include/helper_functions/angle_utils.hpp rename to common/autoware_auto_common/include/autoware_auto_common/helper_functions/angle_utils.hpp index 6cca2440d5680..ea974774dd9d5 100644 --- a/common/autoware_auto_common/include/helper_functions/angle_utils.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/angle_utils.hpp @@ -14,8 +14,8 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#ifndef HELPER_FUNCTIONS__ANGLE_UTILS_HPP_ -#define HELPER_FUNCTIONS__ANGLE_UTILS_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__ANGLE_UTILS_HPP_ +#define AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__ANGLE_UTILS_HPP_ #include #include @@ -63,4 +63,4 @@ constexpr T wrap_angle(T angle) noexcept } // namespace common } // namespace autoware -#endif // HELPER_FUNCTIONS__ANGLE_UTILS_HPP_ +#endif // AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__ANGLE_UTILS_HPP_ diff --git a/common/autoware_auto_common/include/helper_functions/bool_comparisons.hpp b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/bool_comparisons.hpp similarity index 85% rename from common/autoware_auto_common/include/helper_functions/bool_comparisons.hpp rename to common/autoware_auto_common/include/autoware_auto_common/helper_functions/bool_comparisons.hpp index c6bf09365af4f..45da098ad0066 100644 --- a/common/autoware_auto_common/include/helper_functions/bool_comparisons.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/bool_comparisons.hpp @@ -18,10 +18,10 @@ // FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS // IN THE SOFTWARE. -#ifndef HELPER_FUNCTIONS__BOOL_COMPARISONS_HPP_ -#define HELPER_FUNCTIONS__BOOL_COMPARISONS_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__BOOL_COMPARISONS_HPP_ +#define AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__BOOL_COMPARISONS_HPP_ -#include "common/types.hpp" +#include "autoware_auto_common/common/types.hpp" namespace autoware { @@ -47,4 +47,4 @@ types::bool8_t exclusive_or(const T & a, const T & b) } // namespace common } // namespace autoware -#endif // HELPER_FUNCTIONS__BOOL_COMPARISONS_HPP_ +#endif // AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__BOOL_COMPARISONS_HPP_ diff --git a/common/autoware_auto_common/include/helper_functions/byte_reader.hpp b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/byte_reader.hpp similarity index 90% rename from common/autoware_auto_common/include/helper_functions/byte_reader.hpp rename to common/autoware_auto_common/include/autoware_auto_common/helper_functions/byte_reader.hpp index d9e55c4ecfbfe..3852361caebeb 100644 --- a/common/autoware_auto_common/include/helper_functions/byte_reader.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/byte_reader.hpp @@ -16,8 +16,8 @@ /// \file /// \brief This file includes common helper functions -#ifndef HELPER_FUNCTIONS__BYTE_READER_HPP_ -#define HELPER_FUNCTIONS__BYTE_READER_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__BYTE_READER_HPP_ +#define AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__BYTE_READER_HPP_ #include #include @@ -70,4 +70,4 @@ class ByteReader } // namespace common } // namespace autoware -#endif // HELPER_FUNCTIONS__BYTE_READER_HPP_ +#endif // AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__BYTE_READER_HPP_ diff --git a/common/autoware_auto_common/include/helper_functions/crtp.hpp b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/crtp.hpp similarity index 88% rename from common/autoware_auto_common/include/helper_functions/crtp.hpp rename to common/autoware_auto_common/include/autoware_auto_common/helper_functions/crtp.hpp index 0e8110a9a3bb9..e75674eb73c70 100644 --- a/common/autoware_auto_common/include/helper_functions/crtp.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/crtp.hpp @@ -16,8 +16,8 @@ /// \file /// \brief This file includes common helper functions -#ifndef HELPER_FUNCTIONS__CRTP_HPP_ -#define HELPER_FUNCTIONS__CRTP_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__CRTP_HPP_ +#define AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__CRTP_HPP_ namespace autoware { @@ -49,4 +49,4 @@ class crtp } // namespace common } // namespace autoware -#endif // HELPER_FUNCTIONS__CRTP_HPP_ +#endif // AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__CRTP_HPP_ diff --git a/common/autoware_auto_common/include/helper_functions/float_comparisons.hpp b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/float_comparisons.hpp similarity index 95% rename from common/autoware_auto_common/include/helper_functions/float_comparisons.hpp rename to common/autoware_auto_common/include/autoware_auto_common/helper_functions/float_comparisons.hpp index de1f459f21d0a..1a64fe71a1720 100644 --- a/common/autoware_auto_common/include/helper_functions/float_comparisons.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/float_comparisons.hpp @@ -18,8 +18,8 @@ // FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS // IN THE SOFTWARE. -#ifndef HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_ -#define HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_ +#define AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_ #include #include @@ -146,4 +146,4 @@ bool approx_eq(const T & a, const T & b, const T & abs_eps, const T & rel_eps) } // namespace common } // namespace autoware -#endif // HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_ +#endif // AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__FLOAT_COMPARISONS_HPP_ diff --git a/common/autoware_auto_common/include/helper_functions/mahalanobis_distance.hpp b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/mahalanobis_distance.hpp similarity index 92% rename from common/autoware_auto_common/include/helper_functions/mahalanobis_distance.hpp rename to common/autoware_auto_common/include/autoware_auto_common/helper_functions/mahalanobis_distance.hpp index fb9bdccf32b25..70c29eaf220d8 100644 --- a/common/autoware_auto_common/include/helper_functions/mahalanobis_distance.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/mahalanobis_distance.hpp @@ -14,8 +14,8 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#ifndef HELPER_FUNCTIONS__MAHALANOBIS_DISTANCE_HPP_ -#define HELPER_FUNCTIONS__MAHALANOBIS_DISTANCE_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__MAHALANOBIS_DISTANCE_HPP_ +#define AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__MAHALANOBIS_DISTANCE_HPP_ #include @@ -69,4 +69,4 @@ types::float32_t calculate_mahalanobis_distance( } // namespace common } // namespace autoware -#endif // HELPER_FUNCTIONS__MAHALANOBIS_DISTANCE_HPP_ +#endif // AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__MAHALANOBIS_DISTANCE_HPP_ diff --git a/common/autoware_auto_common/include/helper_functions/message_adapters.hpp b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/message_adapters.hpp similarity index 94% rename from common/autoware_auto_common/include/helper_functions/message_adapters.hpp rename to common/autoware_auto_common/include/autoware_auto_common/helper_functions/message_adapters.hpp index 352ef7c7b65d5..d3bda57b3374f 100644 --- a/common/autoware_auto_common/include/helper_functions/message_adapters.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/message_adapters.hpp @@ -16,8 +16,8 @@ /// \file /// \brief This file includes common helper functions -#ifndef HELPER_FUNCTIONS__MESSAGE_ADAPTERS_HPP_ -#define HELPER_FUNCTIONS__MESSAGE_ADAPTERS_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__MESSAGE_ADAPTERS_HPP_ +#define AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__MESSAGE_ADAPTERS_HPP_ #include @@ -112,4 +112,4 @@ TimeStamp get_stamp(const T & msg) noexcept } // namespace common } // namespace autoware -#endif // HELPER_FUNCTIONS__MESSAGE_ADAPTERS_HPP_ +#endif // AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__MESSAGE_ADAPTERS_HPP_ diff --git a/common/autoware_auto_common/include/helper_functions/template_utils.hpp b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/template_utils.hpp similarity index 91% rename from common/autoware_auto_common/include/helper_functions/template_utils.hpp rename to common/autoware_auto_common/include/autoware_auto_common/helper_functions/template_utils.hpp index b39931a3fd15a..0360908509618 100644 --- a/common/autoware_auto_common/include/helper_functions/template_utils.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/template_utils.hpp @@ -14,10 +14,10 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#ifndef HELPER_FUNCTIONS__TEMPLATE_UTILS_HPP_ -#define HELPER_FUNCTIONS__TEMPLATE_UTILS_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__TEMPLATE_UTILS_HPP_ +#define AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__TEMPLATE_UTILS_HPP_ -#include +#include "autoware_auto_common/common/types.hpp" #include @@ -72,4 +72,4 @@ struct expression_valid_with_return< } // namespace helper_functions } // namespace common } // namespace autoware -#endif // HELPER_FUNCTIONS__TEMPLATE_UTILS_HPP_ +#endif // AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__TEMPLATE_UTILS_HPP_ diff --git a/common/autoware_auto_common/include/helper_functions/type_name.hpp b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/type_name.hpp similarity index 84% rename from common/autoware_auto_common/include/helper_functions/type_name.hpp rename to common/autoware_auto_common/include/autoware_auto_common/helper_functions/type_name.hpp index a95834373d552..106cede1f2f5a 100644 --- a/common/autoware_auto_common/include/helper_functions/type_name.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/type_name.hpp @@ -14,10 +14,10 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#ifndef HELPER_FUNCTIONS__TYPE_NAME_HPP_ -#define HELPER_FUNCTIONS__TYPE_NAME_HPP_ +#ifndef AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__TYPE_NAME_HPP_ +#define AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__TYPE_NAME_HPP_ -#include +#include "autoware_auto_common/common/visibility_control.hpp" #include #include @@ -53,4 +53,4 @@ COMMON_PUBLIC std::string get_type_name(const T &) } // namespace helper_functions } // namespace autoware -#endif // HELPER_FUNCTIONS__TYPE_NAME_HPP_ +#endif // AUTOWARE_AUTO_COMMON__HELPER_FUNCTIONS__TYPE_NAME_HPP_ diff --git a/common/autoware_auto_common/test/test_angle_utils.cpp b/common/autoware_auto_common/test/test_angle_utils.cpp index 031ae144139aa..810c302845daf 100644 --- a/common/autoware_auto_common/test/test_angle_utils.cpp +++ b/common/autoware_auto_common/test/test_angle_utils.cpp @@ -14,8 +14,8 @@ // // Developed by Apex.AI, Inc. -#include -#include +#include "autoware_auto_common/common/types.hpp" +#include "autoware_auto_common/helper_functions/angle_utils.hpp" #include diff --git a/common/autoware_auto_common/test/test_bool_comparisons.cpp b/common/autoware_auto_common/test/test_bool_comparisons.cpp index 67c1c8ddbf9aa..a84d65e569692 100644 --- a/common/autoware_auto_common/test/test_bool_comparisons.cpp +++ b/common/autoware_auto_common/test/test_bool_comparisons.cpp @@ -18,7 +18,7 @@ // FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS // IN THE SOFTWARE. -#include "helper_functions/bool_comparisons.hpp" +#include "autoware_auto_common/helper_functions/bool_comparisons.hpp" #include diff --git a/common/autoware_auto_common/test/test_byte_reader.cpp b/common/autoware_auto_common/test/test_byte_reader.cpp index c83d06c6e8132..a5ab8743f7ed4 100644 --- a/common/autoware_auto_common/test/test_byte_reader.cpp +++ b/common/autoware_auto_common/test/test_byte_reader.cpp @@ -14,9 +14,10 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include "common/types.hpp" -#include "gtest/gtest.h" -#include "helper_functions/byte_reader.hpp" +#include "autoware_auto_common/common/types.hpp" +#include "autoware_auto_common/helper_functions/byte_reader.hpp" + +#include #include diff --git a/common/autoware_auto_common/test/test_float_comparisons.cpp b/common/autoware_auto_common/test/test_float_comparisons.cpp index d292dc0a0cb20..37d3afdc177d5 100644 --- a/common/autoware_auto_common/test/test_float_comparisons.cpp +++ b/common/autoware_auto_common/test/test_float_comparisons.cpp @@ -18,7 +18,7 @@ // FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS // IN THE SOFTWARE. -#include "helper_functions/float_comparisons.hpp" +#include "autoware_auto_common/helper_functions/float_comparisons.hpp" #include diff --git a/common/autoware_auto_common/test/test_mahalanobis_distance.cpp b/common/autoware_auto_common/test/test_mahalanobis_distance.cpp index 262599180abb6..2015a85bc2bc8 100644 --- a/common/autoware_auto_common/test/test_mahalanobis_distance.cpp +++ b/common/autoware_auto_common/test/test_mahalanobis_distance.cpp @@ -13,8 +13,8 @@ // limitations under the License. // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include -#include +#include "autoware_auto_common/common/types.hpp" +#include "autoware_auto_common/helper_functions/mahalanobis_distance.hpp" #include diff --git a/common/autoware_auto_common/test/test_message_field_adapters.cpp b/common/autoware_auto_common/test/test_message_field_adapters.cpp index 34974c1cda9a6..c35f0ff826995 100644 --- a/common/autoware_auto_common/test/test_message_field_adapters.cpp +++ b/common/autoware_auto_common/test/test_message_field_adapters.cpp @@ -14,7 +14,7 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include +#include "autoware_auto_common/helper_functions/message_adapters.hpp" #include diff --git a/common/autoware_auto_common/test/test_template_utils.cpp b/common/autoware_auto_common/test/test_template_utils.cpp index 9c9ca9ae4b5f2..a670aaab83cfa 100644 --- a/common/autoware_auto_common/test/test_template_utils.cpp +++ b/common/autoware_auto_common/test/test_template_utils.cpp @@ -14,7 +14,7 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include +#include "autoware_auto_common/helper_functions/template_utils.hpp" #include diff --git a/common/autoware_auto_common/test/test_type_name.cpp b/common/autoware_auto_common/test/test_type_name.cpp index 1fb60d838f307..4ada59b4fb2e1 100644 --- a/common/autoware_auto_common/test/test_type_name.cpp +++ b/common/autoware_auto_common/test/test_type_name.cpp @@ -14,8 +14,8 @@ // // Developed by Apex.AI, Inc. -#include -#include +#include "autoware_auto_common/common/types.hpp" +#include "autoware_auto_common/helper_functions/type_name.hpp" #include diff --git a/common/autoware_auto_common/test/test_type_traits.cpp b/common/autoware_auto_common/test/test_type_traits.cpp index 7203ab8d649ee..92d01b3d84d51 100644 --- a/common/autoware_auto_common/test/test_type_traits.cpp +++ b/common/autoware_auto_common/test/test_type_traits.cpp @@ -14,8 +14,8 @@ // // Developed by Apex.AI, Inc. -#include -#include +#include "autoware_auto_common/common/type_traits.hpp" +#include "autoware_auto_common/common/types.hpp" #include diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/common_2d.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/common_2d.hpp index da7121bf4e9b5..e3c2e58c9f80e 100644 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/common_2d.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/common_2d.hpp @@ -21,7 +21,7 @@ #include "autoware_auto_geometry/interval.hpp" -#include +#include #include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/convex_hull.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/convex_hull.hpp index e566e2e43ae3e..ae81c55ad6b55 100644 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/convex_hull.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/convex_hull.hpp @@ -23,7 +23,7 @@ #include "autoware_auto_geometry/common_2d.hpp" -#include +#include // lint -e537 NOLINT pclint vs cpplint #include diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/hull_pockets.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/hull_pockets.hpp index fd04c0266e065..cd9fd49f71635 100644 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/hull_pockets.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/hull_pockets.hpp @@ -23,7 +23,7 @@ #include "autoware_auto_geometry/common_2d.hpp" -#include +#include #include #include diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/interval.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/interval.hpp index 17e2789ac0325..54be2c32b1d05 100644 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/interval.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/interval.hpp @@ -21,8 +21,8 @@ #ifndef AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_ #define AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_ -#include "common/types.hpp" -#include "helper_functions/float_comparisons.hpp" +#include +#include #include #include diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/lookup_table.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/lookup_table.hpp index c689638aa2bd9..7b8867ca096ae 100644 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/lookup_table.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/lookup_table.hpp @@ -21,7 +21,8 @@ #define AUTOWARE_AUTO_GEOMETRY__LOOKUP_TABLE_HPP_ #include "autoware_auto_geometry/interval.hpp" -#include "common/types.hpp" + +#include #include #include diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash.hpp index c160685fb0f8c..8936e2c17d779 100644 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash.hpp @@ -23,7 +23,7 @@ #include "autoware_auto_geometry/spatial_hash_config.hpp" #include "autoware_auto_geometry/visibility_control.hpp" -#include +#include #include #include diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash_config.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash_config.hpp index 926b170f807c2..24c4d6e879d4a 100644 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash_config.hpp +++ b/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash_config.hpp @@ -22,9 +22,9 @@ #include "autoware_auto_geometry/common_2d.hpp" #include "autoware_auto_geometry/visibility_control.hpp" -#include "helper_functions/crtp.hpp" -#include +#include +#include #include #include diff --git a/common/autoware_auto_geometry/test/src/lookup_table.cpp b/common/autoware_auto_geometry/test/src/lookup_table.cpp index 092f8a04f2540..81865656c55b5 100644 --- a/common/autoware_auto_geometry/test/src/lookup_table.cpp +++ b/common/autoware_auto_geometry/test/src/lookup_table.cpp @@ -16,7 +16,7 @@ #include "autoware_auto_geometry/lookup_table.hpp" -#include +#include #include diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp index 9157dffe97785..223611520b2fc 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp @@ -14,12 +14,12 @@ #ifndef OBJECT_DETECTION__OBJECT_POLYGON_DISPLAY_BASE_HPP_ #define OBJECT_DETECTION__OBJECT_POLYGON_DISPLAY_BASE_HPP_ -#include "rviz_common/properties/enum_property.hpp" +#include "common/color_alpha_property.hpp" -#include #include #include #include +#include #include #include #include diff --git a/common/autoware_auto_perception_rviz_plugin/src/common/color_alpha_property.cpp b/common/autoware_auto_perception_rviz_plugin/src/common/color_alpha_property.cpp index ac9c5af4ddeef..57a42c95f9d34 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/common/color_alpha_property.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/common/color_alpha_property.cpp @@ -14,7 +14,7 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include +#include "common/color_alpha_property.hpp" #include diff --git a/common/autoware_auto_tf2/include/autoware_auto_tf2/tf2_autoware_auto_msgs.hpp b/common/autoware_auto_tf2/include/autoware_auto_tf2/tf2_autoware_auto_msgs.hpp index b35eb6e93ce6e..50c16ba8eaf7d 100644 --- a/common/autoware_auto_tf2/include/autoware_auto_tf2/tf2_autoware_auto_msgs.hpp +++ b/common/autoware_auto_tf2/include/autoware_auto_tf2/tf2_autoware_auto_msgs.hpp @@ -17,7 +17,7 @@ #ifndef AUTOWARE_AUTO_TF2__TF2_AUTOWARE_AUTO_MSGS_HPP_ #define AUTOWARE_AUTO_TF2__TF2_AUTOWARE_AUTO_MSGS_HPP_ -#include +#include #include #include diff --git a/common/fake_test_node/test/test_fake_test_node.cpp b/common/fake_test_node/test/test_fake_test_node.cpp index d66d0fed3033c..e065f332b75e4 100644 --- a/common/fake_test_node/test/test_fake_test_node.cpp +++ b/common/fake_test_node/test/test_fake_test_node.cpp @@ -17,7 +17,7 @@ /// \copyright Copyright 2021 Apex.AI, Inc. /// All rights reserved. -#include +#include #include #include diff --git a/planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp b/planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp index 3368c49459a55..a4ff1db77e8a1 100644 --- a/planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp +++ b/planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp @@ -14,11 +14,11 @@ #include "frenet_planner/frenet_planner.hpp" +#include #include #include #include #include -#include #include #include diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp index 2cc33f9b5f82b..fecd3c2bc8be4 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp @@ -21,7 +21,7 @@ #include "simple_planning_simulator/utils/csv_loader.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" -#include +#include #include #include From e27b7564f2c9af5cf2527cb12ed5f890e919ad35 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 9 Jan 2024 15:20:06 +0900 Subject: [PATCH 204/276] feat(map_based_prediction): cope with consecutive crosswalks (#6009) * ready for consecutive crosswalks Signed-off-by: Yuki Takagi --- .../src/map_based_prediction_node.cpp | 167 +++++++++--------- 1 file changed, 86 insertions(+), 81 deletions(-) diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index 0091fc6bc38cb..75c1d61e0a19c 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -415,17 +415,21 @@ bool withinRoadLanelet( } boost::optional isReachableCrosswalkEdgePoints( - const TrackedObject & object, const CrosswalkEdgePoints & edge_points, - const lanelet::LaneletMapPtr & lanelet_map_ptr, const double time_horizon, - const double min_object_vel) + const TrackedObject & object, const lanelet::ConstLanelet & target_crosswalk, + const CrosswalkEdgePoints & edge_points, const lanelet::LaneletMapPtr & lanelet_map_ptr, + const double time_horizon, const double min_object_vel) { using Point = boost::geometry::model::d2::point_xy; - using Line = boost::geometry::model::linestring; const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position; const auto & obj_vel = object.kinematics.twist_with_covariance.twist.linear; const auto yaw = tier4_autoware_utils::getRPY(object.kinematics.pose_with_covariance.pose).z; + lanelet::BasicPoint2d obj_pos_as_lanelet(obj_pos.x, obj_pos.y); + if (boost::geometry::within(obj_pos_as_lanelet, target_crosswalk.polygon2d().basicPolygon())) { + return {}; + } + const auto & p1 = edge_points.front_center_point; const auto & p2 = edge_points.back_center_point; @@ -442,62 +446,66 @@ boost::optional isReachableCrosswalkEdgePoints( const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y); const auto is_stop_object = estimated_velocity < stop_velocity_th; const auto velocity = std::max(min_object_vel, estimated_velocity); - - lanelet::BasicPoint2d search_point(obj_pos.x, obj_pos.y); - // nearest lanelet const auto surrounding_lanelets = lanelet::geometry::findNearest( - lanelet_map_ptr->laneletLayer, search_point, time_horizon * velocity); + lanelet_map_ptr->laneletLayer, obj_pos_as_lanelet, time_horizon * velocity); - bool first_intersect_load = false; - bool second_intersect_load = false; - std::vector intersects_first; - std::vector intersects_second; - for (const auto & lanelet : surrounding_lanelets) { - if (withinLanelet(object, lanelet.second)) { - return {}; - } + const auto isAcrossAnyRoad = [&surrounding_lanelets](const Point & p_src, const Point & p_dst) { + const auto withinAnyCrosswalk = [&surrounding_lanelets](const Point & p) { + for (const auto & lanelet : surrounding_lanelets) { + const lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype); + if ( + (attr.value() == lanelet::AttributeValueString::Crosswalk || + attr.value() == lanelet::AttributeValueString::Walkway) && + boost::geometry::within(p, lanelet.second.polygon2d().basicPolygon())) { + return true; + } + } + return false; + }; - lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype); - if (attr.value() != "road") { - continue; - } + const auto isExist = [](const Point & p, const std::vector & points) { + for (const auto & existingPoint : points) { + if (boost::geometry::distance(p, existingPoint) < 1e-1) { + return true; + } + } + return false; + }; - { - const Line object_to_entry_point{ - {obj_pos.x, obj_pos.y}, {ret.front_center_point.x(), ret.front_center_point.y()}}; - std::vector tmp_intersects; - boost::geometry::intersection( - object_to_entry_point, lanelet.second.polygon2d().basicPolygon(), tmp_intersects); - for (const auto & p : tmp_intersects) { - intersects_first.push_back(p); + std::vector points_of_intersect; + const boost::geometry::model::linestring line{p_src, p_dst}; + for (const auto & lanelet : surrounding_lanelets) { + const lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype); + if (attr.value() != lanelet::AttributeValueString::Road) { + continue; } - } - { - const Line object_to_entry_point{ - {obj_pos.x, obj_pos.y}, {ret.back_center_point.x(), ret.back_center_point.y()}}; std::vector tmp_intersects; boost::geometry::intersection( - object_to_entry_point, lanelet.second.polygon2d().basicPolygon(), tmp_intersects); + line, lanelet.second.polygon2d().basicPolygon(), tmp_intersects); for (const auto & p : tmp_intersects) { - intersects_second.push_back(p); + if (isExist(p, points_of_intersect) || withinAnyCrosswalk(p)) { + continue; + } + points_of_intersect.push_back(p); + if (points_of_intersect.size() >= 2) { + return true; + } } } - } - - if (1 < intersects_first.size()) { - first_intersect_load = true; - } + return false; + }; - if (1 < intersects_second.size()) { - second_intersect_load = true; - } + const bool first_intersects_road = isAcrossAnyRoad( + {obj_pos.x, obj_pos.y}, {ret.front_center_point.x(), ret.front_center_point.y()}); + const bool second_intersects_road = + isAcrossAnyRoad({obj_pos.x, obj_pos.y}, {ret.back_center_point.x(), ret.back_center_point.y()}); - if (first_intersect_load && second_intersect_load) { + if (first_intersects_road && second_intersects_road) { return {}; } - if (first_intersect_load && !second_intersect_load) { + if (first_intersects_road && !second_intersects_road) { ret.swap(); } @@ -1197,48 +1205,45 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( predicted_object.kinematics.predicted_paths.push_back(predicted_path); } } + } + // try to find the edge points for all crosswalks and generate path to the crosswalk edge + for (const auto & crosswalk : crosswalks_) { + const auto edge_points = getCrosswalkEdgePoints(crosswalk); + + const auto reachable_first = hasPotentialToReach( + object, edge_points.front_center_point, edge_points.front_right_point, + edge_points.front_left_point, prediction_time_horizon_, min_crosswalk_user_velocity_, + max_crosswalk_user_delta_yaw_threshold_for_lanelet_); + const auto reachable_second = hasPotentialToReach( + object, edge_points.back_center_point, edge_points.back_right_point, + edge_points.back_left_point, prediction_time_horizon_, min_crosswalk_user_velocity_, + max_crosswalk_user_delta_yaw_threshold_for_lanelet_); + + if (!reachable_first && !reachable_second) { + continue; + } - // If the object is not crossing the crosswalk, not in the road lanelets, try to find the edge - // points for all crosswalks and generate path to the crosswalk edge - } else { - for (const auto & crosswalk : crosswalks_) { - const auto edge_points = getCrosswalkEdgePoints(crosswalk); - - const auto reachable_first = hasPotentialToReach( - object, edge_points.front_center_point, edge_points.front_right_point, - edge_points.front_left_point, prediction_time_horizon_, min_crosswalk_user_velocity_, - max_crosswalk_user_delta_yaw_threshold_for_lanelet_); - const auto reachable_second = hasPotentialToReach( - object, edge_points.back_center_point, edge_points.back_right_point, - edge_points.back_left_point, prediction_time_horizon_, min_crosswalk_user_velocity_, - max_crosswalk_user_delta_yaw_threshold_for_lanelet_); - - if (!reachable_first && !reachable_second) { - continue; - } - - const auto reachable_crosswalk = isReachableCrosswalkEdgePoints( - object, edge_points, lanelet_map_ptr_, prediction_time_horizon_, - min_crosswalk_user_velocity_); - - if (!reachable_crosswalk) { - continue; - } + const auto reachable_crosswalk = isReachableCrosswalkEdgePoints( + object, crosswalk, edge_points, lanelet_map_ptr_, prediction_time_horizon_, + min_crosswalk_user_velocity_); - PredictedPath predicted_path = - path_generator_->generatePathForCrosswalkUser(object, reachable_crosswalk.get()); - predicted_path.confidence = 1.0; + if (!reachable_crosswalk) { + continue; + } - if (predicted_path.path.empty()) { - continue; - } - // If the predicted path to the crosswalk is crossing the fence, don't use it - if (doesPathCrossAnyFence(predicted_path)) { - continue; - } + PredictedPath predicted_path = + path_generator_->generatePathForCrosswalkUser(object, reachable_crosswalk.get()); + predicted_path.confidence = 1.0; - predicted_object.kinematics.predicted_paths.push_back(predicted_path); + if (predicted_path.path.empty()) { + continue; } + // If the predicted path to the crosswalk is crossing the fence, don't use it + if (doesPathCrossAnyFence(predicted_path)) { + continue; + } + + predicted_object.kinematics.predicted_paths.push_back(predicted_path); } const auto n_path = predicted_object.kinematics.predicted_paths.size(); From bd54e48129371ac3b912aca51d44c1933fd06315 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Tue, 9 Jan 2024 17:28:01 +0900 Subject: [PATCH 205/276] refactor(map_projection_loader): make important part a library (#5992) * refactor(map_projection_loader): make important part a library Signed-off-by: kminoda * style(pre-commit): autofix * fix: add const Signed-off-by: kminoda * fix: fix function arguments 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> --- .../map_projection_loader.hpp | 2 + .../src/map_projection_loader.cpp | 45 ++++++++++++------- 2 files changed, 31 insertions(+), 16 deletions(-) diff --git a/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp b/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp index 16442eb43c740..54e794e2742bf 100644 --- a/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp +++ b/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp @@ -23,6 +23,8 @@ #include 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); class MapProjectionLoader : public rclcpp::Node { diff --git a/map/map_projection_loader/src/map_projection_loader.cpp b/map/map_projection_loader/src/map_projection_loader.cpp index 9fdba288601cc..5966baaed8383 100644 --- a/map/map_projection_loader/src/map_projection_loader.cpp +++ b/map/map_projection_loader/src/map_projection_loader.cpp @@ -20,6 +20,7 @@ #include +#include #include tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename) @@ -55,28 +56,40 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & fi return msg; } -MapProjectionLoader::MapProjectionLoader() : Node("map_projection_loader") +tier4_map_msgs::msg::MapProjectorInfo load_map_projector_info( + const std::string & yaml_filename, const std::string & lanelet2_map_filename) { - std::string yaml_filename = this->declare_parameter("map_projector_info_path"); - std::string lanelet2_map_filename = this->declare_parameter("lanelet2_map_path"); - std::ifstream file(yaml_filename); - tier4_map_msgs::msg::MapProjectorInfo msg; - bool use_yaml_file = file.is_open(); - if (use_yaml_file) { - RCLCPP_INFO(this->get_logger(), "Load %s", yaml_filename.c_str()); + if (std::filesystem::exists(yaml_filename)) { + std::cout << "Load " << yaml_filename << std::endl; msg = load_info_from_yaml(yaml_filename); - } else { - RCLCPP_INFO(this->get_logger(), "Load %s", lanelet2_map_filename.c_str()); - RCLCPP_WARN( - this->get_logger(), - "DEPRECATED WARNING: Loading map projection info from lanelet2 map may soon be deleted. " - "Please use map_projector_info.yaml instead. For more info, visit " - "https://github.com/autowarefoundation/autoware.universe/blob/main/map/map_projection_loader/" - "README.md"); + } else if (std::filesystem::exists(lanelet2_map_filename)) { + std::cout << "Load " << lanelet2_map_filename << std::endl; + std::cout + << "DEPRECATED WARNING: Loading map projection info from lanelet2 map may soon be deleted. " + "Please use map_projector_info.yaml instead. For more info, visit " + "https://github.com/autowarefoundation/autoware.universe/blob/main/map/" + "map_projection_loader/" + "README.md" + << std::endl; msg = load_info_from_lanelet2_map(lanelet2_map_filename); + } else { + throw std::runtime_error( + "No map projector info files found. Please provide either " + "map_projector_info.yaml or lanelet2_map.osm"); } + return msg; +} + +MapProjectionLoader::MapProjectionLoader() : Node("map_projection_loader") +{ + const std::string yaml_filename = this->declare_parameter("map_projector_info_path"); + const std::string lanelet2_map_filename = + this->declare_parameter("lanelet2_map_path"); + + const tier4_map_msgs::msg::MapProjectorInfo msg = + load_map_projector_info(yaml_filename, lanelet2_map_filename); // Publish the message const auto adaptor = component_interface_utils::NodeAdaptor(this); From 7838b829a92554483b08d300416693ded9ebe1da Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 9 Jan 2024 20:15:43 +0900 Subject: [PATCH 206/276] fix((merge_from_private): fixed first attention lanelet calculation (#6030) Signed-off-by: Mamoru Sobue --- .../src/scene_merge_from_private_road.cpp | 71 ++++++++----------- .../src/scene_merge_from_private_road.hpp | 4 +- 2 files changed, 29 insertions(+), 46 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index f56d0a4adcff7..b929959e43f12 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -108,14 +108,12 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR return false; } + const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; const auto local_footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0); if (!first_conflicting_lanelet_) { - const auto & assigned_lanelet = lanelet_map_ptr->laneletLayer.get(lane_id_); - const auto conflicting_lanelets = - lanelet::utils::getConflictingLanelets(routing_graph_ptr, assigned_lanelet); + const auto conflicting_lanelets = getAttentionLanelets(); first_conflicting_lanelet_ = getFirstConflictingLanelet( - conflicting_lanelets, interpolated_path_info, local_footprint, - planner_data_->vehicle_info_.max_longitudinal_offset_m); + conflicting_lanelets, interpolated_path_info, local_footprint, baselink2front); } if (!first_conflicting_lanelet_) { return false; @@ -123,12 +121,13 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR const auto first_conflicting_lanelet = first_conflicting_lanelet_.value(); const auto first_conflicting_idx_opt = getFirstPointInsidePolygonByFootprint( - first_conflicting_lanelet.polygon3d(), interpolated_path_info, local_footprint, - planner_data_->vehicle_info_.max_longitudinal_offset_m); + first_conflicting_lanelet.polygon3d(), interpolated_path_info, local_footprint, baselink2front); if (!first_conflicting_idx_opt) { return false; } - const auto stopline_idx_ip = first_conflicting_idx_opt.value(); + const auto stopline_idx_ip = static_cast(std::max( + 0, static_cast(first_conflicting_idx_opt.value()) - + static_cast(baselink2front / planner_param_.path_interpolation_ds))); const auto stopline_idx_opt = util::insertPointIndex( interpolated_path_info.path.points.at(stopline_idx_ip).point.pose, path, @@ -139,8 +138,7 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR } const auto stopline_idx = stopline_idx_opt.value(); - debug_data_.virtual_wall_pose = planning_utils::getAheadPose( - stopline_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); + debug_data_.virtual_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); debug_data_.stop_point_pose = path->points.at(stopline_idx).point.pose; /* set stop speed */ @@ -174,46 +172,33 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR return true; } -autoware_auto_planning_msgs::msg::PathWithLaneId -MergeFromPrivateRoadModule::extractPathNearExitOfPrivateRoad( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const double extend_length) +lanelet::ConstLanelets MergeFromPrivateRoadModule::getAttentionLanelets() const { - if (path.points.size() < 2) { - return path; - } - - autoware_auto_planning_msgs::msg::PathWithLaneId private_path = path; - private_path.points.clear(); + const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr(); + const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr(); - double sum_dist = 0.0; - bool prev_has_target_lane_id = false; - for (int i = static_cast(path.points.size()) - 2; i >= 0; i--) { - bool has_target_lane_id = false; - for (const auto path_id : path.points.at(i).lane_ids) { - if (path_id == lane_id_) { - has_target_lane_id = true; + const auto & assigned_lanelet = lanelet_map_ptr->laneletLayer.get(lane_id_); + const auto conflicting_lanelets = + lanelet::utils::getConflictingLanelets(routing_graph_ptr, assigned_lanelet); + lanelet::ConstLanelets sibling_lanelets; + for (const auto & previous_lanelet : routing_graph_ptr->previous(assigned_lanelet)) { + sibling_lanelets.push_back(previous_lanelet); + for (const auto & following_lanelet : routing_graph_ptr->following(previous_lanelet)) { + if (lanelet::utils::contains(sibling_lanelets, following_lanelet)) { + continue; } + sibling_lanelets.push_back(following_lanelet); } - if (has_target_lane_id) { - // add path point with target lane id - // (lanelet with target lane id is exit of private road) - private_path.points.emplace_back(path.points.at(i)); - prev_has_target_lane_id = true; + } + + lanelet::ConstLanelets attention_lanelets; + for (const auto & conflicting_lanelet : conflicting_lanelets) { + if (lanelet::utils::contains(sibling_lanelets, conflicting_lanelet)) { continue; } - if (prev_has_target_lane_id) { - // extend path to the front - private_path.points.emplace_back(path.points.at(i)); - sum_dist += tier4_autoware_utils::calcDistance2d( - path.points.at(i).point.pose, path.points.at(i + 1).point.pose); - if (sum_dist > extend_length) { - break; - } - } + attention_lanelets.push_back(conflicting_lanelet); } - - std::reverse(private_path.points.begin(), private_path.points.end()); - return private_path; + return attention_lanelets; } } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp index ab368e6b3106b..a44b99c97457d 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp @@ -73,14 +73,12 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface motion_utils::VirtualWalls createVirtualWalls() override; const std::set & getAssociativeIds() const { return associative_ids_; } + lanelet::ConstLanelets getAttentionLanelets() const; private: const int64_t lane_id_; const std::set associative_ids_; - autoware_auto_planning_msgs::msg::PathWithLaneId extractPathNearExitOfPrivateRoad( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const double extend_length); - // Parameter PlannerParam planner_param_; std::optional first_conflicting_lanelet_; From 2635df380aa1b1b9b5edeb1fe36b04bc0d839996 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Wed, 10 Jan 2024 01:50:08 +0900 Subject: [PATCH 207/276] feat(image_projection_based_fusion): add image segmentation_pointcloud_fusion for pointcloud filter (#5562) * fix: roiCallback for Image Signed-off-by: badai-nguyen * fix: pointcloud filter Signed-off-by: badai-nguyen * fix: pointcloud filter bugfix Signed-off-by: badai-nguyen * fix: segmentation poincloud filter Signed-off-by: badai-nguyen * fix: add option in launch file Signed-off-by: badai-nguyen * chore: refactor Signed-off-by: badai-nguyen * docs: update docs Signed-off-by: badai-nguyen * fix: roi_pointcloud_fusion with new template Signed-off-by: badai-nguyen * fix: add param of selectable semantic id Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * fix: launch file Signed-off-by: badai-nguyen * Revert "fix: launch file" This reverts commit 5dfa160964c6db2bcdb402bf47a2ebe30f177010. * fix: reverse perception launcher Signed-off-by: badai-nguyen * style(pre-commit): autofix * Update perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp Co-authored-by: Yoshi Ri * style(pre-commit): autofix --------- Signed-off-by: badai-nguyen Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yoshi Ri --- .../CMakeLists.txt | 6 + .../segmentation_pointcloud_fusion.param.yaml | 30 ++++ .../docs/segmentation-pointcloud-fusion.md | 87 +++++++++++ .../fusion_node.hpp | 16 +- .../pointpainting_fusion/node.hpp | 3 +- .../roi_cluster_fusion/node.hpp | 3 +- .../roi_detected_object_fusion/node.hpp | 3 +- .../roi_pointcloud_fusion/node.hpp | 2 +- .../segmentation_pointcloud_fusion/node.hpp | 54 +++++++ .../segmentation_pointcloud_fusion.launch.xml | 87 +++++++++++ .../src/fusion_node.cpp | 54 +++---- .../src/pointpainting_fusion/node.cpp | 3 +- .../src/roi_cluster_fusion/node.cpp | 3 +- .../src/roi_detected_object_fusion/node.cpp | 3 +- .../src/roi_pointcloud_fusion/node.cpp | 3 +- .../segmentation_pointcloud_fusion/node.cpp | 139 ++++++++++++++++++ 16 files changed, 455 insertions(+), 41 deletions(-) create mode 100644 perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml create mode 100644 perception/image_projection_based_fusion/docs/segmentation-pointcloud-fusion.md create mode 100644 perception/image_projection_based_fusion/include/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp create mode 100644 perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml create mode 100644 perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp diff --git a/perception/image_projection_based_fusion/CMakeLists.txt b/perception/image_projection_based_fusion/CMakeLists.txt index c021dd92dae64..b13f68b07181e 100644 --- a/perception/image_projection_based_fusion/CMakeLists.txt +++ b/perception/image_projection_based_fusion/CMakeLists.txt @@ -22,6 +22,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/utils/utils.cpp src/roi_cluster_fusion/node.cpp src/roi_detected_object_fusion/node.cpp + src/segmentation_pointcloud_fusion/node.cpp src/roi_pointcloud_fusion/node.cpp ) @@ -40,6 +41,11 @@ rclcpp_components_register_node(${PROJECT_NAME} EXECUTABLE roi_cluster_fusion_node ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "image_projection_based_fusion::SegmentPointCloudFusionNode" + EXECUTABLE segmentation_pointcloud_fusion_node +) + rclcpp_components_register_node(${PROJECT_NAME} PLUGIN "image_projection_based_fusion::RoiPointCloudFusionNode" EXECUTABLE roi_pointcloud_fusion_node diff --git a/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml b/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml new file mode 100644 index 0000000000000..914ad13519807 --- /dev/null +++ b/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml @@ -0,0 +1,30 @@ +/**: + ros__parameters: + # if the semantic label is applied for pointcloud filtering + filter_semantic_label_target: + [ + true, # road + true, # sidewalk + true, # building + true, # wall + true, # fence + true, # pole + true, # traffic_light + true, # traffic_sign + true, # vegetation + true, # terrain + true, # sky + false, # person + false, # ride + false, # car + false, # truck + false, # bus + false, # train + false, # motorcycle + false, # bicycle + false, # others + ] + # the maximum distance of pointcloud to be applied filter, + # this is selected based on semantic segmentation model accuracy, + # calibration accuracy and unknown reaction distance + filter_distance_threshold: 60.0 diff --git a/perception/image_projection_based_fusion/docs/segmentation-pointcloud-fusion.md b/perception/image_projection_based_fusion/docs/segmentation-pointcloud-fusion.md new file mode 100644 index 0000000000000..77188aafb3b22 --- /dev/null +++ b/perception/image_projection_based_fusion/docs/segmentation-pointcloud-fusion.md @@ -0,0 +1,87 @@ +# segmentation_pointcloud_fusion + +## Purpose + +The node `segmentation_pointcloud_fusion` is a package for filtering pointcloud that are belong to less interesting region which is defined by semantic or instance segmentation by 2D image segmentation model. + +## Inner-workings / Algorithms + +- The pointclouds are projected onto the semantic/instance segmentation mask image which is the output from 2D segmentation neural network. +- The pointclouds are belong to segment such as road, sidewalk, building, vegetation, sky ... are considered as less important points for autonomous driving and could be removed. + +![segmentation_pointcloud_fusion_image](./images/segmentation_pointcloud_fusion.png) + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| ------------------------ | ----------------------------------- | --------------------------------------------------------- | +| `input` | `sensor_msgs::msg::PointCloud2` | input pointcloud | +| `input/camera_info[0-7]` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes | +| `input/rois[0-7]` | `tier4_perception_msgs::msg::Image` | semantic segmentation mask image | +| `input/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | + +### Output + +| Name | Type | Description | +| -------- | ------------------------------- | -------------------------- | +| `output` | `sensor_msgs::msg::PointCloud2` | output filtered pointcloud | + +## Parameters + +### Core Parameters + +| Name | Type | Description | +| ------------- | ---- | ------------------------ | +| `rois_number` | int | the number of input rois | + +## Assumptions / Known limits + + + +## (Optional) Error detection and handling + + + +## (Optional) Performance characterization + + + +## (Optional) References/External links + + + +## (Optional) Future extensions / Unimplemented parts + + diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp index 9572e62e0e0aa..fe8acb6746dba 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp @@ -22,6 +22,7 @@ #include #include +#include #include #include @@ -49,13 +50,14 @@ namespace image_projection_based_fusion { using autoware_auto_perception_msgs::msg::DetectedObject; using autoware_auto_perception_msgs::msg::DetectedObjects; +using sensor_msgs::msg::CameraInfo; +using sensor_msgs::msg::Image; using sensor_msgs::msg::PointCloud2; using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; using PointCloud = pcl::PointCloud; using autoware_auto_perception_msgs::msg::ObjectClassification; - -template +template class FusionNode : public rclcpp::Node { public: @@ -78,12 +80,12 @@ class FusionNode : public rclcpp::Node virtual void subCallback(const typename Msg::ConstSharedPtr input_msg); // callback for roi subscription + virtual void roiCallback( - const DetectedObjectsWithFeature::ConstSharedPtr input_roi_msg, const std::size_t roi_i); + const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i); virtual void fuseOnSingleImage( - const Msg & input_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, + const Msg & input_msg, const std::size_t image_id, const Msg2D & input_roi_msg, const sensor_msgs::msg::CameraInfo & camera_info, Msg & output_msg) = 0; // set args if you need @@ -111,7 +113,7 @@ class FusionNode : public rclcpp::Node /** \brief A vector of subscriber. */ typename rclcpp::Subscription::SharedPtr sub_; - std::vector::SharedPtr> rois_subs_; + std::vector::SharedPtr> rois_subs_; // offsets between cameras and the lidars std::vector input_offset_ms_; @@ -120,7 +122,7 @@ class FusionNode : public rclcpp::Node std::vector is_fused_; std::pair cached_msg_; // first element is the timestamp in nanoseconds, second element is the message - std::vector> cached_roi_msgs_; + std::vector> cached_roi_msgs_; std::mutex mutex_cached_msgs_; // output publisher diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/node.hpp index d7de10fed068f..78ae152141a00 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/node.hpp @@ -33,7 +33,8 @@ namespace image_projection_based_fusion { using Label = autoware_auto_perception_msgs::msg::ObjectClassification; -class PointPaintingFusionNode : public FusionNode +class PointPaintingFusionNode +: public FusionNode { public: explicit PointPaintingFusionNode(const rclcpp::NodeOptions & options); diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp index e54710ad477da..b9471f2f3b78e 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp @@ -25,7 +25,8 @@ namespace image_projection_based_fusion const std::map IOU_MODE_MAP{{"iou", 0}, {"iou_x", 1}, {"iou_y", 2}}; class RoiClusterFusionNode -: public FusionNode +: public FusionNode< + DetectedObjectsWithFeature, DetectedObjectWithFeature, DetectedObjectsWithFeature> { public: explicit RoiClusterFusionNode(const rclcpp::NodeOptions & options); diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp index e11a62c060480..7d7132309fb91 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp @@ -29,7 +29,8 @@ namespace image_projection_based_fusion using sensor_msgs::msg::RegionOfInterest; -class RoiDetectedObjectFusionNode : public FusionNode +class RoiDetectedObjectFusionNode +: public FusionNode { public: explicit RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options); diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp index 2b4eb822a9edb..fe685baa0b6e2 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp @@ -22,7 +22,7 @@ namespace image_projection_based_fusion { class RoiPointCloudFusionNode -: public FusionNode +: public FusionNode { private: int min_cluster_size_{1}; diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp new file mode 100644 index 0000000000000..4168c483469ab --- /dev/null +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp @@ -0,0 +1,54 @@ +// 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 IMAGE_PROJECTION_BASED_FUSION__SEGMENTATION_POINTCLOUD_FUSION__NODE_HPP_ +#define IMAGE_PROJECTION_BASED_FUSION__SEGMENTATION_POINTCLOUD_FUSION__NODE_HPP_ + +#include "image_projection_based_fusion/fusion_node.hpp" + +#include +#include + +#if __has_include() +#include +#else +#include +#endif + +namespace image_projection_based_fusion +{ +class SegmentPointCloudFusionNode : public FusionNode +{ +private: + rclcpp::Publisher::SharedPtr pub_pointcloud_ptr_; + std::vector filter_semantic_label_target_; + float filter_distance_threshold_; + /* data */ +public: + explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options); + +protected: + void preprocess(PointCloud2 & pointcloud_msg) override; + + void postprocess(PointCloud2 & pointcloud_msg) override; + + void fuseOnSingleImage( + const PointCloud2 & input_pointcloud_msg, const std::size_t image_id, const Image & input_mask, + const CameraInfo & camera_info, PointCloud2 & output_pointcloud_msg) override; + + bool out_of_scope(const PointCloud2 & filtered_cloud); +}; + +} // namespace image_projection_based_fusion +#endif // IMAGE_PROJECTION_BASED_FUSION__SEGMENTATION_POINTCLOUD_FUSION__NODE_HPP_ diff --git a/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml b/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml new file mode 100644 index 0000000000000..96bf47594bfe8 --- /dev/null +++ b/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml @@ -0,0 +1,87 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index 4abd92d7fb063..6bced39bc61ef 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -40,8 +40,8 @@ static double processing_time_ms = 0; namespace image_projection_based_fusion { -template -FusionNode::FusionNode( +template +FusionNode::FusionNode( const std::string & node_name, const rclcpp::NodeOptions & options) : Node(node_name, options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { @@ -81,7 +81,7 @@ FusionNode::FusionNode( } input_offset_ms_ = declare_parameter>("input_offset_ms"); - if (!input_offset_ms_.empty() && rois_number_ != input_offset_ms_.size()) { + if (!input_offset_ms_.empty() && rois_number_ > input_offset_ms_.size()) { throw std::runtime_error("The number of offsets does not match the number of topics."); } @@ -99,9 +99,9 @@ FusionNode::FusionNode( cached_roi_msgs_.resize(rois_number_); is_fused_.resize(rois_number_, false); for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { - std::function roi_callback = + std::function roi_callback = std::bind(&FusionNode::roiCallback, this, std::placeholders::_1, roi_i); - rois_subs_.at(roi_i) = this->create_subscription( + rois_subs_.at(roi_i) = this->create_subscription( input_rois_topics_.at(roi_i), rclcpp::QoS{1}.best_effort(), roi_callback); } @@ -147,22 +147,22 @@ FusionNode::FusionNode( filter_scope_maxz_ = declare_parameter("filter_scope_max_z"); } -template -void FusionNode::cameraInfoCallback( +template +void FusionNode::cameraInfoCallback( const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const std::size_t camera_id) { camera_info_map_[camera_id] = *input_camera_info_msg; } -template -void FusionNode::preprocess(Msg & ouput_msg __attribute__((unused))) +template +void FusionNode::preprocess(Msg & ouput_msg __attribute__((unused))) { // do nothing by default } -template -void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_msg) +template +void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_msg) { if (cached_msg_.second != nullptr) { stop_watch_ptr_->toc("processing_time", true); @@ -285,9 +285,9 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ } } -template -void FusionNode::roiCallback( - const DetectedObjectsWithFeature::ConstSharedPtr input_roi_msg, const std::size_t roi_i) +template +void FusionNode::roiCallback( + const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i) { stop_watch_ptr_->toc("processing_time", true); @@ -350,14 +350,14 @@ void FusionNode::roiCallback( (cached_roi_msgs_.at(roi_i))[timestamp_nsec] = input_roi_msg; } -template -void FusionNode::postprocess(Msg & output_msg __attribute__((unused))) +template +void FusionNode::postprocess(Msg & output_msg __attribute__((unused))) { // do nothing by default } -template -void FusionNode::timer_callback() +template +void FusionNode::timer_callback() { using std::chrono_literals::operator""ms; timer_->cancel(); @@ -395,8 +395,8 @@ void FusionNode::timer_callback() } } -template -void FusionNode::setPeriod(const int64_t new_period) +template +void FusionNode::setPeriod(const int64_t new_period) { if (!timer_) { return; @@ -412,8 +412,8 @@ void FusionNode::setPeriod(const int64_t new_period) } } -template -void FusionNode::publish(const Msg & output_msg) +template +void FusionNode::publish(const Msg & output_msg) { if (pub_ptr_->get_subscription_count() < 1) { return; @@ -421,8 +421,10 @@ void FusionNode::publish(const Msg & output_msg) pub_ptr_->publish(output_msg); } -template class FusionNode; -template class FusionNode; -template class FusionNode; -template class FusionNode; +template class FusionNode; +template class FusionNode< + DetectedObjectsWithFeature, DetectedObjectWithFeature, DetectedObjectsWithFeature>; +template class FusionNode; +template class FusionNode; +template class FusionNode; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 76b561f677c0f..14783a46ba8b4 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -93,7 +93,8 @@ inline bool isUnknown(int label2d) } PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & options) -: FusionNode("pointpainting_fusion", options) +: FusionNode( + "pointpainting_fusion", options) { omp_num_threads_ = this->declare_parameter("omp_params.num_threads"); const float score_threshold = diff --git a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index 492f832e30e8b..1c064e4d0f060 100644 --- a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -34,7 +34,8 @@ namespace image_projection_based_fusion { RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options) -: FusionNode("roi_cluster_fusion", options) +: FusionNode( + "roi_cluster_fusion", options) { trust_object_iou_mode_ = declare_parameter("trust_object_iou_mode"); non_trust_object_iou_mode_ = declare_parameter("non_trust_object_iou_mode"); diff --git a/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 333ec7d7ed206..19defc0a1cab0 100644 --- a/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -25,7 +25,8 @@ namespace image_projection_based_fusion { RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options) -: FusionNode("roi_detected_object_fusion", options) +: FusionNode( + "roi_detected_object_fusion", options) { fusion_params_.passthrough_lower_bound_probability_thresholds = declare_parameter>("passthrough_lower_bound_probability_thresholds"); diff --git a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index 233e568ebee0b..421aa3a453451 100644 --- a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -30,7 +30,8 @@ namespace image_projection_based_fusion { RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & options) -: FusionNode("roi_pointcloud_fusion", options) +: FusionNode( + "roi_pointcloud_fusion", options) { fuse_unknown_only_ = declare_parameter("fuse_unknown_only"); min_cluster_size_ = declare_parameter("min_cluster_size"); diff --git a/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp b/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp new file mode 100644 index 0000000000000..1c9c865b8d21e --- /dev/null +++ b/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp @@ -0,0 +1,139 @@ +// 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 "image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp" + +#include "image_projection_based_fusion/utils/geometry.hpp" +#include "image_projection_based_fusion/utils/utils.hpp" + +#ifdef ROS_DISTRO_GALACTIC +#include +#include +#else +#include +#include +#endif + +namespace image_projection_based_fusion +{ +SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options) +: FusionNode("segmentation_pointcloud_fusion", options) +{ + filter_distance_threshold_ = declare_parameter("filter_distance_threshold"); + filter_semantic_label_target_ = + declare_parameter>("filter_semantic_label_target"); +} + +void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg) +{ + return; +} + +void SegmentPointCloudFusionNode::postprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg) +{ + 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, + __attribute__((unused)) PointCloud2 & output_pointcloud_msg) +{ + if (input_pointcloud_msg.data.empty()) { + return; + } + cv_bridge::CvImagePtr in_image_ptr; + try { + in_image_ptr = cv_bridge::toCvCopy( + std::make_shared(input_mask), input_mask.encoding); + } catch (const std::exception & e) { + RCLCPP_ERROR(this->get_logger(), "cv_bridge exception:%s", e.what()); + return; + } + + cv::Mat mask = in_image_ptr->image; + if (mask.cols == 0 || mask.rows == 0) { + return; + } + Eigen::Matrix4d projection; + projection << camera_info.p.at(0), camera_info.p.at(1), camera_info.p.at(2), camera_info.p.at(3), + camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6), camera_info.p.at(7), + camera_info.p.at(8), camera_info.p.at(9), camera_info.p.at(10), camera_info.p.at(11), 0.0, 0.0, + 0.0, 1.0; + geometry_msgs::msg::TransformStamped transform_stamped; + // transform pointcloud from frame id to camera optical frame id + { + const auto transform_stamped_optional = getTransformStamped( + tf_buffer_, input_mask.header.frame_id, input_pointcloud_msg.header.frame_id, + input_pointcloud_msg.header.stamp); + if (!transform_stamped_optional) { + return; + } + transform_stamped = transform_stamped_optional.value(); + } + + PointCloud2 transformed_cloud; + tf2::doTransform(input_pointcloud_msg, transformed_cloud, transform_stamped); + + PointCloud output_cloud; + + for (sensor_msgs::PointCloud2ConstIterator iter_x(transformed_cloud, "x"), + iter_y(transformed_cloud, "y"), iter_z(transformed_cloud, "z"), + iter_orig_x(input_pointcloud_msg, "x"), iter_orig_y(input_pointcloud_msg, "y"), + iter_orig_z(input_pointcloud_msg, "z"); + iter_x != iter_x.end(); + ++iter_x, ++iter_y, ++iter_z, ++iter_orig_x, ++iter_orig_y, ++iter_orig_z) { + // skip filtering pointcloud behind the camera or too far from camera + if (*iter_z <= 0.0 || *iter_z > filter_distance_threshold_) { + output_cloud.push_back(pcl::PointXYZ(*iter_orig_x, *iter_orig_y, *iter_orig_z)); + continue; + } + + Eigen::Vector4d projected_point = projection * Eigen::Vector4d(*iter_x, *iter_y, *iter_z, 1.0); + Eigen::Vector2d normalized_projected_point = Eigen::Vector2d( + projected_point.x() / projected_point.z(), projected_point.y() / projected_point.z()); + + bool is_inside_image = + normalized_projected_point.x() > 0 && normalized_projected_point.x() < camera_info.width && + normalized_projected_point.y() > 0 && normalized_projected_point.y() < camera_info.height; + if (!is_inside_image) { + output_cloud.push_back(pcl::PointXYZ(*iter_orig_x, *iter_orig_y, *iter_orig_z)); + continue; + } + + // skip filtering pointcloud where semantic id out of the defined list + uint8_t semantic_id = mask.at( + static_cast(normalized_projected_point.y()), + static_cast(normalized_projected_point.x())); + if (static_cast(semantic_id) >= filter_semantic_label_target_.size()) { + output_cloud.push_back(pcl::PointXYZ(*iter_orig_x, *iter_orig_y, *iter_orig_z)); + continue; + } + if (!filter_semantic_label_target_.at(semantic_id)) { + output_cloud.push_back(pcl::PointXYZ(*iter_orig_x, *iter_orig_y, *iter_orig_z)); + } + } + + pcl::toROSMsg(output_cloud, output_pointcloud_msg); + output_pointcloud_msg.header = input_pointcloud_msg.header; +} + +bool SegmentPointCloudFusionNode::out_of_scope(__attribute__((unused)) + const PointCloud2 & filtered_cloud) +{ + return false; +} +} // namespace image_projection_based_fusion + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(image_projection_based_fusion::SegmentPointCloudFusionNode) From b179aee67d9c9c515fb0e60d67cf8d2c33f32e13 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 10 Jan 2024 10:01:55 +0900 Subject: [PATCH 208/276] docs(start_planner): update explanation about start pose candidate's priority (#6003) * add explanation about start pose candidate priority Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara Co-authored-by: Kosuke Takeuchi --- .../README.md | 46 +++ .../images/priority_order.drawio.svg | 319 ++++++++++++++++++ 2 files changed, 365 insertions(+) create mode 100644 planning/behavior_path_start_planner_module/images/priority_order.drawio.svg diff --git a/planning/behavior_path_start_planner_module/README.md b/planning/behavior_path_start_planner_module/README.md index 1a730212f828b..f4aa3936bee56 100644 --- a/planning/behavior_path_start_planner_module/README.md +++ b/planning/behavior_path_start_planner_module/README.md @@ -243,6 +243,52 @@ If a safe path cannot be generated from the current position, search backwards f [pull out after backward driving video](https://user-images.githubusercontent.com/39142679/181025149-8fb9fb51-9b8f-45c4-af75-27572f4fba78.mp4) +### **search priority** + +If a safe path with sufficient clearance for static obstacles cannot be generated forward, a backward search from the vehicle's current position is conducted to locate a suitable start point for a pull out path generation. + +During this backward search, different policies can be applied based on `search_priority` parameters: + +Selecting `efficient_path` focuses on creating a shift pull out path, regardless of how far back the vehicle needs to move. +Opting for `short_back_distance` aims to find a location with the least possible backward movement. + +![priority_order](./images/priority_order.drawio.svg) + +`PriorityOrder` is defined as a vector of pairs, where each element consists of a `size_t` index representing a start pose candidate index, and the planner type. The PriorityOrder vector is processed sequentially from the beginning, meaning that the pairs listed at the top of the vector are given priority in the selection process for pull out path generation. + +#### `efficient_path` + +When `search_priority` is set to `efficient_path` and the preference is for prioritizing `shift_pull_out`, the `PriorityOrder` array is populated in such a way that `shift_pull_out` is grouped together for all start pose candidates before moving on to the next planner type. This prioritization is reflected in the order of the array, with `shift_pull_out` being listed before geometric_pull_out. + +| Index | Planner Type | +| ----- | ------------------ | +| 0 | shift_pull_out | +| 1 | shift_pull_out | +| ... | ... | +| N | shift_pull_out | +| 0 | geometric_pull_out | +| 1 | geometric_pull_out | +| ... | ... | +| N | geometric_pull_out | + +This approach prioritizes trying all candidates with `shift_pull_out` before proceeding to `geometric_pull_out`, which may be efficient in situations where `shift_pull_out` is likely to be appropriate. + +#### `short_back_distance` + +For `search_priority` set to `short_back_distance`, the array alternates between planner types for each start pose candidate, which can minimize the distance the vehicle needs to move backward if the earlier candidates are successful. + +| Index | Planner Type | +| ----- | ------------------ | +| 0 | shift_pull_out | +| 0 | geometric_pull_out | +| 1 | shift_pull_out | +| 1 | geometric_pull_out | +| ... | ... | +| N | shift_pull_out | +| N | geometric_pull_out | + +This ordering is beneficial when the priority is to minimize the backward distance traveled, giving an equal chance for each planner to succeed at the closest possible starting position. + ### **parameters for backward pull out start point search** | Name | Unit | Type | Description | Default value | diff --git a/planning/behavior_path_start_planner_module/images/priority_order.drawio.svg b/planning/behavior_path_start_planner_module/images/priority_order.drawio.svg new file mode 100644 index 0000000000000..ab48c30b6fdae --- /dev/null +++ b/planning/behavior_path_start_planner_module/images/priority_order.drawio.svg @@ -0,0 +1,319 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+ + (0, shift_pull_out) +
+
+ (1, shift_pull_out) +
+ (2, shift_pull_out) +
+ (3, shift_pull_out) +
+ (4, shift_pull_out) +
+ ︙ +
+ (N, shift_pull_out) +
+ (0, + geometric_pull_out + ) +
+ (1, + geometric_pull_out + ) +
+ (2, + geometric_pull_out + ) +
+ (3, + geometric_pull_out + ) +
+ (4, + geometric_pull_out + ) +
+ ︙ +
+ (N, + geometric_pull_out + ) + +
+
+
+
+
+ +
+
backward_search_resolution
+
+
+ +
+
geometric pull out path
+
+
+ +
+
start pose candidate
+
+
+ +
+
idx: 0
+
+
+ +
+
idx: 1
+
+
+ +
+
idx: 2
+
+
+ +
+
idx: 3
+
+
+ +
+
idx: 4
+
+
+ +
+
shift pull out path
+
+
+ +
+
+ (idx, planner_type):= +
+ (3, geometric_pull_out) +
+
+
+ +
+
(3, shift_pull_out)
+
+
+ +
+
idx: N
+
+
+ +
+
+ + efficient_path +
+
+
+
+
+ +
+
+ (0, shift_pull_out) +
+ (0, geometric_pull_out) +
+ (1, shift_pull_out) +
+ (1, geometric_pull_out) +
+ (2, shift_pull_out) +
+ (2, geometric_pull_out) +
+ (3, shift_pull_out) +
+ (3, geometric_pull_out) +
+ (4, shift_pull_out) +
+ (4, geometric_pull_out) +
+ ︙ +
+ (N, shift_pull_out) +
+ (N, geometric_pull_out) + +
+
+
+
+
+ +
+
+ + short_back_distance +
+
+
+
+
+ +
+
high priority
+
+
+ +
+
low priority
+
+
+
From f335fe4caf706a3885d628b26487ad616ffd4442 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 10 Jan 2024 11:30:54 +0900 Subject: [PATCH 209/276] feat(behavior_velocity_planner): add new 'dynamic_obstacle_stop' module (#5835) Signed-off-by: Maxime CLEMENT --- .../behavior_planning.launch.xml | 7 + .../CMakeLists.txt | 12 + .../README.md | 85 +++++++ .../config/dynamic_obstacle_stop.param.yaml | 10 + .../DynamicObstacleStop-Collision.drawio.svg | 236 ++++++++++++++++++ .../DynamicObstacleStop-Filtering.drawio.svg | 156 ++++++++++++ ...amicObstacleStop-ImmediatePaths.drawio.svg | 103 ++++++++ .../DynamicObstacleStop-StopPoint.drawio.svg | 98 ++++++++ .../docs/dynamic_obstacle_stop_rviz.png | Bin 0 -> 157888 bytes .../package.xml | 36 +++ .../plugins.xml | 3 + .../src/collision.cpp | 71 ++++++ .../src/collision.hpp | 39 +++ .../src/debug.cpp | 87 +++++++ .../src/debug.hpp | 40 +++ .../src/footprint.cpp | 84 +++++++ .../src/footprint.hpp | 55 ++++ .../src/manager.cpp | 73 ++++++ .../src/manager.hpp | 58 +++++ .../src/object_filtering.cpp | 71 ++++++ .../src/object_filtering.hpp | 39 +++ .../src/scene_dynamic_obstacle_stop.cpp | 185 ++++++++++++++ .../src/scene_dynamic_obstacle_stop.hpp | 62 +++++ .../src/types.hpp | 80 ++++++ .../behavior_velocity_planner.launch.xml | 2 + 25 files changed, 1692 insertions(+) create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/README.md create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Collision.drawio.svg create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Filtering.drawio.svg create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-ImmediatePaths.drawio.svg create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-StopPoint.drawio.svg create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/docs/dynamic_obstacle_stop_rviz.png create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index b36b40ed6a980..dd1c0604bc86f 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -42,6 +42,7 @@ + @@ -176,6 +177,11 @@ value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::NoDrivableLaneModulePlugin, '")" if="$(var launch_no_drivable_lane_module)" /> + @@ -255,6 +261,7 @@ + diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt b/planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt new file mode 100644 index 0000000000000..20f4b3aa8f4d3 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_velocity_dynamic_obstacle_stop_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + DIRECTORY src +) + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/README.md b/planning/behavior_velocity_dynamic_obstacle_stop_module/README.md new file mode 100644 index 0000000000000..8aa3415c3f329 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/README.md @@ -0,0 +1,85 @@ +## Dynamic Obstacle Stop + +### Role + +`dynamic_obstacle_stop` is a module that stops the ego vehicle from entering the _immediate_ path of a dynamic object. + +The _immediate_ path of an object is the area that the object would traverse during a given time horizon, assuming constant velocity and heading. + +![rviz example](docs/dynamic_obstacle_stop_rviz.png) + +### Activation Timing + +This module is activated if the launch parameter `launch_dynamic_obstacle_stop_module` is set to true in the behavior planning launch file. + +### Inner-workings / Algorithms + +The module insert a stop point where the ego path collides with the immediate path of an object. +The overall module flow can be summarized with the following 4 steps. + +1. Filter dynamic objects. +2. Calculate immediate path rectangles of the dynamic objects. +3. Find earliest collision where ego collides with an immediate path rectangle. +4. Insert stop point before the collision. + +In addition to these 4 steps, 2 mechanisms are in place to make the stop point of this module more stable: an hysteresis and a decision duration buffer. + +The `hysteresis` parameter is used when a stop point was already being inserted in the previous iteration +and it increases the range where dynamic objects are considered close enough to the ego path to be used by the module. + +The `decision_duration_buffer` parameter defines the duration when the module will keep inserted the previous stop point, even after no collisions were found. + +#### Filter dynamic objects + +![filtering example](docs/DynamicObstacleStop-Filtering.drawio.svg) + +An object is considered by the module only if it meets all of the following conditions: + +- it is a vehicle (pedestrians are ignored); +- it is moving at a velocity higher than defined by the `minimum_object_velocity` parameter; +- it is not too close to the current position of the ego vehicle; +- it is close to the ego path. + +For the last condition, +the object is considered close enough if its lateral distance from the ego path is less than the threshold parameter `minimum_object_distance_from_ego_path` plus half the width of ego and of the object (including the `extra_object_width` parameter). +In addition, the value of the `hysteresis` parameter is added to the minimum distance if a stop point was inserted in the previous iteration. + +#### Calculate immediate path rectangles + +![Immediate paths example](docs/DynamicObstacleStop-ImmediatePaths.drawio.svg) + +For each considered object, a rectangle is created representing its _immediate_ path. +The rectangle has the width of the object plus the `extra_object_width` parameter +and its length is the current speed of the object multiplied by the `time_horizon`. + +#### Find earliest collision + +![Earliest collision example](docs/DynamicObstacleStop-Collision.drawio.svg) + +We build the ego path footprints as the set of ego footprint polygons projected on each path point. +We then calculate the intersections between these ego path footprints and the previously calculated immediate path rectangles. +An intersection is ignored if the object is not driving toward ego, i.e., the absolute angle between the object and the path point is larger than $\frac{3 \pi}{4}$. + +The collision point with the lowest arc length when projected on the ego path will be used to calculate the final stop point. + +#### Insert stop point + +![Stop point example](docs/DynamicObstacleStop-StopPoint.drawio.svg) + +Before inserting a stop point, we calculate the range of path arc lengths where it can be inserted. +The minimum is calculated to satisfy the acceleration and jerk constraints of the vehicle. +If a stop point was inserted in the previous iteration of the module, its arc length is used as the maximum. +Finally, +the stop point arc length is calculated to be the arc length of the previously found collision point minus the `stop_distance_buffer` and the ego vehicle longitudinal offset, clamped between the minimum and maximum values. + +### Module Parameters + +| Parameter | Type | Description | +| --------------------------------------- | ------ | ------------------------------------------------------------------------------------------ | +| `extra_object_width` | double | [m] extra width around detected objects | +| `minimum_object_velocity` | double | [m/s] objects with a velocity bellow this value are ignored | +| `stop_distance_buffer` | double | [m] extra distance to add between the stop point and the collision point | +| `time_horizon` | double | [s] time horizon used for collision checks | +| `hysteresis` | double | [m] once a collision has been detected, this hysteresis is used on the collision detection | +| `decision_duration_buffer` | double | [s] duration between no collision being detected and the stop decision being cancelled | +| `minimum_object_distance_from_ego_path` | double | [m] minimum distance between the footprints of ego and an object to consider for collision | diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml b/planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml new file mode 100644 index 0000000000000..14483093e8bb3 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml @@ -0,0 +1,10 @@ +/**: + ros__parameters: + dynamic_obstacle_stop: # module to stop or before entering the immediate path of a moving object + extra_object_width: 1.0 # [m] extra width around detected objects + minimum_object_velocity: 0.5 # [m/s] objects with a velocity bellow this value are ignored + stop_distance_buffer: 0.5 # [m] extra distance to add between the stop point and the collision point + time_horizon: 5.0 # [s] time horizon used for collision checks + hysteresis: 1.0 # [m] once a collision has been detected, this hysteresis is used on the collision detection + decision_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being cancelled + minimum_object_distance_from_ego_path: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Collision.drawio.svg b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Collision.drawio.svg new file mode 100644 index 0000000000000..77beb27c20db8 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Collision.drawio.svg @@ -0,0 +1,236 @@ + + + + + + + + + + +
+
+
+ EGO +
+
+
+
+ EGO +
+
+ + + + + + + + +
+
+
+ NPC 1 +
+
+
+
+ NPC 1 +
+
+ + + + + + +
+
+
+ NPC 3 +
+
+
+
+ NPC 3 +
+
+ + + + + + + + + + + + + + + + +
+
+
+
abs(angle) < ¾π
+
collisions are ignored
+
+
+
+
+ abs(angle) < ¾π... +
+
+ + + + + +
+
+
+ earliest collision point +
+
+
+
+ earliest collision point +
+
+ +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Filtering.drawio.svg b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Filtering.drawio.svg new file mode 100644 index 0000000000000..08638931b599f --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Filtering.drawio.svg @@ -0,0 +1,156 @@ + + + + + + + + + + +
+
+
+ EGO +
+
+
+
+ EGO +
+
+ + + + + + +
+
+
+ NPC 2 +
+
+
+
+ NPC 2 +
+
+ + + + + + +
+
+
+ NPC 1 +
+
+
+
+ NPC 1 +
+
+ + + + + + +
+
+
+ NPC 3 +
+
+
+
+ NPC 3 +
+
+ + + + + + +
+
+
+
NPC 4
+
+
+
+
+ NPC 4 +
+
+ + + + + + +
+
+
+ NPC 2 is too far from the path and is ignored +
+
+
+
+ NPC 2 is too far from the path and is ig... +
+
+ + + + + + + +
+
+
+ NPC 4 is too close to ego and is ignored +
+
+
+
+ NPC 4 is too close to ego and is ignored +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-ImmediatePaths.drawio.svg b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-ImmediatePaths.drawio.svg new file mode 100644 index 0000000000000..3f07c95c7399d --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-ImmediatePaths.drawio.svg @@ -0,0 +1,103 @@ + + + + + + + + + + +
+
+
+ NPC 1 +
+
+
+
+ NPC 1 +
+
+ + + + + + +
+
+
+ NPC 3 +
+
+
+
+ NPC 3 +
+
+ + + + + + + + + + +
+
+
+
object width +
+
extra_object_width
+
+
+
+
+ object width +... +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-StopPoint.drawio.svg b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-StopPoint.drawio.svg new file mode 100644 index 0000000000000..0b0953cbea265 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-StopPoint.drawio.svg @@ -0,0 +1,98 @@ + + + + + + + + + + +
+
+
+ EGO +
+
+
+
+ EGO +
+
+ + + + + + + + + + +
+
+
+ ego longitudinal offset + extra_distance_buffer +
+
+
+
+ ego longitudinal offset + extra_distance_buffer +
+
+ + + + + +
+
+
+ stop point +
+
+
+
+ stop point +
+
+ + + + +
+
+
+ collision point +
+
+
+
+ collision... +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/dynamic_obstacle_stop_rviz.png b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/dynamic_obstacle_stop_rviz.png new file mode 100644 index 0000000000000000000000000000000000000000..169cb40875d2dc5172fe2c7cad01dd5bb66990f5 GIT binary patch literal 157888 zcmYg%byU;;_x~tKVT6EmcZf8M?i_+N4h0G6W^_w~NJ)(@C6tgFDcwlt=m0D#5}0HE?=p(2kgbO)Xw->{vO z4P5~M{LX(blw?kPN&tWkpdv5x77E#K_KSJf{icT5bl}$w zQxCPVgVn-kxj|W5+gSB(+mAi@A3@~isCGgT(=!-Cv*=isXd`A;&%}>u6{mX5mPI_? zv&DJ5idlmVj+&}-)tafbRH;Y3h$3M>iF{BOYEntCJERRiI)%s z@;NNk$*yzIU2L=!a#+9;bVN-b+FV$m0+1-YNht)q3v1_Ic&6q38E6)Bdj7>AtN?=j zbY|~Oh(`}-Tl7TuZI9A>Rhag2iXF?21mOg-NZkUoNV>MSORQ9VwqIVY&&e7sSqm7I zrzG88YItF-6w}_usyPN6JzZC~HrtjxbajVM!MrZwo~{CBYh6#1by&k*1NIlIuX@KA zwQ-hrq~3zgeQ)4Nw;sRkmRv3u40#M68{**?WVCn5V~Gfmx+wv31~nO zJ-SDH!Y{}x)6&vrXJ>QQBRq@YD)r}`ty2%&rEY6&k5jyvj~UrzUef1v4n!rb%-{tr zxOY0;ySZ_z@pC(Mku>~_$$o(nLeEfOM@I*0osg_j9ZE4cJ0))=$k2!KClR5ckr77} zD!>J2qa0s%j^5+9EY^^vj%s-4&)0=VU;psN@O6{_s&VR7aZV94hJNQ7C@p3G`Y|u$ zY+Ib{Z={_4!~Q;(8v|#@DHn8juL<=-`s=Xe`K$BVh3Y^%8U&YuWRr)cDj@&>dJAGw z004e^jzHK^0j7wWR?l&7fWhN&FsOXW{57v3z1hL;Y^7FsS4a6_iG07a}~ zh+2QuI^QYYC5jMB4ui!UQ+V??RO#wjDq331z@42>M4y4`A%LHb2+2oR2M7E$2noh# z296#3Nrb9^bWT+P2jrx2!yq!ElRPygrQrOM`HeX-Q^j1P`ySB8ky9SQtYjLY@k&o6 ziwm-M8432yV~disB$o)uIkflNLhXLjgE7Vq$ojcW^!Jlc#sa?QQZ?_Z5dN^X{b=o~{y2oVY=Lel5>hWxpVb@i9!{>t1Z~jIOSm^fi-ISUP^MF@!^S z`mD}Y@3||@2ew%z%a?=Qm|HKyj#Cr|Sy9_&T5kkP-Q*gcgdY#?=B3zpTVHGuD?OdY zE45rGY43C=d;?Rd{xT8$*_NT19)<`tbx0>#-(EL2V$Ag-%@hiCHI8-MNKD%h6y!wL z)ptBx9+J}{=xqvdTbO0y7ApOV=#OzKS|`${Rec{n9i1O_L9 z5%TU3-EK0AfQwI9P&hxtr35)HBubsP@gO6k)hwM4L&~|+ns$}lieihJkcSl{4qK=; z@0VaiCxyCv-P=NVc}?a+@E@i-$xkMb`w9h+eKTkkDhsZ+pz+4aWs3r$J`2KhOG!Mm zLus44*gN2OqoY$T8wzA$VVOG+0%VH0tHN3)*`o5SV0nzoqt;QNb;5l~}}o_RDaI@Cqyk<-$G z*?(N*WyZ3nAYV=-%g zjidEDAHyZ%0i6x>Apkh=`T7sLzmXZ=%Ddy zKcq*j^!Ta0Az=a;8b&`Y=EkrFEDXKD>pL;8j0e$4DvovVtOY4ztGIf)yX(I|?@xLP zu>kin7`!hz`LsxBe1&o zA(JX#M3Rp^ezx>h+zDB%O0Ry=7P0Ir{ni%>x$iC*Y`?Od)zjgP7!cN9%FNbyGo`&Z=WQy-CsVovG z)o_-_8#ab$4UkgAX>x|}9`~_k%QrxukM9i<76}rJV2Ko~)0@GFhBFO((Fi)3=nf(` zG%t0%hJe1}R4s(5H-`lggvk&>_I^U%jj)Akxo_;)i_BjrS3ICE)^2s9pYQB>;++J} z6aFC55EWzbwp=i7c`cDmo?r0|pp{}V`yloa3{M&ZT}u?fxu2dxCa*Sx>AgXSd?&?e6uMBLxm~RhedwQXf<)iFsq#(c1CNX% zGaoafS1Qnwt&rXzU`J;sx|=1HGD`f702?yVxS%IScl@On$`~3Od!vr&&)pN<^qXbb zBA$}a;%|*3PQq_~?k3B-!vUYGX8W61YDO!br7;nSst*rWPw-u)<(-t~F0igR%fFyJ zlB6^qnD6w>BQxX;3uh)<`Rkj<69gEwsRfA_`A;gRDdyx+bCBodD!&ybc-LJM{_*m3 zW8k*znSDBj2#S$I-8{6dvf2B>=EtOJ=b;`2;(KYs$}uZHfp6pMY_pwHRq%UZ)*D6} zUud7tUkxU^vDv|AD%O`8W`G#XSf_0B7&C$Ba{_9yk10X&2IpdpZCu=Qe4U9IDeb9y zJ)ZG1hTqF(>vQMMd?$lA9RY*mTbI+BUSU~5oL3ZS7OM)szb|mnEPoWf_E2wN-$xr! z0T2JVh|NvGK-o`RH!LNXj-HmJZ)Rh85r!-z_}V8x zc6E1jB`|hE^~a%_qYY(U_}rGLqnPguj{So8;< zyUXy?6qgDfxH$q8-hAuR*Kw8WEvx$haGVplxhUjP6Off)^%v^y&2WL&9zUl$<}y0Y zM0xW6B5f)g%S)CXWX9VG3UjLKdoPRl_~8ReQZ_c@=6x8u`mzMt_PQ)6;QMD|>`FOH ze@#MPzpsuH8#}LbdGeBN9O?v2uy-dIiiBsvG3B|D8EJYX1E31JhD|?b(fcx zs+OGI9>g*f<2YrhCg9NTFExul`4yIymP)o9@Y5j+NM*~djeo)G73|5k2$>#IU$!7` z(bc{?%bP!~{wt}H7eAtvqTR#em#*4d#ae{|0&d=kvo<@I`g&7%t!3Z;Fg1QWu~j1m zA9z0{oTW~+9t-cap3iHSdiUe0J&k8So_BV3Zb?0Pd9CVoNAGI^yY&Ui9-)bGju)6q z3WGep8qfbCpo;lp17s6nN$m&epd@}_!;H`@8{LxK8f?C}w+4Ls?D zsD1qE_*_YeQ{Byb7}>R@ovy>OR6`HLalZNlU7|O4^b^TKuUEov46}ZQ)#eGrI`BQq zJ#^IVZrYfbkhWrpSc^Sy{an?CTE=3@JZi5M^J~)P1Y$l%45F09%5t>$0-Si3`$=Bf znmE2TyYckzM&##uHk_H$nP>J#ik%*I*UEpT1 zHj}SSw?4Wn^Ki3?bE=+=ad*>AoJ9%>*3suq8+gn4843Df|8D(b?}ufVWFDi??Ypu2 zzUZ^205SY`eEqgsO=z#%rlQPQBmucHEgY?-N^#*n@8NVmemcii7@BtBBX zRb0+9Dw)r-wg%K|ob7P<&Q*&}$AZ$G1XZ6?DYWS%Sr%+`j^M6T+>*!L}Q_K6PGgF>9$5yFpo zY_eFl96>@I%s0^+<5{0~RM6@QB4QWsu%Vs(df3N>xKhAdm=%nme1En- zN>d;T?bqE{YB4DZcnmh_Jrb27f!m#~LvVbM8;L_f=)=PKxPSu=;Sq`ZRdeAldh{}O z`q1rw-S@!na|Mo?%e_}fBy3c2XDlfA4m$bRtzFx}=zXUZDx4K*NrJ>2ko5PCEUk5& z<}yM^Ot?L(bb4UhU)3o+WQ{XW5Q6FZb7;OqOrvFs9^G$TbpgcDr$Jw`Li{hx+eDdJ zc2WWk8K>8WXObg@(YA-kHwTm;;`jict0l(uh?k7yUl&M%vril8axq4Rqx!=VZxa;h z)+H`Jtx1G7-sR!+ke`s)+ehJCBlwqSE%!bIuV{yK3zLNYd#tW%Urbj-;lIzGm1vu< zKX;TaHdHxJ>GYHJwRx2o>W9+J8PKwSzBA4=VRiFOuaWR-T|$C@Iy7-TW((A(Fj^$Z z3o?!L;avAX~cP)?2V}EAMrWW)J_PTCDz647s8XPpUP_rF)?AH-@&q)JGfk3Wx#gVj*p9rvfgEyYxcP+ z)hSk9;V=a|*X~xO=9Hw+QX8`l| zTl8$1D#z90V-82|U(jnYvD?KX|5V&&>E_@q(W5>MM%|N`#KfLB>NOWI!Y&vPC`>^g z>b^I{&BGHH7pJMNzCT;NHBqXg6i;&?&Hz!}bY1O?{EsG>q>hr6XmQU1q6Uy*KTS_8 zuzAPDF&$5dL~FlGVg8&)`*DW^bF#(-pHK0GE`wb3hw4Wi$Ht%vob(RszfB71Rn?<7 z*jXRG%a7->D!tO^WNuG~sIOT>DZ4VQtY{tYNB?4`X!@Jz7a@GMz2o!k)^V{h@)F^F zTWedVc)oCsP**A85ssBp@LJh#-N4xG(^z{2^5Z$$VRFmPV`0ms{nrj}>+TP}VmbGb z)t!m{gl}BuuyK*vJ->TWzE?AEzb|5b<>p}X?oz-k`3_7t)*5Zj{3I)36*k9tdE4Oyrrk*EU(U3tHQGt}iA11=f-2TF zvRH|UiRFiU{sJ@Q1}J=}!ctNQhdRnwMTr*VMm@_@`oOSFpZbgVjZcx@I*j0{&1 z=pfX*jx5b7P)uR*X{wBfTSoeoZ)lp!l~boFzFw!Q`-?S?lfo6spWNX|S1zioMigLE zl8Y7XNiQ&>j0}6Ei+z#ECIqHNF-DA{K>J zMGh-gkufwdk)0uVo4kx_>|5!sf-0g7IF5Dg0lHc5WD(o^F*nqbDx6qPeOw-+y@M&eXt)3U$s`p(X7rVf}}6%l;P3O@K%#s_w$b>T=SQ+gd|kI~0h zbsk(05uq<5kXI{XX=Sx{)0v)boIGmF5)uE)_L_a)7fa(UTV{fr`PH`nJCZ=ZofKkaiJ{lRPRf)=qn!`0*V6X#e{QUp2$qndT92zRWu7r3JHA7Vq z;r8!8ytyH2v|eT-r(MYSda^4!`P;~?w!v@K3^LQa^r{YJLe#o`HJ#BheT9H+?QNjE z|M=+xGMZ9|XJOF(bUdDlefqy@r($o1$mum;x-2rJ7=M@<=N_YAD`ciFN6OViz zE}#MI&)0zmd&V|k$V$VIeZS5caGp;aIaOv+`(i>Q!i}X8&hmzF2@k3h?}$-+W{fNW z?Hz*9CD!J=I`5P1#HC-JD%g zI4~HAKba*Sa&uzyDRr}6Mj;E=Tzpa#I?a3jjscJqpMfgZboO`naiIHZ(lVxJGmuBJ0wHK*Xh1D7YC)Ytu?A4THv}V()yBb-ch+a z(vtSR9{PgDHRRe~yOh@*L}2j=jpg0b0;$z1$BG@CvRdHoIF{QPW|G# zmeC`eZEPS?=i!T};6B?@bn@MM?4AmHg4z$g;Tgei61UTZrIK|<*3 zlQpq0g%87A&tQpjEni&gzwG%05gB|fd@E}HSCuDi8bjo#r$|&@n@sK4*cf@fNByEh zI1mC|!2lq+R5LA{7oi12<--Hdku?1NTx3O2(dK3`Th#Xv17)Yr4Co)Fl%$k;@{b~% zo;lM6y`q#2T#>LRPR^_>h&gxe`)P3h=jk?AO)A4{?Jl78;vhiKd*rj@Ltk%v3wtsE z@P2w&#TDM4ND#J>eb>9Db41~HFmojMXq;qszku1K>%c_&blr1xxOjKq7;xut`8VD|CiKzV6HkIyW9`Y^BWSQ{w2!RMK#@zr!C_xwkjD zOj{mzvtbi*aLpH~mCe`PN7Pa`#XaE1u9L(7Uu?^{?u;0iUm~};r(O0dOQGhZvDqLz zwZkx5qRboHk?Wu9mN}#4w6fN44C7%W4&W(kwlE zW~gY&mI$2e1)-adrDf5f{cRH z-bDUSxYT$#y_edNdHUEO{gZ4ty9<5j@p1^kZqmBVy>z*S7Tuj|HkiTR7>YYI zMNExr=gaKJ+EyuWsoA41HG!3>LBwBc4&?$7Z|eubOy)$!&Yb*PZ86iHTpHzJ#$-S}wf;T7mdvA81?Uln4J0X;2Oh*nzlHYR zxchLqIEUYbD-;`KL4TCy2hlv3t5u5vb-!^N1s3o!(*4MqGUP6T7EtB(K) zAuqc^GRb%g_F*5_a}ojnf}r1Z5lVWS|6eejE>ja4(~e1RPiZVjHa`n%#VMfW#HPT@ zw@jccSaTcrhE@y9^%3Nx_R#=!33qQdBbcyk4oDDnqamhwYih%;^epMAj7Y8mDxK1N zu1*gAbCl$U`J!3d(Ma?lX7l46oaBbG--inY5a{1GKuONna0tzM=Z)5QC*Zqou$9vt z{YkeWRp&a6ql8LE{FY;+g>|G1KLS5))PtzMb^8uWr9)9grshD0FLol}K>%1%y!|oH8&=!q?{Gx*pM)mxoBpA^5Zj1w(Go|o+cyAv{_5Pqs z_}elCGQm#MH^F@kk^E15*~{_d?g7G)m*9#42*r3DJGvSV1*h2N*M^1$#rysT;o&i;ZxM;Y?T-`RMN~1hH|_0wv>?{MA)wB{ zpr#}-hx7=fysQpy#w`9Xg3LyB)*c`3nmu%+qkky3Zb`JTF8M|9L)p;N zPv<;cK67FzXA4ht$ni=LTVgEysNz!l?TUHiGc-KhO)iI}V0H8fCHs%yIH^ize>mj| z-^HOE)|ZwY5W`y&-tX7iO{6@!WtxrbRMqu&27c!HxVMMllF4G_{mvtROhPnv zAN4de98VqV0K(R#pZ(JstJ#E^I zC*6TB*&SQt#6Jb|$|WRblA9Z*Y-%`rcuc|Nph4;VTF%$#nIxCTnJ4R;Z7<#?P|l}# z_L_QwBOdBfr0(~Yiwnp~zu(Fwgag$Z!i)F&hO7Wi9LQc$nN|l|O@BYeDDp>C9uOTJt@-So!l~6)_QYVhz-(5cg%=q8TY2phwF|%C2bq|)xEu#L< z3jm|?$}t{JUCOvcO0uU;O8(~>u20+$&B5NNOa?!CR=*5@_hC%jjki8%SKBbd|$A9UJb)Q6E(+CxyJaGpI{b-iw7njv;*J#K|P%K|FYpA!oEbA#(t zYsz_io!@SnJ0uchL#_V>b3lMp@|r!8H$#sD6)OtkCy17cpT%*5}2G|)>W6z&U#--4~7SvS0aUM~5Gr#TUe<4LQTB$gf ztd0n>3KeFH<1B%_H%*H|8`n3oAO{gsefhcOmLelJ$D$dIUlh>%1 zx;Nq{B*Ob9nWOzVlOBA|c~Va-Z#fEydCklEeb+}+(_;$O*Jz&R^Cexj-Qv=pfp*lp z1lpVA3TjYBS2gB!{>O@#9u^kVJ(2F(+8PCalM{qhZN)UOVzBw~cR>j!<7r3VC`yeB zHggRi72|O*eBsA3)TAU9tfE94v9@xGY*)N6DvB&4@P1r&4`&RrKsZ&LgrOlX%JrYn zBhwj*ei5aoQGuYqSZERQWb)f@Wm!>*C>QO#DaNR^V7C1H{9?6Ro139uSmf1-B#(7K zJ;bTNf+Kbx-lj0%pc8HSjC2QjO<>kl(4g)?4J}fWN0q)Jy4xDq+JS!BnbYd$y}u{H z4%!j^eI`s@Dau>L=oT>eEqgUm{hRFZ28g*K^AbVyEz!9MozGM2EU8(so6>dl7UoCD ziyx1B%bs*~FdvRNVJ`+frkm`k;-U?>KZ!d;%9P#6e7Do_clLT>|8oVKRC1wKtAdMN)E^C&tB@nqbDt9B>jBp1yEC}r?mWUOz#zwux)ERa=j0a%*B7g7KT?1!)>|dnD^j9*EA}8O0xFR} zGM3~1v;JSI58PQOf`Wp6<2{Lnjc*vC;?{W?!@8gAcF5VCJ=di&hFBz|t%?Bc7ds-( ziOc0w&!Qq#*t?bB*FZ+r&>Zf3`GH(-54=M5DOgS?KMw?r$%W;)sON%2pJzUz!O8xQ zw*%`#-|jyhVw$|`(Ku9}TK*$DquVMSWcAyv?DorP1>9VYWel5s4KPp#@yEx1?UM0s z={MUS%Y?WrPqScer`3dw$=H(h`=~0_y^ZGF-t_cz$zH<&LpNUW!pR)jxKNzb+}yB>>$feXCc5A{nc7*5*;5tU;Xv zbp;(y)avodA2-o*uBk`s*NKa2C92zjS`0C!H*HdlVnUC((NYpkmS`2J0RtV*EoND9 zo(Gwrx}V3-;LaEoCPAF~mym|4gZ`U?EnbHvsPlZ+&FWxBGcN8GkKJ4|(Er%yiS~X> zD)4E~@0Fj;_;j4Z?BIbDXr)WIBEE6O`=*t~j}id)Sb1HM>L@_rx#+InRDC}G10SNg z+bN@Lx}H>u@mlzk*B9!Y{!UyS?=rq5=`Mxfiq5u2IqgoA zBDMKys}XPi-$vXu)d5eBj7k;p$?3yPy=AI?KULR|9EjipeM;%3`LLCc{EyP(@^ONci0}F|{=bi`kHu@(!cToS zHvxQ7PrRGixBK@}pPz05!hBGcv)jX;Xj)jxun#fn$(9$zS&x#fDx6n_n^2bJQvJKb z%Jp!G`T13vsZO*-#_cF74ZMT&l6^G2Z>g#?UCpl2-$;&LbP|KVWbT8IJOtDUi7t@+ z@bOr@KS{u8svR=nJ1qkq)iB*PTFdLY64nCZ-)?iT z$E&8!jEJB*2?*TW@`mH-Zszo~CnfbMyvftw&a0sTzF-2uugtXO;YDk!$VyzT?L6D! zMQuy5zf{j7D;=cTN$V(b)`};N(Awq(7jb*^r;#KQsK=mWkRD6wIlB`Q;;>41 zAufMG(b^^^NDdtOZ4Livdthd^zA&qLhK-T?8NRzqN3QmWV-D1E>M4!~%Mno*?K@!evZ=6u{t` z>b|{hyYV1@+O{+9?%<*3xB8s1LE4X<$^}jYr2@`{Lbw3r4PR^s@6|5Wu5BtD67~r} z671NClu|%9Q{~2EXGq2LBnl{-qlQXJsn}rsAd6L9UHz}>m4;lP*wrXry3#Sa*<-a2 zB&h3sYQ8VW;#obLD|)mR%0M#I)D=VNlnN_cxbNP`cGYIWPS@Ah4;Pz|(!!)e-5V<# z8=HsQ3)tgNy1Ph;B0@qPP`A;i-EXsFdh@!8Eo3^pVa@L2H{YUz-?*%FV30(8q~E$= zE=sJgGEk-V;}2_BQPH|JaX9=#BYBEwZSh}|GVnb)EfUXeU90FK=3RR{trw$luTY1i z(Tbw+qGh5(@t4B^N)-2+q}N6cXEjN)6r5^se0cFo%t5w zhqI^o^uj0E58NJ-@8N5Y&2D%AGO}Tmwv@hi2WPk$2K7)U1gvhc)&9OGmD2fu4NzvE zC2}=wst^`@U_PwFn1IDpoX1f02M+v}xp%bG+%#rAI5Lu&_0lSrR`y$F=DG|2bX%X{ z$V+V?-@&H^E=|zO1W))HHBy~W@H>1O92~rAxsniI*hkW*d2BzM8R!9265em8RU1?0 zaNzJso3uiKM5Gd5ob5kXW^#kHggECXEglMF45`Xt$TSBU>A1RTyE)!XR4*LP*Hv!u z2qyPplT=N9RzS+-w6wxQEb^bOQ z*K_f%c#WVuU}eYsX$PUk9O$#WI$r_Fz=WUeQZKUFUvl$GiEG=tSUP-Mzh$iu^IfKW zIIH8ze%OnRf84t8L~Xkzd$fE=^*82Nq+3GXk>4^Jt%%Ed?>`0FtAgwgM>8i%r5ONd zo{98)W@Wvw3E}UQr_&FEb4*621aG$9~a4b@3X>A;z(^!UgnK6~r2#&~?w))WWS`%Q>#G@PkIaxZx-CK z$dGS}ZDUCJn38ZN3(&?ATB1v(Esn=hBtizyK!ojNc3QklbR|z);%mqVaKv`aOZ%J z!*pZ_l-+JKhaJ6#xYtQ>xliH_*1{gJTUvZ94HcA<8aXOQq8S4b=ey6A)w9+Dx8$oY zBr~L3RWCTSuIljMRmM8}T+n==EYen3)3TjM_}l~w#pnI1kxb!S-J4=1CHn zA+=fh_ghFkOL9``kvHyB6@8Cy7Vxc94D?}L#WfLHo&Wp80BIGk5a7*D+$v{6x1|7k8z=+o&)6o^ymV`JH+3mSV&@Egn9GH@lLKJJ$yYvDh)-|hy zLUB>ELb5I(Ai4^{c`hiJhG)B6{j&(aHuTj|4&;n*LQ55F-LA9ZYmufb5Erb9A2qHVBMNg=Yp&GY*ij~g7>;ptruZZ%dW~y~u18yk5$o%kIU}YQB!z~U=v`4K*A5s4o(yF66DMIYL+H(mY?^D1; z5^Ul=r!T5G_1vGhLC0c>s9;TYuG2AFFi2c>srq%ghdTX75(1f`tW;C~mjL9GrSZT1 z0EozPE}CgqL*GVE&`D_Emq^@r=5lvc$9C83q7&)1R6H`ZaQTrm@Nc@<1d$oCq1HwR zXgXOdrFz(X9*o0nrs}MG{h%Tchk5{T6Swn5)eGBbmJUMdt46Nu7wlq`TsyUwawvDw zeBHo~?QJ%iREwK1USAYs`dCkxj4azS6oITlU8-jSE06m0NviA6{V~<{@{3X!Hy@2r zRZEb>8ZbE3fdV`}pac#WAa$KOH(DIq_{jDx%ct{voY?;~F}u^|h3vPitgbpPq}RPv zB#q1l9<`w5Gft*JSZ1F&?j#7pAFliQZ0qvK(SpUB1$4yjsJxmSlP-+S`4#{tjSBWb zT231>m(MI_@N(I0G(H=Pd&}Zu)@IYwWDJ=MKfoya(0SV(*f7R=e0GvMs3|GO>-zH8 zu6^00HYCb2us2qoYk9$Zy2o#C_vMHwL(%(o_Ox32_g>i_3d!ECx+{DI@9$U1q1h#h z$F2wiuoj!Jk#^(aIF=6Law~DV80f9l2&@Y&H$IH%dJ*-XtMCAtCF`V$?+M%QByYW2 zJaU+=DrAcy@LfhLpqsLLF01B;`lBYr?o!^AXwqc;XZ^#Saa!aOW|FWhe%9)??&tJ* zqDtYzi1zm>Ju6?Y1z9CFL!qXf)AO~Bdt3BOvL-wwM}4}9?qWh z{^A!B^4K2Dt>WS}ZNdAl9_%R3$U!ENxo+GWG?@1z(z&Ij0eMS)`2$Ll2Ke7eSJRCt zDo=H!u-lt_{CDzfOGQrfv54!umSVRn*;aM0r3kfXt!;OvxU)P^ml1KA*QWaCsDf7rRAjfGhTn+C2wM6d%o2GVw+sg=|mc0+HY9 zx17E}g7?SaqkDXgZxHMc+c8ToY(!g9!7x`Q|2xg1V)OF- z@!*SCj5q_RXD3y?%ozSGuw+yFKfeS$_?0YHCEN_Gw$a8Y!pHZ^VX?8Rs|!h} ztqALmi9CfCrdb!AEwg3FcB-k5w^;SO{T%1paHBR5>*K$&%DG0l1ob{|NhmyvM*L!J zITH1B2uUh5kP3JP7%n%gws0ZyrzdQ1Iazft#E(8ZyMnLfX1{|&*JFhN?_2!*L|nIq zvpgMI&bH_3mamAFQb?!#wrn85%5y?#w(PO@ayccdq5T{j;c9c}6K$6`{_#w6bHxvHh)8{T;z?Xpso zrv{yTT#m65J}yD4l~zH%Z+1S{i%lv%>XX>wlsL!Dj%?1@-|}*$<6_5J3qtT=a?O2(l-u3lR$yFaD>`5xwerh)I^2i0>@wXJvt~7F1P^sjA6qox zngMu}_@>_1vijlHOKcO`)u+bycVxk8An|IDJ%O=E3PxB`awPi6QaF`youkivk;Ex1 zv&s_}Dc)&syQHyg>#8Yk?~~-ol^Rm(iEg+C@6D1sGeS+=Dtp2YS-xhcXJq^^Ql%d` zcpQC@svN_7N_xpyPBpnj#s^`ubN?L(R!VURp9uB8EgoLLr1kyD78T6RE=OJ7M_AWZ zGjfA8_fH;d#X!!{g~O(yE{-|TGkE$p;D@-6sE>Auf3&m#_YZa7HzSk^mA(2QAAfoD zkasxbeA5|eX`X>lM*uQ`SZ|Fye+rnxuW zg@3j^6_>H*Ddkfp4xB{?HhiMmk0qs0J3n9kER!QLCO$sH^mB7z>GZ&r;uYd%u5Gk= zp+3HA*w5rEK_hFSAT`cK)k#!U|15n6M^xUVP4jUF?$1Wpu^0ntmkyinaXV%y&o+mm zR9Kka4~0uUETc5a#=5fe(HC$jSuA2=;%yr09IALPY5LG`TK{XL#R@=2x-&93m_s%5 z-9zB7wLqt=`JfJnl>HAMI8FAwe^k;HQGa4Khow{VebEIOY_{I&m8|ErGXL) z$|1Ueo6zPm=W4=pz}`rvm){TtJ*H(SZ=q>swv^}XIXLO@_Z`A(>vVO`_V>SWn(eaG z9vue4V<}Sp#!U16X5&nmDGIMlj!5A z?g-LVqUC#7k#)S$@4F1{apr>ekB29JDpQB|;twB;A~>SV{QdpIBz^UC#uJfBr|bN{ z*h>buq86h-K{nzHGMxwaCRUj{xp}tQ@uY9;f3l#U zv}K?#Y;NN^y_uFcI&}G5xsX01AXN1@rvXg83_)xK9(LxkMfZMP7+_E6fVVh_e%Q>> zDq>(lWo{TPzGcoV#&4dcKT{1(d(EJ=^kLP*#V9wAt-lJ7^9ERpvw(jViS$)2I*eo8 zKQC~)WKkLIVNQdhH3-UK7DIz6!tjS_L^*?al;1M`Pfnt7rS?-{5i5FcI4(v3XF7OR zr(TWcixBts(#)YpSN-y$aLjtaefr%t(a@{k^9Q48UU>8-^-e)|>ODwd=T%}@s3nhe z!zc9n(AOI6+B6RET*%@`w zE;6syllO7yA<@jOR(zYt8OVf$1f-^PsJ_2DrI={$mE1txT^9jF1*mIicoC3tYS5yQ zBR6WKu&h?d`%fhrdTpqxxF`R;*tSxnq4hV)s=CKXJi&PrJc|6P8Pmy{e3b*SE zkciq&J3>e{v}tpO3ShTnSGjj}tUZW?Wf%HJ4y)`0YKP3SZ%7OlJAqC5Cdj{_@meQ* zn~|R0fmW>nl>e=_!m{#v*YShqvheGT2FfUXbX$QRDS8rnH-Xl75L}ED7m5Vc4j0WE zu!tN~%&3A{IgT|=lqa~2M9pLX>~)yNS$Mj06Z)Jw>)%vl<6@3^Oau>riC&`;Y>p$- z*Z00C^LRb8ifafiiS&@~?Nwf=)-C)>Sr;f}6_Y+Eq(M4K#!m9=>ExB3*Ts%D^Wmh9 z*ulg-9|rUxZ&tPkW!W&`+@*uB@i@X%T5R=GpCm3^kCS}*`OyTUQ2 zP`OWp^j(DGQ-A#{ENoCX-Y4l6HR(6v43tmUGn99v>!_>w!2pr4)tWO(4>gCHl!EY9 z`-TP!SsyP7>sqh$$>K@(@B=(oB}OXeL6?sH8XU;!x@N%8h6Ve@Eb33!o84$e+jZ=4 z>Z>D(hrbC@vM1LKZ0`wFwAh zU38RgeJ|*sH-aV&alv&@DWYlHLx5dA4uA-*)78V38an{+uaLE@pQ|asU-tDi9X!;z zx#fu8p)ajhSt%i{9jO^Xq`L!q6Rjt6RO9&9E9oAggdF!UewedEcnapZr_vufvlz?5 zBGCuR;e(%$$L?Ux)AL3+umdLHqnRb9pmrY`oB}W|EYWY$IT7S7lX+F@Mf6;_VX%yZ z#LiFbniG5%f};o)4*hX&INp?E+M)m4M}aSa0tRPQs7(H8-SGbIYWrsm;n&c18V@gn z$Zc22lSnY=YQYr>;^U)VdUu=$04Tfx-R)OHzi1{3K>RO~aR0hchmB{j@E$E*Rj3^x zC+{FMi|*bZ|J)uui2^eB7M?r~GCSAAQ9MlQB};q8G92mWhciWMEn|~VxrRs9n8gnf z1H$J@bfHW95#LFM z1u`{%eLXXT4O0!*eDfy+?7K>Qo#^~AQce?{!ZyAv3Ge$M&25*V_9ZF=)G-+Vmd+y%*eCiPDC0x)aL!*V!e#v_^FfU0SzaAMhBkN_$V^v`L zx?a%I@PiI4%FD+W=J?&KJOmj_Sw+PyV*XKjJQk&ENV`hd`~2w;#Y%V^He^>tiKa{z zAP2lNBtIl3O^V)-mxIsc?Alo4U+gfQppGaYs#L~67mp$$P*ql?NX3PlU@Z)MN3_CQ zMH1I`bhOvB$(&^b0JL{XHD3#0KEeP0jy~)j0z2vn>o_FGNOWoJ1!d8d?hyyMK#6U; zjT+L*9CncLXD)Z|QQ+eENHEBms=f!Sz4Z~4>Hg&Ijt{Wj;uXIqpKJLC&zku((l1R{0*#Di9Zs@aL8plm_n@^{p1$opM{lb2 z+x)U$|QH&1Ap$d_QCr#HsL)DtRHPgti1RIwUxP-#_9h zwqi>xOv?jsbf}E-jv16GPp_opd`%{pgrG4-FCvYeyG#to$PoB4ZSo;s4{#Q7eJ*qg z49tcmd@_e{KK`6cww^#tmgh~!70)!&7{6zhkXrKNUUWdR(lp!fl3_z?N^RwZ4V!VujXphFC@=aI4tC3h+O& zO9u}6F>MZ%iN4Pf3o-_lqWn5(I3W`UPRrydYS!YL-lWnZt2YtK2So=8(OeF;bbuvF zl1A)8HBlZERQ`@7;d*JWGbT=F<#A^u#OLBFcWEBbo6n(winD3x^E-MLRglwyVy#ze(BM%ez}{Wz1) z2yZ>J6L<4+&gsBwF^IIef23h2Z>{Z;^V2_=$DEpkvFy@B@V9i%#Bfjx|Kz)W_qQls z9liELq+RRx;#U{>rhGOe>u(0aS7~SS5+Ru%+-kCs#qX#M6QT^S;7pzp&$}Da!hhQW zNK^6nOOQc*&D$;AV3VDROgGEdD(&uweRXwYSUsBzVssKQpN#wi6KxsJ`FaY8m_+&w;q+_@8w{4DYJHv>Naa!FM?*+Tt%R=^&kt;Cv zIpRxPm}czUJ6zin6voTmQKNp3=;^agcyXQcgqNL#9qeW6>@A~OrhhZ#CgA)%J1e{F z1!9u+)^|pUB=KJt__3w}s8mU|NLGQnFKXc#5~@v#nlnL|6lTLvYnHcJ%Jinb?{Wa3vO@PW=Sv6kIOnv_i8N+s!Y*<4A}Hr zaliO3!Q(6?)f%(+D-H#((Wp)x7L5aMEld&24DT?FI6n?zX9Eb#QTz75h};L&&pL(U z2EJol?W|ifD357i@A%6t0m)=3i6%xgGzom%;4Pp}8PW#ptxRH|7l$ToLRi*38>J}S zBv88e>?u!;Uy_fVo&U9Yc?Q!^5s}u>l3smey60TF^P6Fj$Xh8bCI*X(e$r2_{^UgT z+FGDi)uPnJs_wJC>msL!h(o2Z3eOTEKw@?VCUbtjv9UZ*ZQ*8 zllD`EoV%IcAOCaCe!ns11^Khyw(hef{_f$QeL19~5>t*q7dARq0>K9D$jJ2c(19Kj zgYHxoo$Q~xC%iVtCfXl1>r^$55tRNK~= zmy|VU;b6YJnZ@p)?vm4yt}xkD1JZ}^|IY7k7WgK@eRD)(=3UoIa}YQLmn1mQLv@U|0S1W;)zMcRr-$ z0$FYVAx6eOnFl0M^0U>`83LFmjcaI8sN$Zfz}i+ceq+QMqO9O&&2}IU2Uuq>w1&cp zROkvr8HaGaS`gol2%1WajErd6{`3y?@kx~l%5B3E@{TY@RVW-LwHo^(40(`}LBCbf zZL^40(>Gy20i{*le@&DMXU7$9C0Z}g(i)Ee?7r{9pZBzSfDgwEw;xs$&}^H*3~JP| z;i=iiV>5sTLP|bcw;cnt(!9Q~;PVxj*yqg71_@T9;s!9JP8V`?dP;6o7XKrQ)S^{iQf}bc_w4Ak<)It|2VRb~U#D6b;nv;)v&x zt;9CvG5=4|*46X#*vLT{Ghk%qOiHxu5$!UqYp5f2bvX9jD^&uH%?m2@d|b4l5agsU z+CmsLpG4fnrc`Mz)5rWn!4$V5s2IjVNwPsb3brbkvrGZV7*ug2^c-}qf_Ls(fo@DS zD&{eT-wyxGJz|pw;AP1MfEV#7H1ta$FQFDz{a}vujnS#3W=};0T<<~4F#>-;yOk1| zU#Ni#8qI;;8?5YmxJh7VBCvt@&o*Hr3d#>RcZ6UP9l$I{c$|*pH{(y&f?vrD6qmVw zqayyRRb{#+op>dS)9vQJQnPp)NTlED5xGc_)v@bIU-o|a__1$6i)sSnGv%&ocyqhQ zMR2lhoUsn|CeOdSOdyLoUqiU0{S%%Sj`m6!g5NXBgP|n9VckjCc8XMKnNRxmD1;u2 zJu;(KaAr#SEOFlNcM^#>^nZpTzsJYxQt5O{kbIclu9AX3HpY4zW~0A(Qgs zU%;;FD7a@Q5-9&9-Y?Q2uF`q9CnAeBEfA9jM-l$QEUBe9pt=itVbgK zbJwb%T*Z{$QcIXdYg_9KV9J%u6Qd>AX~~wYy-zw%kqM~59c9_6$v3$xhfmhJt35;q zPue5SMDh{k;B5Q@xx+&w$japMf*VCLkC3P3OS6@$IH^YZLMHvG!gaf}Q-K>GJEtYE znRGc&>&51AfIoc`a(uD9z%9v0Ch>vfB70PN1gPNAW}}l{>pa0qM8O|lmRsQ ziFrx=il<+Hv}0d}qdZ3tB$To+!xTTd4AXb?L`yX1ty}TnQ8{1>1l-l(TS#7&9K_|k z2nZ1m-wiu1xVF#>rDDq)k_7_t99(%BhH@`j99PtK=~$^`!EKC-`jtmC5#P)H@UVMt zFV$lK8v*UHm>mxe`H&xaRw`}ODYof93_D&mzjvV6bRF|yRn8R@G)A~sz^KZI%On-^ zyE?pIxfZ<}h~To-5dr)hI>L$pZH>KdZMcwyz2*t)BnulEj85mX(i&F0^#qG|09T%t zW(q?P#40e>MQzbf1eDs#_?os0j<_we<^;Q&U%SgG^usOjJou4any%BLOn-EUtgBrJ zPxqm^PJ1h4coI#6gce{!UbsITDcmcpgG7dfBbN_2BO^@+DbRMmjPeIl_n(j&IUh}AK2~57$&mY)JjrI0a9L*VGt4s^!lHuWM%|9rJ zPCYkY@)L8x7G@YB68C_K1duxdy|q3+Cr)jj(~v8PJv!AQVkQjzbM(KQiB4bdeEs;i z*gg9(daf|tF@_adIIB4ypy#c?OkdBa2w?)-e^37@RQQ*1+(8R*L}a+?LhF(64(JmL zc(L=V+ZMVxN2o@Vef1>nD?_VVACQ&yO5dCG8K`aG&ibZ$~H;eWX~Ndw}CoA*;;) zmh(H;G5&>za1@4(D=^A+CySJ-z`$b;M6WHuA?4+^W;;&;rA3SCD}{= zw6vHjCq1X~Ad|G@H z<=xYq=~iLN%A%3``uNfXZSk`6dXwKH<}|lM;tRH~TB;JQgMjopo*($*L+##w)PBq1 zB0#=7n})|RSbj=b77{g;I%N|6!?;3pS*reH;scG~tYt20Ba*z9!<(~*GkB}e{LaYt z0>%gdRBHf^E-~5O^E;6cb)Ay|7#%T)+g9@unj#gW&sZj|EAwqOIo5HDPJl1T*#|35 z6fs6Et1t6zW-|QLHh@p7@o~mB#zE-UJ<)n%*!82xn-@-{&f8SVP$P&V>mK?WjKyXCU)0)cUV)RgwLl>U9ZVIH4Lf19UNzw zl+;T;XhXw~0ryuT0LBRd#{7W8zg#}eFO7fy`!Y4MT;-<4tBel@r{Innt+hRk`M2x= zTM;5dgkD)<{+?4t92JW-$GdKJ#(r|UpnuBg>r5e8F%EV^u`BRmRaaLAFJW@#_<60} zY^GtYW!rN7x8cRrrz;Pgxu?_^tZd;RRM2dLa(TcNM^kWm7v!1WY(FH?x)59NJf9J8 z>;MTKzc%~6xiuA*E_J)LF33#Yosd7p-r52~B8u5t!rVfh-Ik zI{h?SmSEC4b3@IC+;ry)8O2C6Yhlxfi&cL$!|Qa0S5 z8KlXpQ%eW{DN8P16cD!q0FbdUG3zSFwWH`1E^7L_5;$Z9A=jOFM--n1A#tnr-lGXH zKR%C#_R~Ngr|<8h zXEkAd>Uk#c`qy^2u`s}1Aq>S7gDj=HG#-jRF#6TI|GRPck@E-F*XM5{83Iq|a&RB? zA3tV**uJOweRbU?`dl^xNC>)96q1O)dd;F+?>ZxwzOr4ZtBcnzgXE37DL1F2dlx{0 z@tF3O8S4DPnfM?b$GO1(ez4woHDpw)u<|7ZTDqLLIfu);au8$Lh^{c_`!(I$f0@i%3yke-_nOe?1}e+g8esS|wz{-gBiyigQ*VwU6kR_wJ2411nyZMtDQC_a70c z$bI?)pj4K}=_cJhr$@N`@&;g=JzKOc{N693XGrIpE%-9+4YVe~)hWdMO2zM~gIYgy zV$Ip-g1I3H)nh7`(<=R~8f25{+1XbV0*HARtdTQ`g-m(()2a^bW>jQDnf4{!rb zZz@t67{9?aAKGGftKMJsIuX9xXL95C$CJ%$ngN8${qRI;wqC7Fzu48y=4U(EpzG1+ zS3#8`Zni)kiaaz@s?QyAbJHi*=5?|HWEU*10@K@8lL2KF|9^1>U?$dt1(sg|x%0pa zxcI%$Fv4CsOcJHhG?!wv*#}jb&~I0j>Y%F5hagwX4vHr!_3W*#*A(YihE}EGvM}s+F>%LFn z3FQNaNC`kzQANqFKmn1&&91CiWZx3rughim4zCxal$2qajdO3Q3^2Ww2%RBfWn71@Os$+PjjaLKy!VNX?uYBPg&{gTw!M2u1aS%-DE} zLKVj7EzYo>S*mY)?qkKC7jhnR)KNhXw^E4!V&$35?_z6?k)!gi2uFaUN{^=>h|HW% zR#^Y;Eb78|^tvETxjFmFk2wurdcyi$i;j%;3%G_K2cQ!Rnu1v-$$8kq6g*!?z2ZGoh)fAxWN8Bn zWUv)Jj=8?@;R^*+(sDfvVz+WWj(@`uanw+#(wGWAt1&gfx5tgF>v`Q33GFK)SXo*B zB}D)loWf^`VlhuzPV!e4VW-VVhNFoKb(m{s%uL*q2jg z!ry$5O>5M?GAKoz8I;oiUs_9pK5sSlGo6&**PlU{v0hfZIAa+UKQFd9g3`g=@*m=R z1;raBqSaWwtPY7!Lhv4jBvHH_x+IhZ!Pxp0vo|+4|2#%PE?P6{>jH;HyB_Gw7%(Z= zpCI^B{Ua1nHg*9oXa$@L5Ma&!2(T%>Zjm8Tx*o32Xr-j$eHMC-X}8O8e?aZ);Cew^nJ^E`&j9T>rb+iHS|kkn6|D>DZ1+ubVp5}U zj2E&J4R^j(+n1c8TT?;P+GG?pe71^to(kY!JrqAh6A9j`0+I=#gh?}7+sJ#FzV_Si z?Q$|VZY`tkQnJ-p!ZgN}K6euA=hTU%JP{FJ*)MQaR?!KOx84swus@SNPxGxjaXf!| z&{!n`KGO&O?sH71tekRmQYSk(U*bI{A&6Io#wZStFJ`T2L-3#9hZ80NuFVFjPb{ zekG;;eep&5KvWtaWpo}Jt%i#TfD9j&bgJwZQw)HWFcTT2hHf7Aj_jV6zZy4l%wy?I; zJHOif@)Qr*VB$iJE!y)s|QG<>wnSWaT>u8lcCIr)n|wa!WZcDDD>NsbOwd=p3w60Y{w zYRUPV_!;Y=wrH-SU*(ySz2_S5*?03t9oEyIv4A)h%@;5{zbhzr-qUPpg$N0?W^@Vo zn)R=^2-NxXJX;39CuS;Pct#Q^f~}7DWoxfeJRYjH`7%%sP3t(+!=aR`X=A-InmL$@P#U{!z|gvr7Lq|{5Wj$|HPu7A zx;Q?c_5m!!$ESlYjRG_%z$>h&&@*%xm6pO{mN6m)Rw!)Y_?`awGK7De(n4=^csNZU zO(=& zlptfFOA?ADpFTnM>-Rugz;24WZe_30TsUh$KK;O&&hW@0^nEP#ilH*+JM_9V*F`=) z0g$qT$`Bsp4i;E{>Ui-BPc^lbyp~taI~cI&sh!d=;jcnxkZ{e$G|n9_oZr5;X;;I@p{w~a#aHK8HWe$&A|l#E4}N`Pg=O4 zX7^wCe`S}(#%QvI7~*ap_*u}4QpiiyYA?TFYlGO6$l$lj8C@y1ZRZ;TafH+ zjOHJz_|o$}zM;pBe%B1IS->4p2RiL{GgCz>Vc6ao&URFr6D*l?JtmV4I)11MYy><{5W@ybk&pd-G zsYnsL&9f3lsQTg!kiMFG)jJ7YN(unHeM$7Gb7OnuFw95j9ktePDUtQ$!Qb6J!y_YR z?w?>Y?nW~L!pDGce$~d^EthT$1t&|E>kqgsVqVIXiufJxeeS%y?HDS#yk5$?GKo>u zl8;5tXaG;;+b_HIB5>|?XQOOG{a2f>A!fZqFc=KM6sV|M!hO;iJw!fzv1?3<#CbE= zRaZWDg7?@et2BL>(huZ|M{CpX!Z<$JC5B$v(d^Q+c%7zA7>`srH{2kr^j+a zg#t!Wet|GDL~_n`N}rv^`4Uaek}T1TUX4g9_(jNDPjo!~_cE?#Gztxs(+(aA6=TQO zeaFA+PbymvW(BT)7)(AsP8?i`-XAX1A8byS2o}Y%a35!y_-FfkaESJob2nd$wh6EbXGAVe>5C zUQ^D0S@~qBmPW&A>E3?R5A#v~t1NHM&kLbmPp70 zTco@$1Eu#G0&HnCOUS6YrTTO)2D+f4E4_dO%~T&auPcI-r&tas;9-_BMz9Cj=N+la zSU=!I_^VB`M<4zM_m*HU6|T<2hfO`e7}VF%?D)TGc6EDl@$>V)d)G4;h3cy1Q6=>V z`@!e({>- z(!m_0J5Yg)>{F+;s!4^YAZBYRFsmLGEu}?;Pu=w17!B?VNHSlbh`+XJC^pdc zFv`($dE(j2TcueeC9~*VkaW~4_9xJ+X@|I5D1I)os;!pJFdM^G9(MRNmQ}lBWe131 zWP1k5%oA>x?hA+0k(^qANpXgn3{L(GvX?R74gC62scJY|6Nz*6b`is+Lv2RvFaEKo zDL#OQw5MT+C9Ax=lw<0+=>g*-d|4O9`px))g`c_9g^}?(hEJbN!EqVi15>S4ApXkn zmV^0fZEX#h^I3)byD{r=JaSgN%N}(-=wh{O^C2~Zs`OE+c(5`{M(Wa`P$Ahz$ zO||nWKQRCUZ%1cS1c$pbp&lN)UCAR*)LTZJ_EZbz1+Z>&CgdT$NR`KX!;(Mf0%j`! zVZWwEwR^6RD4(zK*bC=2D@4mX+w{$>U_m?ljwFK(G98*VDCqyg{mBgYy#`&|;+B|2 zhln{bQ5kH0<5`_7(RW0O2nt3%uXrvx0OzVeD>dNOVJzN+3j#nPfk;F|#YDQXAJ%B7 z8lX&84n|_ICa9_{5Y*+@vAo4$M8#phOFcKvZycYc> zrHYaDvyp%V|2;(5=X`+S4EgeYvBBY@a}t%RMz!L^DL5DEQyn__uE93q3mZ(gSKgK4 z9hq5}YjqjpQM(03OS$xi(FmHb?kW(%2gZjcuLn{Pzt^ZY_<4A#O>bkt$!OHa`6iDh zjIxiCiI@4;3a&&>LN#-;mPp26(}nh#ipwy22*EuLq-~YPCT+jAyumd8ZZ^ zsioxOmhAMOf4_Ee+y|$4ATc9^vb+l)8%BsKA}D4Z0umf&_{$_v2E+fYzQ_Wy9h_fV zq+#$TI=juO(>?D`=5`l(X=`IAQ(|pobwOh>)oYfY9+7Y^*Xah6Vl5dOlsiKSV z^vQ=(B6J{A207Xf`k!8P=m#N=FjzF6UnleW|`K+ zZ!;LtS&Rm7z{Yhz$|BezWvIIogOGZ~Z)q)zvL>1a2#BFTk-Ql-w??Dn9l8)6b9;!9 zJ>%Z|t3ki6%hq!qwr{>g-SbN(=gclUSG!E_3c>W#z+G}G$yFnB^Ya@e_lXa-0>jy} zTj6)j8#ia4;eRM$=IHlMF3yqL4Ko1}j+eM8S?)g4i`$65w(@X#5)#R|o*K9zcljlu zqpI6KCE+!iE$LQzJ0V5njXV$7@A)2#cAxSjf#UDbF++&da?M0;!2%|@Ztj(3FshU* zK2iNm8y!l5H<5mh#0w+S)1a*G_@R0B=g*(%%Gv#@MU=a@+}6uhcoI49lVD9l7nyws zperEz32pB-9|27ze&^RIUsWA+*^{&+FShKOcAdSZ<1W32B}`w@RFi^{-3fg*(cn$d zHxag-x>J*bdMPTXXPqrg*nJL%^oZ&rD~L?U^L5=GA2SXY{js$i0ZEXC7f!IUelp&n z+nJR8H^VSK;pBkwrq=)Nq_)aUm2cS-t-hd#;&va&uNZE(&I>w8nh{Ka z`4p(@&1W9J_6oieEE{$xQVm{4mDaROMk2j&H7aBRH&fR!0DNtdB}gf?HqOyu*S4Ld^F6B$Mp zl$!Qryr>(Zup&EW%X^pF-jetN%JDwCKvFwX&bTa9;n~RP)_nfrb+h>A2B|kfGlZ~^+jq~gg#3|1fFJpe`w6qLL?Q@ohoI@ z*`?G&yFJZg{)2KcOPX~Ea1>uWQ9l!ZeE zDQ?P|433Cn7zT)XL?k3#rlEotFPi^Vy%29?a%~}T7T!W5tbRU^n(wLx9!Ae#Z5E3O zDk;jCXQ28dEvgR3x+!lBksuVi{ITF>GBS0>^0BOCt*tDl`n!4Yg|HMWpRyyULZKW~ z=9`we00rB+us%xklB7%PatSj^t4#|qx8=N{)YN;)n!KD7;NKfbaC6^Ed4~~*a=ohW zzRyn>jAO>RHQMw&?C$4uth3s*RA+V!%TG#|Nx`3kYW*xPWBMh78jAv#oaWloLxD({CsnLn zwx@wJ$CE5i$Ne`l(SrEoq&NjlARp~F>drfNnqMw4v9Y4S;YvT#Er=^M%3w0~p_o$D z)P_kC5u=1wVpjy9n|fGVQ=s>`Sh@e@B*&xPGqjyC8T9_8rj_N-cY_V->5`AVJLrGz z?pH7KRtsczRa8TmceY&id71)j3juxU| zKY6j?`IE`WbL>-_KDyOcFtzgFoN?!0_Ydx7nhI*iBv1r}Lt-IhOcqJL9=fmoe>Q$d z2m@hRbHf))eojWptOC}UUzP`_QG{T{{L}T>*t`=yQVt~W_{?;L)TSk0wh79AtnrWpRs(>C2p6mCJ#46F*)!c*NYAfe);s9O{(nD5maoeY*#>CK=Hzvv%nE8E)||8! zZB&c$cbhbA6iZZZ&kp+K4Tl!16-Wzyy`-b`omYMRbNaEaV;1`NalS7nT^|($?8j*9 zu2$9E5IqNWd}6~KjoZM;8b&QI{SGBu)u_#yA2O(`|LZ_}^;6Sww2sIz{4oF1NcLbf zVO8&{UIWz%?QU5lP3jp^^#1el{4V2H4A;e&*uu*z-gbeiWt!j0Vj(86+8o^?gkF(k zC#^FWdZ`yEDLfTlh{dfWbS{J`$;q|)!k2T zz79ys>Di4yxEI+c+qW*VQlD~EnzO<}8^nG;^?^*ihqOUALs0(#=B~S-cg*{-1p$#+Y6?^waJB9aw`D%aR(2VG=N&5!x z`S8ZW>7g`lnv#NiE=f8^d9#Cn&0bk!a0e&Sv}V@hvTF&oL2>)CpyuK-i#9cG+iE7Q=YjX-RG8a=U0-#6yz& zR~YsIc3f%@`nq$%c8A(k==NFr-Q=j4^guyx$dCIVhpi@>s;9{+L;ae3Crir#$kb}% zh04{*Ln89Z!?)F-&h~}&i>F7Y8+;I%_tA;iiT3ql(Anx(>lN0@+4vFYR5lFCdV58g zb3gE{irCn5?$9dCO2s4?y_S;)eQ@d+%q%r6S&DtwuN$wqZEdL3RpT_EQ4KVBp^&@u zR(_&EAm5(9YefPg6XxPd!r~SaF!t6xn)y9>O$Ny9-;Y!>)j2n=vHS1mNp_#2ChWO1 zuo0m0322{18hYW*QGhboRN-0W;(A3aD&;P@VN!1NkmMZ@QupAA45vM`+LRg$e!rw+ z)m6UCr8!>qQNL$xE%(~^wJ)Ov4!ZEBc3v5TZnCD5OWU+06h&wjy;M79*6u&DM(E>+pU%=nPiXRPAow*9OfgZy^H3 zItCt1oCLxqBV&fz9?F9J`?`xb*lvT2Px(RcoQLC*fs(+qlFKS`3KCiLa1unV@bSDw zX18zUE_of1(fW@aaX(ymQHR>-oCueQ%R8EWZRnYqP;cl;6V>*d7!LUSNKMi9X(%M9m0mSZGD-(ofpJlBmzhk?0!d&R>8g z3DA+~kj>!HauXI@ouCkJh3U_;@F%>9hc&rXYL`XathGn*_Mt(Tp_P)_2zstFu^H4g zuHKGAW!glIoDer7o=3Nr8PchR42}=+Q+?TO)#l!N@LEN$2B)j@^I8TF$kGa7O}6g| z1r)f&Gm}o*@bJ({NvY?5<})-FxSx29MRrF6x+!W?1Kq6DwS7w^Kul&GqPUG(HLTgg z^vTU7S76v(7lSIQp0LcYl%TpWV7cuDGvo^^bs8G*g{jU z0XkbYR2cL5ou-txbti6y;9@{>`v+-IBj=H#CFj8v5(KvjIl}16$ z`2O;nx4%dbJ(42CZm1Smba_9;TM&Ahsg#n_O^GA$#akE+tR?p z*SKbD2Ur0x{ zUrJZBj_LJ>dvrZrJ#5(&>cy_}yWC!7P>U?40tp-4iEr6 z%o{x4dIa6iCU35iHgevs9Xz+UaXc^d3$;D{7P}kE;cxM;@-Q~+lu4$$ULpsxnuisS+zh?;Ei+uXX zMmQr$yOPx_S3ZEFFK5(2iMYOoQRn*+0@S}%b1JSmO+JZ$cbEUtmX0naJHIsk*<(2o zc`umo)3o=!I&t&2%l?-7u@t1$R~s80rzO0Lr`M1Iw~(K`sYP-KpwYIylc1nQD9E%o zU!nc{p_|9f_%1jx=P@FkBYTgMEZa!vW$N8M^60}6av_Dc&T4{qAa!5lPdcc4b#Wl$ zSj{lEx+YK~SOYwQ(d+|;+9EkAvZInSDJa&yjnM$=$&Kd*i8Nmup#6_h`;M_7+b`%g zJA7TbTA6YxQ#0z`vcDzT%r*WyJ->66!c=gO8D*d?VoyHYHnZ-DNmdxnP**M;bL!v_ zK5OtaO!m05u4Lb?$#*LIrkq85S=8~Ue>>Yj6fEa=GJ*M2_6Euf{=m)}rrW8uor0r) z31UfQ&0n2;GI$qZanw$?<^Np4_XyjMVZdB(53z#D2U(t}KOlf$vn!b6VJxF8sUxjn zD4+lki1S_Tj^XOohQc!nxzP4XmfRj@dbNW+fg4 z(_Zv#Qxx&22Vk@xOlFZ3*vQlcBG68bRN!6qA7^Owj z@3sd39I!08Tp&~N13kr=Y&@WRHv5J2@5_cH+(_KYQfTk^F6T*FrrZ9X-2ycs-eMS} zxyyMRPhL>`Q>Pj`8EH-dA+n9SYs6ltx!#{eezuHp4+&bTjj^)yeKEe#EX`y*wN#Bx zq67&Mqw*NTK=Xrx)4tPFZg%J!JeXkj+9dN@^3EE!Gy1%1*UfY77KOemWsWx5D!;YVc zxuwOmLpnMm2?sl|gO?xJny!r;4^#TrKGLIjdO;TW%Ns6@qgg=>#g<_5n! zvFU$lgy7^{(xnT%SDh=FvHeSPar3hW4LOM^gUU8w^db{Era@T*IP0$;Nl-C6tk_tO zE}yxKLI&vERNtom49Go3#qEEh#!QoWZ*Mr*AW@xy(@A9NGAnv9Zufkgn%Cy?usxLO zRW9<&=XSm~pf;5~^E;%o<+*@{2XCAY9b}i%{^@Gtw(aSuP5Px(JA6Hzr+y)9mQDYf zS{UkdHYt5zTxY!;^`@d}QRW10TEqExxbAWBSS-(QN!j`F{A?23? z^c6DlL>Lf~w2fn>y4oy|2|#kVt!J|{V3u=V)8-xjUmYTfHexU8uWe|S0{QMqUL#dF zB!?@qnCpe|HJ%x*#V5)4b~B#i-X@uAaM~Oo&HNL1k|b{8t&9rz`>!OEPwRWA1UQqv z4k$B^8r0eZo#ua^{Ro`4zLe0a`cawE@9tr5YQ64F{-73>^?B7ab54-&rq@{cv5*_t zoh8RGrf{qGMd^wN_y1`DSck8=^XU{E|EdN^25rwKx5LF8{l~89pAQL>2K8l&iTZ_A>Oy+D90`j-lCq! zzXOl!956d&+hVwkx(E=TtxOd^y5-!Hjg?1wxDny{?7kq)N_roX6WspY7agc75g*2A z+WP0_E7=FN?l9w50ugrD1;>P+1nMLe;+S^a)KMy1`kcVO(1a_n*>+wb-;mCxAs z+&iev+H=57V^#2O``P(!%1QXrk3;lw0%ig?F>2ckC=z@8lb7?z|LyM~gr^n;d+&ll zwod3l+4uZZ z3{N&IdOlq5lHI%=a)2&3I1lC%sOSq2Mkua)Xr+vZ9uSl|xV42;yTO*Z?oy=1UIk0I zgmXhU5N>L&dG^N{#@qrYx{#GJ-Gsc3w>qT+OKC-X>7Z} z#rMEVr>x9}3upp;z6{_lKmQx?zN|1@H;lCjvfZGCSIia;)(o&yrCU(ekPu2EBSs}q zKLlc#vfzsXMOVY4O>nFJ%ImXPi7)#Wv-Yul9%~pgKFBNwAy}e}Sgfx%=qBHw(S3ak zUpW6QLlw3tp?lPQ%$@YsoBEH^5gegoZWUaEzo9EfQ;7-kKH1Y=6d-Iff)w7cJ1QB~ z2qKoHfin*c06boc3RJG!KnCg>*`ATzp(6SyauySEvsp+uDk2Zjy?4b~{}Me$)OwWV zg#2ZoMDF2QVikT)$2UTLaNq|=9$PuR;utm-gq{@zJ`S(8vlUzurjARtZwAB&an&r0rkDxH*%$6mn6?1vFtLzw3!Dl22pSzm{0 zYg5C#0z7XIR=hUv13@qb!v9CpS4KtkeSZ%KNJyu2cPbzq0|?SNbc^87-6@TLv~+iO zNOwsOARrAR-2y}S-0$yM|2G4RH_W-~+;jH+)ZTD=Xm@-Z6K&zjd0y!;y{~k&lmH1` zZFtrqV6}z`*W>RkK_0u+t1L?b(D=B*LT-Vg&vCIzxw@!HKy@o zb$b3@0|c~MH0^tH7iV?`0o4D*?^oY7UXi!mEyyT&`r(1HF8rN!&|B6rK!iVo>yGtY zh?UyQ)+~Nzgr~9e3$s_Xu0Pb**K z9B!ckCtN%=cG(jtI99A6Nflu@Z;v!T-oPnQbi~S*ZALi@bIEem;|4A_ZsM@WqbcElW@l$zA(GMfiR#~QUMre+f8c_wqo4=Py2=GAA zMt~yVFu*uJi@C$2$DA00#^)}-v~=o*#{>m*ghrA;c|7berqg+Wfkc4GkeUV6XcMPE zB-zNj13@{iqN(_aF`^??k2&y1lgP|%#I>lMr}@+M`qCkdNfDupK-?%Y zi%TQ`mH1rS^uCP8bdRi)|AP!M{e@ZqgU0CZi<9#(z>QL^)_vDoH~Jlf>15NJpQ_&EftysBFm8Wb>W zsfhWqIBuqK-|ng__~N1P;aU7CV87oA@w1-&3lmSM)nH-_K~aD6HJ7&r<}Z9tH*G#n z2L04_#QdL}6Zu@L*AOp_)>ivffQKrnLa50evaobBd`&@(q^1X28dUjtA6Kfmz3=?? z>1-;Ma#fs$m*37;UdgFCirQ1!Nn5_YM{t6RHp@ljI3E|TOh#$29E$#kV~hxs-U3CIfm5hT*@yroVWnh4gWZ^n&G{^1@+Y|0H-5^} zW1%gIgVHM1RBRhRl7?74)SKl9pkpTg!wDNW0mVVnrix_XfYCR&@V%PhyL_XMBs>_4 z#2T^6F?!}(FO2+%&;paXmjh$)2#rT_)tQ@ux>9Ypa7tcvRz=ldk#awpo&oe_h1FjV zP@N;00yn+dyx2Cm@?W{;{0&Ome_Th4{VsEJt-GmIFmEhJ&Qfp}&e>YKE386C-SId7 zVqf@|9srYz6rrne{wLNCB`1NLV+BtQs@x14ir09`8mf59RL7?AA4wm$Wq9~O(saq) z1B&IG+~)Xs)TiSz%3r+1`G#up{&9PDxPd{;@VC>{7W$ZPF5DZ~wuIt9R&Q}5_}qsO zP5Nh*yPS4P{@d5^nL^&If(J)^JxgXK>a9W=gfZgh5}~Ev-N2(HN21u}f1;e8fjZjM zPOi{q^!i;$38%LPTt`$*;-0Z~m`F+^LhhlM^BZoNn#(MI6=$VhVxlNEMnuCloBrZ}uFvuuf}gLJBF%aD8^oK{lMH5KPse0|-0u zW5P>Q^4`FmW)3l>Jd>s>tMi4~$NWirGI1fJmZL zF+byr|F|WPUW?splm}@&vB&4zt3b9y$ftLd_f14dAN4=|`~lF?a@6D$LXL_RV)Z`! zKdabr#YsJ8iaWcF+AK$KR-iAZ<(}#`3QfR8M_)$X(E)LTy}>VlqT$t3Yn}v47{I`f zgp?Rmi@+86GvnyV^?ZCeegct{b3Z^xa z@H@Ko8N%S(oLsW*_~CzYoc{PIU;$(g0cQWLufSaq&)x3q;-aVsaP)O8iII(v!?l#= zf2mBmG+hzHrTa>SpGc5}aT+hhT1yzYMCFvmp_>(JZ#4NebR1p>cSv;b11b(BI3VE| zq4}@EfgA8>U1{Jz&Z?fhG2(95>q)8QWalkfxblXc(b51#0i z_#Vhdhe{Go)|Z>Y)G6oGBAq9O-}Pqk^rU+g>A&XT{V?Vx-O%D#_*^2TI!A_jHsSc= zq=iHA6?_e#o8=abF3yB25OSIEI(QY%bvLLK+}WuGC=2@BATk{0nr}{Etoq$)(`E|` zz>i59Kk?!O#6XDCSQV-7{!ki-C@n6F^NF_VDJ;tg+J6N-U2A_^rSYF;`2!uYfSxXm zYPrhyIQnY}V@);bXu)*Z|27s@T3x;e(k#01rK=npy68fM+&{1cx-~r&3Y~~&K+kfG zkz3@T1a}VAL?mvwQ6xJjivDKF=$JwE@Se~VVU!5G^Y-zz_h1EeR)OsxG$5?*b4NwD ztEvEy+Y^zPlOexo_iKEK@SbyNE&(4Q{`t63j?lm&EMeCI_3B~AH8;E4^2CLkCCjx3 z`@ApxHC-$H^cSfFZ3Ys8Mf=Cedtmx?XjZQl=R>}P#h78=VRq-Oe(FU>Xa+Fp9?%_3 zyvefL-}OFSZn?y-Qb3k!HqeQ`)McQ+amxWVnEY*?2XW1KWm)x52U-)3priQ)#WXRo z%NKGFo0p(0S0VpcK`ozjw>w$Y?>_lP{KZ{4uG$ZD|4R5?CkS(`;g)(8 zxjRc5(`|@Am-a{z&2DP!(r8r2QHO5%paQY(tAhiwF2xiR2;3euw-vv5{A?A@sV!4Q z{JuM6Y~$JYkN%Sm+S$`f3B>G1z?pBDSXQPqFM7<<8ha=Nsa!9C$OYOHg$QLjL(xy& z^Ny2Y^?pS=eFe;Lf+!+&-fnf~(XRWKms;z;=kaiRi>?5GM1{UH%^L1pn~fK$T;^+Nr_LV}0ER$=a?!Iel# zE)(M_qjkV9o+cV^zcre`z_?o)vo}RlwE*aCbVyRy`lCA$ZepOSIpz*}y_m1;`EPI< z(a_Kqepgpbk|dg1m^Kd6Xya8#EW2Qpb`e>;u2&pPG;H)FfpqkWyf&qA>jp+JgCD+& z{H2&`|IfrEOv9q2yi5mBqmcRH<6i~5zEpV@qC+&5pw2@N_MabHv-lcU!o#y>T zmo*ftujvDb*&Gr0>5nrs--1zk?UpPg!}L$|GN?9wA29>VpvJ?#YQn`U6Jep}Eq|&^ zI4);ihwi2VN}Z`$jjxY;KYzvO3ixGz+fNNbq&>*B@X#bQuSB0(Gzk*sCPi{ox8$+n=n@jSO&MJ*BOo9x%8R8 zmR9JVSYp6DK`UVhj&4lgw`%iFSibEtEJna`&2pX1U{-11N0hn=x^5sn-5Q^8_DqtX zW?BD#f+>&_Fc2Ngtv`Oa8I@dbTTnye7rPu}6cjl{wg4H}CGg?wk-ntl#lD&k zC!1wU6b79`=tYoYd6Re9zdB%~|gdF}>qeFk?MLg){H&;hsKB zcJ6jVGs5V47vhCp50I`mx!(J)Z!9Gi9qw-b-u{DGOL7!@FotC*&igpPqBEIv=K)Oy z1-?r~4e)+^o4-@84uC=3p-@cYp^W%IZ&Fgov(R1+Z{Jj^q~;`r8A?r3!Sq2ji-}6v zQfAmIAHyb1ZanQ)9l8k8Z*9S!4LlYutN+AYwRx`JTH+#+!PtICeYtk$ z3Mlr6WpzKc?P zy0N@zSPKL|yH4>T!8K6xTKHO<~8qE#!HayRDZx)Z1$As;v z8)8|Eipnx(y6G82@N!XrhL};PfBJpcu^&Iv(n70|-xm72hC5B)8Ot>php1WoO=+2qaql z0ep6du1VEX|MaA_V6s9B=**LFMtJ?Q3+g%&~NPAQb6{ z{Vh#jRx`os82?fYDh9e|b$1a=H9o7vD!fCj)~WWat_^CoZL#TknvpO9a;;0Xa~DyQ zhd~~8^%qJ(O242!scV=Guw8ivBQ%gdOD=(n`~UbH7+(^5s2PKnEf@=wg8~Yw zZnb;rT2e_kPxo<-l7GP9XoLWP`fi4J!_!&mtBlIYk+rx&VBu#4=fuKs9diXeN0}^F z8?Nd9#xv#TI{F_OQZ(=Pj%pp^KiIq!xX6D9A3%fLoKpVRb*b|47fIHe<9}Ag!kc}m z&$afNf-+(TIo5r4n{hbWrxjg=cm>DZl}$KSW-3A$8%}B%k=W}}G^fnAjZLvXOyZrR z%T7%0b)mW;Lb?adH!LmF8~>=E90}+S(iQMskNjiiOZWG`4T6+@2Oa?;Y1oad4*FkG zUrzt}kah<=P+s5|{n2c|UI6WQIkiWQgMEZsNjW%OwE9 zD)zkZTrz#T-4iy)9;Tj&sk1#%#Vm`FA;cSI8ejKL%116dg<1sZWFTv+LW z_7+mvTwFBcMfQ(ZV^DEnuC?ws)TPPp*T1OTI}G4hH=p>~Fj?QMVSBesRC@A(1QBj_ zE&Hne1x9RBSpNFk3u zcbahP^kUpB3XUER;Iw397g04%lc9Pq-qcL9^z#0eynFbZ2FRofj)xzN$kJVGe|#f2gDm|2x~T zH@)8Fd*9=o^MF{f;ZS!8g}s6UYpdp!T%xOPN~$EUwC%3RoAX@hBHC`|(uA=D=Sf`Q z|Mi3zHkw%4QE?2BY-tqGt^t4;<5#go2=b&H*)&0Dn8Hkc#YMVcj_tbTW-+Q73!u#d zDqP&kB;Nj$a~}n89S=O;S=OEUxSboT)<0;-pr|m4TjIO{g4QSTk&D~_afq_&YCXww zKY6_F|M_hFS=@IsbHk|9R`*|y_}d?zh6zo(kWj8Cg=)fGZwKO}lrkpV2^_Y=B7oQ+ zHRw^&-pTuy+DgZis8D+DRrzvRhc_&a#JaS8WzrorMM7=>=2=Y?`94l0^>TSxZ@ZC7 zrO$2t2N{;jcg7S&Irnb1E&WGgx@blkP5v8G*2uu>BY8S{;v5`vus-j6@7R@CRsycJdM> z7}jb1Fal+ugH(RTVj3}ouGcVm>9@RVq~e;g4XTUcR=%4It?khou8h7l;dfb}vzla+ zWb$j($7?Te<^6rlJsd*G{Gl4cp&NWqrEm%Yiaoan`Y+Y+R+K5>as1rR=t`LJ-6!^r z3>Y-{KnZ^ZSRFnd0v~tnj5w{1?uzCec!O)~SczCWsS?sI8XiX^0!F3~)2s(hz5wlr zx86pl&IWGV;|AW^dr$EjGy#+FX3|{32S?+IT5lM%c~$b!JOI7EB8!+WD;;ORrYlg& z!=dxyJ$LJzPJME9I7Hjw_p;a7Kv5X}q$4EI{oU7B(h-0BmEXig%rw|`W@1x)H&u*l zt(q})*ZWPvGhxfzsEdkK9j14lj!|X`$J8MfOUMmr<|9C|J(0pYXjzGbdC<2Fw+i69 zbH5~CrA@0$SRE&d6bqzev6B98847#Z_Lzt-b90tO?;R-m9dIbqF zvirtqIklc%X~}{`BM;*Rd>X%gF^|CV_kZLU5-Mw9HeZ9C@%`CZT)=FLL)4y2ZhMp- ztb1{MokGqZv?`Qe)vtrepl&b}O2m{j^o@?@%S7bWm{n8JZXGO(3c=MSmF1eh$l?@R z-n7^U`$n28+r{Vn9-Y#C$=)BsG-29%yRdHHwKofjTTvV-D< z{(ImQyFAb5f98=^`w3Wes*NODZ(anj%x1)BlDoOlIxbiU;KmrG?q0Rss!Cis~YNKIos`_ z-wZT@F+xnu_6V%iB4q1)R?!d2%cd%kc3%)lFI#!ObjiULy)!H;n3wUNM6U${;xp3} zjW1eF3|tz1bQLUS6s=j>rno3UQ9B6gQYt3DP%IGlMqAFCm@B=}6Po8boyzJ-5&M)k z^;;|i8SIBeD|x*$x?v>wZ*D#8>^S`=<42$Y?&R4psp{t4*mk)8$u?_ zIjai)|KEM*5Sc;}MpDV=>g8J3p?UGLDXk zE(+S&%axg4BKhKz%^za%pNNA#`8P9g@M;CCSYpuX;7SIsa_CM{^$-XO$Wn^Tacdx9$bYh;Y&xhVg zzs(6

9`q`y#|ry^sF0B0_N{`~o8Mmnf8>F6_NU`R$+leqR!F@q&Hp5~D}bxv2qPNpv`eEZ!5HTI63(ra;zwfD-^Wet|&+ zelrcead4kV4Nw?1p~QcMi>rj+J3kU1Cc{0LQP{xT%h_%PUsW?srO)J?*es+;(fq-t zk6-w}ieDVr4S2S=be}Me#4N^i7}R++>h@4{>%P9|ohw$#mpCk_&RME4jsXW$q8)3V zcEMdpId`^u7BmW9EOW)Ut}3Koq{0d!+iJaYZinBA16N>7Z*c(tn#%g%^$S~zoBR}I zXrdu6I?dethd}6#DS%xb@yYE-7gI829L|koEJ?s{!=hmcqew<(jY?QslFAnTCd+nP zEaP%d&(n$HNZ{;i(_E^in#j&gFVhUYJbnp6#Niw6WdzDWOv1)h8h6P?Qc}|KDDhn= zAs2a^-LitKwneWjp&5fA1)84j?y!UjxZA_5=I3QP0oLRa0KaG`WZIPog(ehf-O+LM zGtzwadpS>TUO8NS)Xe0V!G?5z1?LiFPjv$)x8O&`&tOgytZLja{5;PK5BZsT>baex*^Sdy$CwaSvOKI>a9~zUij}r z3xg3KRz}ouU^X540fuv?{^d3;{$C1qF=V%BSBIY&0^jLdUH?7Z&O4e#EZAZ!qgsz~ zar$#G%iZ(@J|_~Pp5JpB@b6-UEN*We3?Rk}%Qsj}fyuAWLY}8+B@8#Jh5$WpF4UB1=nYt|cOt}- z`JhCTRdT%_I^wvay~H*5FoJ_W%-1F4o4k*}aA7Pp|GlGv7HB!K{Zp2#NT%$J{DJ3q zbJT7yy`ZScA!Lr&TK^{v?40$}$Y)b&l4LzC8O1E(RO75piQOUO0wUALZBkb|o`|IX z(*g*f2*4NtsPeMKETvh89vt}TWbNfjYmMF;R}KB1)wX~y2&t3~ben2213iQV;D7qN zk>UND$GM#t1>gG-D+v5CQE_SKrWVsX%(k;U{E}r${Z~)0cF$ zz5!V9bmQuuApLws7^B$Dv(4GvdlNUe@`^ipJ=1}vmfF8sr+thDh^hyc^!`j-r_y@B3cBA9w<;j$Xo$7Ec-*TQ?epeDowfqL@8R9^WD!+MEtXBb!M{ zFYli@uCQ_uyH5a9)5J8`{qNp0u;($w)Wl`r3r}a~b$|K0?u*!>4{Hz4w}IyaG~ozq zZ{QD(cI%z5L4uC!RSsN8!!HT3j73c@qIEkDb!tWY?#^G}iqXb@)?;eub)Le;!3ifO zZfx{_@NoZ~SLptOkTJHkW{&=NmdfLF?K4+&GgU=&6jyawz)`XTr;1urgV|WjcF0Ap z;w(N!M?^c8ak0_6pAtlBKHa@`;pu?BqS~-kwJVi~iK$(c0W)FP5Om(R5-7S6cyTo> zAMKEv{hMEuqge3JtCG#H)7|+RSF+I-RTLfM^r*anAa-@2lnkH@tTL5M3)^8}I4ay} z$8+zr$`?ek?JQ=OuUm<;DlO~8(@zCP$+?PlrqP-&^)6K7H769^$i4~|nO`pKDw>?( z=C`SXg^`1+`7Y+bi0k)yrT9;%5;Q-VND6L)5unIT{StN22Q423i$euPYuzR#@NMU9 zMP+w43o^V4$hQ#Jn(@ER|1C|HT7)+LH$IK|o`CoN4M=E-IbD1?4GD%7$MaHXgUAB zT4?KW@nUCW<1Y=(L*|AbHt6xJ=L+`@I~PdnJzZ&zsca4r=yBKirum}Y!>aEqDS+lQ zSWT2ItpJU%Jw`%^j=QMr{O*d_I(-K7SH_B)KYVA&WtB{-_2|Ae>T@PD-U3(^>a=bm zC-xduEa1pwvG7fO81x3<;-CR?ly^PQ$hH}mu|z{6n40{@{28y9T9(TvS`;r<|IVQi zd%sT9m2WXQfBJ`H$pyC>&sW#)hDo`N#}|Go7`Vh4tkE5MaSR1$aWbS@0>vQ!39ta3 zBKvQIv4dxrPGZ*0i!Jkh;xHmY3M3tS>SuT zWIZsNob^5vul{o(qf&Y#zA8p_xbE^nYkQpQlbFOZa^W%SY~6^=d6mK~*RFOXFs5nr zD7PGk7|-QH8HTsbpaDCk0Dh$tmvBmQ$`KJjYAD78`PDH&ULDND^33Tn4gsZn9dQjW zx9~ZKqc42*--hH}m%N&Cz{Oe5HHE3D>w~Vf$@9-4$@{Ho;He+^pZU^!27a*xF4_3N z%@@aZLBopumA3QfG3NZwKs%c%abgn8-&{K$re3|(i>bjcrIfo1`9kcHa{-=irCWax zo6h{p;>P-B897L78i;})1lPej46SDqnOv-ldHMLZvNFGy1!7@JJz{~Zrw?iD+d4My zJN8ly0mBwCPX+h4Uk?I2{FFZ?%C*^bjZ^Z}0o&bk)xa&#PoZ^rTLD8})x<7jQ>_4% zZoi?^EJ2KgP93yaaT-e!@uzT^->ZIZ7QNZP9w1`m<4u08u_{lvfcULcV_x$hnbh$9 zZnT~b|4oa^bt)Vp7e$v1#LZ@B|M&U*`(^_C!}$he9Y|I8ddpbVuNnJdo)r66gXP}s zW#u#McoXmWd8~2c$J)EA<-&NEu-Kz_%Bm_zy=Xy0JEc=@OSyx!Y@1s&9TUp_X%|3uhK=%4cQ-LmvON+Sz<7ReoCm@X8`D|sY5XE zZF9V~G1y>EQ`JW8E(77%wu@C`4aff_|FoxU4-SU#$d^nvwQw zfyVjwDk&IfqVvIDk<(}zMAAn+12dgbTmwpgbMs z1?bt+Jk6s%jFcv1{Y4Q^_%8c-G{8cy^EO9iC5(98XUw!YK0aSvVb);ruG%3-_B$ng z!N>BU`l$wP1E%OtfY+7+Qj@G1TO8|KPM9i|)duFgUo_lh_&btXg&bt~kTOe6HnhZD z^>SSr;qB;5QR;IE zsj8OFFuuvK6 zB^!M`ccek0=oLojw#^v^g{=KvF>>D;$d2@4!>+3d@Snd?)i}OxMR+Tj+S{bQi4ZLh z=XiV@TrD%0vU^PqWD0|pFGm>wtX&!p zU8e>UsrPj&4PZa2kAtZK9@S$*#7V)-kQ+dS97{_+WjeeyZbX47a7a>aoG zQtUi-Da%h>*+N*IV?}A7Fr22wqCre2UAODC2F;j~*+)kkkNGV@rc$_DQ&-`ZDao)M zeV3HThWYoewx$dtzZ=p6Q3Fafr#)6|hEd49=jUs#pFmC@p$?5+3BN{;YTpU^J4%_2 z>$%6g|;E8+no355lHE zN%Yd@4v5WUj7J_90U zug(W>V}w4gU|mhM>r_I@y<6A4TIub^U~YYjj+h&`+v4!pYRS z15Aslc(yHe;?BEHhyc8`xMkds7ENz_h;dvn8r6r8~N^WC`NMi z_@+Tv#DVMa*N;0hE*ctlygzcySXPKIWnr<2N4k9u8=pYTYD{Z+6$bpRm3xW+jO%Bl|kfWXv}l zJ0Wr|G>b0IA2wT1Of!4ZO!@R<1hJ^oeI?T$U($Vma1 za8xT~2B!83AeAX^RqKB?{ft;aUxAma`%WI7&6MfW<`;u*WPnkmz&qaHrcFN#vkA?{ zwO~?onf<5d;Z^XMY$@r1d(v}rd8LNS)pcGi6X7(#_3@+E?qk>$$mvCIY!c!q;_%rJ zj>JAK;o4b?3j#FeyA+<~nO;b}zb>4CI1-B1&byMmCzc0@WWz^d(6yQx*YlxiB2dBp zjZ))8+?e*9^ad|=AL;~N)yE_C7I*oYA1!txJd7ZWux*fx!)xz74pZ;T-7#QDsvb3{ z3Du}-4d8rJ**l&G2j$>7HY z;g_@dOzcLEdRRz6kc7?r_McgS1)tNbfj64*Eolk_e(e3e@x*M_tJs@8si@9as}_y+ z7uR?$hF!XydNhTS{JK_&&{q|i47zr zRZs!Tah|=$1An*r1?1>_>B)B0PZh}iwQbL<`LvIUAI-eOH6qBU{RK6)-G1ePU#Bg+ z9%@Zb7U&%OdG=F$%g)hRnmcwg&J14eyH#j2;KPf;wT*PB9QqVfYIydmIb@}=RK4SC z#=59}B^Pkw(|?tZqZD>OOvVe(f3I5(L_aOR#0{o1_ZyX1(hZ~3uvd_5iZAmhnO2P% z`f;|qffQ64Ph)8HsvYyhxdM~!8-R}D+op1F|NBcL5-OQ0h_*E-gS&;x0bEza^pALQ zdQIdUmkyz7{Slg&!E z>Q`|-(uZ&Kc{3|KKHx9h@ic8cHY+ak<0)~o8Z3rIE+MUt%nsn;wS}%`dlId^7vi&s z+Dx-mvP@CpP`%vV^lW95MUp`3}FWZ!JA)88LN5t%f`***V&~* zOqqZ-ic&KS^bOwbbAf$RAD;9^kn%YBwBx9zM9T;Z1$wsJaZgud-dPOgbn?Q16@+~v zEfOR+C>i*Kr--sR6qHmzcu^rw51Fsq4JonujXI;#Ij0LiMoJeVgp$w%P2CuRX*sQ` zd9CPXgX&8hK)V<&w@eq7)_q;<#a5uQd!cSa7ecIN`zG(3Giwcv%l+^TVER(eH6f_< zU0h~$K4qU8t&=cZyxm>Ku5`!?{EUm`EZyGPLo;GRcAsv)inu-A!h}Q>je6@~FsN-@ zePH1a(SsHK(V1)Dd1F`!QwJmNURZKu;Y;N0@5D<^eX%s&BSqdVh1K)xtI1Z45;%t` z78B^&pymt|2%vqQeP_~j?y$NNIR|wofu>_HRK(HlZ99w4SV((j2zErI$W}W7B17*f zM~`e*^SS>mGT1$3s#tblVO2@^VbLmzjDli^3Q(iHTiqgW9rKv-KXuK05%lA<0}HFb zpxQ$3+)>YoOvF5^)juFwAPN7y3GJMH1XBQ|z$Z!36zXx2Zj9*<8JXdWk3JI-%z6VP^$10uJyNq;vEQ#d< za>1+c%N0m4gnT6_~!Fo%_UYS@)tP#L#7YdcQ5 z3jBDa8{89k((YJ8m3231{rpxmAk3*}z62QQApG&z6w0@_@vkTu3AE;Ogw^7>kz?v3 zaq5W)n%KC4)&w1eKl%Ozc+1#8>lS+~ngU0~c7k@rThVH5_GSYvo;?L@a zN*~HZ`O9nLus>I?mg5CLBG8la=ovqhY2lFfj7+>rvh^{1C4GH2BSEc)#ZhWLy-o+j z$L!l?kiMvSFU7?}y#?7WEYS-oU^3A*4WnlO7rn1?ZQ=+gDV})uRpy7$5YLyPKKkMH zUiMS<(=0+&O>RvQCRM;37-BYN+6hf3LM2oR6_B>Ajw$gMC*l+TS5UY-}a@3u2z z#xY02S$1E_xImQwq`Zqy=~u!kR&q2!Kx6@p|Fs62{kv34R?nMQ``slzSYhg|3Xq}(e*)sR&Dd)BiLWx_cL_NeV z1_{A`GVI%6B9I>>P1I60rmucT{V*c-;QeaB@NSLB-onDd#%7fLv~FdS4IEiS#2WE6 zMzdt2V4k*pMiNnBTC`D1K}PdE-DfvJ9+*8rvET5 ziU2n@9on3cQjSv($esowZsK3dF1OelGUBN0w?+b4&UE#Q@todA{8Z~5h&EA)9QUd6 zTa*Jcrrw?eXOa6C?pE9weXjuhEzIoEC_pj4ykyQ5l*QeO!iYspBHiz!iA{~G%dqxY z+Y!TsBCw3-6=v%|Rw{_5wumHQIl%ChnHbR$C|UXuU+_b+@84jhvW>y{o&#wTfj-Py z00W_{6T#M@p@|lGD~t_lT}L1%IvVx#`N-69=@D8kqGX0;l%v}pysA#bj2#gTuG{94 zs+-cvx)K{XmITU2)?e+e@GL0lF8~ZCVgi7I;A)^Y2)e!?2~79y-aK-^etF1mPv)g@ z@i%RhU~Bg4_x=&McWk_G%=ztX7p;E5boA*o9ZM3N_IhKM*e@SKtoYA_HM^K> zWL0mBj-!azuk_Nozza};v#y)rX4oP)%k^OVLftLhtyN3P7FZbo`40+w;rR9fuyv>Z zrxnz+tzs`yBI+NQxZx5u4+HCjn_)z4dH_c9BqerGo%z#RW#CL3)d1Hotb=zWTbF4VrBB##0_yd3Op3 z@uKFMdtHVBx8>9qI{AE`$WkT!JQIa$T%qfHE$uIq`Re@fd%fD7x86Cqyv+KURV?(c zGsX9N;8?a2^C5o2QQe$(Uq8?pU1q3OLna!kdU|N)*@;997W=dmeGSo1O@5lZaUiXs zvehKXhadFi%6mx-`p^eNm&!!4E6Np;d^6xRH8VA|)MF1I%{!#lpiL%Hmc{E_pX>S& z)oiF23@5!hdzlx&VE}XW21%mtY!%ha@5V>MU*fgqGd6?OiasZZ#v#=$OM@^ zZclCxY#jQ6*A=EwgZ+m~rK!!vV6>HBQ17%8mto7Xt?2`Kn&I#&u-6{7_gJ-Y%MTou z>!ec{+#(k@hM0&SnBZ%GB_U1Tt_43w@$MDDoL>NktzUi#SL*`aS1Hlx^IsXH(%K_! z-*P!V*$%j}ap4aOO|_3U=`a0h!cEYmRouwfj5<7kHL3kf%QODePNn;oD;jJTtu41B z_f}9abzAdCfksA)Xb_sSCd<$rkVDQP2U5p%T&A0GXqs8}A1UM#t54>N*s=Oe-$aAL z(oj&UY81@X%32{Q#?L8-_I9;JKY^3nTgRka8!Srk&H-fr&?Gk({#Uzbr9cbJRyF=x zma}Y3uRK*73ZMnBok<`jWH{&eE3CVV{pzXw;Ta%MKTuX14__of7hQkZ1LBsYE&)^w*mh!>dkgt4i3MZ$yG1tpH>lL z3e6=GOp4SWA^8O}GIBqs4F3J6E^V`mo@yIuFr^Q0!?Wc2CAtl^56%|KUl5qhYPq|+&C6)7^+FWbvd|OSV%6rZ!7bB5u~S9BqxQ` z6~MYkSiMAWPtRbgwp;rF8C1jatnzPd$Li2$o6=5vHu^iDPeQK0u3uSm9-#tWmbw2~ zeGK)|k$3Pg2TtV_>bUjY4VzzqYM%34i=XLP+~pGj*pxG<>{xX7TSqk{M0R>?Z=74b zzP9o&qI{xoz7e;hq^M_(bA??5I8@1Dns4Jtgxo2!-3F_NT`33$j%UL#udj;@l2tC& zeRr;URr(rPjiJb7C|kJk%JZypQ(P|{ncZ@Kx~hEmPr-)GMhXMi@|Y46dTsQF*B6Vk zz?q##JzV#;3Q`F)oSI)=t8$i?HQKTfRf`=Urp0e5QCyXrt1v3eEhV{ZbGats0MkQC zxgi=_(I_`QkpGHXiBwQig#lxUkU>a@;2~`Mj3GP z!Zwi$a{@tdNP~5=>iAR=e*eLdm%;@rv*MndiWC5T#(yO)=GE}Sotoo$iB04+RKj>E zHsXhkjUD#vmR!SB+G3-sh1v%s(OwX}V(3oa%W|Fi?K&;4P7|9@7eF0!VMDrvkI?pm zw8_2%Gua+s2`{y(>WlmB$uKwNDA4flo}ud1zQ$yZpX>^xMbl$>CHxEjMb&`XzIvW?MJ1qK2F6w%>^SB?N=~dv6t!7B z#n2BNl9{Qm1T9p|lEbNs;Z*o&c&$|9S6Mi64Icy|jsQ`&Sk<@4Vwwa)V9eC`ki5-f z-WG8_UvEPmQfhDFJV=R`&l`wK>z%S=$!n_m(dT4FYErrqM~tMT8Y_2A4T+HQSXf7k zuZZ9Tk1Q1FnEz0xav*aIGa+zeEojWkTSFjLF|T=^^G+uV=I0$rqVSpFgg2{k2DyL? zn|p@lRA+EtG(WBY=LwYwEKTus3-{>qHTbhI+{K<;C>c-X9bJ=Pemajq`9<&fJubZCRdLR4U~k`3rh{`?(ZOxK*W%oD%S)IxsWglv zCmPhHPYC{7j_*{!OlNC1Y}4saAugxVf3*+IlYmJXSYmKVj2Pe zPfo-@SF{(IFj0OvE_>$_+*`Ga3-Rr9qhg->cp1rf6!>>USqBjwoRV1<6T&nyvZ=2B z6P(W%tsqC%R6`$zr^^h3pZ3y}k&}^uf`IB*9slF;Sbv>zdj?+kxY?h|j2S&_?e^Y| zkVK=-3r|k37Z~}(?``qboq%+W#u=7yUAP)Yqm>zORCGLh`#CV_2BrU}L;P7FXH@f^ z?3lLl1UY3u2<{!QKe;w&sJBhG$RE7-)k+@Ln#?6k=8<_|5$~-b4PKLt)F5 zl_%+3(!w-e4-t8-Kb!TLKtQG;0YOzS)Y=%i^3dmOmPWHKRS-`b(x{HUh5LGN+{{?c zfNse8kQlaa8pk=oU1uG1zEuI3;zi-SjoZ+C!I$Xt@AVj5luVhJgphBDy8kUs4!uU$ z|K!q-36iVdZ^AT}dnT865&J(az~J5l0B(DP0)mS&PSw5->VR`x09p@q(eMZ4HhU<- zGyItq$PmdKtfjjm?C19a9bKOfbz<`Tq2#)Yggae_&B5=&RoJx&^i;F|Tx1fIV`rbs zpYSoru5l>lz`qyP|Fw^kYnq)d(CZ=_8=yhQMb=qqk!Qx~SokZOeW6gSxT?j2ai6>UV;Q%Az>DOLm_8(uC3dvBn|r&5=vU!8of-q$@QB)D zHbqyZMa6;+3-mq-!%zV}h|MMwgn;c5(#_cpORbLX+bjDTIQIP6@{l`3gcWJ0%hwD6 zb~rHX+k&MmNhKTNgI3LhiCse}qWCF&;5-Xat31(>iGGq787%(a3(y8TL_E;9WPB^Z zM`d*Eiew)IGAr;3TttcxpR<=u2C<@0Zm_)ljfLiZn-ybI;V_w*S}~M)1l=#1bY3V} zWvP0F=%sSC@73K>TGZr$wTL0nEXrQfLZ~eZOPCGRCdzN;0 ztEGR#O2!`%#P2g8>|q(PXh9$RqWgI$Ca9Wms_OTodzGKQOS2HIzUoczD((XwW0hEx z-c*v2o49wG7lcf4{x5ap_X<0ImA-t+JmU$3<-aGJu6;PzXYr)c6fvNC;?E@P@!rxkOoUIX)I^YG6&go<^zs3ouM+a3YDAl==A7`1e%*0 zJd$vq$iIEappnHd1JMoNK3ofa1?|5}ZbgRpbV$aL;o2(6wi7pS#++#o;aFg5*tl_9 zIAEi+0vH9n-P)C+0-l!=Al5h~th0`3j!Q-$%-e*Vdbm? z%aQYlX4AChej9O-mYRm>f0bxRVL)Ll?ev?`i?_O^oE#1$971n`P(<^u=nl25P+&qf z>BMZ|Pr~`#$CR@yyj;qxlw;^G@4(Xe62er+N!1;*xYBLanx9eOl!8NG21Sjmicm}9 zx20=zgR8%5Xf^Ef&E(t_j?uviGYuolBlC=-@1O;#I6WOM)>AC31e{-d~n z05Rlj@_Apn?5mzjN&%n`KKd(@vcqtdlr*jscxZ-2K!PNk+5oJ#EA>v<-Uu+Wpd;I( zT^z4&Oznk|D+4TI)?vyYROpA&<)sG0MPzvTrm-e!ZJ zjkZmDXyf-9VoW*eB2xjC<)&1+Eed~tSf1TxJo8S!>tIjnBlPO)-x4P>-1%@_26I)0 zE$kF7`s%pClHwc+W)-->7h)I=s0~5%solf;zBBM&fCiH$6utEmHe~{lt!xL2xtTB| zca9#aT77wllYkc`1MtN9sdDVNT^`Y*QME?xiD_@9_y7DUTUjEe+OKe*>t}bKh&-gT zLCB}Ap@UjcTm~~-*+T_5K8gD{idO`VtZ*1^x#rxG2J!(MC?F($ioijV0)7hp#e5s1 z=R&MerCkdIWj`BgYZd@nAwc!VqC;1(2w?9i)rE9_iWKPQ5O{ufR6l(F>+bUQKBii2 zF&Aa;%PuEi?Vu2LZ#enu(VAu4PJd7OqRA z4dF?}r*964zWmR+_oF#zi)ER~W-OSg!*QcKG9%333d2B2F|_Jrxqg6Lh~T0qGjXYP zakm}k#j3_k@P8CM*WO$*>j*l&t=HJ(mDpUlCLh2HV}h!97?A-F@yohe!r46Y8e%5f z`sq2io7E_OhiMFi$tSY`F)FmE~Su64Oo0&#e!>yRf=S>wy z;JSSYviZkF>7w6Pub8@tNcche2)*GjxxnNuN>t>;SE>;i3oBqQ^ACZd9F8w)@Mh^I z)k$F$*ves|%~6Xy1FG|0ggo@Z@_6K~G7uh_piv8B)k{ zvOsN0t2iNrUqV7XMxo4`oP#EDao>*XE1(`>%exoZ%KQv}Hq}|;UhR>`A~J>Z$G(xc zFkjW_dP1{4&&nS<8h&rPW7Au%%at7Ro}6~O5*|^Ux|LrMMFYfTQQalji7lxW>_J6m zGa$6uU%<(=|F`+eYS9am8~qcDSFH5@m5=6X;hD7kxFfKy^?m=cv4jK#xg4&J|1M0& z@~tteT&BjP$uFdY=p-HE=N=|bw!GFDPT@$nS4Nhs=i!1?oez4nVey!jK_VI^Y4_XO z7N0;8Zat=y0O93(R!vt{fNHTF+=qQO@g=C!z{rfoJ{RQw>wZcLf(kU(R2SOzR@;C) zi;4u+aw+00;~3r2{G~FHLzeZPk>$J6Ka*R!KTupwI);$H7CR{a$$^1>$N{bF=c4kI zp_2Q^8cohCfH!&?$o6YK(v;Tk>TpW8Z47z z(jy+BQfJUD5(EDJlAb>LEh&Jj>gx-&mD_a_H)Dq?d)KI%;MIpIX|t0%fU<+mz@q30 z!E9uu@Q()n?a8_%w920)TCpwDQkE+w`gZ021m;^44VhjX4|faUqlbTx7lm-&{XKfR z47dbs#n!{Wp@gL!5fugbDZ&d!qx#1_{@#RVLXe9K@Zv0M5HM7Q-dDt#oW3{)@2;7pQwd@PiM)@rB7;$D%z_grpWo11yqV zvrcpC&R0x(l_Q1}Z?$no8h*(FKq1|EQ@p{>FpJVC@XrF=u(ilDzQCdiJvbcW~Q1upf16rzb?!Dqn$ zx^eeCXrGoHi$NH~9VOVK!Y>kwWIHA0BTV&dNm}(MwpdnBQ1C!t(AnD0&|uY2eDe#Z zTvmxK?ESdC7(wUg&rgi;s7FjGDG>jyvNtX*jL+b4#FMwsN4>PCo#HxCq4t3`@;gkW znB)Y_`?Qhhb~qxB$dc?%e@tTv18J(%n-fA5Bm~XOi>fEem}y*19sbah?$Bf|+`}v$ z@h2YsSY4{<5G^EUP@4h1+PAA8Gk8P_yrN?H@|~DZzMPu5-D_bNdzqw(aw#aACi45d zN%`|z+pxtOLq>N>OoJX=VemXLLy1Cr+^8+kN zY6A~0-r%#@cW3q_+7ECNGK|0{od5d4ve(r+t|`!q_(3&r0g=Avx1YjZPPt#7X9v4Z zt;&TUOBp|Yt_+gF8pXQMbV6XTv(~+`_wcXGTB}XRTFNXcQ=Ol2JKU2@vjPt}_@KU` zAov^#P)6A=BN}bKxd&w%mM6}0oag=H8n)&ib!*9#s>ia$kDp5363oqFkzUg|N8hc@ z3xn}!=u<9wjJs)cJXKPfzQkdP9lkx9FVDJR&+o;2yUP(zKWE7GqRmzW-8(3ev_c*l6-L~dBe)~(ZWO=*W1+@0w;)0kRBw4m{Mp( zgV3j6{uEyC4{xM!$b6@sDG}-aK9KTd;ka%3+s_@ipd8c4ePh*GCJ5%8k%`IuwE|q6wrX}HqIamxYz+Pm8 zv>Q`7K7rNQXX+JjD}&r|WK=wZMTqGs#1qxR*VDyOXol^%^ z?o!UwJM9zm{`~fTQ0{|ZxynCxUG64%tFh1db7}(7ZH($itU)g83_YP|MqUuSCpY}Q z>Y*WPj6cla(f~J5kcOlF=OTBmAflnJ^B_)nn!f2XabZj&D!jtF{qoq*B;raJFy!nU z>Wb=HxzH(wGnh7ZItv9Phnw?SU>IVeeMG}da%>LP7T1>-q6TzLiecsQ+~OQj{U zBf#_7m~e3qBZEbLsP8mX z8Y`hDQL$!z=nPSDs$3gE&Dmo+fL(1A84(ddrm+8xVzR#gwU$i+@4Ij!jo3boy%z>^ z=Yat@NN6ICjdJy>By6X;0yWO_#WOB~9|`T@tv;B3j>mM0u%?ZhgC84?w-M`G&v*=# z(7zSV%?-L?kH%Vav~LB-J|Gwv8RW(bT|01jdQ@fo>G1kHy$525q-c(92+LED+|7~zjZe$bV%X(Q%B@p_DbM{(+b>bXHIz*w?x@%Gw z2qI^%mizUdtA;^$oR?fo_0Cyp5vbJoi02_fpKmJX=1Skdt;7c%=vQ}Lhe(z$Dk74o zc;sKw$;jJ`HVH{b@OegAx0Rc3=abd$2`~-;W&`a%!zFOYEEk)-h5IjXrS5NFR)~Bz z?jVdCf#d1qcGYZO$?#m2sKWAB8Cbu^rLlQ7#789=j9O}$)ns`E$e!rq3j?Mp_jya- zC0ennrz0<~&k)HiHtW>vqi%dJNi6Y3Qki(c3+?}VPQD&Efn$ItY)=()(u@nAr4j!m z;;jE&l0?WqQWERn&%3%~9JYVre)?8wu=mxGu6r@UF&TI%FA%74tdwIxiS?&!EOVhf zq!3{G@;2qAIIQ|4`l%}Z)yU%yuk`tiIl-gMbdP*iKF{heKN7^KMS@3rqDHvTYc!0z?`Qy8#l3CapG8DlI7<_ z4DsNvt~+Tf&1e5svLt6aeQ#h?Zw0Sk-A7fuoZZo58GT$1=ZSJ$xXs9T;xc*ZbtOso z_4x03q4n_Zp~_+3n~-jRgkXnV+IFMT@EM|Eq;cq1^|WDPy``+W{Ho}Ep*$uLiK?e0 z)S)w-b5I)VPphoyGn6kpEYXj$TefE9W;;iu!Mut;CiAk&4U@J9Lfds~<|FtD@|5o) zSdM+P`d$ZVh&!lYtyDDUkjGUnjN4-L7^wURH!}WIXGrgRZ4oKdTVU)s{e#bS1$j#= zU8o@7Id;MrPibSIF*YCHVa$)gaS|#ru0y%pMTP$xefhax43x$ZmckWmLk&5ao~(9- z_<>ZJ7r3y=)}QWmV$pUer}Jpylf%NW0Xry3Q~Nr@Wkqv6?zGfDfhUI0{k513qw?`p(3w>!AUnU7@l56ywF~m(0qap1jUq1-e+KCIqpy z;AC{Hlhl;ab7OcIWqo~4O-;>r)*Wm+O=Z~*^1(Pa8z0Ew@QzH@@dgKeB6t)U6n$AD zSg4+n^P4t!mv-fLre4%SkJp>?=ou6{9B&ITPARviW5i=-3MCz%ANv!ze0|q{Px6Z) zs@`GQ2>sktQZ;50XCqlODTZoELb=s0u=Q6268$!rFtetM9&NP4SbYHZN19AkJPb8gag=l?cc{-uAr=dGTDzo4? zXP>19LwR*JD>#&gV{uZpYU!nE{-p377$lqgC%B~y5Bw^xTsNNVgzaHeZTcx1#^$1T zf-_~Tf8sOLsnsGBdeNn(xBWP)CTZ5_d1fZ&TwOWgwI1~lC$LO%5SET}5O(2P-1zN3 zy%Dq9i6p=o-1oYZe!zj2;@rjc{UMTY)*C!9^RC_e*Z0kQ`3&;amB+ySp}g-#F$va7%^pg~F4P7P>!J#O{hG&H!?$6}`!D<=d;wSANRO7nzb?{P?ZrV1 zLHYUlJbpKW9>WJ^Pp$^e=bQtw3OOYIihr>#>HwJC>s2%v!rxMLuIOH`iV$N%%|E>j ziUw8G9zuG)XL-|LpGcH!aG@n8c$=9B=<)h}if&Gu9~#ek%Jv*BRt2wmQky~{PV3~Q zNs5r8wP1w?MfQgQN^E0i*3NhcsI1=6I!2Lt7c zu`w}P+bJAVX019{{rMFq6Q`2N_n%tOlMLtV-ZRoJ2Osg#D-sA6tO`E&l?weK#mbI8Xr|On(<>qb5=X z5^bPT^lwPIIEjW|y|~*XrHJ~8=TiQD7wqoooL7FmJk8QWrQ#H;uQLNt_UdS^znpny zf|2R5;`j8`eEftjZfE&5rOpuU@tVhLt1VLm{Zb37oWvoaWIQ7Z5>xZjjyRXILeh<# z9I`b>9~VeXDqg1tBMct}3Subt+q4e)o1dEn^-7+JE9g;fuxqZTFus&%8>k+7;mM*N zm26puBmVYyiXV76%Bn@!3j#gK22BfR;yexxCWfJQA3i=4e4xc;7c;3ozt4)e)zZc9B12hcy@>b`!V5&oeIX4bkF;MCjyjNYETQ`vxaGRI8#ps! zeqpL=Y8V&8(F2ZN+bK2+he8h-#TKiJi!YvPAktWeU(!Bw{c+DrSc5U}YBD(184C6^ zG4LL)zGrvg6D%o-0U%auglo??k>d0D_W%$TU=B@W4qH!_$rim3tT!z8u+8x;Viv1o zD^^v`HbX$)|Cj(eiXuOId;3v1*!%L|J648zN1-&&<7E?L<4sRHRZnJBh7O)_LgM8b zlwjf(u&}T~J*V)~i0g(D${#NqY7_~3lZQ%7$wi^Y!}5CHcWXP8x`~vmSBK6+qt4m5 z6jx45>wZxHpXk1=EypVxFQwHT+wb3;B+S8r4#lant-;@4rJVd`O(vxBx8Bj${o+C) zLZ>Jh%#DHsN_Na73Zd2$)>W~!>DC+JVCh z@KK+#Ke3jTaUCB>VE;Ud?eT%=J~9;;Ab{o;7t?KN!*ok^R!bA?>i?QXggGuXdH^^& z0id?+cBww)<&Cj@8K6T1A_N^NhnyzU9WyBvD}-qJV|0u>6d6AIL;G?6z+`WXm_11p zADpw&wB{G^W;WOVDx#^1O%Z02f4LSy4_u#Zpxr3?Ii(JPXtm1uUu2Fcwl{xFIet@Q&0x_b}gt;DE$$TO$Qh+Lm`#?3J z`Y|}3OdBF?BYvHUGQJ6`5Y#R>xC>(>1|Pt1ZY!uPRpHNftTeL4(H|V<^s`PHie<2P zTCN!%8kEZ-Ge}K}$N=UYFX{0#VQ6QIm-Q-Q-S}yfW#qu$?_2 zSkqq%cnrz>p2@KH8nTAvKUXu0P@gEn&V4H5KO@>qiM6b{HphKXfPZ(4BkT|rrS7dF zw30q`?V;_+@Q~DzFJ@%rG~yeDsqYp!6}18ITQsz^Y-<>4YJRN3drwT9To3iqHG&&> z2W5%XkY$YurHf~hFsUm0M>#@wgv;ysRGs=O(<`Acrj2-4?R^? z@H>~4YU;FTMjYmPvpe2Y*@9E@j9DCP4dwY&Uz8+94;2djb?eHn)wa1=VQ|He^B@&QTs4^q zgSR3(a7`C*`l|7~haQ1)hOozI+cwPis_ZH2ma0-bb(kfX`sK@R`nUK0(EWFP-irsv z({jvxeHk08h3et^pbyPh710MV-oa5lO{!QFmsDM%7Typu6#sx_3d}X?d{IeVP~ifL zfwK5OF+lGiaJchTRy@Niu92?qKRww`)EQdKjwEa+qFj{;XFaN-6OC=}XUA5pVeMuX z=i5aC1I;FvEZ$$hY@yywm*dVBH(R+1pZPwIjuD|a`rd4{3$NrEaBF0M*7`mADJ=I- zzK_$H<}Ihku?mxtN+SVo1tgdKC{y%T;<*ggnu6qQOgzh~P7V$*@t34>#%@L&byH22 zG6tW+D}ZWyPxxUh@cf(#!#$Uccfh z&n?C9wem9Gl`u{31qz9WEgrv=M}ZS%wcbY!Da+KbvZ^gZ$@s&~ZwX|EpwY8MFI0-a z_vXuvIQT)j0nnDUi!7iVfcF73>^4IsS@>?^ARUGO0S z?)xi85w_jwERBJpB6`mr^v6(p>!QFxe*Oo7c#SmE zgwiMI*=i(UtmDqWXz1LE`hQq}Yo2B;XpG|0A%iKD-;~hTlnn*X*N4szYP7*4=IYi> zgi?`SLy6gpOj^$5Yo$C_e~bdSo`1WUS9=F2U+_gknb-TlxZYZ^MG7nV%;ZSp1+62i z0l@TFeDCL-cotJ}}RDrOqq##wHsggwf)>(L zv5STZW>nj87f46#tF;+w3e`*nFfZ@cg?y|c1DjG+#$0t!zLqcT7&d}L(-i8!+)VP3 z5}yzIn|ZJzBiD#YNn&z=bE+m{F`&k9ojBzx{=xL%U05O$-1tBN3T1z&R@SKKB}o?_ zHS>G8Ad>!Q`6`0=uc>qDbDw&$tOZh5b)@^{P<%+zyt}--yl#)tTc43L_TeNpH(Tx3I(QTJ@}$r`iWL6fO#|sulFwo&mx?&CpbOcUV7Nh zpN@c8KB!O*!reP;bj-8(yiRO6?SK)nq-X4Vl5~kq-rqgLE&5y<58=dF?x;xFbQk>D zR$b-%U3afcvNSU7rO6_+3o#Q&5*xlgvqsEg%8vk{n_&-B!8Z4>8CElamPzVrJ2kj- zQXrC21(ixAf^V>T*39pvAYg34OeNhnrxO2~r$G7*Rs`Run>Tno+%%q>+o2&-LP!J+D?EE9A8N1RY4CVthRS##5y@+F+3o1Dx}N zZ$0z4`HId1EN~9mjRM62Wpqq??f8YA)Ie<%x4tK5TAd}+h$w~XP)F?PuEuWixVa~bR zynrwaAe#yufPS8qc8}@;MpAh-5*b>5WmN=Xz)AMPOl*UBlN_EFFK~{TzaOkws6G_@ zLUA_G%0%~vhI=hnd^x_5(K;Ib0UKzx8va-Rl>Hyy+U;q3W%Va+uj#cjFc&je7-o2&qzdo>!(kNn3e(CKKp$T=&Um! z$|D|D6|eWwD_~(4vdE#M;TGQh(UFGc&B%nBh_0l2X3OZ)P}%XOi$&8?LECxmxGhv6 z!bNo}YvQb5)-ON1jq~t}Sdh8zLDp(T9eUgv^Yf*)GfY`CxlcvN-SOP(u(0|S-==B% z>^ni4NG64-F+F7{r#Q87G(hi?++*e1NqZtt!XFNltQkdJJldPgx6jEoKG0D40vy6M z*A76gPPna1JVKB-Y{liZVJGf(zeAThJ1R@=TRyntE7+CT_pt}t;OQ^{jqHPzPcLyH zxSEvEI^8pneB@oK>baojZ-#x_dR?D1q)!|Gxw~USlkz#=7xJ+W{ zb2cozN8$xKoR|$}WFbxEK#`A^p*HBSC z&GtY0M#W?%Bks11_q@|u3+jr+;Lf7}fVfaZKQ+x?CwDCH5q@NA(}&J7toCV#- zvaY#)2JozcO|4wV*`%F1uo&sJ{1EkE^`$gnU+sQTT+(Z%r4It$5d`1)h2eXBB1%uf ztvADj64zP(?rRh+W>ysTX5r=;Y0*8|0c@|TxC^zKIzl=Coj71K;gbIhrJ6G>9dNWb zHf>rWV2Fs0&h>F}BJc|$lDL~6J*^|3#6rBq@kz@iwbRJ}df^xQG=JhJ^ub#qj=axSz!&OJFaV6{ez;+^+ z5q$A!vq3HMM;e`K_b2#Gus&pp;?Gr6tJrnrV*(KgoEh9;u!w@Z8TESvS{TWvo6+DG z7rWZ9TQy~j=aL9k%KpyFym4E^-BFWqD1HIZt2~>H_UH=#JlxjEnJ?k$t0K@OAWSqx zBv``JyLU;$Afi^1E97iH^1{g`BZ=Tzha{EE*b7}s3_2>)y*ptXGWJY)o|U{Ti2ClW zo8iZ}+3AiMnjl=S-Yg?Eebc$R84yz$Ar- zlM_WMg71rIR{@ewei1Fge>hPi3zwjI+@1U-)i^;!vT_^Yin4yfky0_a6c8~_1F*|k zkBws(SFl3go=y$=nz+Uh1yC*nDJlDJX~PTALu_@8cQ%DS%1mcO?f-UFVdMicQT1I9 zA2GC?e?eWiY_aZ(3_tQ9G8r1{_nvpc9_-*8R)`>5c{OTmXh?!T z2@Ge0yAJL@L{xb@y&zGSE0O1VFaX()1}GT_FK3y{IaNXA~2^-1MpcW z=tZ92NIptgd?r4a`8LDh(YY%KG9@$pTo}SS+IvN+6m<~R`L}-kE-c_CI5^wi|KX~s zr9O8>Nmio;L#m9`YwboX+6PR$5-tl!g@mzQNy1>OVfEixDwYlA1tnc}E(?U8;yaS% z|BLAkPnRpoAe6UjgA-2mzHdtLpWnZ{{KOb3A?b%`d=&YeY!Gki_FgYh~?Hh=teI*O6(A4EtMpqLR5h>*-A@!A3wtcHd^__!aBCD%@~J)h2w5AV$#kFT$ux?5LI`@i0uluBTtrVbKD zSQM#axk%$^o2{ibXmGgZ75-<}`&(cLcB zx7XthB$>g2CAI^h6qlQHWXH!3%g1$p4<+wACF2=xvm8I{ckpimcdZ%1CCOX}0QK6MI3~ z4`#%B*5`m)c7ABW9PkNw9h}IFKWqxbt=jl+Bs2<&b*9PokL{B711Zq(8RJaeW#Tijjwd@;L4F5v*7L zAvDAv>Q*YUslx>#bEhPewgSjLZs*%_3UN}M9y({3tqMajr_%?X zyzlJ%OY7tbV<~jqqP>GWh1%_uf3k!OmH(wv)fJivJevYlm`D6Hl;)^ zCR*eURW$u*T4*JY;|qlx?J-z8Ew1E0=9lT*DL$RLl z?B)f1R8hD#)VFkcVxtgFmWRpHO$DMnNC}8=w0#_xyj8fCvC;6(P0V95Y^B_V1o5T?9E|{{E(WlD?6(vGy;D)UL!v zyzd!mI;9;>cFhOt9(a_9ve4&VBR=`bGK~3LB%^9O*9-ne2p0M25k8uG##BcDpKRm7 zlw#@ho2FX#nl5EaUB)0}H;*r|sFRr*ZELp*Y`6B!{61n=qe-2I$wB6D{vEKxlcOxd zTdyC2O_^FLy{q@#HFq|w+)GKI1PNi7bbHD6wuUviTN6W$fM~$yARTI%WLCwrU25Uv z9};^S_)i?G9q?8J3R<5HqCtgd<@YPe6!K>5E+mn~g`CzKcrC7wkpr}+e+s`SsH5p6 z=`1(vH(^mcn8~>lIOcf<#jgW-`teMrEX(&Z z$?@EgwC{vbK_2oSBcE>eODkO;fa`M2^c5vF7KPC)qrY6=F7J<%0X`|}H``trEI<{D zl)nWdQPmSW=zzFtjFa+vw)S38Kbf_bR5Rra(>@BqI9Xc5l}8go@DkrJ>fcHe1mNZv zOa&hCk*(?yw)d0gB-=a>50N4h&ARdG;U#j z+$9r|;2r3 z;I$aBxSNi`2^Ha+$DyH!OSaKi4DRfd)YNq^ATfrKva&7DntJ2=*^ZvS2;}jJPZJOTYZWX;7j3Jb)9(`77H4Aj@e!=fm-SG*^&%f9H{fF$^#!ULU;p1b&jA+Ak z21Xnxn=o!TzM{Hx6zlO`ZHF7;eAoVi^nxllr+w_sImxb8MY zf_aiy6SjigDPWvflNshA){b7XZ#~idJUa1Q#OBA1Bs-&-X8QWO1~t5&7<(ehzb3;; zGmpC#K*fQi_uM2_G#p8bJZkEI++2uAgm6FEVo%4EEApc>9fi>vc4$I}_uQaL+u9{zh z*Fr38tQ&FYZ9O*D6V27=->hr)U~NoFCMkl4L)j?e^6c)Py&<2_DoHAgcmu`f&u`~s zLiYVY?2FPKH*1;BKIa`#plBckemjTMUs4c>DBcDH27!V)+N*o{i{J{wC7WL5q#j{9QiRDFQYBV z;C`(RKdldn3_@@OHu+tTDng}Tkqk}h$XT@ue-FsX)ZFJ^D$VZmn?V4CDAK5+9^lUd+0nro+2Uo(B#Dp|wxYV|`iN@k>yYz9u`v5>Pxnq7_N2#zio#e8 zyplR!HScQ~T4{y@#P73(4)ou~sESWcX}l7LR(gg)G?2Qq5{pCSav}VH(@z4sMiq_> zfOQ&~F2yqS)F}CNN#IOEa*QFB_wUANIVcgxR-WaKzZoB<9I~*4r6WEA=)y!Z*w)yN zq~F!F9zFX0s=*wGE{{*{I2Ap8(u6wny$+a}j#0e9%8N1BQUgW1yYtLC@__Y5uk}_3 zJdK6|oO;UnE+d32OUGoVpErO?kg9pJ{Kg?y%19(8fR!%NX-jM3lFGk6A!M<;>{*zc zYWwNPK)2T`zLU1!xKq+z2+(=0&1apCf)eT6Z%YV~@wyT+o1GZ+8XrJ6fo4hm_udb@ z>e|})9gzz#$Z8*hB}2M`)+leMF*%8f`)T)bV7$O;bcN&@$hp2r`14jUYr~xA6wjB_;&^0_gb{&F;GaNagpD4#qWuxfhx!xIEtxfaBVh9|;-UXgNGSj-EI^he zQph}?wArlfQl%qr=;(XBCAPJ>4UXk2izkxpDkA27&9Qzhzz=aCFEI@^qMIZv*F6AA zQ$Qh5!EZ(f60cZ{c8cchTB#0OQ|TXsw{GF*A+Wh1M{2gPV`V%@(;>!*O;g&VjUr&52(?h~8t9Y1|E{YXWXp;@~)*4b0^oKF^HW7<5l~=3jSn-Ns z>=}5wjJ|`=O7vLjsP#V3AM6DKJXgk7JyB1Ewdp|ws?;a0U0a)-rsn1J<7<3*l)jGc zfYFQ8VJa(P>8QXM@0YFgAT9Jn@oB&EG1hlOEP*DbxP2t74)EDxf+$r)22OprsdlZ5 zzTC8C3{EFfWI)uy!rH>xQI>v*d#K1~`)n%imF=gHC<>Nmj+;GZ6!p$zd1d7^z; zJ50UWZd8ShCdi^j$Md{d2OeS+3kIL03eSxUOm@}6@@3M}JyJ{ecI5#VENZPYKi`7E zA!=&xllxk7ihAX3&x%JFVpj9=P;fGRi-HU;5UTkaUI;m49+D-OjNA#P$~PCP0+KP4 z!{!--bLZoZI7A5CE*rL?yKJ?Kq!e)LDv3C2Df>^4d7EGC8qCmQ9M0vlT^cz}!*OS5 z-g5w}>6ez9{6+|}YR<_J4cnoB+)zZ*ZI{-8LG+h*Fku`-_q*uoHSmyJ&kpNv?x*c1 zw)_ml?&x(Eu{bO8COaREvu=e4o#t_cF|G$1v1 z`-ffmf@zjtCf5VS4oBGX`YVRb?j7e8X$_<8u)}c5>r8=hD;8hmuyD<>Pl(DNV%3J? zLKF#{cS%w@AKY{31+$YR1C>=ryS&4{Xa9}!-p_{CjHs81kDlb_gHP~m8*3^5a0>oD z0|Wb2TI;R?qU^unZca1@Ytk(jE|a>B_0_v6gk{eR5_S4mrZeH>O=RROgl%ug=!w0Y z9dxA>w3+yN^!FmPq5~R%#oVk#sNe{veBl9EjK}diV0HQ5R0d}7pJ9}qD!|%>bDh00 z)m0a5z@*5VeC;Vj1{^g#l4dz6h*Je`s6XeEkY1kxdx}YCQ&CeWk7-=BG6K1rTRkRY$uwDyyXqwV<_*bz9UFp??8S_f zD^CnvvSRH`UmuoyVSN&8HB$Ry;C;00#BdOU-IsTq@yRD%R!Zl1zp9Y;&*qq&(>LF7 z_a#g^^Y^S0DxB7i7J7#XyFR*%NqP8B=~$F%mV-5*ZtiTXzru(P=!(myTNzYU|4CR*Doonz!}sGo^`{hiV^ zCcL>b&Guilk4=i%`hl0gPW*K@UFxnf9>mp|Z(Pi8ke{IXW-AH!S^;26n(t)|4(2fK zmT74KsWVmbinJx=@%x&$C!v@2T|m@W_SR+rCxZ}!HLC9d#v|Wj7i3S{hlP+rxcW&c zxdj=55N>pEN)?D#8EeIJ)5+1p-El{u@Mq`Ivzz1_Rwb+$%&gqxZyEjjUs1lsSG(j> z=I_ye`vUZ*3)_Ay(SxTrPrrY#pkm0h&pz3DP4@RhQf!P)z9SlmiiRcJ{(&m8!FtKQ zZmiOUO4jv+6(xu$=V|`moCuN59fEtFipkTOnCD>|I$|ayJ|M>}(fD;#Ol-<{_KX6x z&WHH<7k$^RxU?9wwyjbXeOX=u~z)~Oug)-b*2<%#kaz)IB)ZUE|ZS@J^KP7 zwDn9(LORaB3UPG%m>%H$up|RW0toWbIYn6S)pboMJbeSE6A4u_ ze!)ZSU@nXjYCooXUl=x0U_=nx6b{8m_OiP1C&zo@<**<%S5{;Y=GdH4h)PE zc%=;nC+%byg5-1kTVzG+_`~aGiYrgoFE(*;aWywFFE`=Oc9B%4W52niqmU5YLUV4k zRG{o$pPUU69#4QiQe;PdgRTL?2}4+W_>WZ{9q(IkLkIx3kxotbmPp!}`KVJf@AGgm zJ87o>PH_}yv{7HVJNuOhd7b@(>~;kTFHbZMrEzFvu`c->P!9zQWns_Y*MI5c+8(SU1PQDY#UgVu)HQb;SlSV^boqZ~qx_|Ca zIIm^C{gQnldmFUwmI8i$N`dN))1Ks=*&@W+C}fhd0l=cg<^<8QR$d4MNIdVrbzaAq zVeT-~M%Q6n&aKl6Fhu~@8r2=)xZGAB<``ikwNbj>=L4;J%Xo_!y29 zi0E7yYYs`k+-@Citfby-c6=wzUzgnIm7M=a0`!Zj=tK=inxPr9J-nX-i_`UCUv}Gv z);~4`ha>Md=XP4#3;v8L*08l=>bYmn&WyzQDTpjN$?Y=9@^o2cRFtdy*_UKkt3GZ0 zTWS&>tj@K^ktO4>>sjA5*kxJP_3AjguXc^&92|nGF%+HEV;x^~8g4Et=jb2hS>(*h zc&D6FT!=Rm_Qqq@iP4?>9tzY7Ff9*+HtkJJhIiL~&dy_`PFDSJVJbJ{> zk#T*qt&bl6y$J6sCs0jadH0k~PN9f>uls>ccf|WyoN5tzycmu2O8?yt`*x78Dv?Ol z3soga+XI++Uv-1}tXbrT4Kl<&o=0B!+sj@gj)U$pnlzTpNP7R-y_z7#2hlYkSd%Mw z_3!_LlkjU6Er4)N#f882lc94w?p!n~4X>`|$qO)gC7W^lOerRS;qFW$s_&+LP z;simUm*}R2f5Y^){-=P{pJnpJ@o9Xi1njHbkh>5>5!g(L&*Nm;UGt4qz;sqt3pNfT z2@Hf~AXV42&&cDmdcsXE`Kp4seV+RF`&IIpG6V)RzjKZDMT4(b=*|rP=p=h+chlzd zXP!V)Z${+Qdasdq#i&^lBZ>=4QCpJp{J5Z#5iNofDB!uFt}Ua{2j}NW9a@@6i-Tl@ zqbBNo;JT`35B-()yf`l-aww9Jqt$~FZ`m*G2VSvXa5HUFi^GXI0zt*%O8V3$DAQ74 zkTnA)JJ!F8cS^fdB^Tue;Z&i?sn@NDw3ch6#d<82QwE5pVO`kbLs;coJUPT zX!^@;V;siK^^IRIwNUCt65N(f8M6v1kam=j0dwpyK4_9^i-wr{r0WCX#Mi>REyJ`1Xm?Ywu%2 zlrpD^a3+RgKXf)U01Jt2z`)MBdidW*16`t|uwn%nd)Vp+PxgXwTkR$=bGvBU;^HE( zeID!ld-xkjIF+d7x}{4_|DihbP`BaK-KsUC!^6QuBXICvr~0(v zZNNu%@JQd^X-X6|Yuf$84F$8aV{9ba(1q9TApLB=L0Y>(>b`-7|ctIVZ3p)v^ ztcAJ`4L6>Nw2<}VXy@f-@w@hI;m7~x;%mt4gR|Mu%qMcw)MJU#_4&Ii)YX{|aY_=y z$F8sXR8(zA_kw`Yj1qC%g}=Yq??YrrCd_(m|K4nf@cjU)xr?2}+R7sXK!X}r#Ydd< zJgi(t0t@@q4mgyVag!m)r0L62tKW)ufbx_Ue&wI{6_xhbIUH!WY3iHn>x?tOL;;sD z!l~#drZ+)^1tNq0VT*QP6_)33m;wBs^-5%MHDHB&PNq^9V=WpM$i}ERPH+F$=f`K6PwN#XkcrlV+2hq{z}?v5?h+gM5GfS`F}T2C z03s_T3Lx0ZV`1IQ`O1_hLZ{$VrA6Qs1xApL>m(rM%ADFllH6H~gDzNNLL2o`?6+la z6!5|_!QP3IJ31=SNIb2uOS(rq*?KbC#MpsJyo{zGBIYK~<43?^PR<_G28=PSts@R| z0_@L}=*XIWM_YgXJYM@61;8!?B4g^xP1&?yW)Rt8xa;wLXU_8J`cF`8T0(wX$-#^C zrj9Opu$Q}&Qxx1lu0UhXQE0{Y?h^?PlEUO;UPwv#muub9X&K3n*n(fS4WrKVt54M@zpJirbnsuyLT0#~Z>%`ww%RDuG-k^Ad9yM&Ao^Fqin_M3s zExo%x`B#(4eACtScy|>7n8}ns#rS;ui1)^WLjsZ(M7A6XJS$! z1z=zZ;@lgbG(pW;a-tV;-2{9=oSQEwL=iV1rIS7OfqUrY<`yactkuns!gRK1z-_JV z_ou&&&N1hzo?O~d`KOUDD!R1Uf>I2xHc7NP*~j@S;Hc~}sda)VS@VuwS}U{x(=|q- z1s1d4B2B;4eIqb$e20}?acDbi?FNXkPZetwk&4m=!SWc;QII4|V^wKB%pl$ z+*jh)n`M&wW=gZgYVq^dx=YQ0UMFt6-`oUGZVepaHCBUx1nwtUJm49u{wYg{&8#UN+M z%*bd3I1sI?(pj@LK+0HbObh_%w}V1FTwQ_P*K~%~R>nPHgmAPKuO+C=Sss&fbz<2v zoMtdq>{@UM#l`(m1>$@?L*mQF$47r-htTP?=#-+%LRKjz3i;u2$qBa>aWeCPqdv>M z{CNwu*f@D^)%&x$TK8i)`A5nh+l~hFo_7CMEib#ScPK@-MM^I3 zP3SGVLYMxSnk@rM<`x_C`OFtB2kdxSwR+n248J?>3m+k2U+3by9Uky|5@O=yZ%Y>Uy|a5cFV61n*7b`vjWE@w?=uz;x7}DdZC>}xDeE0Qp}1e$ znAxyF2?>w8FcQ#ur+?elmawHItjZuu-0N;~a8NVRDTn~`gFLc9!Gvha*A}xTpa@Zj zB4KjA+Ik{()@@ESmi&l?oAq^{Ox_*vI@9z2d;pUln8Vy{BqR{M~?lMsu(SF*#pH^;B z7WF`aiBi-p(8Ipt$^n$2kXxW$z1l8WGR0bl|4N8n{)P-xbOOF`#Ai8m0cBB_Gp!CG zWk(6+jTKL0tNX#g`%3@5LmJ>!LYZc>jEv_o~FhhnJ@lZTm5@= zPS>8TJqkt2dD!bl(?UZPJ4mJ!v0r}*#sZ!7t=+9mX8CKaWq0u38&Ur4l<>S%emO|jKy|MM5X9l% z#Y0SY3gwyVb;VCzbIAF3-su?&R2EW>;t6(iy6kQul{vfTc{`7ZI(n3$t&|73RQjE8 zGq%!9;UA)J_EJx?=+xGMTtO#op!&OAb#uXFA(Y6~vI7gbs$He?u z{$XIf=Z3xk$cTU|1=UL^&RL7)Ka~Oqtxc4_kkQ7Jg&*@<*&8b&I!*@jXgrkwk}tcK_NP?O#N;ru6x-vtOKJ%a`GMhUV*+ z;&>C!f!ZTJhM58LK<|PC1>wPuCg6(lt>Iax+8Gr`DaAwYLFgKmqXa_)MTZLvqUzAt zeUY8#y^8*&fu^#n(HP770g;P>YNgpd+P~z0zHE=-w6qj(SbsK7IUD7fc-oT@&sS)5 z6>au@97p@OK>M59)q?)GMq& zCqE^fdfdB~LR=txsm^)YS%tOt?nu6z-rnUGa=D5T$vA?JpNQhbv1Hd`nJ$_a!)y=%~npa6Q;WOS?uf1Z+o8E42Qf~jlF=C(W@0vbY+XAA~k*Qo|& zRh>R_k>!uqKx!6b>UgZuJ6vGj0^X@7ytRX)2LZ^x0YuhKTs49t-$KwB>=6vWia-sVJTaOHjP!Mq&@VID zR8gdEgS2YF*+MSN6PF4p?B}sud+Fs|3%*yI*vyLGeLM<8o*hNG4q1O~2d`O|M-u7b zS;u7)4SFTsWn=J&vyL%czgFOBF^Yar@6=CZ4vR+dHdo6HP1UV~b`pto2RDpwC>1ZB zkeCY10fl@_TRZ%^+EQo!+xwcteNuy|lNqa+W+Ip4CCDO8KnMG-@xhcRqlqgl2P*t( zwI}89l4XmtwxrSC)LctrSUWTJi_c@M??&FFw{t}A$n(_qfq2{^*!P7}mHX+L z63C&nQ=MSJ7o-2R3GHgf3io$d5Afe7o)G<(xRsRKsYfm)h`Aqc@KGAl`{7pb4RV7` zVfrTUZ3OP=-uEMhuc(9Y02qr~q&l6Enrvcyg0s+lJjCSh z=o_&wcd?fub`83M8TN1g`>*SCZl#6pHpLCbMBtQY>)a;(i>Sz)fbc%m$_(Dku2z|If_B9p!N2-!Rgj}E zo``%~(3FV5bFP!T53`$*+NFbYz7=k@{$virV&Up1G4#R*#gNx_Xl-qbnH4y@lmGKe z_zewtTR;rl?NpVI0vI3|HEJ7evTjk)IHT~S#D{R1`{YInudg8A3}TR>LB$%8m4<~; zjl{d%MB2okTT~M>rvQxSD z?8OP)#1Yz^(Vz8-vK$@`!mHC*W=jcJ)Tm%iTx^Kd4Gb6bc@m&??h!?ref2;#<}rKX z!{mN>#w3!6ynsR{W@=b5a+$f}*Kg3$K+7<3Ne*1%-sE3P5E^&`o%r*Ke_9jJF3eMr zA&jE-Xv9HE-rZ>l31ndjv#=OvJ9Q5r-pVFl6LWvABgrPd?mdivT8BUnBZv&JA){wd z`FCt?n2=s;!Ew91oq_h}x5mbH-ebQxQ%+X|*@H@$3#EXWt&=TO>p4I{Su?q_A2QNJe<7> z$+c8YLu8{#KMYTg&6)$*1y3c+bSkU|pHjAm45q!DoO%+ouynX8QS1kqns9hAL5v$2 z7OYeL>D@fdbX*^$~^{WL^^{&_I=B;P>hLYEKVm4ipQX+ z(>Kf5fp#6&(2I?#wDB$l7}{cO!QPFBccWQK>@g>J`FQ zim9cTnhn{}0Dg(J4=OsBtbh~KQYRT6q#7+nQ_Z&6<@~rz#$_S6_Fj*~!Lnff3%XMHJ2jd#Y4p6|C;_ zAT-Th**@Dyny|43Q)Kbp9G}|UHw!E1MhS)@zr7!zG(`0i^~|13K?c+}|B()-G!+l@ zVvVx>XIdZ@=0h9cBC|qa`ZTQ7E@7OjK5`)fo5S?o(nLtyOQ-msTD58x{Y3g~chJ;Q zYH7w!+_bvNXyN0IzJa%k&>w!BU; zY~>U8G)DjdyCHi_O}g7SAT8|ssN9~QGrIC-Vh4&z(_ZCX*~YERS5w0+-Fw+{qI@(U z{@s4RGR33+y#Is#xIz~>!r=}lBuHLXVTm{jK4u!`w?3(PQ{RAwe#Pam2RZ`p48?G1DHHTgT?s~$*6S1Jn^AHofu?vc3^ox; zZ8uWNX1LMYgjRU+DL*yCxs;{|vt?|jc@6rk-@ozt@v|hk)Pyrb=_VSw^h?&CyaH$t z0q*b3PxszY4a$FKXJ?z8`nP)}EsvFI`L1k?8Mh#U!*$pl6j?4}V$l~syV8dHQsqg=o(AT4Y| zQ2&JKe7-V>e1Q;V2TkknKm(z|s$c0pyar8zH_feU?a0@Y>jl2~1c0$REBih@qwEH} z9%=<0`y()Q_`C%HQE?64hl71slm<{ZEqjPTvjd^_CdLdHWWTR=2sM1MzJ)&+_UwG> z#yTBpI0vYgQ{NQzTV0<6am5HyRKhh2>11`9KVz3{?xt>h+#k5^1%_om-wG+f9&b-! zSiZJZu zX^(tCZkLGTwruldqlD!Vy#>8&c0iLBHideB{2}JgEFwiGjma7DrDA-=sI+mhJeXf- zyy2cJ=ThvbPDaqrACl+~4I3`qOQ|NJRQhjue1L4y6E+W6R`|-xjr1aOpz?IVe=plC zNsO^ve{?Hzp0;t~o$dg}hf+6}7Dd-j&&Y2mfNMVd{EQeuCX?gEeM4cx+jdX^l1=yq zxJ>6N-XV(6g|#0r-EQk5squMDA3myLhZhtCf zn833OpOhT^?Ep-dMxq<@mokEv#>jp0&sMsnQd!J#Y7^lt+9M{f|I^=k+WcLgSVjMB zdEG0R$+HAj>rH^SyHn_wQpXDPCCv{2JFpO*?20UlA0xlQ3{5{Eh&f4;!nnbN*a_IL z``sv3%T!on4Cy_bcSj-+Ljximkm+{A!>g2JgWSJP=^+=4=`q1<93ZddK2KaW_NE3( zmvkd$@3i%a1&p+Yjyr1oXRx!s(POS|TZL@}k;0_e1K{u6%H!v|IuOj)rn4y~QCCL? zym@yu1;1us%^$i$@7|aEcUU0{oDMtvdbtGOzEfZCxQz754RQrYskHraQUzdh+P^PJ&BKSm#Oa`d;GfGSIc+b$@{=FuLB(fgkQgZ&+8k?G3OVOn4kTEG=jf6aKa+8|>VA;$EgA~IuUDma81z+ZvV zUMWglBl&7y+MuB}X=3sFk1OFI`-52~W_9q>dhNEy=lWI1{w;x^uy6{u$0VVsmcRRO z+wt_fr-qD1hYk^O-*RqnzyV+9+4G}r4AE)K!jaEr7n60S_XZOn!cNj5xR`jvbJ6)L z>|0&|S94VUHcZV{e|gE`dE{>He{w+8qClP#wv+qsZtB+8O9~Jytz?B<*lvI=$0Ffy zPK*${0xj$>H!xWT0P^=a>3E0@Z*`Kt7tS#z<@m_*i!#u86f|2B@xHQBFQIG6PFo5) zQ$)GR7sEJwXWn+lWsPB{9Za@2{F%Tp-h>nK>c7^t!u%ngJ=G^J`I=NHY*Nx7<}7V*GicPyZ*REqL2#A|V06eB@hYY2M3 zHR|eHmp)nlF{~6hHTYA(E(0=fkG|GNzS>4qKfw@PJ51BT&t7RYk^**idwsh3cQq$L zc=n$o+4IH`gZKAZqEclNx1RWwF?gvuJ95z54c_&K8Jk2YC@2&pT339SaDSX#V-WJN zU`h|~jpJy$B9OZ~{7kDa3VD0pU~1u;CHW~gvPrtee-ie}j%vPNi&AK|ed9Jyj?pL8 zmq3*bSzWdw${k8}%4ZTq-S9l+`2Sh}&uXpz++I`AF_fCMUfb!6B|5*>2_Z{_dZ8fE)p0AFg zWCrl2UM>vb3Qr0Axkd3-M4m%SM!>sLH^sM?axlsR%0Kbl?&v<||EyL6)tN$eWTDRHQxv?at1(c%iqfo*$(>k}Pzi7EQ$MNvVuce{JP;TPgMV*t zcq0^ucD$`Gkrk<370xwniUBx3)ZCwY^XbS}BhPP%&#j`koKL5=*EOg|>#%RjowGV# zGrw&F#DOxYAx`D_wWv+-|XNtb8i@f3v57#H79NCWmyI{?-&`5zsQUSn zv2@&0+!2X8jfnVK^MF>gXIqcjE*t+fMNz+%o;3nDTvzyf(pc+B>~X;Oy&h7d-7B9n zcHC1PjA&qqE`X&9owj_j~!rR9VIkJ9)|BYhcKIFtKJFd<{m+axClHnJ1*2Nl4t38l77s3V0(%_z?fs zClcX->DzJF8@r>}D?-n&VU43A(+V@RL2+)UsFl(YW0dOuIlPhezs*0i00!XFM#*n6 zbHE4xnjm?eXN_*>WhZQ6*GwLapv|!l?v75H*av!!+?MjAZlqm?fQ!!D!|6-IKk*CE zYm;3fuMy7+Kw|`KWKv*9J48hwK-qw>I^S4{=(W@ptHqpx{~`X@&fZ=r^bNhW2hFn- zfpFH5-rd!YHA4FXiNQ9E^deX#ePqb0$8Ym~yd(YE)yAtPXkB9kWt;^jHwiB~B=3lS z-z@!o;z~*bh}#t9ZCXUu*)Y@OW<;W=|0HrJ!Xfv&8Gvpioa>(v{9p8G%qLl3 zjJTr$n(FZoZjn6!@FWvjWoUB}p2}eZG74bf_m92lEvg-EZT6^p%>+i z?E7` zXh~SyF(KJSd_Z{6)RmU3o*DjnW_F@a_xeois+MMn#WE&v z3`QIR_4HLzpjF~?`o|o=R`4Vyd5peQ9Y1jJ&i4Hq02(!QF;GD%g;i8;)mraJT{S*7 z26QbOR&5(w7r3vEfz#!zpUiGOHat8W;I06}t}VA$K?Dvops1LW?rSOCI$(6?cD9b7 zOP!v%V(IEAni5CfszuuD|&@{W+$5I@p}M*BkMCWipHa3i)4$|LMC0 zam&tAf*8=?nHpm$Wz$2=@p8-oc89CPZUwW5OwTY9AJ{loZ7Mowq1w<;dv8hiGZbn+ zzmMlIS7D7aA8VF1VV^b`+I+>iyXv-vQrN+uzDj8+nMGS_ELsagzxr8Vq(6$0HRbU8 z&r~JBmzd2!^~}vHb+xg^8J0=ej2pc|V-*CG_Qo4-0ChN5HfK7I?W7^`1rNI?c#ru@ zQ%fS3J-WZ}T!vkHcnZKGInzmF_g7QXmqRdeb&Z*jcIP1u;;%G`neI&Se6Y?t>P`CB zpJ?3zp6=0bcBfnZfSfCQ03pn}AI!fKs*v5G5$B$OxKk7wCfj!EMc6%2O2YZPc1R2urF3DUf{{- z#qqZyeB_l2ucj@XX}tm-1^W;HK-HbGMQz9NHuSL6x^Q~N^g-~>@m00(6+Zfb6nI|K zjQ8OUx%>G6E}01=>08}3_Jh(_r%xzxl|jXP8A>y5!77c9UB2foNmMMA=FQbQ6k0U- zbCdUSk_)fc^Q03{4H%KFL8@mIibsl$GsIQm55L3#tVru7Vis-h(QgR*+97^dhuQF$ zY!}AUxUgW1>Q%|%^X)`*bTlTlKD zWzYE-zETH@zQ2mi&-GL@HJaC7F`Rpbd7KW0#5C4qGwyBboG}GlD<>z_8HFf9&T3vS>$$%Qn zqb6$&(D073IPrBYJv>Hq|Z%6Ynk zm>29it6wyG!ZW%Dm`kjVbckfNS51o>EafItS9IT&iDJIHkBzYJs_Wd^YoL4E)6Q^VZ`-GEFd?HznFhx%9rlV7C zNV=RxHq3qG-;h!@m2~UwPTuYSXI*L{RFv`B?5gMSZ%pI1RKZm)R1N=SJgO<^7d!RU zZt}O7VLfu9QN73zul&dnQM&i7e0=i_wfjdhHwND?e+hx&Uiz!YfVK^S(NhEEzmaOs z+6%&~X7Knc$E{RT3m z^SL-1L3o%Z0IK-Ud9r1gGChhkgG6zk~oNKwn>vSARl>aH^u*EkZ=hUmr*ymGx|7LML(HqNwkid-$vV|9wY9pPs};cqt5 zriaS0+lOA876dAaSbCZP6qs;|I@G?FWZK;pWzJ;Qks23nnz1_U9cpB!$k*ZpM0scE zB#4~=U-;KluC1TlY2PieYBo%8JRulw6oY5AKBAfZW2ryU9oQLy;sri!YK|9}7o{z1 zE(}C_mAa;KMc?vD%+wcuFu@av*RFGbP~7wS4ID3dgJ$9W6b}E}*b(T<{^V7-Zw>c7 z-J5vyOE04p!OEZuka+TSb*+LunSb0=-~N3ZH3A3^00O;gER)ozzdsXldC2Cy_HOZK zRg4Z4GPz2#=u#)hPQzp35Uc$ZK9 z;}$p4v7j-FdZVIk{N2J7gZOtNI1e9L@ugj)&VcEXrm@weNz|80ccb=*uC6opNYVr# zI$1x`3uxCf83JaCs|#*j&}~*P=@kFHn1{_lJJ&Oh?`5!2eyKk-Z{GmFohDKpN5!i2ES){ zgxUmd=|u&sdcp?tYtg4IFnyLy$erP#{Tn) zDdWP*;s^u$Il@s$a~=Pe&Bw(2qfAD=bjW@$!eXJq*8$#tABht-^`51}9yCKax(5)v zRT*}SUn*?ztZE0&;Ux4PjyA1iG`;)n(~D(S75NrEE5;?A_f|Dp+VuWJ)Cc2yoQl`2 z)sxW3#BXQl9+N(0CiK0O#n@$|0ONp*;rr%5=rg~x= zG9WcRKJFn8kwy9PHfX}rQAG*)Pcmut1mgfHfGu-*aAL#A@<7YJ^I0HlW7?e%V7bD&li&l%|$kHNlBim8vuvR z5eURvdiSa9Cqt9I);o~4uI{_$#=x|8oDM#f^je{%YauOUL-e)L5daL_MQ<9T8{bWDX7?|~+%x7qE;`@K^)tqFyk?WGr zY%GDXy#Zh7PKN)d{S8Uj_YmIe<1?3mg8c#)zc6h)y9G88fC9k4zgTM;O5}340*l(x z_*XzUl@UBiCF9ujAM%#)tn# zy4os6`s^wiY##rH{|gte9iMrhkWUi@N$fBa0- z0icNkpd?c3E;-rcAbJMZP1(o^$MD|C{A|)g_s9@YLxm&D54%6oiZ2`K-JEgAuUToh zg@r@QLqYbyng44I8kW4B&DHz_hIuXvodGzY8{m+jz8zjr5P894NbwBsJrm+Guo%0F zvx^KBI$d?GZjf@vnWjE>S+DapdfaWdF92lubgM|GYPXA=~mH|NrAX&6V*Ixo3THPX+wi5 z$cUJ-fuN=7r^rOc7`-`;OSXUmfVzL)Tv~ejxjHRFC zH_7@!1TeU{iEu};f7z!cDr~tkxGq+)2|+8Bn0IV`{D`)OXDF(bE;4J>TIv7cXVMxT zD*7$28IvEy`jShN{)cuCt+Yrgz{VdLAwIT~1_6-@LF9-M&D$Q@47)l+{UDdNSgmc; zahfd#TX6zXzr0V6m+ko<^zfE1$$rL?b-U+eB+B~Y4m#H>`tb;DF{hyd!Aafx8c8Kw zOe~FM@}I_9{L5ymlJ=eo`O~8+J|)XR*V-^vPfkw_t2Iy#^S5oO5=_}c6z@u?i8nU0 z@j>?6gZP`&?M4ZQAx^Ir#Yb89vMg6zCb*JK7HB<~? zohSA-C&yl{1UP65VJSO`DVUTiNGn=$;aCUNt%8B+LAylWmdsfiau|aNmqR# zTPDZMD%YUhmE4%w=#GFHlJES2uo5e~|0!8=j6B+imZ2by@$%EF7oQw0IQ^C!<^DPGD z>?`%kvLru7gZ49rz#L%&gNa|HloAF_7?=WY!=B%k91Lm zuMBzqNJOWR+q|nqo7JGr;ERB1CL*MjIedx^B2CNE%<{};J3V|efP?W%OcS|svlxMt z%Q+lUhyy85EB$S^CN{2}J4T@8-#{|SEQH4FrCh_G*^txXN}D+K(0!n$r@``{59meb zLza9KnFl^)&@O$q`z1w$$nhyi8i%M-fBQHCbE)uS+9%2OPCz5rKD=Fa`k$3Xo-jMS zKsX0nd~}n1hgWwopOtjmCQu;^rq|{P0g|$lA;FG1FS?rtRDag%j6Mkv`Yu9$cD?b| zC&^XquwVGQ%22Y9g<^d*(osHLyQaFK_|WR-ZlW)D78e@TEFUQADRQls?8`12lZ!d! z>O}kPGT~oTLRSf%y3G*Ef%ve~9f}sA6`yf~%R=b2563rrnkG_iYLq73_8$bsU-{aZ zi7+X5twSgUOLRB!R5f&Y1E>Jp=o^QNZ8v^t*XnfjSfrpj#uJ!{t3I zpJ;iH4s<%6ik;Ze5xtU1i@|P;4O-0WYxgaSuw(XmIx)D!siMfooz^A2N`AtO^u*K*0?y+G#o>ZT;!s(Tw3-lzd+Ypd)>buM&EpdaBOHJI=T-U)_a%y*iH^(;* z=d-I?a0QzIuCmOG+Z0E}?ylgL@%oNuZU) zl@FI)n!bYRcVA8(aA#ETh<@7=GZNaTYL?R6_)x38O-%i#Pvd;6V)5#bAQXryWlR}y z&vyYU0bwZUMJkMt%W>i4)pYxD(ThPE;0J(P#gU$AWZbz2Fw3c{t2^pxGAEVP%+sMW zDdb?kj_d>I66+47Uxs0qJC4oTtS5{0p$9#HmYPT8Zj+=V%upQJ&#{@c3gxWgk{rW$ z+tR`!fXW^4{rxPM;kUIpI$q`B<;4N5u4cK%MU|HBFE^g9bBUWfs^RXJc~p6o*s&yIctu0V-`4G=Uad%A&)-|7sC_wKK6k(2H6V!JZ&E(SC z4^ndl8=^`X!a|sYS`6Lxq<>slSL^G7SllexefOhY+b0=%9c{EULX#?}v6=3?A1Rsu zJ>FtH<@$tm|6W#~UhYAcu^^J}^z7_!<#!cUflVIuRs%+ywsJ=A~jh2e};L zFntMYh|K9W{F7^ptssZ^G*yjE8)aWISO6)nk8@E}_(X49v(wB|S;^+C_-Kcr-Bs(3 zrL)6U0}3&7GBbSTLIgBBRZHTKE7NTS4pcRB9;ZFvkueuT!fk5%BHWUNokh#ntAWg;Zm4 z)@$Zu$h^jS(>VIEB2o)}#Od*F31?gUwt2!qEFxd6^lC`ihhURoOCm2$1y^GySwz&z zw0W!6RP+%rrK}@-sh+HZVqKov4{BeK&wCMfwPYc6&iA8s6bDFu@BFn3*ZXe3v(56m zqMazTAs;L2KQfMRH-_&om7a~7O0l|KLqgB;7n*B*66rtwK52M|rH^B2pXy$u$yW_y z23TqRK*KvQf2XT}xPPvPVf-%Qo!E!Cbx@u*YrZZdVhYU*Q=+J&!|>SUZus!vP^&%6 z@0YPZ-%Zu4#CsYT@$8I-<7+&quH-G{>pG#_{+wS$ouR;k6D6i{f*FkXIj&HqXu3;B zL42#bs&IxubsClj77G9Mg*j=&9JV63^_4lu@I(9ZdUzhgU5X=@m{>NPS#sSb(TWQP z2;>DGI!$jd_rt>jFb7j@HdHHA3zyySQ{c)?MLjs;oTvQFST-Yk3YmdIUx6~c4l5f6 zF9H8ee7Ta6()>9` zefGdUmu+l%MZ3E{ONC$P-yH8RLjSZKAIu%j%#3v94M~+`D??O87iI7gqLj|P@_Fy~ z0(S|$on0CyRx$-WZvqQrvb@9`tgM)Q<-X$)1pFFj(EX^+aE9#xu8!yVJ~xQAyHNXSOw_xv>JPgg3VV< zE)XX-cf4BOg-`xcwZ5T1HDL=e?Kiy?zBhTUM&bls=qSH2&kmAQ-j$<@CL(`S3Cjt` z3Jxflhx8__s!)b!I*m6E4ate12Xu1W%6bw;2UQ~EPfr3@Gc`vSp0@**(E$22*Q^A%I zNB_Dv-)a2K4+6X`%6a?9LN=D_{Ojzoctnt&=Wn{pbsT5>in$ZwwN$`fOAnVh}kvIs7MaR%pe)OsjbGaTbU5^W&t~V=-KVNyCw#gLJ zGP3pszK07V^Ok!z>-ReWqD;CO5EVuCInAyXk0HINrgy&I>1z{vdwX|x?K&IQ0beAf zJSzq1aM5_ohA)v6;JrL7l4J(MZ=eblMrUVdm2k)l{Bg%o5IvyU=eqnK%ADHZTABT= zm{%&XqmC>ODC)T3h5ZvAGHg6+1V(mlX?I#RG{g<3`|ph)u%^5+Zz}w`6gqg313J6% z%K1}xGBVg_)>V`zZi?pV#o9kL@$%5jk8oU`Tiqt#AX4^9v||`a$_T?qc2m&if<)fh zS=n(oiJm*ibe>lZH3!QN3?H%C*yPf^Fh5cE6!t6KD{ReA{?d4N@Q5~ex>)Z7 zBB4Ixx8#tC{!z~(=KIob^g5y@gR(4N$Mlxw_X2ey4BzO z??;c2Z~+FhGi>G-6Zc(y2`!zONnm5ksQ%gt6j;$OyD(UR2B^d(?M(C2dvuXf3z}q` zU=`*hS%w2;`&{x^cmJt}9X`AH9ElUu%;%>E2h?cog5Ck<49XauG>Pp@q#y1y2q<>s z*4|yeq&ytPdHML%+Et_l#5pJV_sc}tgNmMq4D%iqz^K8V1BuQADFmt zJdY}+@Mqrnp51l&%iN080T1zQe}B?QGsb#*A>9ytzSH;bA}I+r@7Q-7HP^OhI&MY^ z6&B#|Q{TGTHcR8v>a&7}mxs4-r@7Rejxk@T+ge)+d$ePSJ?yiF+jgVR;Q|1UY`?DT z*ro-ov}cvA`8BzWtms)D=aywRjO$$x=e)L({F$piczb>QwHfFi=Le~Kl}IPuONHgs z&c9XNl#24J55;6VQwKImt-P+#a*AnXq|x0LZH5Y6y@!Wd;#q9`Tk(ke3Ik(HmgWnU z1LlB<=Po_&cwG#&TCfE->LzL)tR0S)me+_Er{^7CK%6H7lLp)(x@W zOjN%q=Y(F!7wFQno}DBLfcyXj(OQd>t-E_uvxmpu;N7r5s`XRJuy=$FSux(UiAAT_ z62~?!o}N_r$T=&Ebwxp}B^O_h^`5VRJi9zeHIR|wfew$~f#PP!{qn7=t4(Uh@k?uC zYr>0uYKN%P;qGW<#@k>`kzC)BvO@FAtE}ajW8v!K6@?di`hLt{HbO#Ect=qY4hcs) z3*7t64tH*D><*ADalYIxS&MfC&d*1``)*?547_0DuS7nqow);lKHgY_ORSUqzZO8G z$;CSU#d95jf%Its+OBbIQ_8DC*Hx7;sIF0rWUUlDX*#4QA|pZ2)p7Q*l{3qUv6C#> z-yh)tIm{OmP3vUSHgNF!36OXaq8lM5(Znh`+!|z3yJzPS=hxNMRjyTSA+%#lHTkgc z^0lj4gp?4bZ*5(!`@tDgJcSt)@BVcIVIejpS%@HTQ1>UYl>g1`ZREl&Ybzx`y4ELY zuQ&)}m{sXqZbt{DcukJL2R`uchw96|8a9$Q6Cj<3K9B%@fJx^0rd%wAsPb$|X?GOSY)K-qg$Mo+pM}@6UT^3vZ+(cVx#+aNpNh zRW%=1s~)!(Q3_n_rx8(Han7q7y~d*AYW<{T4unp-1`=ES(&>(kKk&+Ly>R)RF^HIz zkuhTq35Sxio9kB!N+ds^JK_rw;)aje`P5&`rtHG6PaV_7e6Px%ES0_h9)c&|2j%!m zX^FhYJ3#3;Jw1KF;CsQqP5mpoHQFUD@=kl_o4tKpwN<5uDNexpQiC-q^3R_wdX2XC z^-+|R=xYH-L)3kHucHBvbo0CM?{PM7%3L0X z&sQ8FO~Y=vJ34p*Tz7}yWuPv>g z1b^?@T@1dzPw9x3!xgWCY;`exhz6+dOV1p{;M-H{A5B7yesb3w)uRj#3q=9DyZW1YqjB1M zVidkl=OG~>T87>l^rYa5!&OJ<<_r>B*@*)1<* zU+nbqF==}^lujg#Y>v#jNKOt9FV_Slxwyx?J87?gJLkotoK<7+6 z=KHm~I8V~JBF44>SC_Ga4!_2mIk5wYB=zt3!|de7n;9d-X0I<^z9MX~Ec)82uxQq5 zXJ%&Vd!7(TB*rCTr?05;Vq;@Z&X*!$BzQ}_?njoJ!wiTgc<&VF6)^7d5&XPQr-e|a z>ozB^NiO!!3monHyx^;Z-4g1A`8Vo9c=7ACh|-wcRv`E_164WXL$}$=PZ}AD6_TgT zXv0j=M==trCyT;&slb;i$Y&ZUsqozE^Gi%Dg0I-mIL@5EXR*H7FI|oQjz%OAxleaz zJ-Ek9NssW`@co0bhkjM1-wh4tIc#ifAgWzL@!!%kqVw7w(^P`>hlilX!lh4YO7B#x zG<>aHVv0mq7ODLeyIWK5y=OWVF{WXvcSwXtIU+lE}JKd9% zja+u0?n=O4;yYVen;fxrtgAM4d1nt~PRTK{(Nwk|CTpPk&tlp?ad!W#mt9Z1`3FC>1w$rXmWM6^2Gd?CYjNL zhc8Q>z$~poGcz`yo$=T0O6y)n3T#oMay4U&1V@n%TnYk$uX`WElU2B<#2Q4f460>+3uT5PHA| z=Rb@X_#qpeoghoAe;q!bWTZzFITpiBb-ww1Ui|**3p$$UsM9h-K~-FjNHmOLtY8V! z5bYnCPP2;v2gDWNX~Nl#)92rQY(AWjet*n z4W%;k(&|!ISQlA)Op$$Mh>`s+BE;w6g4t>~K^#)wP~GtHy1upE3WBCpf%L&iiywv& z(BbOi(Y5yHYpbAg7Mp^yLh-mBaA)QF5ub>5V8hGLZ+Lp_@^YojW_&uE2^0ct&V)?DI}(3(?Z0)c!`Bzq$k*_Ap50=h$_0q)8MK7+;PHd3Y}tPC z+{^QzYJL4{+A6tQv{xDF>BvZP=W?%5lr^ktVkPo8-*(vd<`HA=+gVvT?nA3OMJ`a1 zIyW`d0}oKC^O(zI1#Ow*j*xnrOPEmS=&FW+{|a14G9&ZD9Em=u;vxTCB#6BjQt7dd z#>9U0>LSP8mgrLxXO3s&KndDHw`qHg{A4)o=?iTM z+U4ctS#1bPU^~wR@!BUjhKqK+nN-U{u6D)0`#U$io3v|tG9|O`e#evJKbDbK6+?=k z(2P=%1K%-93eyNkb5{^Vt9DF=sC-_irt7deyDJgA_y{j%`l(hbMKh4|@&pUN9YLvG zSyTHeS0f__e@^PbG#s8MSB9DBWW*+}PvHyJWnS@&)7@XiVU~+@{&8>oIc*yN%XL|( z8I)35KbO-?%^dznzxT$EC|II#`bt9~D}Cdvyv->_1fKzQu0C}CGE%_j$-Ud>Wr@R9 zfMoFP%yOM!-Y!vU(M%~7aw#>Xnf!FR)DL$`$+&9on3D=KGj9(?Kv%Y<58C9Q(J?0A zdz>a!^C(U3+0MU zGB#O*a?)Jea+Bj{D8`l^LwIOy7s(isvV74zkAT##I1 zn>Iypu*pvAL&F_)XQSTCTm@AyY0mYWIBK2Bk@akYJ|mim4!TUmKyDEr7)| z@r(2v3K5?x7TND)|HyvD@wJXZJ}bgezN%C~d)0v+GtjQB6xQlV>PrB^{^2fjba=RR zcqye!;$QqL$BOcu=pbQ3%zaI~7X!W~&95btYIB7UjZ#(y4NLpiDQk!FeslbFoIHH= zOl0$&f5%FbFyy>&?9*a})etr9ZJ`j1X1YOGt`Cxp)e0vMnoD%eEXa-TPY{W*F%m2I z!a9U!x1+-9@@J3U-Zt`x3k<mue)3V!YN4H`HupmK%s%@1mXx{h2a|YYZ0kA)Vq8 zn4E#=^&y~ZGB~U)z5K~}7=wmWd1 zLCaA7{lkj~ndh5OONCefzn-hBJd-R|%hG>Zh z^1+mw{JFS}?g=DFv=bYGLrAAvjx*zxGr)=@t8lbEN~2G0$|R}b7YZp<70C$FLI;?m zZet_~Abtn$mdIjH>#N$^>5ZmckHu#VGpj;i6EjuFKdo1ARZ&=`xJSRZF@Jg}W9Oq6 z$zv3I&z$){qEK*rawgI2^!q;|FYnUdc7nF7@_oJsEop2l%>m3q) zwaSn+N624ibrlt{FQhQ6K1TKJiGIJufp7+yg$K}s&DG7Bahg@SM&aMTe?dg3b?25# ziy1vVeE`T9-QL-m=mjQ9(f=GT!RGM0*B+@zFOg5i`ISSd6n(j!@07Dc*lo%zm;9+J z8;R{6k>&hRj!?em=Nui+wr8AELHuD338q@Li(cD_FmH z!QN)P^9LJ8fb=p_wG_rp83U{mZ%xGwOjdkkdk*5Kl#CDzMmKA+m9bM__cME3 zkh$2J0ajMaR2}D74$ZXfr;N9wgqZImA|m|NA;3cVU}uN+k@@X8k7vizHw!?11*^K1 zA?oHZ-$oh*2FiMwWqJS_usqwjG2c>{GwCquam$`JgLw1&r?RxA|5nQme-V)fA5$C3 zM|*(d)ju#m#319hG5V01WZ}+x5y8Rq)_Z?}yFVC4s%IGy0R}FEkt@}jr7r7$A z>On>gqoTf*tN7)&m^76Q^@&MsY1I#EYr)9Y)h7Mv_IUH5PzB1 zr+~ju&eiYddzeNmWwQ{hkk{F>bCvrh2Hzs_f`i?*P2K31KXM_$sl0*%FM_tmpwkdJh*1UGwnOl?09Rn*1xeQ zefD}`O0a%yQDa2`! zxlH!!k6*GeBgezVMt?FGUppN*NBv0L;EcXDiyTq$44|-Qx-Y&tbx1n&OgC%Aju;A- zXwe6q#8P9wuUH$Dv>J{hPYhly0FHm-<@Fb|_GTSR`{h}DhtZ?5B=W<`Mb~gP zxd$xW|L%cNSQM4W@bHv5>IO*(R&K#K5-kIwKwdW67Qw;q1Lk(H@ z_#yc-760~9l@ZImr-7(p3h=Jr%fT}$nv%e7)ayESN;`&*RN-s>S|u4Og=&s=&>Q3Y zx1LaeWwOAecvCG&I(`(U(@eUxzXH~#BIBXOS(UrWaO6t$l;xdHgOsDxpHqz=NZ zcQJ*d_q4Ihc`5Jx^~HHa9@8gyzX^~-fWc*oYD0cgq8Tk>%N3VsNJyl3d5EmpQ*B~Bq%M^cX_%id}IEL0y{6I8m2)$*!rFQ{EIg%PH%oaojIdWpu zb)=HY`xVQ}R+LMy{aG!h+ENzJOHD!acw~93lV+>QIyKs}4wJ+;YxRF7b6KIeT!sb!l^ zNA^4Qfi&}#r==*p?&o^El$H3)f#ffJeSN*WW*nI>#Ny7+?;G#au6`n=rlHBlU5+x6 z_khz&eDC1IjKTSL@}kytEk~8cuK&Xpb}3Ei;`sxR*%Vpd6VBduo#EDz)4M=n{cl5@ z9b)s=JP=rZg*HER&yuRQgFy$*bmgYllBg0Z5PZ1OxH(@>lJB<1^#3q9KwYqc!Tpxc z)6K27==j!J<7w%n_`7$QRB;X?xP$3jGIjU>#to?nr7dG&;MA{&3E^W*7z2AUtF z)jZl-yw#3Nv)}w=6?BP{G#$OXupw1utx$;QZ$ik&>I&ZDhO)T6WW84LN!98~2c}aR z^&Wx}sSYOeHtZ+jFyoEHMos2dt1Ugmek=`CK8e&~voAE7I~mdv5W^x!zl70=a553g zy!lwpT<&M|W!6OyJN}*@a~dz6EKUdgP@#5zu|=*E+Gw5;r7?VRR-)xUR=H{1Pui z*({GONmFD?&@;U06UsgsTH5!lw{$c#?npMjv2e-QVypIZx4^)Tb6z5a2Hd{`9?epY zDmy^Pr%w#cPbc=F{VadF{2<~`={}~(;c>iLc8%g82?5fe6fYe&U>1kuRp?Uhc{)YY z$P-{@hOVRC?^#Qb)y9nEY==!d_FKv;DC&`0H)Z=^$PPIW2Uy@5eKmw%J^_M^n#|g3 z9bFU)Zit5Jw4CAXHk#*KCM#G~>p2iWB+}C8P0jqA-D-bLT+k8_Smxy1U0z=UyEbed zit97Zd4l$bR@m-775g3banU9(oql5cqxv=##<#QF9kg*A4j=kt#z zcNt*9W$}Ru8hoC#F_g?PA-zeLvx53mhi_b|O$Tnz$I>t-g9q_J2T{w2AEfR|$^t%U zOEbbW^Hf%pjVS^)IWv>Cqoo0W?~M4F<~Q3mh4;?c?dS>F?A^Pv`~}SaP@?}CN-DM_ zubJwRPbhz0e#k%}hCs7wPRN(>X1#LHA0{3$DBvV@dU?3NlUYx9ND|HzxRRMcF_l}T z6nt(knzGV({<<2*eKE}wy;Mjl)$OvAi`nu5lT9Rw1#M z&s}T}agWJola5O-v{Sx;KQ;mp0!GJN7&iqz7Hi^wucmKyz~!rkg$d?ptP% zuOllCu7Qq|suJ1#^XudBWI+gcz?S%c7w6{Tl|6>38aaUWFJq$BFy+9eh`iL3%l?CL zF!X^V>-$ZpWlNe!@;-oW9YVz8!yIJ;A5v- zh_)(3gQMlgx@(y!DG4uy_RClpd?35;c@CsCL25jhls@XeTU#E7U;Yfd>sb2c852Ot zdt($8$g1{Ih!qR6mDyDGk_P^-TQgecy9kRYF|=yw=*!AYL!$5hs%Lk(<($STU6uGr zu0vDe+uxs7&8+2#d~Z#yOd_6}%{Cb6Nm61W|6n_w0urRi{_Fedr^25IRo#yUXJiUL zwpODu-_Wa7VFu9UbL#VaTB>2Ek_hhYwF)J&rUJA;?!&Yv% zuRpG5UVZPllKhc@sYD%4E@Uk2`+I4Lq3=deKR)nPZ{l($i*#jWr5?HXW(XrNit3|3 z28J_3!d}Fhg-Lhx3(LTuk2o($_Yp!f{DUsjG);ce@JkSXK6sDpW@q)cJcE zz0BjO$;rne(rqHQD%Rc(vn*}{FYV>Z&jO@~4=>n)3LUdmx&v&jR|4m2$=+FkgsSD= z0y_=8RY(+GFCZTe8(1=1+}suz>Puk)i62JLlb=89pFEL1`>iUaN+XSXU9$#aL3n+_ z44Elm2f@JYF8MejFSeH|F{JVw$4>Qo0|gh$!vkI}_zmf2KQlz^Qve3XskG~pzd zkdS!({J9TK&Zrv)R+#%7)n_Dk|L54NH(!DsQ&M7>6;18bdV}Sz%2)==0mo<6&Bf*5 z&!3kX5&k-dywhKaqANWJLleB5xJlHT9ojtJ^n^b+F~?|c`(8FI-sCjPe_iw-WcPBu zlqK*2JczISi(?gFOusD2xi!ah2umW*#aKP-F2hwRt%nA2Kma4*)G?u@r)M{w7|*%cb?|{q z=U9_GWIfC^c?{Llx-P!NfTV_zheLT0^!OH$Y3Afo&{cb)N@n7!8r z*Rvh>f(mu~nC~ukF5+mZHZ}*^zO!zTP_b7lL|WdWfb9*qbpLQf*5JJaEW<_7=w@1} z-;K~5?6PAc1FeDlH{}|g%l{smlP+4Qc+N-c080V;*7MAakwsC~bDdX6@oU~Un3>X# zScvb5@#rI;;Os(;r1ml-%KowLZZa zHm&j>c2IaSp{~vx^!x?G1jfzQi)X|5yxc+^imye}K5ZvpWpiCe;q=*%n7-!buA&^` zjOI-JuH-G&`ki>3Dd`7g;wo<}{izk`J>HZS>e2Db&DQ%;j z*r&4TJ1)_)j?0aM*3^{v@4J^43pCCKN1-B~V`cCi1LnBGQpwB&#@W*cfJ(Sc z1n+=`?k<_#1KIH@2;kf4Zw>u>r$nNp_vLcSVOT$=Q*CvMmfqH)BtT-bTky-nX;8S2 zmko$$1>n(7>;c==rX`m;z!@+Dj%Xg>=SU$)$1sAZ|H~hh*ff(ORX@ckQ;dtB7zb#F zu?3y*v&+f&Qs2e+bUAI>0nI_yMYf^2D^3Jyt`55-WPyzfrj4Kg z7wL9HH4v|Lmb8+Q*e5D%HchqkxL5~AUNGQ@nT<`6oJZv!#tINfvD^?-SG^l5^!k^e zX^p8-^6E6B-}SMiQ(8xG_K8}0?*btQSFDW{aTjN#(_>R z;Tc8jR?Ks=vYX(R;cUAsG|LzG$rFEVYO>{y=SiX!){cqQ#e{%qo&GE6DN0MDG~8ak zjI4{|h_1nXE#_>%OF1wwu=OsjP#KY)20%Kh_i)J%^oTL56DUzB00ZQ@LXQ7;gejcu1MOiyQf3>9(80{ArcsK9T z5!Y>`LOhrfM`XLk7Cw-&1YD7#qVQUMuCA`;=jPPHojPC5fbU?*m-m7RzoaaZ+@vO@ z+=CKNH!ei_Riy6PR*(CnzBW2_wWEsM=$quMfaTnw&YdXz*~!W7+|SR|)%SwHPB1EJ z2Xc5tz?0K}9aOl*B{k^%TXVqb8O>u1!T?}gF@|zYsQNTCbbN9BAR8NUR9pwvnJuT; zl}~;)(a_MSa92`gNc>5j_as|OA*czJ3m!wE4YKxHJT@U#TVy%Sx2rKfQSSUXIoc$M zhPPngZv;vRQPJ5SKR%3aF8QoI(9lOQdCHSjXq8SsPJSV{KB3r9RBHFQH*7cJp64?) zOrs65thV>Uy^qvo^2oyTmRMATilu!nx~;rzu>`WWNLtk@ZXf%w4X{n<+zt&2X4mCq z+8nf3SL=)kyeiJ zBDwMe2*ZvS6?^&wbVvz;DhUj^^p{Zs`OI$bsa?^*lnF7pM|`v)jGgCVE|F?e4@Ej; z6!v-|+n*A4u)De@z2nTy)r1(k&`4x-$76x_`FUOyMGXvKwu zhK2&YcP{Q422Ei;2fchiJ9?N0zL(|E=fiqGu)mHcveiw4HE#~FN!RvsEpzSQ@L0Em zj1ofpsyejfmhqYu83|hoJj9P&cG3=Kb2;K>-or}q>{aX<->wGucK73S-RRn~ZEkvy)d>r*JhLg^M>5Gn@;D)5$8o~S}xhP{6SQkOt z$z~O^VcIQ5dI$V!?>XH@gNp2gBHOGqlw@Xp8=>9IrEqHU$3ayUM`-;Q=!gy>2gG7T zHYloJjhQdA947&IWE5s|C<(+pksS4Xk_qdM#L#Php2vBw>>dCtNLCICxFTQuAFq0)xxm(n3-iLPG>l2^>Ci&Ff6KRyM8dGFk%^} zi@9rUsm-Ec{s~hw^R6&2Qb4X1zU|FTv28rP_j{n%nDOGX=wYB|I7!(Ryo64)V)I=N zI@NUQY;LCU!Rn*m3vGO?5J>Sz(~+D~>~_mb&R#o9)E~X;SIQPBgn2icy{)Y+XcpN5 zz8lEFltaqsc84VEoQ4SCUKc&oiD`nWMhL986I0yD3 zFEA??b8sb0Ou)xJBF~n9;cA@&*F>|TygZC7kH7TAC-@&d-UI~PW_d4S1O>I_U{#3K zemhiGRH%j1F)(-|Q`efX5JkGyIyyvwzezWB0Xsg+188ah9~Us2kEX&iEMxB>{$x76 zdKHxqpsyvIATZfaOw@utIB>Ml`F;uJh*c?!nMjDLjH8wKh}u$LQRoCC;plBj?@%2) z0{Vg*(C26gA^c{|a)p9oV&|7T)oWcqB)iooF_qw`SxAaa)}x>?2(9@wISyd_uKOX3 z_j>@gW_i6z^)cFp8CNx)4zGt;^IyimVEPCuI5;>w9Q!Tynoi?$Q&TcD;q>trAN=70 z3jQc!sd189l)X|Z_aE|4%fWWd?uotfY)D%|2rxVa8ZE>+mujEQ5onf~$svc!p+q1q zK)<24oTBVB-9(zoi|@nzG4jX-l7mcBIJ~oEZDwZX^3pfS`OTZfI(vc_(Tks+alYkI z=i9GXZlRP1p?R0Kc&6I;Y%one=`y`kXhO&F$=zt+OsdMx;Z``&q8E5Rap{EkK%ITCrL{jVg! zP5pGhXxHJDB


lTLyCD*1HLshGxUrRb-`y9J6mu~{@|OA8 zXeA5ha)1|ZJ_xG}dRw_-sj-?<-3b37bjAZ)-|t1&u&qqz?<$)qk- zW_kocKjPDeC9i92X_@n5>+`2iT;%u(vbSO~Ea)#m(pqa>AP=&~_2OPn$G^?NjHyeD z4;1tC=P_Hn_yrStF6fCKKL2lSaWQ^pMx8?gTRy1VEs^7aJTbt|k+p^^=jnEWS}B)6 z%b@H19nS0J={eEEjDJ|m{|2Zb%z@qyhzr&%#2c}J456r~2ngSPRKcX)LUj4lMc*uN zQre`iF)`5Pb}R1?3rKk*fm}h4x%Jx`^*tdFgM5EKSt;qycJ}_p@~SJatOkB|V}=JNSP%dpuYdN4$7UsDkQp7INxUDD`%fXz z@-T4n-Rt~b@u>k`wWFGDMec5b{w)|=&CBRMWMwpX(;q`Lad6)8^OH;VVt< zRN=ZCM*|EU#jkfvUD~%Y=jSHT1q?TbJTWn2nwq+85{nGE3P0qGs}MX37TL?1J$Hxg z^mGduAq(%#2#p7>e9ja73u~QRKy*`AD2@y7RE{%z|L-%T@j2(Ckj)IBc;b5`1;02c z_CUFVR`0#+Me?xA?S{U~L9f6K>F&Z7(OW&3a;<(t7w+9~^|gkgVvps`wB>7{cLp)> zU;ywNlKOR9(rUP{(`V{wQTcR1F@~yUmvr(^-sg14Pz1 zym7x0PJds&SKs%95CVSUy&%qL*F5Q9RmgG3z*`A#fQc>`;Fsk%>%ZYrD7z*h&>~Im z+$L5g0Tn6ON1y3-PAdLC}@8nW*~ye75?R@RtV=d8z2F zglb$@Q@RC&OxXbHM*nZ#_F0yyYr(Y`Mj3as7Y$KYqy03Up#@v8;cSYo2edI@j)?g# z)P)3iTDuoq7AaenH5v_+!=uw(@!+ke6v|H1*MoyVNUEFuF6=-oF5afwBrvL=`LyQ zy17(NI3t5=%A-$G4Mrc?NC6q8$2OxKaoB}Zn)M(gD1tFM|JmoKE4Ag>SxP7{+Nr!Y zlVw-d>rGY*S{oBxT9+oh{uAL*)zCl@svRfL-q`52rXrC}9L|)D#cKdI&@;(cyD`qz z)Zx~gPyO;SH(GLGFzxqB{CUa@w?6EpDEZDc&~Y)VTXWq$&0Ojt^-N3xr}570e(Drx zDtiaK07K<}n~U@RC`)FBWMy!t3Ck}~m{7~4UZq;nlHWwX?z7x}vBlix$bt)-J&tBx zwAay1!dnocGRC87Vh@tP-Y&mI+x5J6;l{00kGxuN9R&?Zf4w*2PY0ZyL)5*)==lx|JoqKwVhA_j zzaQs|Sg4nT`wm5V&AS+P5yU$xuwgadu?jFdH*gzQ^C#3xY^H6J1^YX(;fCm!hP8U^ z1Lt>6IRhrhkEyA*7ig4Ct(c5Ve9s%oOM7?_(7=tL(96rq zfQH2IA2wvu%-DDqM6FN%3j`?1)E{w1=9}?@jOn=8Sg3qZs1Km0{%Zf3Lgw3CK?NDd z3>x>_c#;fip?pTCqoX5p5_nM(Lz{~h1w1p>6>_Dr)x4Bv{%|miuOGjJQXSZzt|#jR z++8iH7MbyzUcFeUvzOxUdlLRn2?vIjS8P|HL6rzET|WdZpWE(~xHn)|0E^^ICbsuE zR|}i}8<8$VfkA($h2as^D<;M@{0M@7lpm1EM3b=O8MOT)*c)q7hd&$#{yvh5LtluZ ztV6x8{9z*9!iU2+;+hLF(nF5WYfiUGE@{|tA*Q6$v46JCrabB1u z0ng+#BZJbKoSInr2WQOSVSn}8pJhy#?R+`%CBx!MVSL{y4|tSVM+kIy*(iAt!rV`n z%05%)_yx2?xPeF|^LM`0W^Iojqq~ZpeSSXQC@uCF{jo_!=7!rxjrhfN%eQYU3-0MV zHd}LWzfr&eTBzR)zS{rpvVM(YP5ox>>nl)|7=(APFR~tR2G!@Yx{Rgs`LB{)_CV>97z{gqhtOi`uK5(=0@deVPa!OFrjYrbIyKG51-{3Sm96)UIRc`O3 zrFo4K5O@!4z+==a>HD>`>)>YbfaIZ}%TtoxoV89q>>6W?+5qy~n2vLTl0_>TEL|d` zgLQ6?U~i7icl?q7T=vZ@kEP3*Cc#i0sUzq(xo=2|A_fGvT(o{;nFR`!Ao+URu=Kzi zxsu_Zha)Nw`K#Z&4{^t?gP<$IYJLeYfyL zjctKDw1B!y?0}Ncl~e~EY;{4$;z4f|vITfE04fH(a8hjr?g#3JeY>+#=EA18R`+2J zVLV?`$~Eek>qKuEb0Od4yI-2~VG*t?D`Sl#EQ83){u^*4du8f~cgUo&&no-3ng(iK z9I)@Fa+;i5bg9wFn4Bl^Nmm+1#*O#1TH(~LP4Mmq$A!+EAHnLQFJkluyHML@{8;}+ z_kK5{^CwYRSy`zUWm)?SS%{oFSXWQ;+e52GCqLrU#-~m+Bzcq(8l+(K;-J=C{06BX zHf=5BAnR?&wTPuN5+I9B`>%uKIA<&GsZxNQpyaAZFW3#DZjCx;o*rd3H8v(W@Mjad zAzQW^9yxkLBkb}4Kkg zzyV?8aC&=91wfh{|kSoLW1NzD8MuRi-;GDH@(X)7b=UCe;g%Qvt zhQlg;O^zHY1A)N`V&n&Nr}&^A(ha1?&7ke*bZ0)jrCdc0nLm43Tdyhdc!1S?(okT7 z*!V$kimJr`p^mW!^r?&TV#3GqS*UDck8!?68Patzx+dqp_2rVoEG2mB-E+%!8Ce+_ zZU3wZ1=_=eLzoWXqz$jrq@cs05l)rAw?IH0O{)M0X@7q|WI5-lY$lp4x>f013w-N~ z^GAe`lDoNCZfEXf1{O6U0TK%wpK|xr-YEB$g~`e8js&Pm7DhFXA|qnL&IG-R$pQB= zz--X#uiXBMpUq){G%Y3z3z{20K0xErKU`10GPQ0kqBW6Pdbrb(&$$}?2kxUHb>~If z>y#hLDCWM7`xpX5r>;-lb4GvgMuLoif?hA7-2L|+@hTI{f5l}t&8Wk{Z2yuV2Ld+O z@d-w6F999tl!?>NkKr%4{hK*~i+zkT(acm!x=%z5affj`g2#}^)fzH}aQTAZvlU>R z;-mT@U7HvRR^$=*gT$3*9MZ75^W@}Z|D>dNz?Feo6Ecw(O}NOvCgF9^S2&G0uo-94 z$T^FhCP-q;c#8f+sQaWEn{GSw0W~tYrdl->hoxqLlS=n}m(iOGMUu5v-TWC&43Q|c z2`W7SXbp>ty$0&$XL265dJvn7ArVi#BdDe-Q6M8T$35VD#_z`a_Cr8pLjy{5Dogt6 z7Ijox?~s~TFzh=0xdw_n9%IzH*e*Q#`mnd*xQD0UHO={DW#WHh+esJej4*iEPWw^Z zdj}BI2)Y^?dS0n3-bYuun*SnCL3824pVKTU?LUe!-Vu_%Tgw zWunr({A^~m%U2f_|Grzo^{^ka!;LM*D76>v;jg}!xJ-{#dr>Ks*S!(ek+kd>o#0Am z#|JBdtGiJB-l~C}IDH0$e;)QomPC8Wb)Fq>owx*E&HHrXEMAMA=Tr9uLAdw|$=XSZ>{Tu0D8e%eGY)>e_xc*uON&AyY;)c^1r4uP z23IX!VWf4y#`5+%8Y*9#=2gZm-YWVz%Fx@|x|lFe&3pW=wf!!8hk$_ggdBn{))4?# znVllw?uF#DJ-rf zk>z3ZLK&}2$KNTKhVDNQIPVydc<)L0BTT8HJ{3Lkm8(#NU$X3(vVru7OJ17pZL3lZ z$ntwCi)O?z`=wNGKA`}B$u9&aPjwd8<2N3`Ar_aM^UAQJux0gr#d*8Yu(x#8~&awg?l}W zVspR!zSI}`ubybMc*|6Q%W(`yswL&+PS%fRwAlDHKIP(v z{>C(AnW2P98$AklL}as`Sf#blOT_074)Y3h33mNsx4-78yIy-q98>s8 zBigwG4fH^ZqWLvw{~EDoda45qO63WL>n;Yywal2+N9$cb*3J}#t^)KD#ox@@OnvJE z&*ykl^wQY?&RzB+9PdyEqniLoxMp3{;m*AfAM3#bogj0b{9Yo3P^wQ*>ywDq?wa#w z)bx>Wq@yM*uu};1BOi<1M86ABsu1n3#>zI~@uh1|#@#XF!4*N|Ev*`U&xE1)P?%d6 zHnouibVtP{3b2sOO^s&RcC=jyiCXxe3@dl-b*(nAI22s3=WenZ^0wPQre2MswiGJgaylk7mVi{V)IHKexj_*d1?67?n_ zcyI%v)(bd6Bi=$~S#i}b3SkV~{S{vA|9VZd;wnroLt zst>#MAiv9R%-(1_sLK6kkvKk6EOpLYO+K4rcf?cO`sy`^Dk&F=1jyDZ0Lr*~5k->B zb2S-K`(4EI3}`^6b!opSI;MQ|GfQXh(d9tkUxz@IfiOl~-2{(#$+d+13#?GIT{nYi zH!II7x6YgriECgphob{YYv-g+ErL22I+b5MSn!IJUFXA*V%TzFXWk-i%ceqJ*^&TP z$OkIz=N5PteC#C~2(IOm9YBRTDt?~p_~B(o!0eyF)P=^{UE%T;@hb2p2MdV;xc@_rcLQs`5}WfBqO zdN^(D?WpxLnleELQW3U7GbD}qJne2JFE3hIPqtzSA7XBPdDu!LWYx7o(1LqmI{+SJ zeZ#NJuZ~O`omXVt8b(1u<#njo^wR7YE@%DKinYROUK~=a9*8`SF&4(OzAlnV-yCkq z+4jfz7$9rl_}zMl%q2C_2_S?jt+i_vu+0dGu?abo`dE5aurLg>*j+^<8 zXRVIpBv5(yO_VS_?|?-~Y`$6?3#{5s2ZDe8u$KAFCzkWFpo`ejfMPPDFumH>T#L18 z{jZW2=wNvh!g$Ajj&dj~2x4hb)_FWQcS(N3MxpBnt>)x1^SrRD0w8I_YM^p@_POY7 zcCLkFnjrP5qj_uZ&Jbb>Hl*9_-I9q+N#cbuQnmej^62+P+@j5 zCJWy2iww<;i*z#8-C5ED-qDybMo6yNlDMS1#)rs^#Ns$6==tX;5f-gZ&ryMn>&F~h ze99Sy4zmn^I zL+O*oTPSm=RL;N3s!6W=g&6D4UqMO95goiW+QX&mu_ad_f|pd|`MkKBp^U`A{r3W* z@h5xwz{cE!2NycA&bC9{SojtZ@5)!rGd4}FoE4`^pqo5j>8)!M7k%d(ZDV$8Ad9Vjb{G4#{xH; z#SgJJ2Hs0ymPegllanq$Csh9JMTp=q2N_0?z@miv`e1l}oWpq4NnAj&K37;VhSk>} z8#+6RR@j7EmC7-FA_6Z%=(+TMp>|w=MspJiu@Kb?|A(~0gA?{eF+WMsc=DJt zs0nA&3=r5(RSJB9_D#G=ez?;b5xvEbv$ZYwXKrU^Mc#M(<|T8qF(DgV9^S>2gT=e( zh~~W!>3R?q1UIJ)nU-cltPhFu7<{r42NEbf3u`f6Y3}P)+%~>dv47@lfHUuQ1)YBw z13F?aCz~Vg$9No8Z6_r)DW)Wpxe$Eme;V)dFT65rQy5a^CwRBX5Ct(sU)Tk7e43R9 zEl(Vo1s#WIdG4OUy5Y<;O72%c`rX8J|q z=~z1e)=hiz4SpH$C9Ns@#68aU{L^adomPl$x%@5867vO6aXg4S{koa*>34oe5@MWGn;7WLhOYxz;&@OoE{Y3qYAlRrfS?4 z`bA$-385Yq7huGUi)>B*ElBb1opq}!RpE2w?0RKx;rbJMBer01mK1nR?96CIP~iaj z=c;;#pxsb8pq!U|0=RM66HuAd%SZ*oy2|;WlgZa&%Kv}@lpQ8a7L5KkM(QT$vSU15 zT4v3bK2w#-(H9ECJLy(Krbtt5z{c^>+v#=iyB_K#=-D)p*e!!WmKT%SUlmK_HrO40 z=&TQzrfo?j{M-@kkddftSK}uTpW3@&(w| zla0qrr+XZQc@c)~3lV%&Aus%;!br%gtQrm`-$BQ07r zDFm!gnqcI4sbjOhP*^Gp&r6ew3a@FK#uWGn4PDsUYrBP={nI#*Eqk6Dg zG-GLFNw?JrQ)e1z5KLPKQ=XScjgn(DkD!4jO@nuln~UIIA-7a5JH}+~u+V-^j5Meu zh#gWIVOVfFY1hDlNbo0Mbp9w98A-sMNkZ(5$Wq>|PV@K#UAbIz23JYHqlbUYVxXrl z(u!($dAGf)E~RF`4ArDw(*KeJW6md1YW*dpZ)R{?hM-53OPIuA4;5ED70IIVtw`m2 zNhNK(R+OYWb{rd{u7bgHHB__jX5Im)8ATn-JdFp81X;g#@){&dKJQ5MQHVv52l`q?VAro3utcm&Y zZq_3@gofe~sa)k>pn!Z)69yWl%nGjYJQ@4o%HCB&6dvPuuJUIJNkru$gI`!N@Z`xt z0hbn-DGV}XYJJIK3>Ub6H_(R~-&h8G%M#5E53U!aSc}cNBHvWNRS4@tH;3&c@`)Zf zWLWV(l8QWz!t1_0BkS6SnzguNwT?9fr8dJwI{2qWk_CSOwLFYo+8EUEGDNmphMgI~ z)ORVLI34!&dKC>mZT``=l~z<6R+Xwqbj>wPNLV<`MgF-z6;N-}2y2S*45{{*V~E-Br|0%>h2RC=9DN zZ?tdx8rVAc{bnT6Qkzc7LwmWo7|EYsA`GR-tP8q|5xjzd}&J-P3}5$?IM;{2hOiviTj-kCR&|+Ea2?UYN|-;9^6cL zG{PX+51#$JOc`e9hmUAzNEOX+lXS%YGfv+8RJUD*V%=;3vckz~q%xd^+(;V7w8NLE z;lvclap-w^Ix_#mO%o}8*&M7qS<9W-Y062C4|rNhSpO)M_2e__dI)3VbQ;}|R4$1P zq^pe6i}&;t*H1J1ABHS%J#)^BI9pN=rwV2pw?@rH$8wUa4q?Plm6QhZ)uh1L@>Q^R z2Td>Q(SS*u3Y|x+Dtp$gPbbwyf93!yc7VOC>>qPi(AlH#xXM5Em9t?snm1fD1gW^( z&EJJ4pE?A{oECHx<$zeexnB#1celTnFgxuKq(e)VaK_+DigV?>y%i#rr|DHBQSglH z?od>_KHmqaRVq)f4ePzTryu-r(pF zY<;^$nh4dCgFxQ>T}NisYlMYSW&1z9I}6nDQ&9ldwQ5*!ECCH8gQuJj%m z?ms$Rx=@sm@jWTId$Ag5W_E&88(aX|@X(}z84{>^LOqCjlx-2TmRyr1O;|Lf4 zAH$fY6VsB1S{8SF9DHm}DQ8*gcvTV4wVA;#E=_;r6$M_mW0L*UYCUEBTyM-b_>+pV zO<*W=?aP!L@bANnvHDhg(v;QR!-;*x71--vmP>mp|D!bQK;5VQ)ByYrmXAcr?T58U zVA9h%nG_8eD)vQ`=F~Q|k zmNhO`Opnj&Z%4;l{0t1pEV&Z?Si+Z+gZzfBSGNq_j_Qf~J6;FlKp2-i1uR?bE90wU z<5snc&!5|fH;rD+%RxHrTJAfG_@YV$Rxs?hr<*K!(nn7IT8^nj3tYex>Q)%;YCr0m zZIo*gr`sJ7NxHi_{88?^heKE*Dsz|u2zX#a*;<(MK{xB%K7YG5vvt08`~I)Ek7W^q zsM|Epl~NAVS0541mnriabcvQ%1zoarAyum zSKdX;^d@(^Bav#aatS=R?-Uzm8mZu8r=eM4ZY#hg(ej0j8)IlDaN;VA-F}l}-vkI2 zU?-_PzpQKpa28O8b8%Qt_=t1Y6(i19{VfZv#G-1IwNluZ1Z?O2BY^%7zKPBgb` z@lU7C2#g>~m(pJ|jjyf$67ny)Bl-3}#JPett$RNn9#>^^^ha+;Qzl>?92O%K38l;L zjjnfkB+e@-XEY(G*gn(C%5CVJy$#opqj0(3uQw4)_4MMZUklEz4#8V6-&0I5K zJ3%94%v8njUqMkMc$Hlz#)~nMQ_(v8wycKv#ZfmWsxPT2dbzs z$516oU6od^ET@Tl0yx|z(VM+8*!7T7Z=9vY?cis*_8kklg>Tcf(yCuXl1q+QAn*S3 z^^0%oTCC*b6E>w%CfR?haqxWRS*)VerTre)aAE>;bd8~OOSd3kx&rLv~e zFZxxcs;h&JyTL@3!9!Zk^vwq4$~2KIoelNCA_8J(4)MVfNV<;49{jQrhfi}6t%^Dh zsAa17FD(U)YuWswTK9b!UF^42+QLjz-)jTnOyiz(h=o*Hz%=LyG&(mbaZP~}?0cn} zl#)v9FY!`C<%vyUd>oZVa=AtHD}D;e5yY+bv%Z;ffniUKPV0R}N-|8U!i-0Rk1gqp z;vKt(oreiC`%Iq|!!#JOFb z@lTEJNPl&-X8;kD6_QV))3hxRYsPZs!1Z7k+OUl7SoaW0zZdlLsDdq!j|9?4F-Q4g zv)Zyld-^_=%f$Dzi*go7P=O^-I~cj*UTex236bQ;dO5EwU4I6s+4;dqvW~lulBwzZ z>guY;xHJb@Y|`b1Xom@Rs_(mZHxpup^s!EjMaP(wF6Kc-w)qmTMCz?}YOjIt_6Ce= zJuVE0;XDyU`f12I8qc3_v;~z9;iA$m^Hla3d{&|z@;^jxNDKeucsuE^^yUmYplYy^(lu2i7S z5Z6@i%$Mr+;Iq)*8e{K0zntC0m|y@{cFwb>885&{=>#Eu0$oaL|-}- z4)7)y*yZ{wmV^YTCUVKP(u;W}Wu&UHVXpC}ILD`5dsP!w-|%7D^(Y?ogF_K@J|&dF zMH%@Gb`R}NK$pti&7;|PMTM?!2X`G6sfemS1$j=kXW*mZhMwnK_ss zQtu->`y1^@Df>^;ACCe`4QSPh;<&S5`)uF9L{n@NQC6r#G~e(SMqR(9q<-;W^zLAk zDU!pb^fkP7rj<`yJoa<*bwH94L>@^~!rq+SNv4T_H&XQLJ1aS|)mN02_N*GhQUA7A z>N3*Kl`@0Cm-g{vsa$ooqy6t(r&FguoDGegQY^$b_o;r+A-o(3 z+92Ly?_Gr(dPTeQj+v5*Y?YG10t}ht-(Ws@!fY9@B zKs>FlYbd^@X9RM}(+3=Dzy_{;%=+*|IO|1GItiiPbI2?B=Hh~-({8+PQCH$bwm@nY zpejWQqT^llQ5pvQG!EE^Hg#mpjH*`Y%pLldi6pk@ByJz(C@)$!BH1^sFdBa?#=-)$ zQZ+*W*e3yz^(0@c--q7VMQrhSpEp39JIXKq5|_+shkQY(bb!nSIQJzL6n}OZ%{d0= z|JlKHX8-O+=z)tH8E9#~n_#(zA10P*&6g=a^Dd!wSfBKSwI47divk-zcjMjD=99u_8; zV|hkMWd4u@skO-Y6?)Nb@x*$20_#-k<6T&FLNz4+mcTY^ixet5!Tc5i zrkhbT`_lEdOtw}U^5*|GjOs(3!Jr!XV}LM=C!aG_R$gvK6LFA%?QLd3>-1^+Xx>kb zQ%z6r7BciMbyVBHKxuRNq18vu(2$Hmd*_S^`(^w~KqZx^Wp3)1ti}H05d$^Si2^j^ zU^XN9grDJCtS|3vC3dGoKl!3OVeQ7yOgwT4jw|?nZ)u6~@_{^hsnEC1GcnUjc+)|! z4NGVIDcq|L#J5UiuqV=BC4h)+Xc|ERyv3*{sqj$%c9O75f_RGpXl9bRALTCOK^R*? z{Dx)={1%(afF1O-Lru1WUY2A;o?H%bGizG)Pa)u%A@G)lxEz=z{ley?7fN-wOTdn> z4t)LZF%d~gS36m{2m2`K>jT|9k2g;bL+1~M&h(*@SX#OjvYynEX%p&=;-PK`M&~yM ztG?xPdm)}{qf1EK0~l8GQEYA^$%?h=xe)zWrc%h0t!`_x2_vG zW~lsJ8pNr6ybZ0u3d#*P+S=L&lC#9zlvZjj`)f^l@xOdtkPNK$#?rUxV$UwGYIg7` zlz_mp@2v6Do~y7h)Y2KvB%)j|JS4C=gSM$6)@?c(E(T04;8fcOrdx?9{h6McP2!A9 zqBQodWQxIsqlRUT?j0SMmX40*4kg*BO^d;g-#uY7O5Sr9fNHuQNzIQRv8+62ooAw= zRZ-B7adQg`blHpn^s-h8JIko0_SC6A>@;0+j9E&jyiSOQU)b4UA01;>3uH7?NcL$- zXVGbC;bHK!KxFNFCx!kg!jAf= zk^bBv>EK9=UzotQsrzTsF$r-IE&+*>0a5QCrEe(w{st+5 z;seNH`Pq?Z)kZ0;CceIRcXxkxHXUL!TO6^GOR(+O$yzKWZ4_Eq5PBgFN@(VLH~NhQ znJ7{1#{sy>Q#wGBR3O4j>xYp)d|{Qarg~qpph7}5##Vgng%VXfAgz;5P0bSPrZ!6B zk1=c%k%o9K#aIMpj2%(WFL#D;9kMnQk zhC;Lln3I+H`7UA`aBRh|H~@9M&VYqb*q0HM>1MwTVxix)gPhiB8yfw5UhXXmYMN_n zeP+PU1hOwE(i8H1QJceO^zXhRh6F)fE@jR;P(Eaio1Pq=(&k@|ObGc^`|$HHb``U_ z^LJU;I`KHYGJ`BEEad4IZ5v|AMFcrHodMV&3!Tk?@N-Krfx(nT%~Z4VR#}O<$x=hq zGk528%BRI2zYz!sJx)#A=#1T_mx6=gqjmvLo+x3tH*-jY-bZua+uPfpo}K_DWng3g zr%~rZ@2iB3QU($y5^x@8B-%AXzjP)XSuPpjQ_zCn(*G7k#LS{c@#Vz<8Q$j!Q`&k5MbzZp1Juy;ZuKOkKD^{$`o^88U#Z z0O}Dg!>yHlq4cG_iaY?GwCjg}RoW*4@K{$rlQ_5dFqOmk%tPC#vhd zx~F72w&@_wsPrW6oH_``wJeuQlQSR@MosB!p(TD7uBok^9N|f30Z&g|90ZU1+_Dvg z?;Q#~0aZ!kj@G#)^uF72qy;;7#z4T2X++4w@{S={vM&sEKF*RA&{CLNpMIv7{n$vp zOyW0Te1T!A2v@i(G?}f2;ORVj@3#aT??3oVQ2x<~#M%=8@+^1olf;bzCEN~pKRyvV zEi3-;EC80=)&{g9VyIK6lC^z|hH zHPkn9ynwm_l_-D0P(4CBm&~pnHJ^gM@KRaxMEdD{DI17ZIXqJ(B&MczGIqL~!m3?a z!G3sX?g-@#f%ALxFNlZQHx`BtH8XYF+Bw-}@cCynE%s{4t_$TNn@f-VQCR92{>-wa z&eZtP#^!tPCNg43iAuIH>5#HK6}7Ajm)V6(*nm{L%2R1+=>dEdGgCH|^7h|#XqJQ^HLSHB>gCoa zR5xRkUO{`(&Ss=b9a3AHC7kG`*xKMc?Uj)LCo+tzBctouBOHA3=_{&qK>lomo7(n) zJNY4VP@j7Q)(@64+~8URTKOe!_~GF+Pb4kI9n7ud2Oy{-+sXsUtFUU+2sp;^URlCj zxzP3{O6Q}`&;TYRy22>Eaed6Trw(s7d;3g6Y}`Gh*uP+c#IBr#+PvUi)bzzOqsLI;-2)v zoO=7uoOvx}2 z@8sZMSZhAq9I?&nalG<+PvO{02?O8UAPYtGNJYNnN$?d8Z6d49r%nIqm31k@wBX~} z$>opdJE*z$|L*T^&VlILmbkhC@%?I|$eqimy4ek(zPNuEAwQgD#lXgP;&8gan^qb& zZ_CQeT&Gvr=6Qy}X29@{jtTS}t&}Fn%iYc&<}_D2j2|^`E8_9M11hqz$d0~7>F0L_ zl8gxlKVUTw9gXg65)bDNJD9Kw%29^O3i{;DNrdGqqAV8(fQO7w1iFeukgWc*fXeRY z$Wm3JJ+aB&D11wi5Ps`Ien{!t7f2`0`n^db7bPwcc&571jQW>{G9&Va>KR~p1ov@g z&eqb@Vo|9M@MOg!nCDDO4criA;fLh4N>@)8Flex+5%wIt!j&QNRFkVT3m&< zZc`uqtRq+u8~-v=XqXQmQd6U1pQalOu%3=9w}fNvlZy&F-j=k4OG%|9@KY$Uq-l*H z;Y2`L*;FCYKRBsEg6%iHG}Umr$*W}YDeG%)w@vm7YXV?CKQQN|=uE_Cuf|7rl&I&7 zZy&>q;lE!~U0dt%=hyai-pTLgtt}MI5)A$DpoxkPxk2ZCVaN_CilMbKxbG*~-wYG= zx%PdZ4DwQ^z#BOWb+)YNr_iE?od`gD&7RhR-<+53AuIUO$~UX^72r#V?@}8P#3e$- z>d@pRaVMwQ4BHdH&l5DhbF82^F$Hn~ZVlnGq#2_NwUhEKwz+UKqf;nQq+PiV{DNu%u$N2a&;a3N| zxP^@^yOBk-W2cDHN}&lpR5TZVI4NG<5_+XH1qg*|2W=0Va2k|2oi}6luyrRvzz?5* zSP3FlU%xf)d)vs%ONK&ULpnU1UZT!#%)xUGjBrXx$9>CDOL&Syb#E2aq#2}}o|6$=% zUCbec5^C2zA=#r+F>&u_uK{2uGH^3bn#%tU#K$$y4E{P>k|8MQlaP?0np1(I)Ryp$ z4u6%kqO)<(Y3~M}`17ykOO}+ro12MWzm&pzB`5;@0FBdO8TJ)o64iw{a8V(cmL4`d zu6%eXAZ`vacaWElF}deFR3XW>npekQVPYmh0Ja=aSZdZzAhmBOs75D29SByMT92FS z5&3*N{Iz=|=nPB{L1YCO3M5L7G=kE%LtGF_0bIsght@BUEBvyCMK0>CMFBWUkVW2sB&9NS3>;bh zNkGoyLTnDFqGd$!sV;p-+|b@oQ`3m%ck=T`G`Kewl2JS%U;O0a$35O-)o?hhyr9BO z=L}oOAyLhzvt!U-~an6Mfe`M6$aU#3M+0;6}{=Y}-xAc#*fYi{-GBWZ)>jo7^U!OGx16JOxpdh>?!S zKxfl#*@}>D+`Njeju`Iwv!lI(@>1r6UcyH3f_}(?@^gnoEsL-yto~IueNk$S|9zrw z>A=;uCXpD0YH*H9LrXL`vtf0<-*P)i55E4yN^2T(-Ovk^Ax9H}Eb;yL{*t?KA$Hch zjd2s-xA=O~G*SlbZrhB9Y#vWj7cS!6$C>ta`r~3WLK(`-5*%E~c<`dn{WxmcHtX-+ zQG9KTjSULwyjh?_MK7kOU!0peS-zBzl3EL=a6E^ltfnZdY34Ww6lbXr(66qv;_!8q zJhx+R{sARg<*AxUN$G29PX4A0)QJymph_ag#+O~&{x`S;DEF;@*9E^_E^q-=9pAQi zp+ML0v=wx%lcF$yN|!k(dVBw!ynOFQQ6vsfw=+W?yy4ByJlc{gqrc6mCs_RlTv7mN zVjnk`*{bs=0l(+a$jHp2@SPIdJHy>0E=%MweLk<-s+|*QKL8d@0cj@_u>tmwXSL;4v{278sHAR&)4qk5V)Yo*M z&7@0~?#|8^sc>7MDN0HB^^2R@?c>T~=La>lzku6!o!DiL?+@$KzYi~iW#uGVwpI~B zf0}88gxc!rE&=Eh&wB?9AVx-uaL@LTKC|m1N~7-uVENy8_mydCObG$&2>I&fRTUn% z4DLzbPgYnkH>@fhq&J5LZy(m8vm|bEnSq4c?xIDD8W)RQ+K*MGm<80q$q%j3K!`&+ z_i>NwU^BvorJE-GWPfK4)5uitEebE(nx_2@QKF|^2WkqIrHpu-^YXSoJMzZ`?;}S8 z6uLhI7y)B{OLEkk21(6)ha8bn(4iTzpD(5;m6X$AB`TUb`jO}>AQ^mnJSC>0Axtf9 z@bcG^r#einI+M{|7kP?OODqy&dyjZk1%*!}fFw~i+MY*XJ0PsJ;iy`>n#kT_9yEI> zc|XVBW-KA`Ci9{9Zop!+5f86{m$#p&-#COd!h|G699}VcL$ary9JdMziC~^1&L@i z3Lhn67b0$o54wnQI4w`bi0y40*&xHfKuqsI5>@c>5qM0Du;bQ0DW62Qe}mjuX=uv~ zznM5s8k9p`u;Fy&rK*o}B103F8d{w#Jgu&was0WN+G<=;^Xy*fJ|_kLCCC=^Yxv?q zQ4>26rbS^n3HYR|Opc4iaM0F@1k}~iGG3VD;f3`Syu7^8S0)2_cXU>;$eNn=)R>jT zk}g-ZdojjxOF|S=ScZp&N`a4~tZd8gZ!nskY>Z%hP7aT4QeG*;N1erDA0^8Dxy&0T#o^KOlo{w>R=j2AY#DzQ zA}g%M#pCD%*(N5SsUWLD?b}xXRAveQ92;QdR1_x?TKul<1lkrKCoGt$^mE|-W+Is?Drx@$o(G7$5*=m>QTa0YjqAz-K~hy z+n=&q)x=>TmDBxZ>&ths9)!-%%_xb)B;W*S^u$|2UlimFrDBQ6coWJ&!6#~}u&$!C z-D^vVay)Ouf;y8k@h%T=jh8*Aud+tZyZ67Q=6~fGZu7kFp4-R7j^CXcEbhn)V@2j6 z1}OsvUjCzagKM{ezVh17FZ4n}+>FCM4{nCS>`c_o)GlpnL_|ctRKLn!?(rrkrIGtp zpY~#sYy@^a>vZMUnAz;B%spcz?M8ypTDboA#n%2;GNcmTZx&CguE6T=oa;u;doqcBKC1~i9I2qI4=2Z-D%kb#bc9E829$r-B(jYb>T+M>Y9 zVUHLHZst*d*#rv4z(B^LVQ`PTOyG3+dRbZvTn|Tg)h>Lb!SrSrJm0v3nZmr(a|wuH zoSQ+27{fUmuIfdE^}gHZNNeNuYf^d>S_W35jn3~d8$af;ED`_3?7UgAV_CwM#Wp_o zab>=#bFisqe|XS`n7iQ<_N>lEFl7BQy|Lf>;QzsL3H%m-vvCjut~hLC!&0iTvsu`? z>JQy;9!;q2Ld8`M+QgNm0vb8*3!qrCtJc`Hb=)F}148QoxzG22egQ~bR~M)`_mx2E z0Fr(6$5{o6&`DuVU`w@oez*pt6uf}R*nZP= z5nn#NY(+Ft5<@1QJxVeF&qB6{LB2#*aPASbJ`$M$G4l!=uOk%u029^9y8qQufQ;n1 zAj?HzBuXAq0H96o9qa|{xKvpyR0&;1crAvv0IueOxJ+|UyJ$g*AZJy`bOb*k`hj>YlQ5ZHqSq##zB1+H)0+!?%Shp{XcmuVus zPOh7#Xh@e~$W>sX{F52U`+Ax&8ivz&`hVfd$J?#g;5SlStp@VH0|xW@ch8%$s2WZC zTnwa^N?bur;68^1%L2L^rOs+CK(mR?9#-o!Buf6*Y*Gdi`eE?YqhOErS5Il}ubj#| z4j>1!EF~<&HjzH0jmPef0qsxk>IREP{BFKbo%Z!ptDudysHAl~H^+}n|eJ6D|x#A1d|wu?<)LjC}Db>SQxxy_=`f{xDpiXd``>_}>swxJ(&4kOs;(G^u|c``ZCm=g5`ZvywI$SV40yT!}2djrK{ev{=oKG946M9W28{36 zb7=mSh*21sliQMnzd3KsM+OIfIhjTX%Thl&;EKiYkSp!V4@nL?M8MYJL;3`OA4VwV z(JsP6>j(jh)V>{0(ElO|@MXjv;(@p4ORI)fz#Vp?ZV{g-X9fAvr#=cx>R>w5+U`zu0<-l zv1r~{cAV*Iiz_`^% z{;qY+qYvmm0ASr`^9rrcB&uh)veu2ns*qRZzHw=n(CJ}C`D8LE=p}aJwcD1KnoC+G z-_!z+fWS^CODBghaz|RHg}bvPcdyX-+SbfscWQ5Z#RTmdi+0QTYiP+U;8VHu*VNhh zyiB{?E1!8n$z$xjbbeDi{?Rru<73djfjFz>Lh1eStE|mJ0k$tjtju?g+ z)bJqyGFsRROLj}^SUpuyQ4!r%kPoZXZfLit%S4Z$o}Au%m$pJuNm0RF6{xiX6pFr= z1L-GA9<<;upNtb>eyrnVx!fKF^0$t=r!#&p|i3El~?g~UgN*t zyK$y&<<_gV%PT8mVrQ=^C@269^g@NMxA#AVmmGTq$WnUz*7Q3C6mT$8dFmoUZ=rmm z8-g8Mb~;Z{M}jb1v&00};b6Ti(m+U^z=uA$!)RnRNxU}#usim@2rukg;bKplW-t-D zx?E6xyBC9`ABuWA`Mpc=pslUgok=;3kYQGxbcV@s^d}`{G&j$4v3EUIILT6xGFB3G zz1?4NU5)&;6&$6#S=EW<&6DRb=;+owzu(b^-&ksY9zFGr_%3i=^4|U<|dp zb^xr``g5EF^TY`tsD68ar1L}d{0XdO&ixb~riqCe~X4Cz@!eFnWI5@|q)zV)e1RB#SaKX=a7r7&Q zlob@STVNVvKjB62$g=r<2TX_vdZyQbAei$sVHj6>w-1)Y9P`<)HXFvsNLUd1X3?D+2; z(~ZvKp*jIW#**fX+dziZsnp}m8x#3W@vG)pitp=CFsrECZR8>|qJHrVS10S+bHC41 z;$TF58LKy#jdFwvmRMS~h60MT2RoXeW8X%vF+vj># zGPNhVR|bOqydznV|A)eJE}0UD`s%2YYU55ee8>ty(jS?1Fz9IAiJ-qTU;_vmr_3L! z4=)o$0tfOGY=m;K6~u^!H;l~Zfh=}|r(=-k7akuaH}Q86)dl-JLG(RNRd-(>1o#KD z5zJvz)1U`lYF<#47H;?Eb(7Z|odo;Y+wSZH0IB+N63^|3l}~NN?siCN)*)QRVoTab z;}2{)@K}K{N2!_?qd9Cux}EI+kBE^T^e=@#U&YiJI|v!AWFY(KkdI7JP*ck~!Xz|1 z&@`}Oqa!0+wcOKlUc@c+_|nC-SoW-B5T3MbwsZT1_O80R_oQNn3XYuCiTc*X?btYU zN`N4ylC!O!TeYXK(Dui6TY$g-^xdz49!1h{bsB$WShEZ~%UHsUApjslIUe4ALLbzp z!RWX>o`h?5QqR&_V2*qyxC7SO6=PT0{|}axbCCDw5@J-1L4iz!qQGa|RaQN6X+6g# zpdY==GIMlzD)7-;?J=2r*B6RCWf!4mL}DL--jwCuwRt%BjMFQau2x$;rUf#8}wahz~CXP7%E%iL$s`#M5@F?!a zfH^J52z2J&>iAvC2-Np;A7D%1bX@nmv;3{#n&0A-kcfuQ@;hpe(Os=bt$@*+mI$F# zgQlM*5UUEFi~PGJ@X3d9H(nhu1{#9RZ0?-%L#fhELf2*OV#>lDE%?c zzkX{UlnKAUs!W_-*uc(|4`%bVIFMa3Vy|-h`X5k0M%i@--~)}&Z!XstBQEYlIE}C_ z5Fr2?4Si&Xeg1LkzL^yn81#zpjT`y{WX^t`uH(Obm2{7L`-QS6)NQrBCrRu>ZtqUX_IOiN6_aYh%czrprgIkz;Gb+RGo&B zl8iR4#)$k=;mKOreVI>CpZe{TJ_A6fV50=}(d@^IWSC5x7QrP89u&dH6JX+IYmt|; zg!Ld@bUYD%5-xkJx0!u=nS!v#dYtZ6bUQ&Wd|SzSf4lfdvF3A8Tl5m$ULkxv=)mCO z&VX@>dw0o&6DUkm)wepa*P~C-q5eRJ3HQi_nTearEm&3Fblgv1G=->N^k+u)DWJ3c zgIn4_Gqz5^Vp=lm85A;RqG+JDo@Q+FIC1;VYyd01?pxgDQ#K^f%4%XMKj$3h?uQ+L z;p0U{R~(03fW31(zj974G2>Fkj0+_%@AbOxSvI#->=3gm?HQ9sH7!xyvHx=6mpy~a|CO9f<(^Fc9ib?YM_?@#feXZ)ERt2IDdXd} z;xC~(lDMg;kuN1$sIQt_+pGg#ovEHA9^V>c6a3w*2>a@2$k{He^_Q))cIv(p77NVY z@VKepCHkQUWlbk?IUohcern?YA_X2<2p5{AvGk@c)3J=|{PsqR!v**j5Y7CaA(;ho z;>nDipX1}>yZEkm@2&FkCd+F^@1laGAU=Pkz(jEYrB~Qp?;`iL-07aIIM5OOBdgT+ zVThI?|IzhdE!N9Bl$+(cRzacr!Mebw5DMjV;ob74wXv6W$MdcBigrUG(FM9DnaMO- z|DMun+uptL%zyp>gDs`9S3CHF|1k5ctgQYhf~cK~-BB_OBvsS%KW=OZ`nmU4-Y6PP z=JHizV@k4K@ASU{*k5BKAMxSb;y%__B5q4-C(c3}MvPrnMgR(C`z9IRygn!vJYysu zOF7Z-LLmO{K1^|Bso=}@V{O!}zKB~!A9cHkP&)Fh`ay5E*LmPF^+F9-d9Ex!w=W|( zHq}=MDX?%{(hw_=8BaD7fYC%`-BR>N*3*x+TaLZ+&eYxgnmzD-6i_-i`_*ze43;0?TcuAwjZ%c-A%_5cR2Mta((^ zQ|_L%iz5<)PaSd=jjr4O?*INR&amEkE7Yj#s-$DMdwM8v*GFR~wuFt2n8?j#9dUQ? z|F{5E2KQ^uu6ug+5v&fZs!unI;TYPlzuPvtT-K8zJD2yJE~7Et_bRu|5k)w3${9Sv zj!jNW)tkN>k4CDhFd!nl{S)=Wx#)Sd|K3cqa+SpA?0$8SKCpJ_&<(IPz3+N`?4s~F zpemT=Hyel!rwH%@d_V#1TcZx2>rAK4<*6x3LH2%qm6FSUig3HB#*TcMV)r|Vz<^0t zS=kZr3!{2#5CHeCE3&ohOyx<1g@s`X|NZ%Nf9b%d@8EC>2mp6^U+xta76v|TQ>->Q zQHTXRoh;YE1^vw6wIdI>+XSrHEOKQR-)PazoM1L`sXis8 z|36y$Ygnk8=|#euSDblbfdMZ@e2J|S)VU1#B3FvIib8e?LDJKCNyc(8%JD%1z+#&Y z8!PXe-nt%TiGOUj!83IELm$W8I`^sadrUrvJR=jtB=?==G{KX>;Nuo=2s0&Y)0ktYQa zyX(f};^ww`Hg`Y%RkV?r@i>Z>ee3@*FyHC`!*j3Srrvrz3y=iQ+0X+BE5K;ZEueAi ze=$t|Z;y%I{WgBNNd2ezjQi(uWoH49*9W|AUV)OYd;5GWS1j;wrbx%oJ$c&N5BOX} z$R{xa?|LI6BY~X=pi_U=+HQf(%f`TPchl4*VmX%9_NVoD&2z&aD6;_xSrTGmKzi;J zAS=AC0{S8=4R-&wZ&Lmts_a*qHTr08E%TB>zW;0?I9&I5WAK+v?LpR@@i#c? zi1Bm_o2x$FD6J>b8ug2as_0p%Z!5|&1aaam7FW#@D+V7#{AT9WshL4R+zo#B7pJRD zVwYpwkgIMailo%k{oUQ{z?XXf$Fs4qQGMC_zM?q@wa)k53W|I_YkySHQ#g8m_ObJi z)A73Bu`)F<($Zo3^7i&F0*ML3AU6@`SBu#b+N5_xyHKOPJz6s8Vs>yH~=8=fFm{ zYaVTF55vo%!$mgHyO+IR@`(Yr`(pmp{+VLGRjYOFj$(K5cAUIlJAV9etXppHGJSQA zA}FCNc5`!k+MyQ{@Him^=~gZPQup7zUffRudL3}MUp_8BJVxSEKbXu4QLwSIGclD_ zRP2zm8F%`ft~98M-h&_O8XDZkGkAfhDo%+7G+sbJpuS(83;@Jd2gE6>Ek;uojRT+i zB5(q_x=Ko{0N05`RZ-`*wI~Ai#$|iJER8+06|if%SnPVa{z~HLb-U&n(*3R9bh+L8 zpZgPVnaWK}y!;7=2^^&^z^gGq5&KIPs13EZqQf^t>|uH$At4Gz&TGFc>3fT<{`Y?W zd+SQI1sbSER}*MF0j5GDTJM5?P|BbhFJ-1VOGcWJV#tn}FceF;0U*$TU%2{P*jw7a zMd5s7w@0U}4NYBsiba&woD$Ju~*>>lwZEOjuUj zby4MK$3Tfdv=2Gm9l*UeCnF^M?I&!)&ByTP@UMZfoBR^RR#C?<87|B5e)(af^=gA~ zBI^SEg}3eJMRh-~ldZyejGX`1)ke8o(c=IJCc=Vw3cf~~Hl&paLxIllz4`ea5Vuo~ zVX6F(UIX|!?RiYjAJ}Cqf@3Ac)k&qz5k-4O=W;h$+javyEekBZvW)@Ef~pExjf@#8HDF z(7oRa&Ae{~$|;|nt^TUGVx5S{nhB46famP(%ZBGltD}^msu%C zc-gV(a(4~L^|rQUqq}95mG4-wx;(4=U!DN}?0_La-}0X#>2X!p3oyLRvdHUwVV*dg zl#*gux4gts#O{BnXlQ8o&+}$-pN2Z5n*&gJ4tTl~I%@~)sVaf({P{BnH@7Q*@*^N1 z&?O$~Z#;ZRLJA^O`c@b+w3w30PBn7%IQ#UXM!fgCd!@yddoWfRr}L(?kEqZAT>Vp; zsB`JmqlT7fWo4xvg$c3GmA)u`BRDwt;bH0!za%&hsRMgO77S0mkes3IOoVyudf@{sI~uZx{d4848}w4Ow{1z(g`Ba6W6@cKs+qe*Zb`IU zJ9KG!Bs6qi>Y5`hkctQp)!##BvhPCpfaR*FIO)uNf&wD~u8Cxf-6qu=VoMsnTepFF z9arUwuP=Lr1vpM2g0bm*)=oWt~kkZLP@hlx=!`&vbJ`Zg;Yq~){lQc_w!`ov|NH?-t&d!$ScW+aT zxqKJKbj1{F16!SLC)RSuGI)jPg$8ZwVp-XU?ay2VvvUDsL0MT@Kvi5(F>3L+$mFxL z@%+8vxW{EZvk*p-2d|LEN%m;!FHTbk8;S#gg0rA3(Ji@TLRY!mAcX>A<@?J6G4&%IRET z;bi16dO~zT(pcbS*Vm0uWz~m=fj0$+W3{!l>608=n-N%$N=df%+w&pi`o=`*(~E$W?a6N4iQas{*{v^f|GA2Z2R^n@(vVabY3y!30U1*z}HaL7+i@);2KD~*Z{k{jbvH=8ACFGe`QGx|h{nkz$DCJMM9GJcL((eKEGdYrAfZbqZE8=d8aXdC4=H5Bc}7J2@v z_L8@;S)N`YE*}TX+wXq08-#SLseSa4`qX_#Ny|_ACh@!bR$t=fp0U?+Dy;KnaStYz zZxRPBUaAmTUT(PD^DS1+b&y~3xt@m;S%YYCd0)8Yk1IO<^$v$xe=u4%F+MAKzm_CY zY@M=P`y9!<>gwuv4V1;@avSQB2DmmTl@fBZ!G0()&4b&e6c;~~JYgC<|Vb+53f z==n1D)%>2dVA|{T`SxtJ2_|6Dpm&dY2LPnar;V!tw{07|@86@*X5mS)GyO2`x;ZR4 zych-A`dsU`SF?L{0c0BOB9Y=xQ1L4M$e61aj75D%H*^?1S9N$yEjq1y51c&L)Wu99 z`kFshmET2t@vj5%0Uv;vz7-G9zW(=Pp%K6==7!4ZAk@mLFx>-KY6FDl$#U#3v%PFu zkfkMdMq(kPK`HcGGyoosEK#Fgt-z4g9+1xU5-OcJ`1)NcWY;b1MX5L;eTaKp39P3b zpc@u)CZh%gFww_7lRu3P7Z~}QyMO>7#qGsO3aujb3vOIa&ieFpUiR;V+}yy2E1L-O zEtZZ?^`Q$lU}~Djq?rDpCIRA1lEGN=#PsCd%llea7ktBpA=|o%F4F)jPXZ8cBTwMv z52p;Jy>W_m&*`x!?pbbt7R!P^dJl|B&8;s$cI1>ZO?k*ChL*H7{3IlM){}NJwt!@% zcEZ%kv8XG?epJ~W!h_G^MH#8VA=|#Lyt&fsm`!K(Z;Hj91HP3@p?9I`g%5`K+@7|4n@YZ0dHCWvl#&xK z>Rnb+x81Jlc^gY?!9$Ez5%Jg*n3j;UetiBB=kyWdx_rI`Y)qi|?)$Eq|(f`JpKE z^qs)y{;H{ymxCiNF|iJC@E9cbJ^5GTclzD0clhS|-z@9aSpsqM8n{flOG}3ho439^ z922nWx$S3r)=KY$mxE+nT>i~VJg#oMq)4j(krJq>Zl|WE=yUzJfY(h+yPKA!KnUsX zdfH{j6npv%XnM!f$U+YQ3Jy=Y5}*|MNjWt+*}Wf6r~Pt5D3MON_32`igoLDM)$pn? zWXv|F($B*WQrO^9R8yN!4K*^VN>nhqFbH)?{nwk>*c|c(kix~$z#ki`T0W##O)3kDj!b_4`pqJ?=vL%nd> zC>g@@k;jN6w|ufCZfJ(A-ZLAyOei%rUi(0Yrtlv=ph#&X6m@MVD$8EZY6_&=s-FBI zL4KabB0kL@8YVI=%#T)w4sCvhhA{e7D6hJH#7ay^n3?5%I!t5W$WXQ}mQzr0QC00r zV~+~YYVm$ohIwyMY*p{hfN!KKuX1>J8lPXv#=!@Wi;0LFdfxsiK$ThZ9z7jAiY2S8 zWF*#~TUhs4FT4zRn3`OIZr;yYv2;EE*rtzteN2QI;i5-l&RDl~{C+_q4tSP(4T6K1 zPmB>>&ILBMU-{h%kz|XtZs=+K>NwBc8)FHXKXP(X%n`Br8@@r4zq27a+p&}J^U#O7 zcFn_T%m3EXh(lm$!^sUFfWcC`V{bYi&&-Y`=GI<&_0FbtE?RUK*M6@x@-EFfq-*~X zGgxc8$h5X$E2#S!my&U@pZXMD*1p=5t}vjB&qC_;v_aC;*)^RWxLC(NM^SO$XyaHa zy3^_PVdCx_#?tbqD%(L-?7H6WD(zIL@%HLQDU-|pD2cJ@SB=}RK9u)Hx4S6Y16{zj zuv@5LWMTO~G@WyB-0j=NH@4l_HXGYcnlwpcHnwe>4I87e8r!z5#zvwYNTUEGw9UFB;RD~^tv|K?o~hHO1P-^Id^ zCo;V&+_M|X8FS6E?i`gc*oFeZ`&8rHDHIN~&qHtBG{&)!|(Za{A0dGDeU zrin&rL3*gW8;mJ04ilxl8>T@3MgQ|jp~#rCku4-ZP&zE{{puFB*MMcb-Quv9zM3s_ zV$IE3$ocO}Y*Dk&)m4yQby~Qps;aB?re4>JTehEjXyp$}I;L7ieb%daR+x&^@=ylVrB&8qv$UYs6FhGUc*Q`@P|<@@oYvH1@cvy+CwoXyyU zDFT5X?~Zz|+S;qTR#i?)&eRkX1VRqp@2AxYIc$`SUng?n{}V>lN)!bE)f12}xHsMR zdP5NSB$d31SpODv9<`}CmY7j*zJ82MLhzY+zwFKy$=%-E0AT{3cO^o=Vza2EMCfTd z2c!9bZ>9fig$-48_`vJsCmCQ{d(L2vDsNUj z!W_oy;1B#>Hs#`b`bm}_Mk_0Qobe;6cBJ|vV3;I?b|B*L7ubCxo#>MNayUc?&vj4; z!}T6JqE^35wPyjgjXJ5w_)0%UT}=c08uoz47s*KNr=dxT!s0^LM`sKbFCFndOYMOL@-9br$7a}unzsK8^#$&R3L}pP`%SrizD_*(bk>%m z0tCGJvadAlWewx{S~I``+aNZ5F7af%+S+>AhQ+(GfNx`OB{4(KFoK1KxyyMxomFfj z2eB6XE9*W$H0C0E!!t|-L&cKXRDZB-M!phAy z%`qnubJS|gh~7R~FfYtfQom&3K_C=^j!6lz)J-(nPU2f&r`D!sY^Lz4)`@(J}NhX}=Mg>2P93#tb$d4XO%o zCT->A59A}l(Vk=64smjXogr2B#i{<34ligf(QH|ab(FR;FvzQrL$fL_Dx!Vv%pp41 z!xLyii|YmNzx8KO1k9f7u(IY=I_-ZgtP^e!ZC{SoTJO-DpCh7E7=`mx(WiPD$iA=- znsz>+18bAp^No$q?WvjXIoPA$whOk0@9;Jr!ikUgH_?ltnbJ&OpaK_ILYr*invj*? zmY{XS=fy%NBq7jr6SMiwg(bokUT_QzJlFqTvzzO(&9nc#?_dDA2We=n-qP2lb&$h&4+#q zB}qVIqC)oZh8@QAK84CZzMIP@|JD=thkNtvxtbGV>J27OCX_>JcVi1JoCQ4z`tz-%yH>d>3Pz`F^6es2`KdREF|-X|XEj1^690qc0T3_O zDj!ZF=^iq09)9)$Z*QAy_aLt2I)WGXbuT6QTrG6q*+fUnCA@q+V3xYvczs`~Cy(xR z2TsCg$FkMGF(S`@el%Ksv$Q+`>fGN3@$G8dqk2VfW5kDx#_-^8S4&TOZycR?=q#)( zcS$v!2{RV{GkS#pgPH&TNG5@Hvdu`i+H&j6&!%m|_;lHkDFwj|3T8HOahZ|SkKv`L z@Y3$JNi`~!_>9E)MRtN89|4FKtz(7CNDer7Eyo*2ZO#nn z;Liyb2}pRY*)thkAIIQwC={(k^znDGNIsYHjl~TdUbO2l2E>#@%qEriWaX{u;e&rr zvv_G{e6s_C$YjMXB~k`gD_E=)@_^n zb_{5%wo=zef9^?j!!shmO8N?knCs zfb_WTgd)-TM2>73e#@BuC#_n($i&o)P7K@hpRj1l?leknrBMU!3=K-)O$dofFbqxb z9G%hGteLCHGRE2~bht%tY1Te9F6hF+-8Nupj&;n0dd+z*YbA{?J7M*$I$rk}0AO;X+G1L2nvwz(zW+8ST5X ziyjLP7b*#nK|s2swwf~}sf0EyTC&m$JG7?pOlY6ciMj%2P5h>oeY}{wR&-$dHPks+?2XK2b&-Rd6YFP%Y zy8ZkpCO~d2!DL9J0vi;oa?ir~4P31Pf-!($g{h)Xq(TGubSE?ZUdZ`!wUgS!MP_Mb zdD6KX8EQWt{srt>)-RbNh=~v!u(mVAy6f@|KgkbbG)lL;CiJs;JpG7DhzUcz8>A#) z5OyeD{nCo{l?XB?^uJlbT1p{`jO(Bsv+iF<7l4{1Q|yEV>v{E`j)s#MLl(grn%~`! z7gf)T0MbMe&vAnk@HJUh{6W?n_LRg+CikGZaK<$hN8g=PF(IAbQT3;v97+6lb$(@? zJ`7DvD|=-e<-DMN(n|(du6b@tD(e-eY#)W+l2PuAXekI!K-|_vT>Ick7UMxo(a=zUL!6ymXLYr3XTXm$D}aRO_y2nV z6cF&uCVqu%>Z(W5DLK6~>gV#mzZDQV{-PFIS^VCiPZmKVG~lb9ZZyzij8@XOdDpYW z6K87^uDN+bbMeXv(~5wapaByB#I3LcPfk+syUGcTOfMNQctj_6ssgbp036N>_}~B- zO_ID&h>YyBInRw>#dnSx*#wFldd@8PlK~mPp(0BsaXs}(F?S{=8aQZ+oy1}ALtz8I z-XLOBpsan9+m@87@2QzHG0I?!O@i*bke2M#Tu(Y|c5y8({%q>d{iVp%8Sk#NM2&2> zx7Z-pyr3@Eqak0zBA59uGG{B2cy_$;|9fo4v zi)YF6AlHuIJ?XLH-iP;_6Xz1yZ|h7R^g*Lx8C=~)W~)P8sVeZk0aMtXO0vnQC+i~B zNwDVC82#6BoqZmyYNUE+OuVc4;n8w+QH|cyB2cuGFGL~8Xn5gOZhE<95#h~$;NWt8 zlald1tmamVC2x~P?Y_sO_H!SG4->`~NrrJ}?a?4l(< zcvGlEo<~mxhGMpH?bC5l^K5!)lEH;L`R0z?H90&{l3H1om$dPj)eNMr@?I8f2z>kI zwlH7Ayu$){$cPWP>#y(s$h9>M5=5&}Apoaq>tI|p;TQA*dTeXjbGTD0G*ct&$gdhz zKQhwOrNvdlLp5AP`5lR_|ETWnGh%C+nwt@6H-wWFFx_T-?PS!UxhT8K<<|3nPN6U) zijdkduI>sUiHy9)Zq)|}^t*mhvhXEn4)Wos!hQc)qMg8F9PheUjM;f@{ALLlOUQn5 z>XZl1DOmKSu>wiu)wpDKX({IFF%S4ti#;sNVhgl!csgTDGRIhloD0?PLgtUrn*@%7}snTjJ< ze&eReAs$hX?2~0mj0PE7j`I0s=mzUekas<>>Q{UGL%bJs3(S;jrPZ-)lgo!=X5#Ff1GJ5|aUebupFY zyoav!A%A!A_ALd}f>vQ&w2FeH@viZhU5RCjA|T>S=KdjxI6@*ht#Z2aKbD zHJ^l!1_2$WNCQr@3Sw}UIR6dIb!*;|OouXW8Il$SWPQFVRX#~6Q3*V$kOJWxstU_J zqFgk_0Y=c7Lw~OIZZ7nj(z={@(jeq>lS%`k<*f8@i9(j6J|03V`I(_IURac+N}7AUvrg!>SU*;Q%m* zfu0`2m=pPqWD%h z*g_!uSU(!^2sukmOeGqK`SPj}$Db5*xQM4Lk_~Cm zND0^RtZ&q7+n-N*^jJ@&zRL^*23kmzo!ctL%F}R(0mDW#u+XPSnD7Il*Gak2p@IHg zf@D?js8GWeG_dZcrnBm(xbXN^$Z$4KP+oE(d0oCd1~qvPOA4T0PZZUwj z$wbhobSrR~1TChi5^-}l=oc2%vlvUr_k(F^K`M?nutz^*qUYJ|+Cc8@4O&Oa7jTEy zn@>^IoCV(e4yPKh%1uU`-OipnwzMcEH|Vll089l8=X@!US)@qJMMDkBCp6ilF}DQ6 zo9C{Yli3xzAhO#yKWm^3X_-q$H1M5RLTZd&fO?!9h@|?>;rKw~uXbXe03^n$Qp8{| zY>Fy5Cr{4;X#u9rfzfEym|r3E9CJdLcOWC19p*T=ab$uwQEKjP>DkjL^e3&zt6ACMen=Ts; z{Qz(D%eMzwL-X$rh|u}`Vp?i7f!PF#H$u;!*5n!RFJ*cr%T2(+f-j@aB7FZNo_Lof z*%>A-lHxUYjXm^Jjw|`j@(f9wi|z{c12;Sx_y!jpqHNf2J=!KS9R2$?R&2BTlPMP_ zWZ*q85r(BBQ3iCYK%8>_VTaQ4|Au}=7z3O0CJx5-OAcI2ikyrNTP_10Jjc_QXUmEM z2NL>J%qJn-JK-l|T>REe;*7>slVKBA*MOep{x$ZL-EVs^umKvtpqh4#2Rg=&k_+UN z8bBuA&4%iMe%3~v;qc{08^~Bs6rAs4*I}i$MpN;4E;21LwJFi*=UDh-U>`fxyyWvy zG3JN!Q&D_>^Fe56%RAKORF+nTeRn458(iAh!S(cVEyn8Vuks2k2+LOfh(H?l?hm)_ zPT2l@CI_8BTz83|BU4k{^+FiK*VvY{{p`}ujF@vIA5{^?FejEDUem)#^m3Vi{yZ}F z$VEqGgF54}NP?+_1A;Y336m_T>5z*pQ zWDs~s@Zg;<)47I;(c*{Gd$z;gA?BqX!+godrC)ICaM82Q&s|I=g|sej5sRMRau&Io zmvH1|6j^@BOD4@+qCiHpw!Xf7EYBfgC$Vndx^b82%<9a_EkcER z@4#d%D9_^aTmB9ND>p}BBhn2a_Uns|f%h!a<1j$!WCykWjtU>5QtT(ET&>v_Ti;&$ z%%i|J7q-n=KZ610?5q&*u$XJ>t*BK zS99}}xcTIva=e{$BM6Lg^@Xfp_s~r#XZ%lj)$9FN?x}Cyc^N~3HF8_uGJ|swy*UYs zR(*}T@)MC7p&pRGi0Ml33{#)H`J;ihmvkU{3Y!m_hr~9UG+)&9`QkQbx%Iurf&w;G z>CQiu^7`Jtwkx<757Ix4WxVV}SkrzukZ!tJdp!DlE_8YQ6Z`cQwLvt0luob3k&;D^ zWDmA@ekZ~HVm)cbfwL&^n_cyN-wSDPQi>p<@ zOiCMpdhf@$=~02r%!SMAf+a;D_~oW-&NIq7)3XZ}jP<_GcTGzM#Yc_)gHA5kQ8BZB z0u{RwGAFR48xq3VR({d4zF2SVv0}cu$WE#oDex8^c~TpNPw_GP({U77m#j%KEVCUu z1MaQ6!_A?-n9MRGG>MWB1}~&C`oeP8NQ~rV$Pr{)J-oDy`)I1G*vottusq2}+Ox_x z$e{sD{-GX{=zY<@rC8utH1;=A&?E-Hz|3$wq!65uytMufXVSx@s@k;})RI+KcMC|9 z%VrGhN^~~nr!N%9j;gE1yK^$idon%$RO=X^uEcPtJ_&&}51_gN)xnwK6Fx*PH1^kJxXxNjNqJ3K9e zYc#7WnNMv<(~=M%!Q=^S#bIiHZQHuP#m!v4Hn6R_>U{LEaB-O+Z^;2HARelI_Vo6+ zgXf_(pNKEl4|E@!CJmK6`hqn;0Ixl~^lKntOgUcPdJ=nIG^q{9) z$d{$$|Fhcz5@tGI2|naOGLD|DG@R54&2ESg$nYAs=NiL?N(p;zyJiYVOsOa$w)MOj^EY>s4pg-E^pS<$AN% z+jo#^@O#S1(ib&jX5{a7eott-LH&ux2}`9`r*xgO^(gFRh;0%!^PLxuriQ;)PB(Fs z!l+b~B5|0zp)ltJN&XACG~&5{?n~9Gkr=fl0>5|yE!|?+PqlYc+8X{rNb!VAkLjy{=Jcea^ZTHuRJPk9 zG#ANZMkva5-$P29PH#=_mRAOe+O#=4&_8*NrY$j}<@dFTamy zTP{EHu6Rk@1lZqvr%2J^NgXjU8oDiOS(!gGq4X9 zEZZ`RDVj{T@qON=(F;7n`Q-b~{OJqAiMe?OHTPHqy}^yR>WkVVkmz=`Z|ES&DRcxA)! zYuL12r;A~(40Nu4i(YqO{mw4OP34cmJX?QXTiu`92^ZwE4ef7Xf&&WnK1ckLm|#OB z4$s2JyuJ#?enuES`h7(zD!&5-CrIIgdpj_TqcxlGXnsQ3_8%;$bt9mu)o#!1PlJ>F zJRh72%EzzY7;l8d>bx~$`(YCY3c9}1M=-fF=iS&*WTknbpM`7Ue#UE>Q6-s0J*tcF z72-Nk1GDxKR)n|pPIPxqbHwleOk5q^j9+&Lq5_N%x?}9mAn2KkPK$69g`$5i-$X0G zr!nbj>*?j>=HiI{sU&2uDn9#Zy5Hr{mD|$N;@Q#J(13~iPxay6(*xKZI}m_k_e|=O zYQNvSJ-b2t^}H_^VsXHIVwUV}I{%MBsjsh(ii#Q=8{4t}z6mH|M_k+;QI%0vc3-pd37N4DF}$41{+go$3fk^bi<|zBbxf@;#qCwL6wB#7HAn9BpD{FxifSOu|qT9<#99R#1L; zwS1bS&i*B8@<@q! z;}H}O4z^f6FDwe1rlZ@uVCkk^>H4$F*UYsF8~t374{gjYt(=U&wFSRH6mO^8GyYNmtHPTf7CN?w<@8sd;+jXQ$`!B+35%x;t^d3fZp%CLLhCzPx9`-(g7idS54g@{PS{GYvJ) zNSmR*f9>xs$y3Y~yj?bqYteOcGhSmS_Wt?vxbgY%q=?w}Ii+jT`bWpx{7|R!bD~h) z0bZ90N9oe(`-MfgsAQ9TQ1{gRIFHQR4m9-VbJ6NE=L{|CHZk0GY1D> zSJ#_ZG3BrTp=KJxR$3?zHA^=`LqivrZ{lVFOy02 z#%m;`X-zjM8mVUcIfA3QrySF+`~`a)1q3AXvw z86Sc5ZA3{TMp33!b20HV{?~j5l3;JbQ&l_K#JCg2XF3^}V{AIMMmHS+=jh4mh@elc zda(^-US%`fgR8tXNHZbYlopx!pO&sIy5RaY~W|G^6~53sccu8?0YrRv^HF|;{7Qh;aG7Sg`-t7 zoT<`iH8W#YiKt0Q!a-3C)Mznv@~(6#@I$*Qd?uHdY1-$9l@lG((GC}*CrN?g^)su> ztKt2wDUmRigw7umz=u~6fWbMjAk4yMj5)1QU*)ooKWt#Eqs=1xhnN-7U$p^wV<821q zJ>QX5kk4+Oe*Z?kjSmQWvT>Gdd>;&ml;zwfCm>Qim(`^_wR^tDF6)!JUkp%8MCzza zR?91T^UQb~w#zYb&RDos-1ijN&F(59d znnZN6A3O`Rs+XwhFpTLAho#V7D|66wUd9b{t&d%rK9)XTxvi?-7Cw)8gs)&vNEhlO z0ju3oS}N!gB7(>ZOU->Zg8HxB2pC9B?Z4`^WRdEa7$lh-zQ=t4f6&leBJz6!1En!< zEw5FK9{;GXUttx2XSPZwB6KeSG5z=(FHK?pPk8A+8j%?a#N+dFmqM@UENNN&ox$}f zilA@oG=Z+4ozpjZ^G3Lf_G^W1Qxv!DA53^ztb4zclC!QiIZ(;&wN*?g1sK8d(B6`s zx5_m-@L?3W_1UQ}cYScMYxn88o%z!<3FsoCK(=Y4J_g~S>1QKq-aXOobLKq(NY$nPKGGTfM%*VYnH88 zJqES4y2+#|_rpFOSACDlAB`1UMA$z-3og&$aMNopBUxCR1hQ!Yj1(D~9E=n+84_~L z)bxWiIK1Ygke+9~bWP#xvPm}MGo7xTVu(#JSp$u3u|HDZE+lM3T(G<-Rranh_+Ah>&a9&Tmrqk^178eqwiwCwZT8 z;4jbC8}x3|C}-?> zxJ!OnMTHJB8d0y;P*^wxiDoMfKZ-FY*m4{#E$*)ASTkKhf8~b%L$0^KbN+sMJN%@9 z-ym0N#qa;VApo+n0*d9FHee#gl|FkbA3wN>(EXjB2lPMIt4)HZmma{P_tbwY1MP=u zQ*=ave?!(n0x?5dO?bb=jBGC+9$qX|z#IgF%SjMG?=?oPerp-%gKS0iP~!#c&Q&G{ zYhetXl;6^5cU`2@(UaXm`^Gx^x}B}w&2z3#80XxU?yl**A0yssQ6KBVf@D|-zZqnl z*+qF8oiOsef9G5#qGs1Raj?+b4gXWeOi?=)Rg$%NH)oObQC z?fSN*ZwHq!-Va5Z9h(>z$I4oFZ^N>6ZR*o1SA4&8RNm{Wm52W$h$_+<;8N5ai@Eg$g_W-Gt~BN2Y=<;E zGf)q{mDrC;h0L%N=C|*R%i!Fp-LR`c+ECmPYW6kpZu1P@!UKLqbz)U1I6l~Z>E_LC z(303-GrzZivAnn3{mnMVF50fn3C#tkyVUhW?h9>M^IQBXy$azU?-a}bUS#w&onj$K z-n*^gjX?dMGI!Y6qe)3bMF%1k3znR}?ma7iFn!)h34K8sa^r3SB2B(^EuZ-8HhVpG z4vB%=Gj+MYoKEdm>-%*zHBI4`-e{{Pc&FVS`5n2nOPZ}~{E}BtI6pfZcBM#Uz=X%Z zD3dH`>C{_Y!OI9^qFl0pnQjgeoBYT7rqHNeIWeJ7)DT+^FaO{MHQS<3iUl8%qW{|1 zH%9eNX4)-JRI!!pi#?|Rb@Rra+q3na4G_$<`*z1*Z&I?5ot16~0lRSiGW>)KzWfh| z7j2t6^_L&QAIlMlb`uJU1aaSgyZ@p7UZI`ifa=Qk?EaMgPd=XSd>Ycp360u_RD5{# zy^!(n@TjsoC<9+H#|^B7~(&Q8#`4#OR*$vYK+L)|By@(c-a@M3Q6y-g(Qj=l4xw zDhrEfG`)k}ej#rD={+)c;oiM>hqzBQJ#og{5Qg;zN8){C-US94HBM&uPt)?F(aJekt2)T@5PHC7UOZy3_cnMXMuiVF#WTF@|}{}PibyM}>53#x9f z%kN+8?PXm_PfyRtq%Q@V-+wE`DY(^tnN6$G>wq@^BE)*_FVMydT4Kw}XcsyGj2(!b z>v})8OOvG(_*3-e&NS$(M&$*CVdshAtjF8zcbrD$cdv;Bx4o*SH1cQHFw5X>!Z7!P z!|R+A&o_yCfcXc_+i3N_lL=?F$ffss{U@l-_HpJP|A2w1zw4QMw*FnN%h~P34(#t! z?csi@ZItUUP@6@cF+j8(#nz0`)+jg|- z+VSq#^JHYeqaBf9M}>-!isZTX8g96j9B8*wdtxfwiC->9KrJKwW^r#ufR_+$d-Y1f z3uB-PhdAF+q7nuNh13P6k*o&x<}Hp@|2TQ@BB`0?ctU0cCnpmQZ6g^Tb?8K)0@aB< z%=$b^7^9Jp#XJ7QN3FsQhKB4W#jO)i*%h_-M^Lrij3|!LquNlFziu8RY-uT|LlUbm$)aA$66(LuTN-fBDa|uzz5?SLR;|q3k zroMUyFoBKFu7uKr(6kD9kHGSToTroaNy|VEbS^< za}xHSv0$s^wx}^l*wVgU+ETshZ(fe(*5`u$*k9ct6-vJJy9%mUy*dXiE=Ho_vKMYc*{1KAfg)uSHs{|a-_im{ zVn3K3_~opSV9zLZE$w5zNcB954{1$e1S zx;uQ;%I61cl0u~dM@IN2GSwqT1W}7!pyUzx;NdItLf7Ia^YV=xn27+2JDPN1`vQ5;317F`rzQ@2`(7UMY zp2~S=65@pgYu5kqO`IxAs9|u-^&0SJ<{2Tp-t@tdPOz#HsNS&O8DQvGYI1>0%9imM z#pv|Kq@`F^9>0;rkY7^6g_CYQF38?5msY{v)D4zxB9QPpU##q^pP|?(Z{@2y2R*T1 zwcuX8tca;&is@}Jj3TgV*JF~%ia96$QRxsr4q7caK?TERirnlB3kF4DNw|Ib6G;B3 zJkwHHgC=HU>aI1;Jt5L5w^E{}<)>)fX*?ZO)jdhS$-zy1RBz@S{9X-JzB<~86;nmb zw|I)&>5Jj?tkHpO+g!iKH_{=us*@z7l+jTSAKdETJ@oB-BTLh?i(fy>=QlvFC z<&I>hX}*;!>y+RuE|w}-Y`T;$W3nDWut3DAgw`+zdPE^R-hnw;rd6X3NV`&_Yb!T5 zQz&(+fd1rQ)m-ovuj8e(UqI+}%u2~yUL1qy15B^n`&{W@HN1S)E>x~+FWm!}utt0#&(a%=%23Z;mB)XV!!0J=^bKrmt)TfBi^ zYrO0g96JWY**n|@N@>hW6E9-Un+aD?NlrhswZ;$k%{D?Hm zN#ZRws{7dC%xxv)-ZP5nbZTnt&;72Ci+i1@d0VI2x>nm}tE?#3wm#Ji3U}%pI0eNm zc5VUuFK>ow3;`O1*xMk)8aQNwfJD3*MwDJ{#2~10JQ@NV+dUFYe^R>v(-<|a3owdb z=ZgUJegThzC=Q8t5C{rb`5G{rm&lC)f;6=B^mMo;kdnFjnPvlr8V2fyVvv8VnIQe^ zkLb+mfWA)34VM#`X+qZSdTPeSo+dB=TCREQ#|K~TLxJoLuz4eeVJPG)y<^3l+`png z$bAUA{2fSJcC@pQhm|gq>}`O475^d7&bxv8kLzYm+2#{HvW~k1OK`!9U7Z1j66`*( zw3R-C<1QXVwY-w({>|-wLx1Si7y1L{uJn&kOFn5QbxBVsSXh-#=Ee7G#+C-MKEpko z&E67UIiX|YVc94}sO$tb)P4~%#uKcOcI=N4JG@;TrFNJ5&L}?@)Gfyj=#RX4U2*cX z*EQp)Tb=Qg|r+$vYm8b|Mc8TAEdGqIcS6Xc@@K(6q zl~98em1HoXkygOhY=`lTV8+w!JMYyNlKpoq0s27Pi({709Tu`D=x@eMCdIlM(BZv0%Yrv*|`K^So}G*sClOCDJenj%_V9)nm2>h)-L5{pIeX$Lj?j@5TVlFYZOLn)|PFQc}oHj?sm7 z^|cn6RCrPx8~LIW zi_7=TODLxDy$nMA6C_{ttTE=$oM(>#dan>vm4I7}viW9D0ShB5!<}W%>;7ZgF7@xy z@G36_Lh3+Rh>r`Pu0J2;=4NN7oWA{Nbso9YI`2FZxby%xJuYB!yKkL5MMKcF2Fk?G zFD^{$lf1liJim`MEXRJ%?-|yi>|>P~=>q#80N7HddAkY|y2I`BPRO~6?o~M-(%;X% zF87&_`da=@T5XP4b_?by*Mq5t;QUf%d_BG{n)ip5>K;2X;AYr_Segi{)rnW5A+e16 z*M;bK%Zh}XIfku%WVUbDJpgMWVy?f`?1KZHGjmy_4r!G*9b8WJ=CII9P!n?Qsb$}ul%>@p+!wWM2>qi+0) zq5!;)!4NwT?BCvmAXnRyEyC9Ewkl5A+TZ;fS>m>;QmM1D*k$A))rn;iMw+2)j%*ua z9Rl$Uk~OX(-IHNmiE`2Og6aQnb%P9#gYP{c0le%yYtV1rpEzQEBT zr7)t&4+cj!8iM(435>bjPYtraY#9S4jTGN-za_O(y#q}wlvP}UsDI5m-Vjm}62n-c z=TU$n*sihPaL*se5yF(POP5ckAeQ{`&CGtd#@%-JO!igcl>FqtX+hxLL^r~ z@mD&#Y2H>J<}ZxYYBHp;3;1Kq-rRmJ1LXDXcq6ld`&pIhOe|{0BZx2T=|t}DOIE5s zJKU`eeM*axm&*gHO4xC{biZcn;pn`agq^##&Dm~g>ra{10Z9=+sG7%(kCLL2QX2PT zuHVHokQJsuNU6e<_8ca-@^1cV?6*UtgcIsQ3@)X?dGQB*gIT;`!#B3}`8g?0@Ws7R z8%nuSgO)&>Imf=dalWxJB*eI)!j4wRk|P@kp#jPbf#$pADn^FL-k!&g8|$mp4F^-;CK)km)YCk-FRR`$w&f!CtXqJTUp;R#mChcDn9Do4S7w z+|m(B>L%wICkHd~zKe34Qb^%K^Y}~H3t#{J#|eEbVN=W>W#-WZIcqk7AxuI| zy1ru>fk>kDA>uz!t>@)p?uHME-D!?$QgdXegjVQ)?5)2T3xkT>Jee&QMABbbwN`Jf zDGW=&bJ8dJBM9$~AW*!W+A`HE+G)mZgC+Akim9HBujR9nadBb0NHxrGKlA%zJa{;n zK4DdUsj;`JlKH;<@sW$_>N>0QQ7gULJL86=FGJn$#0W=C37lWWgI9KS<**V1@FSqq_Qn z*WFL{&*FaMf3JRS8%Jm}Lr&kPq%66*{d}HsR3d>@I(hEzy!3jTEJzr8f2TsCykKx~ z*WrKOe^q44IcfI%xJSj3$7*89BD^GpkRtwS^^uvn;QjQ@7DYYNaw)$T@VYDHF7Wn} ziGh*P^%V7~?EZ3mTA8Y+;R|5;7`ac7gOl0Z3LYBDDW?iVo1~DP_+i1a%)8-ugUwE} z#CY;JKX(;aR)}4=d`Q}_D}@8FrHzt5=WE?P)0H@&^1(g8l?gwb{v<>`+DUeL#9Pjw z;YvVs*FQ^AbYe_Q-YmMd(EV}&?LSzrS-SBuL9?90>7u`JG=!)1H*fXa6#3ClOvx1BNa)saE>Sk-q4W@)Sru9iXLq4|h zKhf@_-s=Lochh1g*Ig-1DBI;Ey0k!7dLTbQeA3PLh1AVyy> znPk`q26|}FXy;Pz?4+X32S+ad90!#mfX)By3H~dXpY6R?(6b!b;LdE$pU?x2k zA(bxjurtz~^XH4|9Z#TrzUnWBbeePG(&n`tmVgShO%tIsocmuwKP>`BrV_SWr12&^ z7wf7H;>!F}MUm#U1z%%2bp3o_1@f?lfqceS!KAS zZnr~4FFt=GyXxm9{k!l=AeG?;NCN$sIa+UVnjDl2xDDy;Xr?j;0WvE`X604ECBS`4 z>UUUQo}~!A1vHJR#at}d`Mm3n6cR!Gn;cu6rid#L(>Ot-3@lu zBbgBVZ)ri^<2%hgS$M9!H3gY~_z_w*(GSVBony@VhY(bMVK+HvJGk&u&Cbq_HVF;r z(rMw+k%(ImT75~#GB%_zY_}tW7CQLwLkN8-9Z2vB77Q3JLn;5J^C9J&T^CPKw`^G3 zDrsJHkicX^W-~@;expGE!Mq43M!p(JB<>pci*e8hL)|jCH?B4u;iFqHBl0798#Evu zmOXyF=%8b$&!5_jgzg>)VU*(()E~Nd#lfsdtJN}V=e+0;8E4C@)l#~?l)78X-!~_! zTSF@B#F1cUIVxdfd!mwJ}M6U*$aSuGE+IXhG%JySH zcP~0$;E=ItZw4bL5ucP3(ln4yM21l{aTpShyiVJIM^n|cbj%8xc%K4RuD6YFyNu#x z{AV%d9QGVyeO|e+Xfv=YmTi?}jea)+d|xPD4}5(U6LY+=Ol<9Gzy^jtqw=qE;Wca*o*o3@ zMIFc=Fc#-nZp0crIG6&{rDuFqULQ?Fz5He0BhN=Pcy^^asU>>&gx7MToDZ|*w2x!C z$Ha~~mBkN{KVwD&PL5aloFs&7 z0aV|a3TLEg;!Vm^A$LY>{%B0x#biM7SJp#y&+eMD3cyEd_j#-8K_l|M z&*8;MnWTlKK{nct`JD~6jSTu3{`TIS0_iXETWJhOPt@ifRIO*FohR>sYHt7!A7EcI zYEt%tX#_7rs*f1*6IqXItk5z|NkaPR<_jHhdrX#(kUW2+B|({%Ga;Gb2V#1L@r6#) z2s08fZN1r@zQh5|TKwAD_LyNuJRt<+r*YQ`RTlKP&z9&BPy#egDWJY3VJ{{4zAz(C zPiXq+L3Tm?S}T!Wf0He=1LBl)`$)^e3`rB{Ba z!CM!v=`Nbg0?OZ9ycK%sM=|&#Y1j2xxeY$HC->0sb41Xz$Z{Fr_l3(Ot*1W;VewcH zzobgbt_rB2HMv=zzaJQvj&W<|(;dGA>M`fE2zYa51Fkg7`vn5#0wD z@6T1{rn8|f$mj~`+k$fBmr?pP6Xrv-fqc}GeonZq^(iGIN+Xm3uUf-1G%_z5AdPt6 z76=J&aapw5x|tk!vHD)v7`&vPUYqJX0?728)mI*biK;Nj`FoFqs`738^2X2gqv&H$ z=oZVn3_n;j4=u`k|3D$p_9c5=N2fMSCBu1g7wT`12pCa#( zhz{qYnd@sungk`4A%TOt!sLk@p$|aU^;3)cRsNVL35UUc8ix?c4y*VTB8k49|8R^a z<}K9@fJfi|1)`D&`L5OA4S3V}rph00&5L<%;HzBA|M{D7it6_# zK>|K_+4=i4Q)#*N2qp&0F-u|D7%d`8&^lwAOMtPvH^4ou!_WH^*MPB86u2N(B>FMm*32fJN*_qAZUK4NzfBh zEnODIEA>JOV>}J~Kr1&zIG9PH1H&1Y>!BFsqyC@FR@zJ5NjZ7sM16YaKYg6Ua*9Xn__FPwGrDvBvL zIQ0OTrU*AF4KZI@!&<|MZRz$=9ry4T9kX@dvyP{?j2Q-Xb_dT8ZM|-GO|=OK0(ewk zHk61sOf2h3g^)=6X&nv~P)J~(3mAEbPmj&WpEN+t=BuJJ8%yvW);> zpH^GH+5>F=Ht0$C+johA2&N8WB#|>S%B`AW^}hwp;2RRYnv*# z>DT9eNLpm=bujvu31P5;2YXXlv0+ZYg%sGvQQnIG5MlM*M6VjdLtuC>24{Rm?I*KC zRb2_A%q#SRPcQ;P-AmMtZZXqr`7xx;*rZw@fZ$|e!_jt=+*yZloOpJhO%xoo3JYax zVTxu#rUvy3g0oUkfxEOD25p6mFi5|qsU6HHwJbwbLD>jL&eChhL;+8hgfh7Obv0U~ zP=o{Jb9?(WY|%<=U5Ru_) z#Qa=e9%nuiZanK;PNY~wtD_oQ?)-GD9rlBq>jpfIbHDN$Y+&y3D$&c?S>BQDy6Js4 z>^aI3H=INC??&ths@KS?Y&Ng$0&P{cX5z5=q``Ulh~_`j7dyR9$+3Wpy{I}na3{;NJ;kFo+Dm&wva zx-4$Mblvcy3(XM@R29)jRY1C2>B*t%_zJ*=0ymj;`J@xSF(0txJ647xeRgi5mqx@n8Pqrl^ zSl&FS2KSQvx!`zwdinkfUzr0sGfbG#z?7I=&8V2aG!py@2i z3>W6D9?c1_f{dR|H6C1RFr}iJzUhisdRTc_JQ#`y2lo_`|BkpHiq|fY&yo(>=@dWM zZvqRxEKinCYaqj2U;P~~@r_g17h|tmM@c0*(Dki*^7D?b_9MlMG_~ee@qJa;9j+G5 z`|?dCv_Ia)W|2kD^QZ~)iSXlybpoujENjl3^AITwpq&hWm*fjM$OQA$lF!nb2#QT9 zA(5QxPp+ntrKjqDaggSetrreCR|EqBlwlf|nR8B802e)8YCx5NI(TtyO;<1{rPs#F zY8dMZv4cKg=@C6ylE->xT4?RZhT6u}qAJ6$&IBF;i9x#)}+@cqTrdeY@;22;e09(`q= z<)mM;SWt5AV#~)R;6@`3#Ov6=&xUcCtO~94(@XfWIg4yzSmWXPR-hi z7mqEb%aMcFadt!@>cnkora>}6dZXzw?LzJz<2>)+CzS+dW|Jj2=zoy-yzPwoY8}=? zviY_re~k^5Sz{MtuD??wqwcIh3*3~xTv=dX8xZ?!D;PT-O0Y>A9h$$hWCf{f%D5b5 z*fVi;P9z^A^DD-;bq=Tg-W2S#59{8d{XT?Awxjdzy&X_z)Wu&waZwc+>-pVZOKd~y z>K+AEXo>iqjdoJ!U^??7!!ocg0|f8chNhj5W@6E` zsdcQFgWlcUU@<}xtw7B1IBJt7o_vL-AOPbJsJ)5iUB)G0Pp$}tg!tay988Wr7ri^@ z`9;5G>D>#NMs`z9{*A;-zVHOf%Cc;SgShWtQ8r)wZAq28PN2$?g!^BWC8c2t#7?zZ z?7yIQAb`%M(#SLwW4TaytnPGgN|_ltuv4kDTr~%(AonDuz(8BqPZ|6cZRc{PC}=(U ztkd&lg&pq?{QCYM%VKdVNOwX!pbAT*nx^sjlmEXcU*L;3Fq4H!-eY|FM+PA}Fb@Gw z&du9LmofTj_kJhKzFl{N!mzuM(qFwquV&Ha4mdNxb3F@$ls93R{9Kd*_xZB*W_Zc7 zHgdRJL~VRY58i^HC6u$3*=PWmgT%!U@nKx#U##3UGJ8%X4(2T&bE~L7sikb7oX$vD zN(s+XbKy_TMD6Y8a9{8!9w7W^LQA(lC1du!YveZ&_nG~xooCb+5dl;?Bq2Z$QV=F9 zOzuQ|ZA>qfKfs^PDkvd@Z$p$=?#40wGdVVeLKDiq!>a6m`f+CPX`V#9DjiS5&&GNu z-QIiA2vHZN8Us0}Gu*Iq+Lqr&tLBSqlB8HIl_}Z@fe9-{8JT(yKP&T(Jp_X&RLf6_ zUzvF*-}iO6K6Vw}`&7!q{SFh}P+!4WF>jM^{UNVN@+YJa5{J(ZNWXJ`g^+#^ zFUd~lbF01z@q^FRWeEx0FqRExR;i?$LKPpZX=>uY-s5%JA7iZPpzyeR+`#R+guyPK zM&&=2iW$jx&2aA~9e(s64hSjL!@f$-&Sps&E%#morbv=gQUFFP;MH_{oA&F7LQdsf z?!GtzbyuM9{N~Gjd6oN{+7&~a$74l-}Da>i)n zOZuZQhPju}B<;a{Tc+HE*|b5$T&Ysh6G(i{9*nQ$${zj0or2(}<>L*jS?ufL27$T& zwIVypG$j~DM@KX+pcns#9X07^aau<GuR>9(YeB3Mz*_JVq5m3zcD?8E;?a8KgMZ57}plY%owS^Rvw~63p`$b zVp7K%HyT%#v#pa=ntOQjl%c`gn$@wT(Ig~B0Ft2NA-4Yay8iuZohZ*h%l`UiJg>TC z_k=nw{Fmpt;BG6uaT7#73Xjg{)6R#~IV_4OjXozu z_Z4BMYPh<(zlbRS*}~NF)t)GiWVQ|6o4~|FyHZKJ;e$JDb&u0AzKxnpkdF)CuDksV zxI3ELh}#_1Ugwz}zIhMSL_ZabDX4D0H?;!+_%T&adC#Y7Gy0Aov`+mRRfh4&NucST zmXZeOhG;hi}E5=Z_m$q((As&GH8S0{SRv5YPyIl2*gR7M@WHO4?>10B>y}HoR z*@;8iqf-GRiTC^a?MsQV@Q-Wz&yX_KX>5T&lR>Vde01J>`$(O?H6@F0dC9k7h2Fs~ z^o`j{g&~C;l<%H{9VY00?Ow^1=`KUYIYz=;|BfT_6^9N3*WM(yW17ZYiH_3Kj409s z^0Ohj=GSx19>tYzm$xcH-4=+R&{O(zdjx+bG)iHXsL->lY&5TF&}rSx0cIHgfz(8K zE+Y9fCI?Gjl}?dofrx8N=r)(fewgSi@}ft>I?Y^+%5Bo&6>G&@9tou)Ws1BfEXQ5B z_^@y)39WPNIqVyw@7y4sTnF4t41EHgcv~Q1C7V8sZtp=n1dm+zy!~}g^1OVBE716u`ne0XCut%Qa<-}&230>#iPVo6v z!+NmFNy)_cX^matNV|ic1Q-Sly?j3Xq%CYGB9w-vq~tsbwL)*`=K!o!XOX%6vcH(J zV*v7RR?&(HlPh<;&$Yb}!bXY`5VfMhCCmGDbb*#!D{uNWD{eZF5J6<*WCY{IWB_{M z`AHr`w5-19u#AEvF;ggeVQ>R=odkkrrUrglS( z432a>3-#R-rbX}%tn>1?xc(YelVYMGfd?qCjjLIof@^Obx4Onmd_;4GBYX$_y`$&WI5G+xhblgyGC(jTGp8vxgcWy3e$y zh>Oj-+*?%+zTIstie+jSIWfT*9Ccq{z|4}jMo3^7*wJQJ84h7?6ljFnTH%t}9nfwN zh=~M~iivNaG8L`Jyuu*_2HnoqUawX8yMMj3xc5v3*(!+7C)m4*JwNo5XOAs`unw7&P&&XcsrtfL7u3@OI<9Smgn% z7B-lk-4P+*gPpU^)2WRM+Aj-9H}jkEQ3VT|BZ_rIst0eSci{N;ktetVZuAKj8jUXZFsMj74iWN;mH< z%2+^amWKL9xWUf1YBmnp1e$2kO`e=c>q#w}noYLZ)SztZY?F0S|JDA>1*=dEykp8Z zs5rSMtm(sqkS+o>m8)X;lVW@d9ot(aJRu?HfDO=Q0Jyl)#pO+brT)L9B-38qPm|K@ zyE_`!&K?TK7??7b+L~Z;XKlMLdyyQm0A4=CoWh$Oly=0=1M32}RsZB)Rz%Yt54|ua zvpMRocSY3r3m6IlcdpwyAt6j7!F7MCz)-UpKUATgzalgh^zQIq>IM}4Li9N@>%;<} z#l{8+N~dje^s05i6>jlgR`=Jj^>`2N~OWA&JwmSaClm1_zU zwzL}-&YO0AmYleLzXGu!ptW@jrk^!6x9ePBn`>1;g}B_yG=&}En@{g?X%J=bkxv9O z6&IDKVpx9R$o_i#^CY{7da(-3M?qjxT^k(Qv_hD|QsdfQ_k)TgVlYg!88d;Jf>&Vr z?C$=aq4nrpzf46}aNfE*PSP}3FN3?4Wc2Ll6T@9OXAzj6lcbZ{;7xh|%Oxpwf*T2t zW-Yi2NzFK?khQ-zWA7Z@ahdA)-8moWJ4fe6Bqsan_x3>z$(oJwQCl9c;b%Nv zU0fc`T0lrfB~6&RZwj<3wp{OH`^_kl@|zyVDv-K4H53;b8Ok#LfbLyFN6{ve+nN*l zIM8^wKV&qxlHKBUJ6{7P<9$2LuKlR=^*S(ga$eRB{;TxI#dsHLS3Of}(I8KdM&8{=e)Iopj(lwDqY7G2Cl9-6W`mv@3C*{$0u9nI)P7IS6!WbT&UAN2b+)!EAn%dcAFuf(RU^dG0U1)*>|^hc4iH)ykIBGOR!n3 zBFg#SQBMD0uu3{floo62vC^W;LCfHuIgxCZFd>fYTHap&5RhR zRBXhS={|zgX(t@S+2_?v+465vqwyC+s|!bV6GNcEC;sPevZr(2wxR}W#JK4U=hEC< z%{HvSbRC-1eYFouDo%v8z2#l7qqhau19HD=y3o6c_5Bv+%x+*+1?9ej^tnfXbSGXx z>}GzUjmm|{1&wW))Yp_4D&b1W15@^%W&;{fZy}Z3KD=03e+J23u6{g_ezbH|kliJ3 zlI%x(rGAmUCpoazIFK9c^=`XTM0q1%#FRNZKRdfP{S?bK`ptVp?>$ce^04#eFJR7B z5k>MlUpkFm^CiRfWuKUd&BtA`2u99U>d<4r4f0)C$K=?N9vUT@ChFQX_od_HeKJR= zruPd8ae{maV^a9;->uqh$~eh(VzNOwW$`DCSi}LW2sU!X?bJ+Yf|xBi$s%Q77WKA1 z#J`%L)AJi|vNoC8cDioLkjdbL4WjemO}3_PGnJon&mUc< zYEFX-+=3=g#Y^3`>2Q{_WpwGwA1BPzw0XP~_r>j{57e}J)GlDp(|%WMdB#!RF3+7g zUNmexM!`tbob}}^MMUNg=NhAsUi8s=ifP4?Nu~_y0>>y4ihSR0DA<8YX^#*s*MhzK z=d3PGx|Dmu@%;>q%}hyfwXOpXc?kTve$T}}A?Qea$#?XRP|{C@m2sY<-#m~+uBukI zKkP1SO?KKQ_&(O~QFw?Pf3yAt=TTYHh3AXM+s(u?&epG1V*ZusWByDoa{b3Z`2cC! zKAm+L_6dUt&DjW#4$;(2#a4$M;kbAiM>^0YUoErcNIUK{h*2wgw~nbkUtcPm$gvMh z&a*q_%e_54%`^EiAuva*6h(vp5>LpbFjhJJH<4;q?d&~8ctUWcxT-M zeljf`s+xL~`SZHjp~bY{?(Xhr6|$))QeX&JPkx^U;cO)k{i?!4Yjqo-6DlYj^(iP>_MXh zQP0oMnoR0CI$k&XS!s?^OgNMj7iMrPYwd0q>N(kDGWc>S7wYQj>AdLuJ3sB@WnRH~ zc}C{@=PEMLRaI3W_OD;b_dBUx9xl3n1U$KxV8>l!25{o9yaD#HC?xztoWF&OKRhJv zrn90z&OGO6N*4R)Oapt^KIWo(fi!j7A~6csP*q`08o;T`;~MF0cGy%`!=};BnF^m{Vi4L^$1m5_*V5O~t3uIWWnyAtWj;uD z{ovS=cZv4r#fDg_L8nN$nHQ z4fzrFX7Xmy5`QcO13Ab~1GlHwFs|!nlnS6XjOE~g9e#~r=PQGwZ{67>)Z}MnCG|WM zEM^)V@BLi%_u^f=J2Ut*>C-`ZwP$%7KII7mg>@tsh7zDZV*gbF6zm-kidbP2{HiVZ zAET$-118c#8Qo01oN>4s&)3!Blvd;XJh^^`%?J9hqvv=iXu+bnvA=J-NB9F%fg9-1 zY1g{Knz^_{(PMnO0^@@!(wbW3Dx$*JxcFfV$pDLCpudJ?$trv{f3@I0vms@Lj zu&~%{!&E$_dJ9gbk6PE{9|X>sxXfzU@Q4aUZ{qJZ(qMu2eD~Q`A^w*##>JZZ^JT&s zhtv^y*1en23Y+L1RSgXVc{zZ&QnjnmtF|TS(ucsE7asnDTeja=joaJHb>U~`nla$* z;q2<7*XmhRS4WN$#musI{p2lHYwTfFrpY8PD+`#|0hT$-2;3^ODiIM#{l-eVOb#@Z z+>Vc-JKUr`uhVn40(@}COfzvp6~MYh6Ew}+y(#e{A&NJlSYsW*W5rz4GnOi`!_&RT z_4o)VX&|qxV%#7hoz}uHK}DQ}mbDM&eOCyhCTz;bn44e3j7x1{*hSigL1&&|W@2VG zW5Yjt@u9;Sak|;u?oBa1_%_$pj<@NnG5L*pR6sUrW{KxYnFYZrf$^{$_d-U}$<7Xh zrAERhxVVsPXT9?C{Z&^dqg+U}wo^S0CYjUeFB>N(O@x@;fDECOQ!hr=eiNJMZvj9G z{G#I~dXDsSY4P+W9?jL#gWO=q9cWsuVMA1cw9tVUE{9u_4hshtw_G%dnS;3KRZSU*uZdJIjn3T&u$A`tJr?)AJlRz!h^C9- zVCns^cro+LmI>0&%O`hm!1|PrC;AOp8P`Hu>l?N9>HtluV_s2_m>`v`x>B$=If+AN zX3I^*Oz6fVrK2myTC*p5C3$gnmeh?!B~_%HkdUx% zNP($Jo9C`Gg#&swKVte%Fn`nc#ZJytu5S%_l_h;ybXK@hXiL7XtqP$x(&CtT4sQm= zymJrtFm~kEug;UJ-|lK^*w|J^Kl94#*}ehxW1(CNT!7K+;PJ7xj)n3#3oAxrTG4Rnf0X*F$gt z)|8BmR87+TpanV%rDAu9to7+BbsZ{Wj3K1_`mhD@gBFA9uL-!J9DFfD+foJeBnDbq zX;~QsUP$!XH7<>a1?}xGfCWl9Md;uTV5GZZCXgme(_G`{Y95y!UoH>2yGpm+KbH-o z+R)BOOYKH)<6Dv6_q6$Lde`}3Ry|wCF%Ec_j3T!a2i=@$!=9c`rQz z?i}}bcR*!9O`nX_FffcRNxDdx{w&?ISE?Rx>jPN%byD?$rMcv5T52giB3YtsxQdX} ztvTWxm5!Hn>&X8=6zGWoN%}e(FPax7>a?hZ1qo;~=%>T5X|;cX5*p`~+Tl5~vGtsF z_@A*zyhKuT>200(zF*jv;%B#dvC%cI=^b76YMU^k!z}s*4=49jdHMcY$z6w3Sv+>11s?`dRud%ng?p3@AeKa~29D-WaZ?;wgaFz!){ zhQ=K1BCp3Ce3Y-i)=F{Iqs@|gQDXZVa_oAEOe}LDzm~naqlF;&X=;w|8piP1i4a+S z4ljx^P&SOg@u_2G>rG8cUCrCt$=$t*%Fk-m`EnGjcQdK?+;7U#!vpk^Md%w0~>{BO!G9&u?9-%n%2SjN~E z6)8zMa|TwXZuy;tvGVuUVwMxaIXlV2%YomS?$}c>G&-ZjX=~?6aFUsJQtLyP42IFM zI~#wDtDHWC33#A!=hQiUgPzD`Hh4AOT?fpxG4Ca6hh>x)o0klGc|9R~0BxC&zvkJ5 z=ZVP>BN7EAC2kiRJ_!kFy7oVR{)|4a>Rf_Lj<;|^$neJCSC8r;tIbEElPaY2YhQ3DViF&gv6(@zms~ zhm}^>Z{LrUzt&Xhxh|@qZZ1q#f}C^dJ$;YQ(_|M|)?Kz_!1y17+Z^3{`}bPwMN>wj zDC$gQ7Y6f_ePL}wOLqHIg~ws@?HR>&#hxp4eCz^UBbo7P$JP{J+;gi&Uykn}jxEVy z4=gEigVJ&UbC~mvE)WIJH)*mnB)hZ6R#!nw?e4KIPYEO-+de5{R_Uj<^BJd2Wlf@J zKU>*UkdjVf#I-$t2gR*SQMeUr-1#BQOLaD}ao6P^TsW?nTYxlwLOuUU9{OnSKQ)(> z5Tx@{w~*+8SqNfE0R6E;N=O*B3DD87>dd6bZyIP`7%_B`8@ffWmCNOqGfgv_Fs~c* zP{+zmz>m0{E^g9&)lw`tr63snZPBdS=R{##x3t_~5kt(kzmX3eOs=QQCJd|z7fH7h z8%F4gjVmV~CujLFleH6d1`EET{TTEZQui31+myYl5ckXdnMs21FnOoXAm_oMhKrhr z9<6mvSx0M6COSvwZU+(rB_~XS^-mFI^)-5}V#`p1eqyKj0W-T$Jq*#Nh~gHqa-4e% zy#V#5L{Kslb(r{HQf80mbn?)--@f%@eO^L;pF-^lPFvGXeVV7}c>GBuNP@Mtj48@1 z^cXQ01>JK(K~cdI)S_Gm%)3SgUNU2PWwbC?+Wg-czwoxP61@Gem*-cIc~6pe!M!?6Pcde#>s0ku69?!W@PQxN<`dk zYg|{U(9rEWjy?gnBt7i%iZE_)ja5FCBD$tt+ks_7a=0md0XEBid@LD36~J!bvcYZc zi{s@xGEQbX)s5(5(%J@e%A%k2UViC*FqoKhP82&JM3D{|pVCRbP-nO}o-G3G?&w#i-Veg)Ae2X@uGgo=!)P&uVTz5FfJeiwwSBaLy!9kj7MapT1nn^bNHQlW;IQKdPkDQjEf=sTvtO(TIJODMiT&n)-=50+IJ0xZue#$H$Z|ro^DY09wdFHA`FmbXhnHrP+bR0%wUctc8WLO$TT^_raXiAR zD^J3t-N6sG68hcpbquo9)RRs4%`6)beQ)_lVpi9f5;A;#&aS9t`C1V_%A74Qs#>al zsodor*6KGhhqzM2<$p8o;H$F8BqAf~cK(C2Saa=biKeb$iKgc69@7dI67Mc~XJzhA z%T#~eJYtnBk0P$%q@FSjx`Z9$$j{J^Ao6O@4LloSdcArPeGHH|x|Z^T`)CH=p;ORp z2y!zDWvmb*i6#7j`hskhF#k;8>`vD7R8k!JMUmRD_O7q+e!ITM-sb!Hg{qit)g8dx z`mpp^=JC~i`QDfw_&U8D9hLH@o`eneT~!maH>%uom}UxuHDj0XH9|>*EzQ<)$tYQO zeO)gF=o&7jje&-rm^n$YB89IidA8hBCh7$xEgXo2qbM+gj&?e(M;KSCCaC?WKFwc5 z)Vvw!dH$;nVZf=l?$0z3(M)2}M@eVN9gh+0LB*!?a3aOdb=S#)fhkbnkgi|j&7fs$ zGc=RuCOH}!l(rD-efFWD{D|1r`Y>hV5fXCnU5E{v+nXf{+GurJl(bJ;i1~JnH-lf+ zcHR9E;$EeEz8*iGgFQU8*L3;c6)UrsvoM8&`JW|YCj{ja00M1n)$;Ok0nnRd7tB^gj@Ozgb$p>bbsf9&Mi=)gu%+`;8XW$E4O6*mts_m*@ zVJC?_)}%C*l!_g5O8&wfj0u}VH{hv~&Nm$)<8Hc&3Qp^-Yg0fQS!b*X^s+rqYVK&N z)jrj^7jd>P!h2i^fXHPLb1_^+{uv*sc>js;AeY7>MSf|Fr(E~lZu(p*bThe)1)_e+ zb=>pW%(t6(oq#t+sbL|%IVr06I?c{|Ra#7sx{hYg7EbO%$9aB&)fXbQ?&|1=XxppT zryGDRWsEA_68FoiH@|eAy<4FN93w>I^L5a&eo>AfyU){ z4uMlYS*uU4#0*EL5@8Eld`_#-Z~t4)(dp@&JqhR!T^iP79kCm!lO6g~0rTE@O@;6x zNXxMdQ%_$VLn&U;B7yv0%rA7hY>o$|l(TY#&_#1;`Y)&iQ||`q@xz5I=;%re{RV}` z6|24bfn#wK>1fg5c_80ON&p!42m^h~)Yc^twc^ECbngOdX5M=awGc~<|9A$@1@TFf zy6gx;PW1#;Erm=^M!Y#99@NHJZtFxMq3@%SDThib$b_xTn;~5^7Z6X2w;RJ-v6Wpy zlMh^^(d4fni4DDrqocR1O%HK>h(t-M`P~R8D4W1Q&@Pb>$?Jq$=FVW&&S3xi6~kK~0va@Ia288%gpvQQXqJa;->sso-p z3?&VX#pwcxB75U@vpCcWo9(5g(iZGE=4N;|#54K-?#&eae|wAW3HiiwcOJUWrff(^ zs$^DlPBt?T4mJOGm0>p}MZCBG9UVBjHXNvCKm!kxN^X~LsXJ9Xc%32!x>O~Gy;Nld z*Rs(q?8~j4R|K+&pqzgwi$NDRC#SUgx*}Qif@2IlChFhyU&aO;v~44D!+{xXa(l(M z@ND3DbUKnF__=FK9pm3yIjgFKbb%13a_*LzfYdVp=Y#oqFm?n z*bQ`Mj14=(5fQX(gXz}^kd2Mz4UYfs%s{t+t5~wDz!p*2SOd65Dw$^qc;Qe_&dl{~ zB1Xwh!RNZOQ-^uS0(--KRo<#Cv(nT4Qt0f3^<$o?+4XdZ#OFS(>5qt#d>8`rHZSAt zgtPWQsr#5jPdK#mPZw{_42}rqZ&IK5;tL-ekkd+yj12^UzZx2nWWq_n)Wevgn^C$> zXF;_eqD9lhY0ym@>jUojT<5J)y3L>FwmuX78R`}LNfHI=bTU0cDGw}VLbXZyV;kjd zm9n|@6L5U)^LJjz{swAVMhvBJMshu8=x_;MNEgH-rcxyxVxJg^tFFV+5?^YQlbCHS zzY0TAm(|_4iC@3oW|T^Rwb4?n1|k3_*Q`J^bqm>{tg9)QY%ztVw@4l%7@3$s>miOF}yU;K+29gWfclT9ViQ2 zfl`UB3u7$8%=jjcVRec{yTtp^>5msNMA`h6U-1&2S|XIc81$wHpRB!_V0H zDDqdV(l}JS#1}G`s`yd|0;}uIzKbp$k#YbrZ{Q6rE+MfjK6}J&oft)1x%!;zt}a2- z%xfbr-oY=JTSO;C5yyXf{xmT`qGZd#H5g{;v6+1uk<(UNRdxI~=0xFD8ApepRH?84 z2n8-^(If)Trwx;BSUM}A!=_V`);aWzHPW%wD7|$igZh4NcX4rX)z#ID`d)G@tmPp; z=i!JqmR0z+;!>{Cqgm!tEU&KFgSI=VV*a~WAlwB8-o}@DL9&UoF*O&4t=@obWt3D| zR|iUjn?jv&up;9{c(1R-B%+>+UO0N2d6A@N)FpB!C`fhI5!u;%k3#EdVuYjW1?iSp zN6s9O_~22ow;%MAAI{LRlibNQP#ai%%isH0n}q5*C)&J+teCGlD#qJ*HxSvUn_#vk zYvwS+sL=b3?>IP`=I7&pdM`k+-WlLHtNSrz;bgRc38rI2J@BpV$DyWgJ+c0D-JQQ5 zn!EiQ0FlE0q71W$jJ@67TK@T zGZIsW@fHCG{VwrgFI#Y7b@M3fRGU5#-qOQvLIN@I-1^yPRLr=wJw*#3Tn{`ym$tV9 z{a1M>r*m2%`eNk>Krur=AOHE$;)6B;f6{bdaIgjiwS+dFn9KJTRZlPL@81-};3i#r z@)RAid|C6%$Ukwp>-u8vdC7%y(?cc7Wq<-qKtRC#{k<*cO9epur~+@W?M&l<+N3Gs zLd6SiZf>3lVJ(9=Ousvt&Kx=G=;+AF$(fj#=;&k+6m%`bGx3yL3j$)IVW9l>cCW>1 zJ!E9$JVm;cQ8Tu*cq!||xoMm^;VW%H0fEl5Gd@Cs^zeRRDrG`MV9rR9ogiv(r>Ut4 z8#~VsaBzk-dmR}WS#IcNST2Qq*`lVzN4Pd}QKw2daGEwIIJUue^0)iq8w>GziMUEhu`aQXy3 z$-H}$M}*Q++y`jxZ>FOLb4gKQtgv1tXIxhehDqff1Lx}zQ#M>y{W;3l;_hytILXHi z;wDN4)M6DvaT0bc-~g z+xK=218m(R)yOEY;u3rn6%yJy^UBBrz=-KOZu>`$*S0Y zHN`}#a0ySgw2t=dROs0i-y)S0*#=1Nq?cpo-Pawq^B;>^*pNwig= zN@Mg>`r%+zaxj=QiWk{uP!Yz&lV2v&j4Yb}0NjsHPHZeKFXKBRJ+At3CB(%GS#X)= zkH(t!+Uo`0>;;g@&&~byKFmGd>=StG_fq{WU?BcQ6L-_ivnu z9Nb|WDe3QJz?;%`zVVIDWg8O(-IWICro@~ zEVWmn{GPX#4h|07L?rn59y?K7fEww9?;(86{?G&`2M2JD6)RAxTToY0GSb&5aFr&6 z=9CJOsr6fC24iq-Z0JecXlN|0!bJ0oz4+F<&P*FXs%u?Y3kyWGbj8)nX^i&G zp%&rgG=%r6ABsyj@x%Yzx+rN%IrqbaPgEdTD^wpEynysl{~AWpFb$M;Bl;=g;8#PngxJPom}|$<^J7u+%`m#rPiEjorL|C<7%; z@QkLt~K_Q?|5B z-{Z0#RNvh2iOb7s4gIvIe^6>zrNdZou%+!fuP2_*M`e@};dgiPPB+AHLp;9TAHBVE zbE?2Ud+bG;n2Nm>2^>4NE;#O!^77(aEdv%JGA71?4PQ>;Cf8CL3es?xkb?z`;5tR4b+i{n`{Ut zk1Hj`OQ=W)*DuMI_6zdg^E@5ZT;>f3R!CMFsm$!HaU&)c!!O~H0fze55` z6mU_A5j$>Bn3-WFvYht!X;MPaAgy<0JCi^EiH83 z`fj!tC;v_!Lad{%N{^qLH{kGm!2S{C5cGaJ8ESbqYEb=n(w*$NHI>(E5~KF|wuzhL z*X4d^{c|$AC+*ur5~He0!~L9!suuq1@?rFbkLD;^JaOy4|9{^DMRsQa8npl->E4uY&^v9ZV%a zGZk%mqtmP3IFl-6^uJ>#M|eEQleC2Z?n&opNS6vo5VLC?POHt)Nl8W1(@27@h)+w$ zO!_BP%v1Y-G;GDV2@;zGFK=M}V@SCQd}3i$^h(o=R$Q(9`)+a%LswZ@S!-+BS>oDu zxe-GW#kmIk)DRgl^^x!4oLVK=_pSod?+O=`_%SPl+5T_@Mr>nT$ zJIE9xemjKNACECrewT125fL`)>v`Z!7H4N@76TUB)n+d>Q;;*PUerl zg=+Y>2CZwpkZ$CKBz9)$Kd8Vq-tvvs=gpax(aC)BXOT4ZX92?$vA7Y22L04mYI4PR zjQ4b>kZ^X+gyK8iq_bTSNgYdIxHgSY!lqk(_Vbh|A-&akJQgHz~>~=lLYx3c9#V+RUKeAt4nu(+m+%rF3~1-7MKn# zQ(J$iwB`q@Eo;q;cg9MYFU{M*c~DYPZx=F}maamfIyA95x^X*h%bOFYPUs!mSTXF| z?aJo)l&LCxzTao6y)(%UM)kU^_M>Sx_}k5GC2s7?*V5AMV%xVA{0u!X?WBR8o6T2+ zbrT^!>wZ6}arW(3v(d=}(rd@}d%6oLU9KNXXR*I#XVWq>NpA(M#!L!-Z;8W1<+`Q3 zOwqm6&us|3#Zu_O+5P1=YPVM+MZCj)8aU6XFK{bs5pNk=XXIW<5F8-A8`7io^1IDv zGYgP41MFWAqj&R1g*B&UGWtJ$JUAD=RZjF>lg%g?WW3R6>zgwHidvGZX`5p3EM*~& z(@mSZ+wA`UX|4nVXt$%3|G8JXuYjBP<3L1C~_qz#GC3_mEL9+-cK+okFl|#Yq z48B5Wz{a4H0&kIeYy@mBJdEHolreuHf=Ky_*HQJ+HWGMVsqI~0RX6SSboty$^@7@% z@}u%7#Mk4};tuICWBd_N4HNflgRA5pc;CsjV7q3mmh-2pO6#>7gX;~HA(d%8hhITv z4+U8JbY?j_&ep9ALrMLRq8Nu?WU}Sg@w9cWK+{# zWMM)40cP@-1B(zf*m(m34WB{f0?(@Ts!hYm(!oODdjubX!K#U`tT$~mRlJWBY~9`2 z)O6hNw74S^R8nh^C!IUJJwV@|V(l2tK<58HI;5bWjI;^MQ07OJ-E~xiTIZv;n9dWk zW&8nu$+@9hruc+cH1Gh-b~YG=ie8X@gel+mQ6b4 zI!|?nSC6=8+oOt8?ovBX~qvbm#2dO-JRatq?%Mi|@?BMml z4gw8jHV#x$$i}ib>nnq%9Uup;jX&rsYe!wC*bDdg=I5LrrmO;r|iL|Lo^cn7M z&Ge+qgrM!jDA+-$B%aBx-|WsGobilrXh*rzzNq&qSz`Qi^HEXDE;3{2OGE+{ zzEA_xbO5|_b`{|p@!okoXK-U9@Qr~gsjlxZSd$VwIsr9<1j%|39{xEGJE!kfd~+)p zi;6od0C~E# z&+6$Hy*mut_A_agd8pZd__TL62EK`umD4P0wC1od#97gJkdT_t4Fq@e?}-)XQk_<# zA08h}U~JsgrrUCAnD@$8Xvm%@s$(tNvZ6_6M(vmJPM z&lE+3U2RHDx#&K|fUluRED^*iME)<_ zm$~QRCvQdO{(L&B@8$J_FuGhRP$blvLZCd3f1K+FUcGv?K?8+-_D`R|Vgh^r@6fNJ z_C@%8p|OUbS5y=CynFX~^bLaRcOmeze_>8o0>wy%R-5Al{CbFnm=L4kgJ5tf@%F_k zePdt&R2mK;Tff(70XsM`%d(Id^<@5nTj{0=4wntohP$FZ;-S7)L%7u1>^%!DvaT+;5bp}@ws&S^rgwiL-pL7F7r z`9Z)VCMOXQF8lpz_RSA*q_xHg()Q{wXy5@aFopv|A9!$^qr+K2Y>RtI5GE+ZF>rm^ z9Cg}|!lMhG4COWhwO{ZY#mbG&Y3&tq=D;y2DbT52%7I;EWRz#|T$L{cmAO0s(v2;@ z%FK5Z!p)@D$J&CW;9VdhaU3}NWK%@PdrI!>z1zPh_xKz*#LX0C8?z{~A%Mw2t|cA% z2F4SS0WXHjEzm>+~ zE*SF_U%$qY4_dnO{0s6wagMXD&rG@F7nP+$mqCYeFaJo2A|2#F7w}HEzYOUxs-lXhU>XAvVtnXDK^@~?C zMm~+kosMp`!%`xqkOrs*#pg}g0tDq`JvNJcaDef(%SvxFbJ|lqpk%_mu}lN^du?s$ zbM?h9_dnC=LI?S3N9MtWj+vyoI{)~t&NvUC3_dk(OglRGc+mJ3B3w_8!B1MIFBXOJ zMfM_W%wiE1mRPGx^4{AUt3()yIjGFCG7dE|+H$l9~Y-&F9%rZ*u<0G5@Yl>Pf z#kCYxF&5}CgZjN*g+?W*Jd6w+%bdFEY^=E7H7*DgW{GxadU!5C~-QpTF#x9=Ge~%~sMWRhe>n zY|4V1j5u{&o&OF10l`4L9E#*klYi%+@A`>P1eoalGixRnETrs3*%e-T-z~^hTO87v zexxXdphWb((9N%Y=?D&nmTN$WV<0Lc z`-QGLo3>d5#viRkb8bz*E?fW}*=g@daM4aCOV?XbBDUL~k+AA+di1Mx2bRiqHVy5; zD1tmO+EikF44hHu-d5q|;V`#{5*fDOi(tCo{(0KvB3m$f8;o@amwJt4`@xN>7+U+_ z@Y}a<7r!=wc1q>hrR=2$(AbVvY@9UBbTRC?ZZ~3^sL4*(O_zV3qu$x!ndikhVg(LR z7)Y{P=3{45_Nn8bw3&X-?BoHdb;K{40sfGWPyL#&4HEiGlAkGRIgWDQ?v>}opC0)D zqP7o&?tp8UnJ~@pN*9pSEJXVbAJ$|EOz#5C-p<-OwH6KDH(rlze2s?TZG3oG6tLMt zc$VisIuBn@$2_Tve868bf>%rus-$MED!gvY@@O3CUkn5L+v)qrMY2Fy7vD1N!%>ko z19Jq1!>Wi;5)Z=?HS8Om%)0%0fxP4*!2Ux|P<>pWCLN_YH>rot1216GO6o@p|D^Yg zH-g{Qps6+hvklUl(ll zGHul_j`Z;{bSK%{X=5esG-$yM@cFLt@q9L6zLMHmHa|92=YYI!2`UpJpw=6JQkOJs z>~zFRh8oG9IP5jig5AoXH1XkXJP!H0Jc(`e?W#8~mG8RP)X-NNa;@g_quxXf(ntBU zxtYr#E&KQhXWRo-w!85=Ah^kbcMaA_8PsXQ#k39Ny5ibmEQ+d~^29JX>r~6%DbAn+ z+0Du*JlS0Idm?CfpPCDg|mQJ_*j+KYbb1Jy?8=4_tAVl9B@7-ZT+a zI*7ckpHYjR;UbAspfdNx$WL#d7OM|SoFj)-SD#_Exgo@o>QS9#mU4Gxm*eL1MWW#N zHQh0P3|=sz#p!{^Sh74JG4uWsw(C&$&KtB-wR12MwbDB!GE$;`B$#j)ta0DmgeU(k zJXSE_5a)lQz+eM4tTOX!h#a%t@GLHlp&{W7uHl4Mx$g*t@WNlG+04eKx2-JNxTbciaT>v1gk4}iGJFA*`L7XmwZN8QB_t(_ zii)mAFnZ<8E?(gpZHl=jff6(J^qgyNf23ROiZKH|mS*6}4+ua5eSc`5>D3|?iBZ>M z5{wtWpI!HV7-Kqaxpjq^k((Q#NnJTU8fShMM1f>gX4}DYtlZ)B z{M`-^b+8VkZ1m-%)^qx}CB4Krdw6rEvST-7*`oio8SZj67kDg8ZQ&IrPGSE8*#+@% literal 0 HcmV?d00001 diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml b/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml new file mode 100644 index 0000000000000..7e9599c49bc2d --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml @@ -0,0 +1,36 @@ + + + + behavior_velocity_dynamic_obstacle_stop_module + 0.1.0 + dynamic_obstacle_stop module to stop ego when in the immediate path of a dynamic object + + Maxime Clement + Mamoru Sobue + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + autoware_auto_perception_msgs + autoware_auto_planning_msgs + behavior_velocity_planner_common + geometry_msgs + libboost-dev + motion_utils + pluginlib + rclcpp + route_handler + tf2 + tier4_autoware_utils + tier4_planning_msgs + vehicle_info_util + visualization_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml b/planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml new file mode 100644 index 0000000000000..2f5662c7998ac --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp new file mode 100644 index 0000000000000..46c58d6be8805 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp @@ -0,0 +1,71 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "collision.hpp" + +#include +#include + +#include + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ + +std::optional find_earliest_collision( + const EgoData & ego_data, + const std::vector & objects, + const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints, DebugData & debug_data) +{ + auto earliest_idx = ego_data.path_footprints.size(); + auto earliest_arc_length = motion_utils::calcArcLength(ego_data.path.points); + std::optional earliest_collision_point; + debug_data.collisions.clear(); + std::vector rough_collisions; + for (auto obstacle_idx = 0UL; obstacle_idx < objects.size(); ++obstacle_idx) { + rough_collisions.clear(); + const auto & obstacle_pose = objects[obstacle_idx].kinematics.initial_pose_with_covariance.pose; + const auto & obstacle_footprint = obstacle_forward_footprints[obstacle_idx]; + ego_data.rtree.query( + boost::geometry::index::intersects(obstacle_footprint), std::back_inserter(rough_collisions)); + for (const auto & rough_collision : rough_collisions) { + const auto path_idx = rough_collision.second; + const auto & ego_footprint = ego_data.path_footprints[path_idx]; + const auto & ego_pose = ego_data.path.points[ego_data.first_path_idx + path_idx].point.pose; + const auto angle_diff = tier4_autoware_utils::normalizeRadian( + tf2::getYaw(ego_pose.orientation) - tf2::getYaw(obstacle_pose.orientation)); + if (path_idx <= earliest_idx && std::abs(angle_diff) > (M_PI_2 + M_PI_4)) { + tier4_autoware_utils::MultiPoint2d collision_points; + boost::geometry::intersection( + obstacle_footprint.outer(), ego_footprint.outer(), collision_points); + earliest_idx = path_idx; + for (const auto & coll_p : collision_points) { + auto p = geometry_msgs::msg::Point().set__x(coll_p.x()).set__y(coll_p.y()); + const auto arc_length = + motion_utils::calcSignedArcLength(ego_data.path.points, ego_data.first_path_idx, p); + if (arc_length < earliest_arc_length) { + earliest_arc_length = arc_length; + debug_data.collisions = {obstacle_footprint, ego_footprint}; + earliest_collision_point = p; + } + } + } + } + } + return earliest_collision_point; +} + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp new file mode 100644 index 0000000000000..ccc3fa94df603 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp @@ -0,0 +1,39 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COLLISION_HPP_ +#define COLLISION_HPP_ + +#include "types.hpp" + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ + +/// @brief find the earliest collision along the ego path and an obstacle footprint +/// @param [in] ego_data ego data including its path and footprint +/// @param [in] objects obstacles +/// @param [in] obstacle_forward_footprints obstacle footprints +/// @param [in] debug_data debug data +/// @return the point of earliest collision along the ego path +std::optional find_earliest_collision( + const EgoData & ego_data, + const std::vector & objects, + const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints, DebugData & debug_data); + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // COLLISION_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp new file mode 100644 index 0000000000000..cc5dafa218654 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp @@ -0,0 +1,87 @@ +// 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 "debug.hpp" + +#include + +#include + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop::debug +{ + +std::vector make_delete_markers( + const size_t from, const size_t to, const std::string & ns) +{ + std::vector markers; + visualization_msgs::msg::Marker marker; + marker.action = visualization_msgs::msg::Marker::DELETE; + marker.ns = ns; + for (marker.id = static_cast(from); marker.id < static_cast(to); ++marker.id) + markers.push_back(marker); + return markers; +} + +std::vector make_dynamic_obstacle_markers( + const std::vector & obstacles) +{ + std::vector markers; + visualization_msgs::msg::Marker marker; + marker.header.frame_id = "map"; + marker.header.stamp = rclcpp::Time(0); + marker.ns = "dynamic_obstacles"; + marker.id = 0; + marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + marker.action = visualization_msgs::msg::Marker::ADD; + marker.scale = tier4_autoware_utils::createMarkerScale(1.0, 1.0, 1.0); + marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.1, 0.1, 1.0); + marker.text = "dynamic obstacle"; + for (const auto & obstacle : obstacles) { + marker.pose = obstacle.kinematics.initial_pose_with_covariance.pose; + markers.push_back(marker); + ++marker.id; + } + return markers; +} + +std::vector make_polygon_markers( + const tier4_autoware_utils::MultiPolygon2d & footprints, const std::string & ns, const double z) +{ + std::vector markers; + visualization_msgs::msg::Marker marker; + marker.header.frame_id = "map"; + marker.header.stamp = rclcpp::Time(0); + marker.ns = ns; + marker.id = 0; + marker.type = visualization_msgs::msg::Marker::LINE_STRIP; + marker.action = visualization_msgs::msg::Marker::ADD; + marker.scale = tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1); + marker.color = tier4_autoware_utils::createMarkerColor(0.1, 1.0, 0.1, 0.8); + for (const auto & footprint : footprints) { + marker.points.clear(); + for (const auto & p : footprint.outer()) { + marker.points.emplace_back(); + marker.points.back().x = p.x(); + marker.points.back().y = p.y(); + marker.points.back().z = z; + } + markers.push_back(marker); + ++marker.id; + } + return markers; +} +} // namespace behavior_velocity_planner::dynamic_obstacle_stop::debug diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp new file mode 100644 index 0000000000000..02f550d314d39 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp @@ -0,0 +1,40 @@ +// 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 DEBUG_HPP_ +#define DEBUG_HPP_ + +#include "types.hpp" + +#include + +#include +#include + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop::debug +{ +std::vector make_delete_markers( + const size_t from, const size_t to, const std::string & ns); +std::vector make_dynamic_obstacle_markers( + const std::vector & obstacles); +std::vector make_polygon_markers( + const tier4_autoware_utils::MultiPolygon2d & footprints, const std::string & ns, const double z); +std::vector make_collision_markers( + const tier4_autoware_utils::MultiPoint2d & collisions, const double z); +} // namespace behavior_velocity_planner::dynamic_obstacle_stop::debug + +#endif // DEBUG_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp new file mode 100644 index 0000000000000..6a0c61963ac81 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp @@ -0,0 +1,84 @@ +// 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 "footprint.hpp" + +#include + +#include + +#include + +#include +#include + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ +tier4_autoware_utils::MultiPolygon2d make_forward_footprints( + const std::vector & obstacles, + const PlannerParam & params, const double hysteresis) +{ + tier4_autoware_utils::MultiPolygon2d forward_footprints; + for (const auto & obstacle : obstacles) + forward_footprints.push_back(project_to_pose( + make_forward_footprint(obstacle, params, hysteresis), + obstacle.kinematics.initial_pose_with_covariance.pose)); + return forward_footprints; +} + +tier4_autoware_utils::Polygon2d make_forward_footprint( + const autoware_auto_perception_msgs::msg::PredictedObject & obstacle, const PlannerParam & params, + const double hysteresis) +{ + const auto & shape = obstacle.shape.dimensions; + const auto longitudinal_offset = + shape.x / 2.0 + + obstacle.kinematics.initial_twist_with_covariance.twist.linear.x * params.time_horizon; + const auto lateral_offset = (shape.y + params.extra_object_width) / 2.0 + hysteresis; + return tier4_autoware_utils::Polygon2d{ + {{longitudinal_offset, -lateral_offset}, + {longitudinal_offset, lateral_offset}, + {shape.x / 2.0, lateral_offset}, + {shape.x / 2.0, -lateral_offset}, + {longitudinal_offset, -lateral_offset}}, + {}}; +} + +tier4_autoware_utils::Polygon2d project_to_pose( + const tier4_autoware_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) +{ + const auto angle = tf2::getYaw(pose.orientation); + const auto rotated_footprint = tier4_autoware_utils::rotatePolygon(base_footprint, angle); + tier4_autoware_utils::Polygon2d footprint; + for (const auto & p : rotated_footprint.outer()) + footprint.outer().emplace_back(p.x() + pose.position.x, p.y() + pose.position.y); + return footprint; +} + +void make_ego_footprint_rtree(EgoData & ego_data, const PlannerParam & params) +{ + for (const auto & p : ego_data.path.points) + ego_data.path_footprints.push_back(tier4_autoware_utils::toFootprint( + p.point.pose, params.ego_longitudinal_offset, 0.0, params.ego_lateral_offset * 2.0)); + for (auto i = 0UL; i < ego_data.path_footprints.size(); ++i) { + const auto box = + boost::geometry::return_envelope(ego_data.path_footprints[i]); + ego_data.rtree.insert(std::make_pair(box, i)); + } +} + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp new file mode 100644 index 0000000000000..c28e89ac6c9f6 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp @@ -0,0 +1,55 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef FOOTPRINT_HPP_ +#define FOOTPRINT_HPP_ + +#include "types.hpp" + +#include + +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ +/// @brief create the footprint of the given obstacles and their projection over a fixed time +/// horizon +/// @param [in] obstacles obstacles +/// @param [in] params parameters used to create the footprint +/// @param [in] hysteresis [m] extra lateral distance to add to the footprints +/// @return forward footprint of the obstacle +tier4_autoware_utils::MultiPolygon2d make_forward_footprints( + const std::vector & obstacles, + const PlannerParam & params, const double hysteresis); +/// @brief create the footprint of the given obstacle and its projection over a fixed time horizon +/// @param [in] obstacle obstacle +/// @param [in] params parameters used to create the footprint +/// @param [in] hysteresis [m] extra lateral distance to add to the footprint +/// @return forward footprint of the obstacle +tier4_autoware_utils::Polygon2d make_forward_footprint( + const autoware_auto_perception_msgs::msg::PredictedObject & obstacle, const PlannerParam & params, + const double hysteresis); +/// @brief project a footprint to the given pose +/// @param [in] base_footprint footprint to project +/// @param [in] pose projection pose +/// @return footprint projected to the given pose +tier4_autoware_utils::Polygon2d project_to_pose( + const tier4_autoware_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose); +/// @brief create the rtree indexing the ego footprint along the path +/// @param [inout] ego_data ego data with its path and the rtree to populate +/// @param [in] params parameters +void make_ego_footprint_rtree(EgoData & ego_data, const PlannerParam & params); +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // FOOTPRINT_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp new file mode 100644 index 0000000000000..99981007b20c2 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp @@ -0,0 +1,73 @@ +// 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 "manager.hpp" + +#include "scene_dynamic_obstacle_stop.hpp" + +#include + +#include + +namespace behavior_velocity_planner +{ +using tier4_autoware_utils::getOrDeclareParameter; + +DynamicObstacleStopModuleManager::DynamicObstacleStopModuleManager(rclcpp::Node & node) +: SceneModuleManagerInterface(node, getModuleName()), module_id_(0UL) +{ + const std::string ns(getModuleName()); + auto & pp = planner_param_; + + pp.extra_object_width = getOrDeclareParameter(node, ns + ".extra_object_width"); + pp.minimum_object_velocity = getOrDeclareParameter(node, ns + ".minimum_object_velocity"); + pp.stop_distance_buffer = getOrDeclareParameter(node, ns + ".stop_distance_buffer"); + pp.time_horizon = getOrDeclareParameter(node, ns + ".time_horizon"); + pp.hysteresis = getOrDeclareParameter(node, ns + ".hysteresis"); + pp.decision_duration_buffer = + getOrDeclareParameter(node, ns + ".decision_duration_buffer"); + pp.minimum_object_distance_from_ego_path = + getOrDeclareParameter(node, ns + ".minimum_object_distance_from_ego_path"); + + const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + pp.ego_lateral_offset = + std::max(std::abs(vehicle_info.min_lateral_offset_m), vehicle_info.max_lateral_offset_m); + pp.ego_longitudinal_offset = vehicle_info.max_longitudinal_offset_m; +} + +void DynamicObstacleStopModuleManager::launchNewModules( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path) +{ + if (path.points.empty()) return; + // general + if (!isModuleRegistered(module_id_)) { + registerModule(std::make_shared( + module_id_, planner_param_, logger_.get_child("dynamic_obstacle_stop_module"), clock_)); + } +} + +std::function &)> +DynamicObstacleStopModuleManager::getModuleExpiredFunction( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path) +{ + return [path]([[maybe_unused]] const std::shared_ptr & scene_module) { + return false; + }; +} +} // namespace behavior_velocity_planner + +#include +PLUGINLIB_EXPORT_CLASS( + behavior_velocity_planner::DynamicObstacleStopModulePlugin, + behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp new file mode 100644 index 0000000000000..e461cc9c16445 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp @@ -0,0 +1,58 @@ +// 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 MANAGER_HPP_ +#define MANAGER_HPP_ + +#include "scene_dynamic_obstacle_stop.hpp" + +#include +#include +#include +#include + +#include + +#include +#include +#include + +namespace behavior_velocity_planner +{ +class DynamicObstacleStopModuleManager : public SceneModuleManagerInterface +{ +public: + explicit DynamicObstacleStopModuleManager(rclcpp::Node & node); + + const char * getModuleName() override { return "dynamic_obstacle_stop"; } + +private: + using PlannerParam = dynamic_obstacle_stop::PlannerParam; + + PlannerParam planner_param_; + int64_t module_id_; + + void launchNewModules(const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override; + + std::function &)> getModuleExpiredFunction( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override; +}; + +class DynamicObstacleStopModulePlugin : public PluginWrapper +{ +}; + +} // namespace behavior_velocity_planner + +#endif // MANAGER_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp new file mode 100644 index 0000000000000..0411ab2d01cfe --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp @@ -0,0 +1,71 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "object_filtering.hpp" + +#include "types.hpp" + +#include + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ + +/// @brief filter the given predicted objects +/// @param objects predicted objects +/// @param ego_data ego data, including its path and pose +/// @param params parameters +/// @param hysteresis [m] extra distance threshold used for filtering +/// @return filtered predicted objects +std::vector filter_predicted_objects( + const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data, + const PlannerParam & params, const double hysteresis) +{ + std::vector filtered_objects; + const auto is_vehicle = [](const auto & o) { + return std::find_if(o.classification.begin(), o.classification.end(), [](const auto & c) { + return c.label == autoware_auto_perception_msgs::msg::ObjectClassification::CAR || + c.label == autoware_auto_perception_msgs::msg::ObjectClassification::BUS || + c.label == autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK || + c.label == autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER || + c.label == + autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE || + c.label == autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE; + }) != o.classification.end(); + }; + const auto is_in_range = [&](const auto & o) { + const auto distance = std::abs(motion_utils::calcLateralOffset( + ego_data.path.points, o.kinematics.initial_pose_with_covariance.pose.position)); + return distance <= params.minimum_object_distance_from_ego_path + params.ego_lateral_offset + + o.shape.dimensions.y / 2.0 + hysteresis; + }; + const auto is_not_too_close = [&](const auto & o) { + const auto obj_arc_length = motion_utils::calcSignedArcLength( + ego_data.path.points, ego_data.pose.position, + o.kinematics.initial_pose_with_covariance.pose.position); + return obj_arc_length > ego_data.longitudinal_offset_to_first_path_idx + + params.ego_longitudinal_offset + o.shape.dimensions.x / 2.0; + }; + for (const auto & object : objects.objects) + if ( + is_vehicle(object) && + object.kinematics.initial_twist_with_covariance.twist.linear.x >= + params.minimum_object_velocity && + is_in_range(object) && is_not_too_close(object)) + filtered_objects.push_back(object); + return filtered_objects; +} +} // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp new file mode 100644 index 0000000000000..22857f6db1bda --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp @@ -0,0 +1,39 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef OBJECT_FILTERING_HPP_ +#define OBJECT_FILTERING_HPP_ + +#include "types.hpp" + +#include + +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ + +/// @brief filter the given predicted objects +/// @param objects predicted objects +/// @param ego_data ego data, including its path and pose +/// @param params parameters +/// @param hysteresis [m] extra distance threshold used for filtering +/// @return filtered predicted objects +std::vector filter_predicted_objects( + const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data, + const PlannerParam & params, const double hysteresis); + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // OBJECT_FILTERING_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp new file mode 100644 index 0000000000000..98b7984bab1dc --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp @@ -0,0 +1,185 @@ +// Copyright 2023 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 "scene_dynamic_obstacle_stop.hpp" + +#include "collision.hpp" +#include "debug.hpp" +#include "footprint.hpp" +#include "object_filtering.hpp" +#include "types.hpp" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ + +using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; + +DynamicObstacleStopModule::DynamicObstacleStopModule( + const int64_t module_id, PlannerParam planner_param, const rclcpp::Logger & logger, + const rclcpp::Clock::SharedPtr clock) +: SceneModuleInterface(module_id, logger, clock), params_(std::move(planner_param)) +{ + prev_stop_decision_time_ = rclcpp::Time(int64_t{0}, clock->get_clock_type()); + velocity_factor_.init(PlanningBehavior::UNKNOWN); +} + +bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +{ + debug_data_.reset_data(); + *stop_reason = planning_utils::initializeStopReason(StopReason::OBSTACLE_STOP); + if (!path || path->points.size() < 2) return true; + tier4_autoware_utils::StopWatch stopwatch; + stopwatch.tic(); + + stopwatch.tic("preprocessing"); + EgoData ego_data; + ego_data.pose = planner_data_->current_odometry->pose; + ego_data.path.points = path->points; + motion_utils::removeOverlapPoints(ego_data.path.points); + ego_data.first_path_idx = + motion_utils::findNearestSegmentIndex(ego_data.path.points, ego_data.pose.position); + ego_data.longitudinal_offset_to_first_path_idx = motion_utils::calcLongitudinalOffsetToSegment( + ego_data.path.points, ego_data.first_path_idx, ego_data.pose.position); + + make_ego_footprint_rtree(ego_data, params_); + const auto has_decided_to_stop = + (clock_->now() - prev_stop_decision_time_).seconds() < params_.decision_duration_buffer; + if (!has_decided_to_stop) current_stop_pose_.reset(); + double hysteresis = has_decided_to_stop ? params_.hysteresis : 0.0; + const auto dynamic_obstacles = + filter_predicted_objects(*planner_data_->predicted_objects, ego_data, params_, hysteresis); + + const auto preprocessing_duration_us = stopwatch.toc("preprocessing"); + + stopwatch.tic("footprints"); + const auto obstacle_forward_footprints = + make_forward_footprints(dynamic_obstacles, params_, hysteresis); + const auto footprints_duration_us = stopwatch.toc("footprints"); + const auto min_stop_distance = + motion_utils::calcDecelDistWithJerkAndAccConstraints( + planner_data_->current_velocity->twist.linear.x, 0.0, + planner_data_->current_acceleration->accel.accel.linear.x, + planner_data_->max_stop_acceleration_threshold, -planner_data_->max_stop_jerk_threshold, + planner_data_->max_stop_jerk_threshold) + .value_or(0.0); + stopwatch.tic("collisions"); + const auto collision = + find_earliest_collision(ego_data, dynamic_obstacles, obstacle_forward_footprints, debug_data_); + const auto collisions_duration_us = stopwatch.toc("collisions"); + if (collision) { + const auto arc_length_diff = + motion_utils::calcSignedArcLength(ego_data.path.points, *collision, ego_data.pose.position); + const auto can_stop_before_limit = arc_length_diff < min_stop_distance - + params_.ego_longitudinal_offset - + params_.stop_distance_buffer; + const auto stop_pose = can_stop_before_limit + ? motion_utils::calcLongitudinalOffsetPose( + ego_data.path.points, *collision, + -params_.stop_distance_buffer - params_.ego_longitudinal_offset) + : motion_utils::calcLongitudinalOffsetPose( + ego_data.path.points, ego_data.pose.position, min_stop_distance); + if (stop_pose) { + const auto use_new_stop_pose = !has_decided_to_stop || motion_utils::calcSignedArcLength( + path->points, stop_pose->position, + current_stop_pose_->position) > 0.0; + if (use_new_stop_pose) current_stop_pose_ = *stop_pose; + prev_stop_decision_time_ = clock_->now(); + } + } + + if (current_stop_pose_) motion_utils::insertStopPoint(*current_stop_pose_, 0.0, path->points); + + const auto total_time_us = stopwatch.toc(); + RCLCPP_DEBUG( + logger_, + "Total time = %2.2fus\n\tpreprocessing = %2.2fus\n\tfootprints = " + "%2.2fus\n\tcollisions = %2.2fus\n", + total_time_us, preprocessing_duration_us, footprints_duration_us, collisions_duration_us); + debug_data_.ego_footprints = ego_data.path_footprints; + debug_data_.obstacle_footprints = obstacle_forward_footprints; + return true; +} + +MarkerArray DynamicObstacleStopModule::createDebugMarkerArray() +{ + constexpr auto z = 0.0; + MarkerArray debug_marker_array; + // dynamic obstacles footprints + const auto obstacle_footprint_markers = + debug::make_polygon_markers(debug_data_.obstacle_footprints, "dynamic_obstacles_footprints", z); + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), obstacle_footprint_markers.begin(), + obstacle_footprint_markers.end()); + const auto delete_footprint_markers = debug::make_delete_markers( + obstacle_footprint_markers.size(), debug_data_.prev_dynamic_obstacles_nb, + "dynamic_obstacles_footprints"); + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), delete_footprint_markers.begin(), + delete_footprint_markers.end()); + // ego path footprints + const auto ego_footprint_markers = + debug::make_polygon_markers(debug_data_.ego_footprints, "ego_footprints", z); + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), ego_footprint_markers.begin(), ego_footprint_markers.end()); + const auto delete_ego_footprint_markers = debug::make_delete_markers( + ego_footprint_markers.size(), debug_data_.prev_ego_footprints_nb, "ego_footprints"); + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), delete_ego_footprint_markers.begin(), + delete_ego_footprint_markers.end()); + // collisions + auto collision_markers = debug::make_polygon_markers(debug_data_.collisions, "collisions", z); + for (auto & m : collision_markers) m.color.r = 1.0; + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), collision_markers.begin(), collision_markers.end()); + const auto delete_collision_markers = debug::make_delete_markers( + collision_markers.size(), debug_data_.prev_collisions_nb, "collisions"); + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), delete_collision_markers.begin(), + delete_collision_markers.end()); + + debug_data_.prev_dynamic_obstacles_nb = obstacle_footprint_markers.size(); + debug_data_.prev_collisions_nb = collision_markers.size(); + debug_data_.prev_ego_footprints_nb = ego_footprint_markers.size(); + return debug_marker_array; +} + +motion_utils::VirtualWalls DynamicObstacleStopModule::createVirtualWalls() +{ + motion_utils::VirtualWalls virtual_walls{}; + if (current_stop_pose_) { + motion_utils::VirtualWall virtual_wall; + virtual_wall.text = "dynamic_obstacle_stop"; + virtual_wall.longitudinal_offset = params_.ego_longitudinal_offset; + virtual_wall.style = motion_utils::VirtualWallType::stop; + virtual_wall.pose = *current_stop_pose_; + virtual_walls.push_back(virtual_wall); + } + return virtual_walls; +} + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp new file mode 100644 index 0000000000000..c7bca149890a0 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp @@ -0,0 +1,62 @@ +// 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 SCENE_DYNAMIC_OBSTACLE_STOP_HPP_ +#define SCENE_DYNAMIC_OBSTACLE_STOP_HPP_ + +#include "types.hpp" + +#include +#include +#include + +#include +#include + +#include +#include +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ +class DynamicObstacleStopModule : public SceneModuleInterface +{ +public: + DynamicObstacleStopModule( + const int64_t module_id, PlannerParam planner_param, const rclcpp::Logger & logger, + const rclcpp::Clock::SharedPtr clock); + + /// @brief insert stop or slow down points to prevent dangerously entering another lane + /// @param [inout] path the path to update + /// @param [inout] stop_reason reason for stopping + bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + + visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; + motion_utils::VirtualWalls createVirtualWalls() override; + +private: + PlannerParam params_; + rclcpp::Time prev_stop_decision_time_; + std::optional current_stop_pose_; + +protected: + int64_t module_id_{}; + + // Debug + mutable DebugData debug_data_; +}; +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // SCENE_DYNAMIC_OBSTACLE_STOP_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp new file mode 100644 index 0000000000000..74fd5ca818fb0 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp @@ -0,0 +1,80 @@ +// 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 TYPES_HPP_ +#define TYPES_HPP_ + +#include + +#include +#include +#include + +#include + +#include +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ +typedef std::pair BoxIndexPair; +typedef boost::geometry::index::rtree> Rtree; + +/// @brief parameters for the "out of lane" module +struct PlannerParam +{ + double extra_object_width; + double minimum_object_velocity; + double stop_distance_buffer; + double time_horizon; + double hysteresis; + double decision_duration_buffer; + double ego_longitudinal_offset; + double ego_lateral_offset; + double minimum_object_distance_from_ego_path; +}; + +struct EgoData +{ + autoware_auto_planning_msgs::msg::PathWithLaneId path{}; + size_t first_path_idx{}; + double longitudinal_offset_to_first_path_idx; // [m] + geometry_msgs::msg::Pose pose; + tier4_autoware_utils::MultiPolygon2d path_footprints; + Rtree rtree; +}; + +/// @brief debug data +struct DebugData +{ + tier4_autoware_utils::MultiPolygon2d obstacle_footprints{}; + size_t prev_dynamic_obstacles_nb{}; + tier4_autoware_utils::MultiPolygon2d collisions{}; + size_t prev_collisions_nb{}; + tier4_autoware_utils::MultiPolygon2d ego_footprints{}; + size_t prev_ego_footprints_nb{}; + std::optional stop_pose{}; + void reset_data() + { + obstacle_footprints.clear(); + collisions.clear(); + ego_footprints.clear(); + stop_pose.reset(); + } +}; + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // TYPES_HPP_ diff --git a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml b/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml index 22220ccd182a1..c1631fdb739de 100644 --- a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml +++ b/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml @@ -26,6 +26,7 @@ + @@ -69,6 +70,7 @@ + From b566f84ab9e455c2c5ae163d12e797ab530688ce Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 10 Jan 2024 13:25:30 +0900 Subject: [PATCH 210/276] fix(map_loader): show traffic light regulatory element id per lanelet (#6028) * fix(map_loader): show traffic light regulatory element id per lanelet Signed-off-by: satoshi-ota * feat(map_loader): show traffic light id Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../lanelet2_map_loader/lanelet2_map_visualization_node.cpp | 6 ++++++ 1 file changed, 6 insertions(+) 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 e14defcb47f26..a0c57759d51a6 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 @@ -215,6 +215,12 @@ void Lanelet2MapVisualizationNode::onMapBin( insertMarkerArray( &map_marker_array, lanelet::visualization::autowareTrafficLightsAsMarkerArray(aw_tl_reg_elems, cl_trafficlights)); + insertMarkerArray( + &map_marker_array, lanelet::visualization::generateTrafficLightRegulatoryElementIdMaker( + road_lanelets, cl_trafficlights)); + insertMarkerArray( + &map_marker_array, lanelet::visualization::generateTrafficLightRegulatoryElementIdMaker( + crosswalk_lanelets, cl_trafficlights)); insertMarkerArray( &map_marker_array, lanelet::visualization::generateTrafficLightIdMaker(aw_tl_reg_elems, cl_trafficlights)); From cd54589bb395207e7d9ad272f99792d68c6c7da8 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 10 Jan 2024 14:10:43 +0900 Subject: [PATCH 211/276] fix(start_planner): don't update start pose when backward driving is finished (#5998) Fix conditional check in updatePullOutStatus function Signed-off-by: kyoichi-sugahara --- .../src/start_planner_module.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 9870a324caf64..66e04d7e9bb7a 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -839,8 +839,10 @@ void StartPlannerModule::updatePullOutStatus() return {*refined_start_pose}; }); - planWithPriority( - start_pose_candidates, *refined_start_pose, goal_pose, parameters_->search_priority); + if (!status_.backward_driving_complete) { + planWithPriority( + start_pose_candidates, *refined_start_pose, goal_pose, parameters_->search_priority); + } start_planner_data_.refined_start_pose = *refined_start_pose; start_planner_data_.start_pose_candidates = start_pose_candidates; From 1731cbd476209f5b4772de58389128ab064a1154 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 10 Jan 2024 15:16:13 +0900 Subject: [PATCH 212/276] docs(start_planner): update Purpose / Role of the document (#6002) Update Start Planner module to stop in response to dynamic obstacles Signed-off-by: kyoichi-sugahara --- .../README.md | 20 +++++++---- .../images/start_from_road_lane.drawio.svg | 34 ------------------- 2 files changed, 13 insertions(+), 41 deletions(-) delete mode 100644 planning/behavior_path_start_planner_module/images/start_from_road_lane.drawio.svg diff --git a/planning/behavior_path_start_planner_module/README.md b/planning/behavior_path_start_planner_module/README.md index f4aa3936bee56..2f90cc2ee3cf2 100644 --- a/planning/behavior_path_start_planner_module/README.md +++ b/planning/behavior_path_start_planner_module/README.md @@ -2,17 +2,23 @@ ## Purpose / Role -The Start Planner module is designed to generate a path from the current ego position to the driving lane, avoiding static obstacles and implementing safety checks against dynamic obstacles. (Note: The feature of safety checks against dynamic obstacles is currently a work in progress.) -This module is activated when a new route is received. +The Start Planner module is designed to generate a path from the current ego position to the driving lane, avoiding static obstacles and stopping in response to dynamic obstacles when a collision is detected. -Use cases are as follows +Use cases include: -- start smoothly from the current ego position to centerline. - ![case1](./images/start_from_road_lane.drawio.svg) - pull out from the side of the road lane to centerline. - ![case2](./images/start_from_road_side.drawio.svg) + +
+ ![case1](images/start_from_road_side.drawio.svg){width=1000} +
pull out from side of the road lane
+
+ - pull out from the shoulder lane to the road lane centerline. - ![case3](./images/start_from_road_shoulder.drawio.svg) + +
+ ![case2](images/start_from_start_from_road_shoulder.drawio.svg){width=1000} +
pull out from the shoulder lane
+
## Design diff --git a/planning/behavior_path_start_planner_module/images/start_from_road_lane.drawio.svg b/planning/behavior_path_start_planner_module/images/start_from_road_lane.drawio.svg deleted file mode 100644 index 7a89cc2183acf..0000000000000 --- a/planning/behavior_path_start_planner_module/images/start_from_road_lane.drawio.svg +++ /dev/null @@ -1,34 +0,0 @@ - - - - - - - - - - From 8e2f836448302794a7576c94ae5c2d8ced4254b0 Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Wed, 10 Jan 2024 21:23:04 +0900 Subject: [PATCH 213/276] refactor(motion_utils): clear the repeat definitions and correct the dependencies (#5909) * change .hpp name Signed-off-by: Zhe Shen * change .cpp name Signed-off-by: Zhe Shen * correct the #inlcude and #ifndef Signed-off-by: Zhe Shen * toPath(): move the prototypes and the implementations in .hpp and .cpp Signed-off-by: Zhe Shen * correct the dependency for /home/shen/autoware.universe/planning/behavior_path_planner/src/behavior_path_planner_node.cpp Signed-off-by: Zhe Shen * toPath(): deleted the repeat definition in planning_interface_test_manager_utils.hpp Signed-off-by: Zhe Shen * toPath(): corrected the call and dependency in planning_interface_test_manager.cpp Signed-off-by: Zhe Shen * convertPathToTrajectoryPoints(), convertTrajectoryPointsToPath(), lerpOrientation(): moved to conversion.hpp and conversion.cpp Signed-off-by: Zhe Shen * convertPathToTrajectoryPoints(): corrected the call and dependency Signed-off-by: Zhe Shen * convertTrajectoryPointsToPath(): Corrected the call Signed-off-by: Zhe Shen * lerpOrientation(): deleted the repeat definition in longitudinal_controller_utils.hpp and longitudinal_controller_utils.cpp Signed-off-by: Zhe Shen * lerpOrientation(): Correct the call in longitudinal_controller_utils.hpp Signed-off-by: Zhe Shen * lerpOrientation(): Corrected the dependency and call in test_longitudinal_controller_utils.cpp Signed-off-by: Zhe Shen * name of conversion.cpp: modified the CMakeLists Signed-off-by: Zhe Shen * namespace updated, but maybe not correct, will be tested in the next commit Signed-off-by: Zhe Shen * Correct the dependencies the test_trajectory.cpp and test_interpolation.cpp Signed-off-by: Zhe Shen * style(pre-commit): autofix * [namespace problems fixed] conversion.cpp & conversion.hpp: The dependencies have been added. Also, the namespaces have been corrected. Signed-off-by: Zhe Shen * style(pre-commit): autofix * correct all the dependencies in #include Signed-off-by: Zhe Shen * style(pre-commit): autofix * avoid using the ../../ in the paths Signed-off-by: Zhe Shen * dependencies fixed and package added in .xml Signed-off-by: Zhe Shen * style(pre-commit): autofix * change toPath() to convertToPath() Signed-off-by: Zhe Shen * lerpOrientation(): move from conversion to spherical_linear_interpolation Signed-off-by: Zhe Shen * style(pre-commit): autofix * fix the missing relative path definition. ../../ will not be used. Signed-off-by: Zhe Shen * the unneccessary dependencies eleminated. In specific, the lerpOrientation() related dependencies in coversion.hpp and unneccessary dependencies in conversion.cpp are deleted. Signed-off-by: Zhe Shen * change the function to template in .cpp and .hpp Signed-off-by: Zhe Shen * style(pre-commit): autofix * change the corresponding calls to template Signed-off-by: Zhe Shen * style(pre-commit): autofix * change name to convertToTrajectory() Signed-off-by: Zhe Shen * style(pre-commit): autofix * change the template of convertToPathWithLaneId() Signed-off-by: Zhe Shen * fix the dependencies Signed-off-by: Zhe Shen * refactor(motion_utils): specialize class Signed-off-by: satoshi-ota * fix(motion_utils): remove unnecessary header Signed-off-by: satoshi-ota --------- Signed-off-by: Zhe Shen Signed-off-by: satoshi-ota Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Co-authored-by: satoshi-ota --- .../spherical_linear_interpolation.hpp | 4 ++ .../src/spherical_linear_interpolation.cpp | 11 +++ .../motion_utils/trajectory/conversion.hpp | 71 +++++++++++++++++++ .../longitudinal_controller_utils.hpp | 12 +--- .../src/longitudinal_controller_utils.cpp | 10 --- .../test_longitudinal_controller_utils.cpp | 12 ++-- .../src/behavior_path_planner_node.cpp | 4 +- .../utils/path_utils.hpp | 2 - .../src/utils/path_utils.cpp | 13 ---- .../utilization/trajectory_utils.hpp | 5 -- .../src/utilization/trajectory_utils.cpp | 43 ++--------- .../planning_interface_test_manager_utils.hpp | 13 ---- planning/planning_test_utils/package.xml | 1 + .../src/planning_interface_test_manager.cpp | 6 +- 14 files changed, 111 insertions(+), 96 deletions(-) diff --git a/common/interpolation/include/interpolation/spherical_linear_interpolation.hpp b/common/interpolation/include/interpolation/spherical_linear_interpolation.hpp index 516b3ab09e8b7..8c1d49fb5f607 100644 --- a/common/interpolation/include/interpolation/spherical_linear_interpolation.hpp +++ b/common/interpolation/include/interpolation/spherical_linear_interpolation.hpp @@ -39,6 +39,10 @@ std::vector slerp( const std::vector & base_keys, const std::vector & base_values, const std::vector & query_keys); + +geometry_msgs::msg::Quaternion lerpOrientation( + const geometry_msgs::msg::Quaternion & o_from, const geometry_msgs::msg::Quaternion & o_to, + const double ratio); } // namespace interpolation #endif // INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_ diff --git a/common/interpolation/src/spherical_linear_interpolation.cpp b/common/interpolation/src/spherical_linear_interpolation.cpp index c3595d212f349..e44626498a80b 100644 --- a/common/interpolation/src/spherical_linear_interpolation.cpp +++ b/common/interpolation/src/spherical_linear_interpolation.cpp @@ -57,4 +57,15 @@ std::vector slerp( return query_values; } +geometry_msgs::msg::Quaternion lerpOrientation( + const geometry_msgs::msg::Quaternion & o_from, const geometry_msgs::msg::Quaternion & o_to, + const double ratio) +{ + tf2::Quaternion q_from, q_to; + tf2::fromMsg(o_from, q_from); + tf2::fromMsg(o_to, q_to); + + const auto q_interpolated = q_from.slerp(q_to, ratio); + return tf2::toMsg(q_interpolated); +} } // namespace interpolation diff --git a/common/motion_utils/include/motion_utils/trajectory/conversion.hpp b/common/motion_utils/include/motion_utils/trajectory/conversion.hpp index 6e77c1ec4a186..7d4be216e89fe 100644 --- a/common/motion_utils/include/motion_utils/trajectory/conversion.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/conversion.hpp @@ -15,6 +15,8 @@ #ifndef MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_ #define MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_ +#include "autoware_auto_planning_msgs/msg/detail/path__struct.hpp" +#include "autoware_auto_planning_msgs/msg/detail/path_with_lane_id__struct.hpp" #include "autoware_auto_planning_msgs/msg/detail/trajectory__struct.hpp" #include "autoware_auto_planning_msgs/msg/detail/trajectory_point__struct.hpp" #include "std_msgs/msg/header.hpp" @@ -23,6 +25,8 @@ namespace motion_utils { +using TrajectoryPoints = std::vector; + /** * @brief Convert std::vector to * autoware_auto_planning_msgs::msg::Trajectory. This function is temporarily added for porting to @@ -45,6 +49,73 @@ autoware_auto_planning_msgs::msg::Trajectory convertToTrajectory( std::vector convertToTrajectoryPointArray( const autoware_auto_planning_msgs::msg::Trajectory & trajectory); +template +autoware_auto_planning_msgs::msg::Path convertToPath([[maybe_unused]] const T & input) +{ + static_assert(sizeof(T) == 0, "Only specializations of convertToPath can be used."); + throw std::logic_error("Only specializations of convertToPath can be used."); +} + +template <> +inline autoware_auto_planning_msgs::msg::Path convertToPath( + const autoware_auto_planning_msgs::msg::PathWithLaneId & input) +{ + autoware_auto_planning_msgs::msg::Path output{}; + output.header = input.header; + output.left_bound = input.left_bound; + output.right_bound = input.right_bound; + output.points.resize(input.points.size()); + for (size_t i = 0; i < input.points.size(); ++i) { + output.points.at(i) = input.points.at(i).point; + } + return output; +} + +template +TrajectoryPoints convertToTrajectoryPoints([[maybe_unused]] const T & input) +{ + static_assert(sizeof(T) == 0, "Only specializations of convertToTrajectoryPoints can be used."); + throw std::logic_error("Only specializations of convertToTrajectoryPoints can be used."); +} + +template <> +inline TrajectoryPoints convertToTrajectoryPoints( + const autoware_auto_planning_msgs::msg::PathWithLaneId & input) +{ + TrajectoryPoints output{}; + for (const auto & p : input.points) { + autoware_auto_planning_msgs::msg::TrajectoryPoint tp; + tp.pose = p.point.pose; + tp.longitudinal_velocity_mps = p.point.longitudinal_velocity_mps; + // since path point doesn't have acc for now + tp.acceleration_mps2 = 0; + output.emplace_back(tp); + } + return output; +} + +template +autoware_auto_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId( + [[maybe_unused]] const T & input) +{ + static_assert(sizeof(T) == 0, "Only specializations of convertToPathWithLaneId can be used."); + throw std::logic_error("Only specializations of convertToPathWithLaneId can be used."); +} + +template <> +inline autoware_auto_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId( + const TrajectoryPoints & input) +{ + autoware_auto_planning_msgs::msg::PathWithLaneId output{}; + for (const auto & p : input) { + autoware_auto_planning_msgs::msg::PathPointWithLaneId pp; + pp.point.pose = p.pose; + pp.point.longitudinal_velocity_mps = p.longitudinal_velocity_mps; + output.points.emplace_back(pp); + } + return output; +} + } // namespace motion_utils #endif // MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_ diff --git a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp b/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp index 9c01f7bc26c4b..cc1c9c08887ba 100644 --- a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp +++ b/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp @@ -16,6 +16,8 @@ #define PID_LONGITUDINAL_CONTROLLER__LONGITUDINAL_CONTROLLER_UTILS_HPP_ #include "interpolation/linear_interpolation.hpp" +#include "interpolation/spherical_linear_interpolation.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "tf2/utils.h" @@ -74,14 +76,6 @@ Pose calcPoseAfterTimeDelay( const Pose & current_pose, const double delay_time, const double current_vel, const double current_acc); -/** - * @brief apply linear interpolation to orientation - * @param [in] o_from first orientation - * @param [in] o_to second orientation - * @param [in] ratio ratio between o_from and o_to for interpolation - */ -Quaternion lerpOrientation(const Quaternion & o_from, const Quaternion & o_to, const double ratio); - /** * @brief apply linear interpolation to trajectory point that is nearest to a certain point * @param [in] points trajectory points @@ -107,7 +101,7 @@ TrajectoryPoint lerpTrajectoryPoint( points.at(i).pose.position.x, points.at(i + 1).pose.position.x, interpolate_ratio); interpolated_point.pose.position.y = interpolation::lerp( points.at(i).pose.position.y, points.at(i + 1).pose.position.y, interpolate_ratio); - interpolated_point.pose.orientation = lerpOrientation( + interpolated_point.pose.orientation = interpolation::lerpOrientation( points.at(i).pose.orientation, points.at(i + 1).pose.orientation, interpolate_ratio); interpolated_point.longitudinal_velocity_mps = interpolation::lerp( points.at(i).longitudinal_velocity_mps, points.at(i + 1).longitudinal_velocity_mps, diff --git a/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp b/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp index 9791a1f0b5e3e..33a54663ccaef 100644 --- a/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp +++ b/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp @@ -141,16 +141,6 @@ double lerp(const double v_from, const double v_to, const double ratio) return v_from + (v_to - v_from) * ratio; } -Quaternion lerpOrientation(const Quaternion & o_from, const Quaternion & o_to, const double ratio) -{ - tf2::Quaternion q_from, q_to; - tf2::fromMsg(o_from, q_from); - tf2::fromMsg(o_to, q_to); - - const auto q_interpolated = q_from.slerp(q_to, ratio); - return tf2::toMsg(q_interpolated); -} - double applyDiffLimitFilter( const double input_val, const double prev_val, const double dt, const double max_val, const double min_val) diff --git a/control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp b/control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp index 5c7698180f82b..58aa867b2deab 100644 --- a/control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp +++ b/control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp @@ -13,6 +13,8 @@ // limitations under the License. #include "gtest/gtest.h" +#include "interpolation/spherical_linear_interpolation.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "pid_longitudinal_controller/longitudinal_controller_utils.hpp" #include "tf2/LinearMath/Quaternion.h" @@ -303,7 +305,7 @@ TEST(TestLongitudinalControllerUtils, lerpOrientation) o_to.setRPY(M_PI_4, M_PI_4, M_PI_4); ratio = 0.0; - result = longitudinal_utils::lerpOrientation(tf2::toMsg(o_from), tf2::toMsg(o_to), ratio); + result = interpolation::lerpOrientation(tf2::toMsg(o_from), tf2::toMsg(o_to), ratio); tf2::convert(result, o_result); tf2::Matrix3x3(o_result).getRPY(roll, pitch, yaw); EXPECT_DOUBLE_EQ(roll, 0.0); @@ -311,7 +313,7 @@ TEST(TestLongitudinalControllerUtils, lerpOrientation) EXPECT_DOUBLE_EQ(yaw, 0.0); ratio = 1.0; - result = longitudinal_utils::lerpOrientation(tf2::toMsg(o_from), tf2::toMsg(o_to), ratio); + result = interpolation::lerpOrientation(tf2::toMsg(o_from), tf2::toMsg(o_to), ratio); tf2::convert(result, o_result); tf2::Matrix3x3(o_result).getRPY(roll, pitch, yaw); EXPECT_DOUBLE_EQ(roll, M_PI_4); @@ -320,7 +322,7 @@ TEST(TestLongitudinalControllerUtils, lerpOrientation) ratio = 0.5; o_to.setRPY(M_PI_4, 0.0, 0.0); - result = longitudinal_utils::lerpOrientation(tf2::toMsg(o_from), tf2::toMsg(o_to), ratio); + result = interpolation::lerpOrientation(tf2::toMsg(o_from), tf2::toMsg(o_to), ratio); tf2::convert(result, o_result); tf2::Matrix3x3(o_result).getRPY(roll, pitch, yaw); EXPECT_DOUBLE_EQ(roll, M_PI_4 / 2); @@ -328,7 +330,7 @@ TEST(TestLongitudinalControllerUtils, lerpOrientation) EXPECT_DOUBLE_EQ(yaw, 0.0); o_to.setRPY(0.0, M_PI_4, 0.0); - result = longitudinal_utils::lerpOrientation(tf2::toMsg(o_from), tf2::toMsg(o_to), ratio); + result = interpolation::lerpOrientation(tf2::toMsg(o_from), tf2::toMsg(o_to), ratio); tf2::convert(result, o_result); tf2::Matrix3x3(o_result).getRPY(roll, pitch, yaw); EXPECT_DOUBLE_EQ(roll, 0.0); @@ -336,7 +338,7 @@ TEST(TestLongitudinalControllerUtils, lerpOrientation) EXPECT_DOUBLE_EQ(yaw, 0.0); o_to.setRPY(0.0, 0.0, M_PI_4); - result = longitudinal_utils::lerpOrientation(tf2::toMsg(o_from), tf2::toMsg(o_to), ratio); + result = interpolation::lerpOrientation(tf2::toMsg(o_from), tf2::toMsg(o_to), ratio); tf2::convert(result, o_result); tf2::Matrix3x3(o_result).getRPY(roll, pitch, yaw); EXPECT_DOUBLE_EQ(roll, 0.0); diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 12715520e1146..9b3fbedc37203 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -17,6 +17,7 @@ #include "behavior_path_planner_common/marker_utils/utils.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include #include @@ -700,7 +701,8 @@ Path BehaviorPathPlannerNode::convertToPath( return output; } - output = utils::toPath(*path_candidate_ptr); + output = motion_utils::convertToPath( + *path_candidate_ptr); // header is replaced by the input one, so it is substituted again output.header = planner_data->route_handler->getRouteHeader(); output.header.stamp = this->now(); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_utils.hpp index 4ac6f01da65fb..f109bb2cbb213 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_utils.hpp @@ -58,8 +58,6 @@ PathWithLaneId resamplePathWithSpline( const PathWithLaneId & path, const double interval, const bool keep_input_points = false, const std::pair target_section = {0.0, std::numeric_limits::max()}); -Path toPath(const PathWithLaneId & input); - size_t getIdxByArclength( const PathWithLaneId & path, const size_t target_idx, const double signed_arc); diff --git a/planning/behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner_common/src/utils/path_utils.cpp index 2eceb0ffb81c8..1d51426793de8 100644 --- a/planning/behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_utils.cpp @@ -155,19 +155,6 @@ PathWithLaneId resamplePathWithSpline( return motion_utils::resamplePath(path, s_out); } -Path toPath(const PathWithLaneId & input) -{ - Path output{}; - output.header = input.header; - output.left_bound = input.left_bound; - output.right_bound = input.right_bound; - output.points.resize(input.points.size()); - for (size_t i = 0; i < input.points.size(); ++i) { - output.points.at(i) = input.points.at(i).point; - } - return output; -} - size_t getIdxByArclength( const PathWithLaneId & path, const size_t target_idx, const double signed_arc) { diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/trajectory_utils.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/trajectory_utils.hpp index c86272cff1c2e..2184be4fbd2fe 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/trajectory_utils.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/trajectory_utils.hpp @@ -35,11 +35,6 @@ using TrajectoryPoints = std::vector; using geometry_msgs::msg::Quaternion; using TrajectoryPointWithIdx = std::pair; -TrajectoryPoints convertPathToTrajectoryPoints(const PathWithLaneId & path); -PathWithLaneId convertTrajectoryPointsToPath(const TrajectoryPoints & trajectory); - -Quaternion lerpOrientation(const Quaternion & o_from, const Quaternion & o_to, const double ratio); - //! smooth path point with lane id starts from ego position on path to the path end bool smoothPath( const PathWithLaneId & in_path, PathWithLaneId & out_path, diff --git a/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp b/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp index 7fe8612cc6858..314281a954b49 100644 --- a/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp +++ b/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp @@ -13,6 +13,8 @@ // limitations under the License. // #include +#include "motion_utils/trajectory/conversion.hpp" + #include #include #include @@ -41,41 +43,6 @@ using TrajectoryPoints = std::vector; using geometry_msgs::msg::Quaternion; using TrajectoryPointWithIdx = std::pair; -TrajectoryPoints convertPathToTrajectoryPoints(const PathWithLaneId & path) -{ - TrajectoryPoints tps; - for (const auto & p : path.points) { - TrajectoryPoint tp; - tp.pose = p.point.pose; - tp.longitudinal_velocity_mps = p.point.longitudinal_velocity_mps; - // since path point doesn't have acc for now - tp.acceleration_mps2 = 0; - tps.emplace_back(tp); - } - return tps; -} -PathWithLaneId convertTrajectoryPointsToPath(const TrajectoryPoints & trajectory) -{ - PathWithLaneId path; - for (const auto & p : trajectory) { - PathPointWithLaneId pp; - pp.point.pose = p.pose; - pp.point.longitudinal_velocity_mps = p.longitudinal_velocity_mps; - path.points.emplace_back(pp); - } - return path; -} - -Quaternion lerpOrientation(const Quaternion & o_from, const Quaternion & o_to, const double ratio) -{ - tf2::Quaternion q_from, q_to; - tf2::fromMsg(o_from, q_from); - tf2::fromMsg(o_to, q_to); - - const auto q_interpolated = q_from.slerp(q_to, ratio); - return tf2::toMsg(q_interpolated); -} - //! smooth path point with lane id starts from ego position on path to the path end bool smoothPath( const PathWithLaneId & in_path, PathWithLaneId & out_path, @@ -87,7 +54,9 @@ bool smoothPath( const auto & external_v_limit = planner_data->external_velocity_limit; const auto & smoother = planner_data->velocity_smoother_; - auto trajectory = convertPathToTrajectoryPoints(in_path); + auto trajectory = + motion_utils::convertToTrajectoryPoints( + in_path); const auto traj_lateral_acc_filtered = smoother->applyLateralAccelerationFilter(trajectory); const auto traj_steering_rate_limited = @@ -117,7 +86,7 @@ bool smoothPath( motion_velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); } - out_path = convertTrajectoryPointsToPath(traj_smoothed); + out_path = motion_utils::convertToPathWithLaneId(traj_smoothed); return true; } diff --git a/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp b/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp index 4d8d7be96b44b..371a6316ce993 100644 --- a/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp +++ b/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp @@ -492,19 +492,6 @@ void updateNodeOptions( node_options.arguments(std::vector{arguments.begin(), arguments.end()}); } -Path toPath(const PathWithLaneId & input) -{ - Path output{}; - output.header = input.header; - output.left_bound = input.left_bound; - output.right_bound = input.right_bound; - output.points.resize(input.points.size()); - for (size_t i = 0; i < input.points.size(); ++i) { - output.points.at(i) = input.points.at(i).point; - } - return output; -} - PathWithLaneId loadPathWithLaneIdInYaml() { const auto planning_test_utils_dir = diff --git a/planning/planning_test_utils/package.xml b/planning/planning_test_utils/package.xml index 23bfb2f44cb96..278813818de0d 100644 --- a/planning/planning_test_utils/package.xml +++ b/planning/planning_test_utils/package.xml @@ -23,6 +23,7 @@ component_interface_utils lanelet2_extension lanelet2_io + motion_utils nav_msgs rclcpp route_handler diff --git a/planning/planning_test_utils/src/planning_interface_test_manager.cpp b/planning/planning_test_utils/src/planning_interface_test_manager.cpp index a9d096bf00fd4..0a6b4246348eb 100644 --- a/planning/planning_test_utils/src/planning_interface_test_manager.cpp +++ b/planning/planning_test_utils/src/planning_interface_test_manager.cpp @@ -12,6 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "motion_utils/trajectory/conversion.hpp" + #include #include @@ -289,7 +291,9 @@ void PlanningInterfaceTestManager::publishNominalPath( { test_utils::publishToTargetNode( test_node_, target_node, topic_name, normal_path_pub_, - test_utils::toPath(test_utils::loadPathWithLaneIdInYaml()), 5); + motion_utils::convertToPath( + test_utils::loadPathWithLaneIdInYaml()), + 5); } void PlanningInterfaceTestManager::publishAbnormalPath( From dfef78b07dfefc107f1199a566e0826f610c0842 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 10 Jan 2024 22:57:35 +0900 Subject: [PATCH 214/276] fix(static_drivable_area_expansion): fix bound extraction logic (#6006) * fix(static_drivable_area_expansion): fix bound extraction logic Signed-off-by: satoshi-ota * refactor(static_drivable_area_expansion): define as anon func Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../static_drivable_area.cpp | 66 ++++++++++--------- 1 file changed, 35 insertions(+), 31 deletions(-) diff --git a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 1aa55e5f350b3..44c3025a8c5d5 100644 --- a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -148,6 +148,40 @@ geometry_msgs::msg::Point calcLongitudinalOffsetGoalPoint( return offset_point ? offset_point.value() : points.at(nearest_segment_idx + 1); } + +std::vector extractBoundFromPolygon( + const lanelet::ConstPolygon3d & polygon, const size_t start_idx, const size_t end_idx, + const bool clockwise) +{ + std::vector ret{}; + for (size_t i = start_idx; i != end_idx; i = clockwise ? i + 1 : i - 1) { + ret.push_back(polygon[i]); + + if (i + 1 == polygon.size() && clockwise) { + if (end_idx == 0) { + ret.push_back(polygon[end_idx]); + return ret; + } + i = 0; + ret.push_back(polygon[i]); + continue; + } + + if (i == 0 && !clockwise) { + if (end_idx == polygon.size() - 1) { + ret.push_back(polygon[end_idx]); + return ret; + } + i = polygon.size() - 1; + ret.push_back(polygon[i]); + continue; + } + } + + ret.push_back(polygon[end_idx]); + + return ret; +} } // namespace namespace behavior_path_planner::utils::drivable_area_processing @@ -1261,36 +1295,6 @@ std::vector getBoundWithIntersectionAreas( const std::shared_ptr & route_handler, const std::vector & drivable_lanes, const bool is_left) { - const auto extract_bound_from_polygon = - [](const auto & polygon, const auto start_idx, const auto end_idx, const auto clockwise) { - std::vector ret{}; - for (size_t i = start_idx; i != end_idx; i = clockwise ? i + 1 : i - 1) { - ret.push_back(polygon[i]); - - if (i + 1 == polygon.size() && clockwise) { - if (end_idx == 0) { - ret.push_back(polygon[end_idx]); - return ret; - } - i = 0; - continue; - } - - if (i == 0 && !clockwise) { - if (end_idx == polygon.size() - 1) { - ret.push_back(polygon[end_idx]); - return ret; - } - i = polygon.size() - 1; - continue; - } - } - - ret.push_back(polygon[end_idx]); - - return ret; - }; - std::vector expanded_bound = original_bound; // expand drivable area by using intersection area. @@ -1336,7 +1340,7 @@ std::vector getBoundWithIntersectionAreas( const size_t end_idx = std::distance(polygon.begin(), intersection_bound_itr_last); intersection_bound = - extract_bound_from_polygon(polygon, start_idx, end_idx, is_clockwise_iteration); + extractBoundFromPolygon(polygon, start_idx, end_idx, is_clockwise_iteration); } // Step2. check shared bound point. From 69b294a1308d28f10722bdcc102c3499a14b62ef Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 11 Jan 2024 00:32:30 +0900 Subject: [PATCH 215/276] feat(avoidance): check traffic light info in order to limit drivable area (#6016) * feat(avoidance): don't use opposite lane before intersection Signed-off-by: satoshi-ota * feat(avoidance): check traffic light info in order to limit drivable area Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/scene.cpp | 2 +- .../behavior_path_avoidance_module/utils.hpp | 2 +- .../src/scene.cpp | 6 ++++-- .../src/utils.cpp | 12 ++++++++++- .../utils/traffic_light_utils.hpp | 15 ++++++++++++++ .../src/utils/traffic_light_utils.cpp | 20 +++++++++++++++++++ 6 files changed, 52 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 66d11d044966e..b76a9e5645b48 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -166,7 +166,7 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData( std::for_each( data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) { data.drivable_lanes.push_back(utils::avoidance::generateExpandDrivableLanes( - lanelet, planner_data_, avoidance_parameters_)); + lanelet, planner_data_, avoidance_parameters_, false)); }); // calc drivable bound diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp index 4508cbc3c18f6..dc602edcc8b86 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp @@ -163,7 +163,7 @@ std::pair separateObjectsByPath( DrivableLanes generateExpandDrivableLanes( const lanelet::ConstLanelet & lanelet, const std::shared_ptr & planner_data, - const std::shared_ptr & parameters); + const std::shared_ptr & parameters, const bool in_avoidance_maneuver); double calcDistanceToReturnDeadLine( const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 31849c716971c..9d7f5cc459e9e 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -223,10 +223,12 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat utils::avoidance::getExtendLanes(data.current_lanelets, getEgoPose(), planner_data_); // expand drivable lanes + const auto has_shift_point = !path_shifter_.getShiftLines().empty(); + const auto in_avoidance_maneuver = has_shift_point || helper_->isShifted(); std::for_each( data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) { - data.drivable_lanes.push_back( - utils::avoidance::generateExpandDrivableLanes(lanelet, planner_data_, parameters_)); + data.drivable_lanes.push_back(utils::avoidance::generateExpandDrivableLanes( + lanelet, planner_data_, parameters_, in_avoidance_maneuver)); }); // calc drivable bound diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index 493ca35f09a3b..83e96d83b995f 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -1953,7 +1953,7 @@ std::pair separateObjectsByPath( DrivableLanes generateExpandDrivableLanes( const lanelet::ConstLanelet & lanelet, const std::shared_ptr & planner_data, - const std::shared_ptr & parameters) + const std::shared_ptr & parameters, const bool in_avoidance_maneuver) { const auto & route_handler = planner_data->route_handler; @@ -1967,6 +1967,11 @@ DrivableLanes generateExpandDrivableLanes( // 1. get left/right side lanes const auto update_left_lanelets = [&](const lanelet::ConstLanelet & target_lane) { + const auto next_lanes = route_handler->getNextLanelets(target_lane); + const auto is_stop_signal = utils::traffic_light::isTrafficSignalStop(next_lanes, planner_data); + if (is_stop_signal && !in_avoidance_maneuver) { + return; + } const auto all_left_lanelets = route_handler->getAllLeftSharedLinestringLanelets( target_lane, parameters->use_opposite_lane, true); if (!all_left_lanelets.empty()) { @@ -1977,6 +1982,11 @@ DrivableLanes generateExpandDrivableLanes( } }; const auto update_right_lanelets = [&](const lanelet::ConstLanelet & target_lane) { + const auto next_lanes = route_handler->getNextLanelets(target_lane); + const auto is_stop_signal = utils::traffic_light::isTrafficSignalStop(next_lanes, planner_data); + if (is_stop_signal && !in_avoidance_maneuver) { + return; + } const auto all_right_lanelets = route_handler->getAllRightSharedLinestringLanelets( target_lane, parameters->use_opposite_lane, true); if (!all_right_lanelets.empty()) { diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/traffic_light_utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/traffic_light_utils.hpp index 6380830806c33..62fd87bbd91bc 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/traffic_light_utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/traffic_light_utils.hpp @@ -92,6 +92,21 @@ bool isStoppedAtRedTrafficLightWithinDistance( const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, const std::shared_ptr & planner_data, const double distance_threshold = std::numeric_limits::infinity()); + +/** + * @brief Determines if a traffic signal indicates a stop for the given lanelet. + * + * Evaluates the current state of the traffic light, considering if it's green or unknown, + * which would not necessitate a stop. Then, it checks the turn direction attribute of the lanelet + * against the traffic light's arrow shapes to determine whether a vehicle must stop or if it can + * proceed based on allowed turn directions. + * + * @param lanelet The lanelet to check for a stop signal at its traffic light. + * @param planner_data Shared pointer to the planner data containing vehicle state information. + * @return True if the traffic signal indicates a stop is required, false otherwise. + */ +bool isTrafficSignalStop( + const lanelet::ConstLanelets & lanelets, const std::shared_ptr & planner_data); } // namespace behavior_path_planner::utils::traffic_light #endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__TRAFFIC_LIGHT_UTILS_HPP_ diff --git a/planning/behavior_path_planner_common/src/utils/traffic_light_utils.cpp b/planning/behavior_path_planner_common/src/utils/traffic_light_utils.cpp index f77fafb42d829..ecd02bfd63485 100644 --- a/planning/behavior_path_planner_common/src/utils/traffic_light_utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/traffic_light_utils.cpp @@ -127,4 +127,24 @@ bool isStoppedAtRedTrafficLightWithinDistance( return (distance_to_red_traffic_light < distance_threshold); } +bool isTrafficSignalStop( + const lanelet::ConstLanelets & lanelets, const std::shared_ptr & planner_data) +{ + for (const auto & lanelet : lanelets) { + for (const auto & element : lanelet.regulatoryElementsAs()) { + const auto traffic_signal_stamped = planner_data->getTrafficSignal(element->id()); + if (!traffic_signal_stamped.has_value()) { + continue; + } + + if (traffic_light_utils::isTrafficSignalStop( + lanelet, traffic_signal_stamped.value().signal)) { + return true; + } + } + } + + return false; +} + } // namespace behavior_path_planner::utils::traffic_light From cdce59fabba9c0745595789cfe9dbe7a6d28e684 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 11 Jan 2024 01:39:06 +0900 Subject: [PATCH 216/276] fix(avoidance): return shift path was not generated expectedly (#6017) fix(avoidance): output return shift path properly Signed-off-by: satoshi-ota --- planning/behavior_path_avoidance_module/src/scene.cpp | 3 ++- .../src/shift_line_generator.cpp | 8 +++++--- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 9d7f5cc459e9e..61941eeee6f00 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -1390,7 +1390,8 @@ void AvoidanceModule::insertReturnDeadLine( shifted_path.path.points, getEgoPosition(), shifted_path.path.points.size() - 1); const auto buffer = std::max(0.0, to_shifted_path_end - to_reference_path_end); - const auto min_return_distance = helper_->getMinAvoidanceDistance(shift_length); + const auto min_return_distance = + helper_->getMinAvoidanceDistance(shift_length) + helper_->getMinimumPrepareDistance(); const auto to_stop_line = data.to_return_point - min_return_distance - buffer; // If we don't need to consider deceleration constraints, insert a deceleration point diff --git a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index 8ed56ce9aff4d..dabb0d7257555 100644 --- a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -1101,12 +1101,14 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( const double variable_prepare_distance = std::max(nominal_prepare_distance - last_sl_distance, 0.0); - double prepare_distance_scaled = std::max(nominal_prepare_distance, last_sl_distance); + double prepare_distance_scaled = + std::clamp(nominal_prepare_distance, helper_->getMinimumPrepareDistance(), last_sl_distance); double avoid_distance_scaled = nominal_avoid_distance; if (remaining_distance < prepare_distance_scaled + avoid_distance_scaled) { const auto scale = (remaining_distance - last_sl_distance) / std::max(nominal_avoid_distance + variable_prepare_distance, 0.1); - prepare_distance_scaled = last_sl_distance + scale * nominal_prepare_distance; + prepare_distance_scaled = std::max( + helper_->getMinimumPrepareDistance(), last_sl_distance + scale * nominal_prepare_distance); avoid_distance_scaled *= scale; } @@ -1219,7 +1221,7 @@ AvoidLineArray ShiftLineGenerator::findNewShiftLine( const auto & candidate = shift_lines.at(i); // prevent sudden steering. - if (candidate.start_longitudinal < helper_->getMinimumPrepareDistance()) { + if (candidate.start_longitudinal + 1e-3 < helper_->getMinimumPrepareDistance()) { break; } From 933add3b576bdd90bbc5107fad01e8de82aa9b16 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 11 Jan 2024 01:58:37 +0900 Subject: [PATCH 217/276] refactor(ndt_scan_matcher): fixed ndt_scan_matcher.launch.xml (#6041) Fixed ndt_scan_matcher.launch.xml Signed-off-by: Shintaro Sakoda --- .../ndt_scan_matcher.launch.xml | 7 +++++-- .../launch/ndt_scan_matcher.launch.xml | 16 ++++++++-------- 2 files changed, 13 insertions(+), 10 deletions(-) diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/ndt_scan_matcher.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/ndt_scan_matcher.launch.xml index e4b04d3d4a32e..bee300c587816 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/ndt_scan_matcher.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/ndt_scan_matcher.launch.xml @@ -2,13 +2,16 @@ - - + + + + + diff --git a/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml b/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml index 891d172aaf8fd..cbcb0a9f74bc4 100644 --- a/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml +++ b/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml @@ -2,27 +2,27 @@ - - - + + + - + - - + + + - - + From 23eaf2e7387fa4e7a17634b2d2b7a16834ba36ae Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 11 Jan 2024 03:35:07 +0900 Subject: [PATCH 218/276] feat(behavior_velocity): add the option to keep the last valid observation (#6036) * feat(behavior_velocity): add the option to keep the last valid observation Signed-off-by: Mamoru Sobue * keep_last_observation is false by default and intersection/traffic_light is explicily true Signed-off-by: Mamoru Sobue * for intersection Signed-off-by: Mamoru Sobue --------- Signed-off-by: Mamoru Sobue --- .../src/scene_crosswalk.cpp | 9 +++--- .../src/scene_intersection.cpp | 31 +++++++++---------- .../src/scene_intersection.hpp | 9 ++++-- .../behavior_velocity_planner/src/node.cpp | 16 +++++++++- .../planner_data.hpp | 19 +++++++++--- .../src/scene.cpp | 8 ++--- 6 files changed, 60 insertions(+), 32 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 0dc7b78b6fe46..7175cd0895fc0 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -1055,19 +1055,20 @@ bool CrosswalkModule::isRedSignalForPedestrians() const crosswalk_.regulatoryElementsAs(); for (const auto & traffic_lights_reg_elem : traffic_lights_reg_elems) { - const auto traffic_signal_stamped = + const auto traffic_signal_stamped_opt = planner_data_->getTrafficSignal(traffic_lights_reg_elem->id()); - if (!traffic_signal_stamped) { + if (!traffic_signal_stamped_opt) { continue; } + const auto traffic_signal_stamped = traffic_signal_stamped_opt.value(); if ( planner_param_.traffic_light_state_timeout < - (clock_->now() - traffic_signal_stamped->stamp).seconds()) { + (clock_->now() - traffic_signal_stamped.stamp).seconds()) { continue; } - const auto & lights = traffic_signal_stamped->signal.elements; + const auto & lights = traffic_signal_stamped.signal.elements; if (lights.empty()) { continue; } diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 292a6e6a8843d..b6201057f5e23 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -940,12 +940,11 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason * return true; } -static bool isGreenSolidOn( - lanelet::ConstLanelet lane, const std::map & tl_infos) +bool IntersectionModule::isGreenSolidOn(lanelet::ConstLanelet lane) { using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement; - std::optional tl_id = std::nullopt; + std::optional tl_id = std::nullopt; for (auto && tl_reg_elem : lane.regulatoryElementsAs()) { tl_id = tl_reg_elem->id(); break; @@ -954,12 +953,13 @@ static bool isGreenSolidOn( // this lane has no traffic light return false; } - const auto tl_info_it = tl_infos.find(tl_id.value()); - if (tl_info_it == tl_infos.end()) { + const auto tl_info_opt = planner_data_->getTrafficSignal( + tl_id.value(), true /* traffic light module keeps last observation*/); + if (!tl_info_opt) { // the info of this traffic light is not available return false; } - const auto & tl_info = tl_info_it->second; + const auto & tl_info = tl_info_opt.value(); for (auto && tl_light : tl_info.signal.elements) { if ( tl_light.color == TrafficSignalElement::GREEN && @@ -1004,8 +1004,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // at the very first time of regisTration of this module, the path may not be conflicting with the // attention area, so update() is called to update the internal data as well as traffic light info - const auto traffic_prioritized_level = - getTrafficPrioritizedLevel(assigned_lanelet, planner_data_->traffic_light_id_map); + const auto traffic_prioritized_level = getTrafficPrioritizedLevel(assigned_lanelet); const bool is_prioritized = traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED; intersection_lanelets.update(is_prioritized, interpolated_path_info, footprint, baselink2front); @@ -1259,8 +1258,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // If there are any vehicles on the attention area when ego entered the intersection on green // light, do pseudo collision detection because the vehicles are very slow and no collisions may // be detected. check if ego vehicle entered assigned lanelet - const bool is_green_solid_on = - isGreenSolidOn(assigned_lanelet, planner_data_->traffic_light_id_map); + const bool is_green_solid_on = isGreenSolidOn(assigned_lanelet); if (is_green_solid_on) { if (!initial_green_light_observed_time_) { const auto assigned_lane_begin_point = assigned_lanelet.centerline().front(); @@ -1413,12 +1411,11 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } } -TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel( - lanelet::ConstLanelet lane, const std::map & tl_infos) +TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel(lanelet::ConstLanelet lane) { using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement; - std::optional tl_id = std::nullopt; + std::optional tl_id = std::nullopt; for (auto && tl_reg_elem : lane.regulatoryElementsAs()) { tl_id = tl_reg_elem->id(); break; @@ -1427,12 +1424,12 @@ TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel( // this lane has no traffic light return TrafficPrioritizedLevel::NOT_PRIORITIZED; } - const auto tl_info_it = tl_infos.find(tl_id.value()); - if (tl_info_it == tl_infos.end()) { - // the info of this traffic light is not available + const auto tl_info_opt = planner_data_->getTrafficSignal( + tl_id.value(), true /* traffic light module keeps last observation*/); + if (!tl_info_opt) { return TrafficPrioritizedLevel::NOT_PRIORITIZED; } - const auto & tl_info = tl_info_it->second; + const auto & tl_info = tl_info_opt.value(); bool has_amber_signal{false}; for (auto && tl_light : tl_info.signal.elements) { if (tl_light.color == TrafficSignalElement::AMBER) { diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 6a350e66706e6..d533c7316b264 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -631,8 +631,7 @@ class IntersectionModule : public SceneModuleInterface * @fn * @brief find TrafficPrioritizedLevel */ - TrafficPrioritizedLevel getTrafficPrioritizedLevel( - lanelet::ConstLanelet lane, const std::map & tl_infos); + TrafficPrioritizedLevel getTrafficPrioritizedLevel(lanelet::ConstLanelet lane); /** * @fn @@ -738,6 +737,12 @@ class IntersectionModule : public SceneModuleInterface const std::vector & lane_divisions, const TargetObjects & target_objects); + /* + * @fn + * @brief check if associated traffic light is green + */ + bool isGreenSolidOn(lanelet::ConstLanelet lane); + /* bool IntersectionModule::checkFrontVehicleDeceleration( lanelet::ConstLanelets & ego_lane_with_next_lane, lanelet::ConstLanelet & closest_lanelet, diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index 8ecad4d9c1548..e2c29ef868257 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -327,7 +327,21 @@ void BehaviorVelocityPlannerNode::onTrafficSignals( TrafficSignalStamped traffic_signal; traffic_signal.stamp = msg->stamp; traffic_signal.signal = signal; - planner_data_.traffic_light_id_map[signal.traffic_signal_id] = traffic_signal; + planner_data_.traffic_light_id_map_raw_[signal.traffic_signal_id] = traffic_signal; + const bool is_unknown_observation = + std::any_of(signal.elements.begin(), signal.elements.end(), [](const auto & element) { + return element.color == autoware_perception_msgs::msg::TrafficSignalElement::UNKNOWN; + }); + // if the observation is UNKNOWN and past observation is available, only update the timestamp + // and keep the body of the info + if ( + is_unknown_observation && + planner_data_.traffic_light_id_map_last_observed_.count(signal.traffic_signal_id) == 1) { + planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id].stamp = + msg->stamp; + } else { + planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id] = traffic_signal; + } } } diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp index 2ea9f6ed2648b..606e41ad4b1d1 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp @@ -76,7 +76,10 @@ struct PlannerData double ego_nearest_yaw_threshold; // other internal data - std::map traffic_light_id_map; + // traffic_light_id_map_raw is the raw observation, while traffic_light_id_map_keep_last keeps the + // last observed infomation for UNKNOWN + std::map traffic_light_id_map_raw_; + std::map traffic_light_id_map_last_observed_; std::optional external_velocity_limit; tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states; @@ -125,12 +128,20 @@ struct PlannerData return true; } - std::shared_ptr getTrafficSignal(const int id) const + /** + *@fn + *@brief queries the traffic signal information of given Id. if keep_last_observation = true, + *recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation + */ + std::optional getTrafficSignal( + const lanelet::Id id, const bool keep_last_observation = false) const { + const auto & traffic_light_id_map = + keep_last_observation ? traffic_light_id_map_last_observed_ : traffic_light_id_map_raw_; if (traffic_light_id_map.count(id) == 0) { - return {}; + return std::nullopt; } - return std::make_shared(traffic_light_id_map.at(id)); + return std::make_optional(traffic_light_id_map.at(id)); } }; } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp index a17fc43b86f23..9982ec34c4bca 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp @@ -353,15 +353,15 @@ bool TrafficLightModule::isPassthrough(const double & signed_arc_length) const bool TrafficLightModule::findValidTrafficSignal(TrafficSignalStamped & valid_traffic_signal) const { // get traffic signal associated with the regulatory element id - const auto traffic_signal_stamped = planner_data_->getTrafficSignal(traffic_light_reg_elem_.id()); - if (!traffic_signal_stamped) { + const auto traffic_signal_stamped_opt = planner_data_->getTrafficSignal( + traffic_light_reg_elem_.id(), true /* traffic light module keeps last observation */); + if (!traffic_signal_stamped_opt) { RCLCPP_WARN_THROTTLE( logger_, *clock_, 5000 /* ms */, "the traffic signal data associated with regulatory element id is not received"); return false; } - - valid_traffic_signal = *traffic_signal_stamped; + valid_traffic_signal = traffic_signal_stamped_opt.value(); return true; } From dbbfb7d4bfa466238b98ca5f54e17b5a4581243b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 11 Jan 2024 04:56:03 +0900 Subject: [PATCH 219/276] feat(intersection): distinguish 1st/2nd attention lanelet (#6042) --- .../src/debug.cpp | 16 ++ .../src/scene_intersection.cpp | 137 ++++++++++++++---- .../src/scene_intersection.hpp | 44 +++++- 3 files changed, 159 insertions(+), 38 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_intersection_module/src/debug.cpp index 83e218185a5ad..5f103e0ecd3b0 100644 --- a/planning/behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_intersection_module/src/debug.cpp @@ -188,6 +188,22 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray( &debug_marker_array); } + if (debug_data_.first_attention_area) { + appendMarkerArray( + createLaneletPolygonsMarkerArray( + {debug_data_.first_attention_area.value()}, "first_attention_area", lane_id_, 1, 0.647, + 0.0), + &debug_marker_array, now); + } + + if (debug_data_.second_attention_area) { + appendMarkerArray( + createLaneletPolygonsMarkerArray( + {debug_data_.second_attention_area.value()}, "second_attention_area", lane_id_, 1, 0.647, + 0.0), + &debug_marker_array, now); + } + if (debug_data_.stuck_vehicle_detect_area) { appendMarkerArray( debug::createPolygonMarkerArray( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index b6201057f5e23..1bc7bfe04d271 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1007,7 +1007,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto traffic_prioritized_level = getTrafficPrioritizedLevel(assigned_lanelet); const bool is_prioritized = traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED; - intersection_lanelets.update(is_prioritized, interpolated_path_info, footprint, baselink2front); + intersection_lanelets.update( + is_prioritized, interpolated_path_info, footprint, baselink2front, routing_graph_ptr); // this is abnormal const auto & conflicting_lanelets = intersection_lanelets.conflicting(); @@ -1018,6 +1019,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } const auto & first_conflicting_lane = first_conflicting_lane_opt.value(); const auto & first_conflicting_area = first_conflicting_area_opt.value(); + const auto & second_attention_area_opt = intersection_lanelets.second_attention_area(); // generate all stop line candidates // see the doc for struct IntersectionStopLines @@ -1028,16 +1030,20 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( : first_conflicting_lane; const auto intersection_stoplines_opt = generateIntersectionStopLines( - assigned_lanelet, first_conflicting_area, dummy_first_attention_lane, interpolated_path_info, - path); + assigned_lanelet, first_conflicting_area, dummy_first_attention_lane, second_attention_area_opt, + interpolated_path_info, path); if (!intersection_stoplines_opt) { return IntersectionModule::Indecisive{"failed to generate intersection_stoplines"}; } const auto & intersection_stoplines = intersection_stoplines_opt.value(); - const auto - [closest_idx, stuck_stopline_idx_opt, default_stopline_idx_opt, - first_attention_stopline_idx_opt, occlusion_peeking_stopline_idx_opt, - default_pass_judge_line_idx, occlusion_wo_tl_pass_judge_line_idx] = intersection_stoplines; + const auto closest_idx = intersection_stoplines.closest_idx; + const auto stuck_stopline_idx_opt = intersection_stoplines.stuck_stopline; + const auto default_stopline_idx_opt = intersection_stoplines.default_stopline; + const auto first_attention_stopline_idx_opt = intersection_stoplines.first_attention_stopline; + const auto occlusion_peeking_stopline_idx_opt = intersection_stoplines.occlusion_peeking_stopline; + const auto default_pass_judge_line_idx = intersection_stoplines.first_pass_judge_line; + const auto occlusion_wo_tl_pass_judge_line_idx = + intersection_stoplines.occlusion_wo_tl_pass_judge_line; // see the doc for struct PathLanelets const auto & first_attention_area_opt = intersection_lanelets.first_attention_area(); @@ -1146,6 +1152,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( debug_data_.attention_area = intersection_lanelets.attention_area(); debug_data_.occlusion_attention_area = occlusion_attention_area; debug_data_.adjacent_area = intersection_lanelets.adjacent_area(); + debug_data_.first_attention_area = intersection_lanelets.first_attention_area(); + debug_data_.second_attention_area = intersection_lanelets.second_attention_area(); // check occlusion on detection lane if (!occlusion_attention_divisions_) { @@ -1659,6 +1667,7 @@ IntersectionLanelets IntersectionModule::getObjectiveLanelets( std::optional IntersectionModule::generateIntersectionStopLines( lanelet::ConstLanelet assigned_lanelet, const lanelet::CompoundPolygon3d & first_conflicting_area, const lanelet::ConstLanelet & first_attention_lane, + const std::optional & second_attention_area_opt, const util::InterpolatedPathInfo & interpolated_path_info, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path) { @@ -1680,15 +1689,16 @@ std::optional IntersectionModule::generateIntersectionSto const int base2front_idx_dist = std::ceil(planner_data_->vehicle_info_.max_longitudinal_offset_m / ds); - // find the index of the first point whose vehicle footprint on it intersects with detection_area + // find the index of the first point whose vehicle footprint on it intersects with attention_area const auto local_footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0); - std::optional first_footprint_inside_detection_ip_opt = + const std::optional first_footprint_inside_1st_attention_ip_opt = getFirstPointInsidePolygonByFootprint( first_attention_area, interpolated_path_info, local_footprint, baselink2front); - if (!first_footprint_inside_detection_ip_opt) { + if (!first_footprint_inside_1st_attention_ip_opt) { return std::nullopt; } - const auto first_footprint_inside_detection_ip = first_footprint_inside_detection_ip_opt.value(); + const auto first_footprint_inside_1st_attention_ip = + first_footprint_inside_1st_attention_ip_opt.value(); std::optional first_footprint_attention_centerline_ip_opt = std::nullopt; for (auto i = std::get<0>(lane_interval_ip); i < std::get<1>(lane_interval_ip); ++i) { @@ -1716,7 +1726,7 @@ std::optional IntersectionModule::generateIntersectionSto stop_idx_ip_int = static_cast(map_stop_idx_ip.value()) - base2front_idx_dist; } if (stop_idx_ip_int < 0) { - stop_idx_ip_int = first_footprint_inside_detection_ip - stopline_margin_idx_dist; + stop_idx_ip_int = first_footprint_inside_1st_attention_ip - stopline_margin_idx_dist; } if (stop_idx_ip_int < 0) { default_stopline_valid = false; @@ -1732,7 +1742,7 @@ std::optional IntersectionModule::generateIntersectionSto // (3) occlusion peeking stop line position on interpolated path int occlusion_peeking_line_ip_int = static_cast(default_stopline_ip); bool occlusion_peeking_line_valid = true; - // NOTE: if footprints[0] is already inside the detection area, invalid + // NOTE: if footprints[0] is already inside the attention area, invalid { const auto & base_pose0 = path_ip.points.at(default_stopline_ip).point.pose; const auto path_footprint0 = tier4_autoware_utils::transformVector( @@ -1744,32 +1754,32 @@ std::optional IntersectionModule::generateIntersectionSto } if (occlusion_peeking_line_valid) { occlusion_peeking_line_ip_int = - first_footprint_inside_detection_ip + std::ceil(peeking_offset / ds); + first_footprint_inside_1st_attention_ip + std::ceil(peeking_offset / ds); } - const auto occlusion_peeking_line_ip = static_cast( std::clamp(occlusion_peeking_line_ip_int, 0, static_cast(path_ip.points.size()) - 1)); - const auto first_attention_stopline_ip = first_footprint_inside_detection_ip; + + // (4) first attention stopline position on interpolated path + const auto first_attention_stopline_ip = first_footprint_inside_1st_attention_ip; const bool first_attention_stopline_valid = true; - // (4) pass judge line position on interpolated path + // (5) 1st pass judge line position on interpolated path const double velocity = planner_data_->current_velocity->twist.linear.x; const double acceleration = planner_data_->current_acceleration->accel.accel.linear.x; const double braking_dist = planning_utils::calcJudgeLineDistWithJerkLimit( velocity, acceleration, max_accel, max_jerk, delay_response_time); - int pass_judge_ip_int = - static_cast(first_footprint_inside_detection_ip) - std::ceil(braking_dist / ds); - const auto pass_judge_line_ip = static_cast( - std::clamp(pass_judge_ip_int, 0, static_cast(path_ip.points.size()) - 1)); - // TODO(Mamoru Sobue): maybe braking dist should be considered - const auto occlusion_wo_tl_pass_judge_line_ip = - static_cast(first_footprint_attention_centerline_ip); - - // (5) stuck vehicle stop line + int first_pass_judge_ip_int = + static_cast(first_footprint_inside_1st_attention_ip) - std::ceil(braking_dist / ds); + const auto first_pass_judge_line_ip = static_cast( + std::clamp(first_pass_judge_ip_int, 0, static_cast(path_ip.points.size()) - 1)); + const auto occlusion_wo_tl_pass_judge_line_ip = static_cast(std::max( + 0, static_cast(first_footprint_attention_centerline_ip) - std::ceil(braking_dist / ds))); + + // (6) stuck vehicle stopline position on interpolated path int stuck_stopline_ip_int = 0; bool stuck_stopline_valid = true; if (use_stuck_stopline) { - // NOTE: when ego vehicle is approaching detection area and already passed + // NOTE: when ego vehicle is approaching attention area and already passed // first_conflicting_area, this could be null. const auto stuck_stopline_idx_ip_opt = getFirstPointInsidePolygonByFootprint( first_conflicting_area, interpolated_path_info, local_footprint, baselink2front); @@ -1788,14 +1798,37 @@ std::optional IntersectionModule::generateIntersectionSto } const auto stuck_stopline_ip = static_cast(std::max(0, stuck_stopline_ip_int)); + // (7) second attention stopline position on interpolated path + int second_attention_stopline_ip_int = -1; + bool second_attention_stopline_valid = false; + if (second_attention_area_opt) { + const auto & second_attention_area = second_attention_area_opt.value(); + std::optional first_footprint_inside_2nd_attention_ip_opt = + getFirstPointInsidePolygonByFootprint( + second_attention_area, interpolated_path_info, local_footprint, baselink2front); + if (first_footprint_inside_2nd_attention_ip_opt) { + second_attention_stopline_ip_int = first_footprint_inside_2nd_attention_ip_opt.value(); + } + } + const auto second_attention_stopline_ip = + second_attention_stopline_ip_int >= 0 ? static_cast(second_attention_stopline_ip_int) + : 0; + + // (8) second pass judge lie position on interpolated path + int second_pass_judge_ip_int = second_attention_stopline_ip_int - std::ceil(braking_dist / ds); + const auto second_pass_judge_line_ip = + static_cast(std::max(second_pass_judge_ip_int, 0)); + struct IntersectionStopLinesTemp { size_t closest_idx{0}; size_t stuck_stopline{0}; size_t default_stopline{0}; size_t first_attention_stopline{0}; + size_t second_attention_stopline{0}; size_t occlusion_peeking_stopline{0}; - size_t pass_judge_line{0}; + size_t first_pass_judge_line{0}; + size_t second_pass_judge_line{0}; size_t occlusion_wo_tl_pass_judge_line{0}; }; @@ -1805,8 +1838,10 @@ std::optional IntersectionModule::generateIntersectionSto {&stuck_stopline_ip, &intersection_stoplines_temp.stuck_stopline}, {&default_stopline_ip, &intersection_stoplines_temp.default_stopline}, {&first_attention_stopline_ip, &intersection_stoplines_temp.first_attention_stopline}, + {&second_attention_stopline_ip, &intersection_stoplines_temp.second_attention_stopline}, {&occlusion_peeking_line_ip, &intersection_stoplines_temp.occlusion_peeking_stopline}, - {&pass_judge_line_ip, &intersection_stoplines_temp.pass_judge_line}, + {&first_pass_judge_line_ip, &intersection_stoplines_temp.first_pass_judge_line}, + {&second_pass_judge_line_ip, &intersection_stoplines_temp.second_pass_judge_line}, {&occlusion_wo_tl_pass_judge_line_ip, &intersection_stoplines_temp.occlusion_wo_tl_pass_judge_line}}; stoplines.sort( @@ -1840,11 +1875,17 @@ std::optional IntersectionModule::generateIntersectionSto intersection_stoplines.first_attention_stopline = intersection_stoplines_temp.first_attention_stopline; } + if (second_attention_stopline_valid) { + intersection_stoplines.second_attention_stopline = + intersection_stoplines_temp.second_attention_stopline; + } if (occlusion_peeking_line_valid) { intersection_stoplines.occlusion_peeking_stopline = intersection_stoplines_temp.occlusion_peeking_stopline; } - intersection_stoplines.pass_judge_line = intersection_stoplines_temp.pass_judge_line; + intersection_stoplines.first_pass_judge_line = intersection_stoplines_temp.first_pass_judge_line; + intersection_stoplines.second_pass_judge_line = + intersection_stoplines_temp.second_pass_judge_line; intersection_stoplines.occlusion_wo_tl_pass_judge_line = intersection_stoplines_temp.occlusion_wo_tl_pass_judge_line; return intersection_stoplines; @@ -3249,7 +3290,8 @@ getFirstPointInsidePolygonsByFootprint( void IntersectionLanelets::update( const bool is_prioritized, const util::InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length, + lanelet::routing::RoutingGraphPtr routing_graph_ptr) { is_prioritized_ = is_prioritized; // find the first conflicting/detection area polygon intersecting the path @@ -3262,13 +3304,44 @@ void IntersectionLanelets::update( } } if (!first_attention_area_) { - auto first = getFirstPointInsidePolygonsByFootprint( + const auto first = getFirstPointInsidePolygonsByFootprint( attention_non_preceding_area_, interpolated_path_info, footprint, vehicle_length); if (first) { first_attention_lane_ = attention_non_preceding_.at(first.value().second); first_attention_area_ = attention_non_preceding_area_.at(first.value().second); } } + if (first_attention_lane_ && !second_attention_lane_ && !second_attention_lane_empty_) { + const auto first_attention_lane = first_attention_lane_.value(); + // remove first_attention_area_ and non-straight lanelets from attention_non_preceding + lanelet::ConstLanelets attention_non_preceding_ex_first; + lanelet::ConstLanelets sibling_first_attention_lanelets; + for (const auto & previous : routing_graph_ptr->previous(first_attention_lane)) { + for (const auto & following : routing_graph_ptr->following(previous)) { + sibling_first_attention_lanelets.push_back(following); + } + } + for (const auto & ll : attention_non_preceding_) { + // the sibling lanelets of first_attention_lanelet are ruled out + if (lanelet::utils::contains(sibling_first_attention_lanelets, ll)) { + continue; + } + if (std::string(ll.attributeOr("turn_direction", "else")).compare("straight") == 0) { + attention_non_preceding_ex_first.push_back(ll); + } + } + if (attention_non_preceding_ex_first.empty()) { + second_attention_lane_empty_ = true; + } + const auto attention_non_preceding_ex_first_area = + getPolygon3dFromLanelets(attention_non_preceding_ex_first); + const auto second = getFirstPointInsidePolygonsByFootprint( + attention_non_preceding_ex_first_area, interpolated_path_info, footprint, vehicle_length); + if (second) { + second_attention_lane_ = attention_non_preceding_ex_first.at(second.value().second); + second_attention_area_ = second_attention_lane_.value().polygon3d(); + } + } } void TargetObject::calc_dist_to_stopline() diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index d533c7316b264..38feada725872 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -53,6 +53,8 @@ struct DebugData std::optional> occlusion_attention_area{std::nullopt}; std::optional ego_lane{std::nullopt}; std::optional> adjacent_area{std::nullopt}; + std::optional first_attention_area{std::nullopt}; + std::optional second_attention_area{std::nullopt}; std::optional stuck_vehicle_detect_area{std::nullopt}; std::optional> yield_stuck_detect_area{std::nullopt}; std::optional candidate_collision_ego_lane_polygon{std::nullopt}; @@ -82,7 +84,8 @@ struct IntersectionLanelets */ void update( const bool is_prioritized, const util::InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length); + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length, + lanelet::routing::RoutingGraphPtr routing_graph_ptr); const lanelet::ConstLanelets & attention() const { @@ -131,6 +134,14 @@ struct IntersectionLanelets { return first_attention_area_; } + const std::optional & second_attention_lane() const + { + return second_attention_lane_; + } + const std::optional & second_attention_area() const + { + return second_attention_area_; + } /** * the set of attention lanelets which is topologically merged @@ -178,17 +189,25 @@ struct IntersectionLanelets std::vector occlusion_attention_size_; /** - * the attention lanelet which ego path points intersect for the first time + * the first conflicting lanelet which ego path points intersect for the first time */ std::optional first_conflicting_lane_{std::nullopt}; std::optional first_conflicting_area_{std::nullopt}; /** - * the attention lanelet which ego path points intersect for the first time + * the first attention lanelet which ego path points intersect for the first time */ std::optional first_attention_lane_{std::nullopt}; std::optional first_attention_area_{std::nullopt}; + /** + * the second attention lanelet which ego path points intersect next to the + * first_attention_lanelet + */ + bool second_attention_lane_empty_{false}; + std::optional second_attention_lane_{std::nullopt}; + std::optional second_attention_area_{std::nullopt}; + /** * flag if the intersection is prioritized by the traffic light */ @@ -219,16 +238,28 @@ struct IntersectionStopLines */ std::optional first_attention_stopline{std::nullopt}; + /** + * second_attention_stopline is null if ego footprint along the path does not intersect with + * second_attention_lane. if path[0] satisfies the condition, it is 0 + */ + std::optional second_attention_stopline{std::nullopt}; + /** * occlusion_peeking_stopline is null if path[0] is already inside the attention area */ std::optional occlusion_peeking_stopline{std::nullopt}; /** - * pass_judge_line is before first_attention_stop_line by the braking distance. if its value is - * calculated negative, it is 0 + * first_pass_judge_line is before first_attention_stopline by the braking distance. if its value + * is calculated negative, it is 0 + */ + size_t first_pass_judge_line{0}; + + /** + * second_pass_judge_line is before second_attention_stopline by the braking distance. if its + * value is calculated negative, it is 0 */ - size_t pass_judge_line{0}; + size_t second_pass_judge_line{0}; /** * occlusion_wo_tl_pass_judge_line is null if ego footprint along the path does not intersect with @@ -650,6 +681,7 @@ class IntersectionModule : public SceneModuleInterface lanelet::ConstLanelet assigned_lanelet, const lanelet::CompoundPolygon3d & first_conflicting_area, const lanelet::ConstLanelet & first_attention_lane, + const std::optional & second_attention_area_opt, const util::InterpolatedPathInfo & interpolated_path_info, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path); From 4b9a9ae0699c82e87079210baf4c10d3b655ba27 Mon Sep 17 00:00:00 2001 From: Berkay Karaman Date: Thu, 11 Jan 2024 02:08:30 +0300 Subject: [PATCH 220/276] fix(motion_velocity_smoother): make stopping_distance and stopping_velocity be able to work (#6037) Signed-off-by: Berkay Karaman --- .../src/motion_velocity_smoother_node.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp index 90f7295c4cf6f..5138da6a43c0c 100644 --- a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp +++ b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp @@ -453,6 +453,9 @@ void MotionVelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstShar return; } + // Set 0 at the end of the trajectory + input_points.back().longitudinal_velocity_mps = 0.0; + // calculate prev closest point if (!prev_output_.empty()) { current_closest_point_from_prev_output_ = calcProjectedTrajectoryPointFromEgo(prev_output_); From 5106b335069b07cf81d600c4823751aac065e22c Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 11 Jan 2024 08:43:59 +0900 Subject: [PATCH 221/276] refactor(tier4_planning_launch): remove duplicate arguments in launchfile (#6040) Signed-off-by: Maxime CLEMENT --- .../behavior_planning/behavior_planning.launch.xml | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index dd1c0604bc86f..1c7643359c496 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -16,17 +16,6 @@ - - - - - - - - - - - From b45bb53af01df7ea31f6e53f7d1bcba9a83ba963 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 11 Jan 2024 11:08:40 +0900 Subject: [PATCH 222/276] fix(lane_change): check able to return to original lane in abort (#6034) * fix(lane_change): check able to return to original lane in abort Signed-off-by: Muhammad Zulfaqar Azmi * fix cancel state Signed-off-by: Muhammad Zulfaqar Azmi * revert changes Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi --- planning/behavior_path_lane_change_module/src/interface.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 22d85a2a1fc2a..448f83ecaf15e 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -276,6 +276,11 @@ bool LaneChangeInterface::canTransitFailureState() return false; } + if (!module_type_->isAbleToReturnCurrentLane()) { + log_debug_throttled("It's is not possible to return to original lane. Continue lane change."); + return false; + } + const auto found_abort_path = module_type_->calcAbortPath(); if (!found_abort_path) { log_debug_throttled( From 4593dd3d8bd8881939810d7c624ac18492dbd603 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 11 Jan 2024 11:39:43 +0900 Subject: [PATCH 223/276] feat(start_planner): keep distance against front objects (#5983) * refactor extractCollisionCheckPath Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara Co-authored-by: Kosuke Takeuchi --- .../behavior_path_start_planner_module/README.md | 3 ++- .../config/start_planner.param.yaml | 1 + .../start_planner_module.hpp | 2 +- .../start_planner_parameters.hpp | 1 + .../src/manager.cpp | 2 ++ .../src/start_planner_module.cpp | 15 +++++++++++---- 6 files changed, 18 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_start_planner_module/README.md b/planning/behavior_path_start_planner_module/README.md index 2f90cc2ee3cf2..80ad8d6675e9a 100644 --- a/planning/behavior_path_start_planner_module/README.md +++ b/planning/behavior_path_start_planner_module/README.md @@ -75,7 +75,8 @@ PullOutPath --o PullOutPlannerBase | intersection_search_length | [m] | double | check if intersections exist within this length | 30.0 | | length_ratio_for_turn_signal_deactivation_near_intersection | [m] | double | deactivate turn signal of this module near intersection | 0.5 | | collision_check_margin | [m] | double | Obstacle collision check margin | 1.0 | -| collision_check_distance_from_end | [m] | double | collision check distance from end point. currently only for pull out | 15.0 | +| collision_check_distance_from_end | [m] | double | collision check distance from end shift end pose | 1.0 | +| collision_check_margin_from_front_object | [m] | double | collision check margin from front object | 5.0 | | center_line_path_interval | [m] | double | reference center line path point interval | 1.0 | ## Safety check with static obstacles diff --git a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml index 514d61e225ecd..d04728861a52e 100644 --- a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml +++ b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml @@ -7,6 +7,7 @@ th_stopped_time: 1.0 collision_check_margin: 1.0 collision_check_distance_from_end: 1.0 + collision_check_margin_from_front_object: 5.0 th_moving_object_velocity: 1.0 th_distance_to_middle_of_the_road: 0.5 center_line_path_interval: 1.0 diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index a451a92c16ff1..eb1827ec0045d 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -174,7 +174,7 @@ class StartPlannerModule : public SceneModuleInterface const Pose & start_pose_candidate, const std::shared_ptr & planner, const Pose & refined_start_pose, const Pose & goal_pose); - PathWithLaneId extractCollisionCheckPath(const PullOutPath & path); + PathWithLaneId extractCollisionCheckSection(const PullOutPath & path); void updateStatusWithCurrentPath( const behavior_path_planner::PullOutPath & path, const Pose & start_pose, const behavior_path_planner::PlannerType & planner_type); diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp index 783aace0983ca..2df75107d872c 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp @@ -44,6 +44,7 @@ struct StartPlannerParameters double length_ratio_for_turn_signal_deactivation_near_intersection{0.0}; double collision_check_margin{0.0}; double collision_check_distance_from_end{0.0}; + double collision_check_margin_from_front_object{0.0}; double th_moving_object_velocity{0.0}; double center_line_path_interval{0.0}; diff --git a/planning/behavior_path_start_planner_module/src/manager.cpp b/planning/behavior_path_start_planner_module/src/manager.cpp index 58d0fbee7921b..f719718a3389e 100644 --- a/planning/behavior_path_start_planner_module/src/manager.cpp +++ b/planning/behavior_path_start_planner_module/src/manager.cpp @@ -46,6 +46,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) p.collision_check_margin = node->declare_parameter(ns + "collision_check_margin"); p.collision_check_distance_from_end = node->declare_parameter(ns + "collision_check_distance_from_end"); + p.collision_check_margin_from_front_object = + node->declare_parameter(ns + "collision_check_margin_from_front_object"); p.th_moving_object_velocity = node->declare_parameter(ns + "th_moving_object_velocity"); p.center_line_path_interval = node->declare_parameter(ns + "center_line_path_interval"); // shift pull out diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 66e04d7e9bb7a..fd23adf654502 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -645,7 +645,7 @@ bool StartPlannerModule::findPullOutPath( // check collision if (utils::checkCollisionBetweenPathFootprintsAndObjects( - vehicle_footprint, extractCollisionCheckPath(*pull_out_path), pull_out_lane_stop_objects, + vehicle_footprint, extractCollisionCheckSection(*pull_out_path), pull_out_lane_stop_objects, parameters_->collision_check_margin)) { return false; } @@ -660,7 +660,7 @@ bool StartPlannerModule::findPullOutPath( return true; } -PathWithLaneId StartPlannerModule::extractCollisionCheckPath(const PullOutPath & path) +PathWithLaneId StartPlannerModule::extractCollisionCheckSection(const PullOutPath & path) { PathWithLaneId combined_path; for (const auto & partial_path : path.partial_paths) { @@ -912,6 +912,10 @@ std::vector StartPlannerModule::searchPullOutStartPoseCandidates( pull_out_lanes, start_pose.position, parameters_->th_moving_object_velocity, backward_path_length, std::numeric_limits::max()); + const auto front_stop_objects_in_pull_out_lanes = filterStopObjectsInPullOutLanes( + pull_out_lanes, start_pose.position, parameters_->th_moving_object_velocity, 0, + std::numeric_limits::max()); + // Set the maximum backward distance less than the distance from the vehicle's base_link to the // lane's rearmost point to prevent lane departure. const double current_arc_length = @@ -924,9 +928,12 @@ std::vector StartPlannerModule::searchPullOutStartPoseCandidates( back_distance += parameters_->backward_search_resolution) { const auto backed_pose = calcLongitudinalOffsetPose( back_path_from_start_pose.points, start_pose.position, -back_distance); - if (!backed_pose) { + if (!backed_pose) continue; + + if (utils::checkCollisionBetweenFootprintAndObjects( + local_vehicle_footprint, *backed_pose, front_stop_objects_in_pull_out_lanes, + parameters_->collision_check_margin_from_front_object)) continue; - } const double backed_pose_arc_length = lanelet::utils::getArcCoordinates(pull_out_lanes, *backed_pose).length; From 29992405cceea540e1473d4348b317055a082716 Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Thu, 11 Jan 2024 05:13:56 +0100 Subject: [PATCH 224/276] feat(ekf_localizer): tf publisher as an option (#6004) Signed-off-by: amadeuszsz --- localization/ekf_localizer/README.md | 1 + .../ekf_localizer/config/ekf_localizer.param.yaml | 1 + .../include/ekf_localizer/hyper_parameters.hpp | 2 ++ localization/ekf_localizer/src/ekf_localizer.cpp | 8 +++++--- 4 files changed, 9 insertions(+), 3 deletions(-) diff --git a/localization/ekf_localizer/README.md b/localization/ekf_localizer/README.md index 87cc510c5fe14..02f14a86cd7df 100644 --- a/localization/ekf_localizer/README.md +++ b/localization/ekf_localizer/README.md @@ -83,6 +83,7 @@ The parameters are set in `launch/ekf_localizer.launch` . | show_debug_info | bool | Flag to display debug info | false | | predict_frequency | double | Frequency for filtering and publishing [Hz] | 50.0 | | tf_rate | double | Frequency for tf broadcasting [Hz] | 10.0 | +| publish_tf | bool | Whether to publish tf | true | | extend_state_step | int | Max delay step which can be dealt with in EKF. Large number increases computational cost. | 50 | | enable_yaw_bias_estimation | bool | Flag to enable yaw bias estimation | true | diff --git a/localization/ekf_localizer/config/ekf_localizer.param.yaml b/localization/ekf_localizer/config/ekf_localizer.param.yaml index 1db45db411b0c..9de7f56f5c006 100644 --- a/localization/ekf_localizer/config/ekf_localizer.param.yaml +++ b/localization/ekf_localizer/config/ekf_localizer.param.yaml @@ -4,6 +4,7 @@ enable_yaw_bias_estimation: true predict_frequency: 50.0 tf_rate: 50.0 + publish_tf: true extend_state_step: 50 # for Pose measurement diff --git a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp index e0e34f382e3dc..5139f900a339e 100644 --- a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp @@ -28,6 +28,7 @@ class HyperParameters ekf_rate(node->declare_parameter("predict_frequency", 50.0)), ekf_dt(1.0 / std::max(ekf_rate, 0.1)), tf_rate_(node->declare_parameter("tf_rate", 10.0)), + publish_tf_(node->declare_parameter("publish_tf", true)), enable_yaw_bias_estimation(node->declare_parameter("enable_yaw_bias_estimation", true)), extend_state_step(node->declare_parameter("extend_state_step", 50)), pose_frame_id(node->declare_parameter("pose_frame_id", std::string("map"))), @@ -60,6 +61,7 @@ class HyperParameters const double ekf_rate; const double ekf_dt; const double tf_rate_; + const bool publish_tf_; const bool enable_yaw_bias_estimation; const int extend_state_step; const std::string pose_frame_id; diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 0ab88202e0c0d..b3ee3665cf45e 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -60,9 +60,11 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti this, get_clock(), rclcpp::Duration::from_seconds(ekf_dt_), std::bind(&EKFLocalizer::timerCallback, this)); - timer_tf_ = rclcpp::create_timer( - this, get_clock(), rclcpp::Rate(params_.tf_rate_).period(), - std::bind(&EKFLocalizer::timerTFCallback, this)); + if (params_.publish_tf_) { + timer_tf_ = rclcpp::create_timer( + this, get_clock(), rclcpp::Rate(params_.tf_rate_).period(), + std::bind(&EKFLocalizer::timerTFCallback, this)); + } pub_pose_ = create_publisher("ekf_pose", 1); pub_pose_cov_ = From 25f1dfc85870c68fbc486edf95f1c603699b8f57 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 11 Jan 2024 13:18:56 +0900 Subject: [PATCH 225/276] refactor(behavior_path_planner): remove create_vehicle_footprint.hpp (#6049) Signed-off-by: satoshi-ota --- .../src/utils.cpp | 1 - .../pull_over_planner_base.hpp | 3 +- .../src/goal_planner_module.cpp | 3 +- .../utils/create_vehicle_footprint.hpp | 47 ------------------- .../pull_out_planner_base.hpp | 3 +- .../src/start_planner_module.cpp | 7 ++- .../src/util.cpp | 1 - 7 files changed, 6 insertions(+), 59 deletions(-) delete mode 100644 planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/create_vehicle_footprint.hpp diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index 83e96d83b995f..f72f8279d4351 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -16,7 +16,6 @@ #include "behavior_path_avoidance_module/data_structs.hpp" #include "behavior_path_avoidance_module/utils.hpp" -#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/traffic_light_utils.hpp" diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp index ddd7c93998654..fe24d66ddc850 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp @@ -17,7 +17,6 @@ #include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" -#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include #include @@ -114,7 +113,7 @@ class PullOverPlannerBase PullOverPlannerBase(rclcpp::Node & node, const GoalPlannerParameters & parameters) { vehicle_info_ = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); - vehicle_footprint_ = createVehicleFootprint(vehicle_info_); + vehicle_footprint_ = vehicle_info_.createFootprint(); parameters_ = parameters; } virtual ~PullOverPlannerBase() = default; diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 493e7ec57f063..7bd97b3775bad 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -15,7 +15,6 @@ #include "behavior_path_goal_planner_module/goal_planner_module.hpp" #include "behavior_path_goal_planner_module/util.hpp" -#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" @@ -94,7 +93,7 @@ GoalPlannerModule::GoalPlannerModule( // set selected goal searcher // currently there is only one goal_searcher_type const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); - vehicle_footprint_ = createVehicleFootprint(vehicle_info); + vehicle_footprint_ = vehicle_info.createFootprint(); goal_searcher_ = std::make_shared(*parameters, vehicle_footprint_, occupancy_grid_map_); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/create_vehicle_footprint.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/create_vehicle_footprint.hpp deleted file mode 100644 index edb6d32bda205..0000000000000 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/create_vehicle_footprint.hpp +++ /dev/null @@ -1,47 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef BEHAVIOR_PATH_PLANNER_COMMON__UTILS__CREATE_VEHICLE_FOOTPRINT_HPP_ -#define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__CREATE_VEHICLE_FOOTPRINT_HPP_ - -#include -#include - -inline tier4_autoware_utils::LinearRing2d createVehicleFootprint( - const vehicle_info_util::VehicleInfo & vehicle_info, const double margin = 0.0) -{ - using tier4_autoware_utils::LinearRing2d; - using tier4_autoware_utils::Point2d; - - const auto & i = vehicle_info; - - const double x_front = i.front_overhang_m + i.wheel_base_m + margin; - const double x_center = i.wheel_base_m / 2.0; - const double x_rear = -(i.rear_overhang_m + margin); - const double y_left = i.wheel_tread_m / 2.0 + i.left_overhang_m + margin; - const double y_right = -(i.wheel_tread_m / 2.0 + i.right_overhang_m + margin); - - LinearRing2d footprint; - footprint.push_back(Point2d{x_front, y_left}); - footprint.push_back(Point2d{x_front, y_right}); - footprint.push_back(Point2d{x_center, y_right}); - footprint.push_back(Point2d{x_rear, y_right}); - footprint.push_back(Point2d{x_rear, y_left}); - footprint.push_back(Point2d{x_center, y_left}); - footprint.push_back(Point2d{x_front, y_left}); - - return footprint; -} - -#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__CREATE_VEHICLE_FOOTPRINT_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp index de3d376fa4b3d..e345e3dc91337 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -16,7 +16,6 @@ #define BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ #include "behavior_path_planner_common/data_manager.hpp" -#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_start_planner_module/pull_out_path.hpp" #include "behavior_path_start_planner_module/start_planner_parameters.hpp" @@ -45,7 +44,7 @@ class PullOutPlannerBase explicit PullOutPlannerBase(rclcpp::Node & node, const StartPlannerParameters & parameters) { vehicle_info_ = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); - vehicle_footprint_ = createVehicleFootprint(vehicle_info_); + vehicle_footprint_ = vehicle_info_.createFootprint(); parameters_ = parameters; } virtual ~PullOutPlannerBase() = default; diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index fd23adf654502..6702e37f19077 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -14,7 +14,6 @@ #include "behavior_path_start_planner_module/start_planner_module.hpp" -#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" @@ -623,7 +622,7 @@ bool StartPlannerModule::findPullOutPath( 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 = createVehicleFootprint(vehicle_info_); + 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); @@ -902,7 +901,7 @@ std::vector StartPlannerModule::searchPullOutStartPoseCandidates( { std::vector pull_out_start_pose_candidates{}; const auto start_pose = planner_data_->route_handler->getOriginalStartPose(); - const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_); + const auto local_vehicle_footprint = vehicle_info_.createFootprint(); const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); const double backward_path_length = @@ -1356,7 +1355,7 @@ void StartPlannerModule::setDebugData() const // visualize collision_check_end_pose and footprint { - const auto local_footprint = createVehicleFootprint(vehicle_info_); + const auto local_footprint = vehicle_info_.createFootprint(); const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose( getFullPath().points, status_.pull_out_path.end_pose.position, parameters_->collision_check_distance_from_end); diff --git a/planning/behavior_path_start_planner_module/src/util.cpp b/planning/behavior_path_start_planner_module/src/util.cpp index 73a1e94399503..b34398083a95c 100644 --- a/planning/behavior_path_start_planner_module/src/util.cpp +++ b/planning/behavior_path_start_planner_module/src/util.cpp @@ -14,7 +14,6 @@ #include "behavior_path_start_planner_module/util.hpp" -#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" From 4d8d4f868fd5fdb087f8de49268afbbb8663c522 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 11 Jan 2024 14:53:37 +0900 Subject: [PATCH 226/276] feat(start_planner): define collision check margin as list (#5994) * define collision check margins list in start planner module Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../parking_departure/common_module_data.hpp | 2 + .../README.md | 26 +++++------ .../config/start_planner.param.yaml | 2 +- .../start_planner_module.hpp | 2 +- .../start_planner_parameters.hpp | 2 +- .../src/manager.cpp | 3 +- .../src/start_planner_module.cpp | 45 ++++++++++--------- 7 files changed, 45 insertions(+), 37 deletions(-) diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp index 91683f4547659..3dc230f0e92ed 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp @@ -41,6 +41,8 @@ struct StartGoalPlannerData Pose refined_start_pose; std::vector start_pose_candidates; + size_t selected_start_pose_candidate_index; + double margin_for_start_pose_candidate; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_start_planner_module/README.md b/planning/behavior_path_start_planner_module/README.md index 80ad8d6675e9a..aeefd18357a5c 100644 --- a/planning/behavior_path_start_planner_module/README.md +++ b/planning/behavior_path_start_planner_module/README.md @@ -65,19 +65,19 @@ PullOutPath --o PullOutPlannerBase ## General parameters for start_planner -| Name | Unit | Type | Description | Default value | -| :---------------------------------------------------------- | :---- | :----- | :-------------------------------------------------------------------------- | :------------ | -| th_arrived_distance_m | [m] | double | distance 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 | -| th_stopped_velocity_mps | [m/s] | double | velocity threshold for arrival of path termination | 0.01 | -| th_stopped_time_sec | [s] | double | time threshold for arrival of path termination | 1.0 | -| th_turn_signal_on_lateral_offset | [m] | double | lateral distance threshold for turning on blinker | 1.0 | -| intersection_search_length | [m] | double | check if intersections exist within this length | 30.0 | -| length_ratio_for_turn_signal_deactivation_near_intersection | [m] | double | deactivate turn signal of this module near intersection | 0.5 | -| collision_check_margin | [m] | double | Obstacle collision check margin | 1.0 | -| collision_check_distance_from_end | [m] | double | collision check distance from end shift end pose | 1.0 | -| collision_check_margin_from_front_object | [m] | double | collision check margin from front object | 5.0 | -| center_line_path_interval | [m] | double | reference center line path point interval | 1.0 | +| Name | Unit | Type | Description | Default value | +| :---------------------------------------------------------- | :---- | :------- | :-------------------------------------------------------------------------- | :-------------- | +| th_arrived_distance_m | [m] | double | distance 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 | +| th_stopped_velocity_mps | [m/s] | double | velocity threshold for arrival of path termination | 0.01 | +| th_stopped_time_sec | [s] | double | time threshold for arrival of path termination | 1.0 | +| th_turn_signal_on_lateral_offset | [m] | double | lateral distance threshold for turning on blinker | 1.0 | +| intersection_search_length | [m] | double | check if intersections exist within this length | 30.0 | +| length_ratio_for_turn_signal_deactivation_near_intersection | [m] | double | deactivate turn signal of this module near intersection | 0.5 | +| collision_check_margins | [m] | [double] | Obstacle collision check margins list | [2.0, 1.5, 1.0] | +| collision_check_distance_from_end | [m] | double | collision check distance from end shift end pose | 1.0 | +| collision_check_margin_from_front_object | [m] | double | collision check margin from front object | 5.0 | +| center_line_path_interval | [m] | double | reference center line path point interval | 1.0 | ## Safety check with static obstacles diff --git a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml index d04728861a52e..d174b54b9ccbe 100644 --- a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml +++ b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml @@ -5,7 +5,7 @@ th_arrived_distance: 1.0 th_stopped_velocity: 0.01 th_stopped_time: 1.0 - collision_check_margin: 1.0 + collision_check_margins: [2.0, 1.5, 1.0] collision_check_distance_from_end: 1.0 collision_check_margin_from_front_object: 5.0 th_moving_object_velocity: 1.0 diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index eb1827ec0045d..41a80e59d56bf 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -172,7 +172,7 @@ class StartPlannerModule : public SceneModuleInterface const std::string & search_priority, const size_t start_pose_candidates_num); bool findPullOutPath( const Pose & start_pose_candidate, const std::shared_ptr & planner, - const Pose & refined_start_pose, const Pose & goal_pose); + const Pose & refined_start_pose, const Pose & goal_pose, const double collision_check_margin); PathWithLaneId extractCollisionCheckSection(const PullOutPath & path); void updateStatusWithCurrentPath( diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp index 2df75107d872c..66dbddebf99bb 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp @@ -42,7 +42,7 @@ struct StartPlannerParameters double th_distance_to_middle_of_the_road{0.0}; double intersection_search_length{0.0}; double length_ratio_for_turn_signal_deactivation_near_intersection{0.0}; - double collision_check_margin{0.0}; + std::vector collision_check_margins{}; double collision_check_distance_from_end{0.0}; double collision_check_margin_from_front_object{0.0}; double th_moving_object_velocity{0.0}; diff --git a/planning/behavior_path_start_planner_module/src/manager.cpp b/planning/behavior_path_start_planner_module/src/manager.cpp index f719718a3389e..8cc0b34082e44 100644 --- a/planning/behavior_path_start_planner_module/src/manager.cpp +++ b/planning/behavior_path_start_planner_module/src/manager.cpp @@ -43,7 +43,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) p.intersection_search_length = node->declare_parameter(ns + "intersection_search_length"); p.length_ratio_for_turn_signal_deactivation_near_intersection = node->declare_parameter( ns + "length_ratio_for_turn_signal_deactivation_near_intersection"); - p.collision_check_margin = node->declare_parameter(ns + "collision_check_margin"); + p.collision_check_margins = + node->declare_parameter>(ns + "collision_check_margins"); p.collision_check_distance_from_end = node->declare_parameter(ns + "collision_check_distance_from_end"); p.collision_check_margin_from_front_object = diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 6702e37f19077..d523f57125679 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -584,9 +584,16 @@ void StartPlannerModule::planWithPriority( const PriorityOrder order_priority = determinePriorityOrder(search_priority, start_pose_candidates.size()); - for (const auto & [index, planner] : order_priority) { - if (findPullOutPath(start_pose_candidates[index], planner, refined_start_pose, goal_pose)) - return; + for (const auto & collision_check_margin : parameters_->collision_check_margins) { + for (const auto & [index, planner] : order_priority) { + if (findPullOutPath( + start_pose_candidates[index], planner, refined_start_pose, goal_pose, + collision_check_margin)) { + start_planner_data_.selected_start_pose_candidate_index = index; + start_planner_data_.margin_for_start_pose_candidate = collision_check_margin; + return; + } + } } updateStatusIfNoSafePathFound(); @@ -617,7 +624,7 @@ PriorityOrder StartPlannerModule::determinePriorityOrder( bool StartPlannerModule::findPullOutPath( const Pose & start_pose_candidate, const std::shared_ptr & planner, - const Pose & refined_start_pose, const Pose & goal_pose) + const Pose & refined_start_pose, const Pose & goal_pose, const double collision_check_margin) { const auto & dynamic_objects = planner_data_->dynamic_object; const auto pull_out_lanes = start_planner_utils::getPullOutLanes( @@ -645,7 +652,7 @@ bool StartPlannerModule::findPullOutPath( // check collision if (utils::checkCollisionBetweenPathFootprintsAndObjects( vehicle_footprint, extractCollisionCheckSection(*pull_out_path), pull_out_lane_stop_objects, - parameters_->collision_check_margin)) { + collision_check_margin)) { return false; } @@ -666,23 +673,21 @@ PathWithLaneId StartPlannerModule::extractCollisionCheckSection(const PullOutPat combined_path.points.insert( combined_path.points.end(), partial_path.points.begin(), partial_path.points.end()); } - // calculate collision check end idx - size_t collision_check_end_idx = 0; - const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose( - combined_path.points, path.end_pose.position, parameters_->collision_check_distance_from_end); - - if (collision_check_end_pose) { - collision_check_end_idx = - motion_utils::findNearestIndex(combined_path.points, collision_check_end_pose->position); - } + const size_t collision_check_end_idx = std::invoke([&]() { + const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose( + combined_path.points, path.end_pose.position, parameters_->collision_check_distance_from_end); + if (collision_check_end_pose) { + return motion_utils::findNearestIndex( + combined_path.points, collision_check_end_pose->position); + } else { + return combined_path.points.size() - 1; + } + }); // remove the point behind of collision check end pose - if (collision_check_end_idx + 1 < combined_path.points.size()) { - combined_path.points.erase( - combined_path.points.begin() + collision_check_end_idx + 1, combined_path.points.end()); - } - + combined_path.points.erase( + combined_path.points.begin() + collision_check_end_idx + 1, combined_path.points.end()); return combined_path; } @@ -949,7 +954,7 @@ std::vector StartPlannerModule::searchPullOutStartPoseCandidates( if (utils::checkCollisionBetweenFootprintAndObjects( local_vehicle_footprint, *backed_pose, stop_objects_in_pull_out_lanes, - parameters_->collision_check_margin)) { + parameters_->collision_check_margins.back())) { break; // poses behind this has a collision, so break. } From b2c05a6850337b591dac55e378dc0500dd9478e0 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Thu, 11 Jan 2024 15:09:38 +0900 Subject: [PATCH 227/276] fix(map_based_prediction): yaw rate can be overwritten by max function (#6039) * fix problem with negative yaw being replaced in max function Signed-off-by: Daniel Sanchez * add check for delta time value Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../map_based_prediction/map_based_prediction_node.hpp | 9 +++++---- .../src/map_based_prediction_node.cpp | 8 ++++---- perception/map_based_prediction/src/path_generator.cpp | 2 +- 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 02ca62a61717c..02db91b989116 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -316,8 +316,11 @@ class MapBasedPredictionNode : public rclcpp::Node }; inline bool isLateralAccelerationConstraintSatisfied( - const TrajectoryPoints & trajectory [[maybe_unused]], const double delta_time) + const TrajectoryPoints & trajectory, const double delta_time) { + constexpr double epsilon = 1E-6; + if (delta_time < epsilon) throw std::invalid_argument("delta_time must be a positive value"); + if (trajectory.size() < 3) return true; const double max_lateral_accel_abs = std::fabs(max_lateral_accel_); @@ -343,19 +346,17 @@ class MapBasedPredictionNode : public rclcpp::Node delta_theta += 2.0 * M_PI; } - const double yaw_rate = std::max(delta_theta / delta_time, 1.0E-5); + const double yaw_rate = std::max(std::abs(delta_theta / delta_time), 1.0E-5); const double current_speed = std::abs(trajectory.at(i).longitudinal_velocity_mps); // Compute lateral acceleration const double lateral_acceleration = std::abs(current_speed * yaw_rate); if (lateral_acceleration < max_lateral_accel_abs) continue; - const double v_curvature_max = std::sqrt(max_lateral_accel_abs / yaw_rate); const double t = (v_curvature_max - current_speed) / min_acceleration_before_curve_; // acc is negative const double distance_to_slow_down = current_speed * t + 0.5 * min_acceleration_before_curve_ * std::pow(t, 2); - if (distance_to_slow_down > arc_length) return false; } return true; diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index 75c1d61e0a19c..6a6f24081655e 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -613,16 +613,16 @@ ObjectClassification::_label_type changeLabelForPrediction( case ObjectClassification::BICYCLE: { // if object is within road lanelet and satisfies yaw // constraints const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true); - const float high_speed_threshold = + // if the object is within lanelet, do the same estimation with vehicle + if (within_road_lanelet) return ObjectClassification::MOTORCYCLE; + + constexpr float high_speed_threshold = tier4_autoware_utils::kmph2mps(25.0); // High speed bicycle 25 km/h // calc abs speed from x and y velocity const double abs_speed = std::hypot( object.kinematics.twist_with_covariance.twist.linear.x, object.kinematics.twist_with_covariance.twist.linear.y); const bool high_speed_object = abs_speed > high_speed_threshold; - - // if the object is within lanelet, do the same estimation with vehicle - if (within_road_lanelet) return ObjectClassification::MOTORCYCLE; // high speed object outside road lanelet will move like unknown object // return ObjectClassification::UNKNOWN; // temporary disabled if (high_speed_object) return label; // Do nothing for now diff --git a/perception/map_based_prediction/src/path_generator.cpp b/perception/map_based_prediction/src/path_generator.cpp index 5cb7e186b7cc4..d3f610583577c 100644 --- a/perception/map_based_prediction/src/path_generator.cpp +++ b/perception/map_based_prediction/src/path_generator.cpp @@ -162,7 +162,7 @@ PredictedPath PathGenerator::generateStraightPath(const TrackedObject & object) { const auto & object_pose = object.kinematics.pose_with_covariance.pose; const auto & object_twist = object.kinematics.twist_with_covariance.twist; - const double ep = 0.001; + constexpr double ep = 0.001; const double duration = time_horizon_ + ep; PredictedPath path; From 6378ce65e6fe1a78b3b53c26a8895b2b2e4a051e Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 11 Jan 2024 18:27:54 +0900 Subject: [PATCH 228/276] fix(intersection): fix bugs (#6050) Signed-off-by: Mamoru Sobue --- .../config/intersection.param.yaml | 2 +- planning/behavior_velocity_intersection_module/src/manager.cpp | 2 ++ .../src/scene_intersection.cpp | 2 +- 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 6fc136c512689..4e9eb50f2a462 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -72,7 +72,7 @@ enable: false creep_velocity: 0.8333 peeking_offset: -0.5 - occlusion_required_clearance_distance: 55 + occlusion_required_clearance_distance: 55.0 possible_object_bbox: [1.5, 2.5] ignore_parked_vehicle_speed_threshold: 0.8333 occlusion_detection_hold_time: 1.5 diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index e859b15b345b8..c92f16dd7b474 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -152,6 +152,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".occlusion.creep_during_peeking.creep_velocity"); ip.occlusion.peeking_offset = getOrDeclareParameter(node, ns + ".occlusion.peeking_offset"); + ip.occlusion.occlusion_required_clearance_distance = + getOrDeclareParameter(node, ns + ".occlusion.occlusion_required_clearance_distance"); ip.occlusion.possible_object_bbox = getOrDeclareParameter>(node, ns + ".occlusion.possible_object_bbox"); ip.occlusion.ignore_parked_vehicle_speed_threshold = diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 1bc7bfe04d271..dad0c194b5c9f 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1195,7 +1195,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } } - const double is_amber_or_red = + const bool is_amber_or_red = (traffic_prioritized_level == TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) || (traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED); auto occlusion_status = From cb23bb065f9493adcffff0ba6215510bebecc634 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 12 Jan 2024 00:36:03 +0900 Subject: [PATCH 229/276] feat(mission_planner): check shoulder lanelets for check_goal_footprint (#6053) Signed-off-by: kosuke55 --- .../src/lanelet2_plugins/default_planner.cpp | 6 ++- .../lanelet2_plugins/utility_functions.cpp | 50 +++++++++++++++---- .../lanelet2_plugins/utility_functions.hpp | 3 +- 3 files changed, 47 insertions(+), 12 deletions(-) diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 5d1c0c68d8208..e98084204ba78 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -292,7 +292,8 @@ bool DefaultPlanner::check_goal_footprint( lanelet::ConstLanelets lanelets; lanelets.push_back(combined_prev_lanelet); lanelets.push_back(next_lane); - lanelet::ConstLanelet combined_lanelets = combine_lanelets(lanelets); + lanelet::ConstLanelet combined_lanelets = + combine_lanelets_with_shoulder(lanelets, shoulder_lanelets_); // if next lanelet length longer than vehicle longitudinal offset if (vehicle_info_.max_longitudinal_offset_m + search_margin < next_lane_length) { @@ -351,7 +352,8 @@ bool DefaultPlanner::is_goal_valid( double next_lane_length = 0.0; // combine calculated route lanelets - lanelet::ConstLanelet combined_prev_lanelet = combine_lanelets(path_lanelets); + lanelet::ConstLanelet combined_prev_lanelet = + combine_lanelets_with_shoulder(path_lanelets, shoulder_lanelets_); // check if goal footprint exceeds lane when the goal isn't in parking_lot if ( diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp index 690a864fcdacd..e3983b7f3b962 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -54,7 +54,8 @@ void insert_marker_array( a1->markers.insert(a1->markers.end(), a2.markers.begin(), a2.markers.end()); } -lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets) +lanelet::ConstLanelet combine_lanelets_with_shoulder( + const lanelet::ConstLanelets & lanelets, const lanelet::ConstLanelets & shoulder_lanelets) { lanelet::Points3d lefts; lanelet::Points3d rights; @@ -70,17 +71,48 @@ lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets) } for (const auto & llt : lanelets) { - if (std::count(right_bound_ids.begin(), right_bound_ids.end(), llt.leftBound().id()) < 1) { - for (const auto & pt : llt.leftBound()) { - lefts.push_back(lanelet::Point3d(pt)); - } + // lambda to check if shoulder lane which share left bound with lanelets exist + const auto find_bound_shared_shoulder = + [&shoulder_lanelets](const auto & lanelet_bound, const auto & get_shoulder_bound) { + return std::find_if( + shoulder_lanelets.begin(), shoulder_lanelets.end(), + [&lanelet_bound, &get_shoulder_bound](const auto & shoulder_llt) { + return lanelet_bound.id() == get_shoulder_bound(shoulder_llt).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); }); + }; + + // check if shoulder lanelets which has RIGHT bound same to LEFT bound of lanelet exist + const auto left_shared_shoulder_it = find_bound_shared_shoulder( + llt.leftBound(), [](const auto & shoulder_llt) { return shoulder_llt.rightBound(); }); + if (left_shared_shoulder_it != shoulder_lanelets.end()) { + // if exist, add left bound of SHOULDER lanelet to lefts + add_bound(left_shared_shoulder_it->leftBound(), lefts); + } else if ( + // if not exist, add left bound of lanelet to lefts + std::count(right_bound_ids.begin(), right_bound_ids.end(), llt.leftBound().id()) < 1) { + add_bound(llt.leftBound(), lefts); } - if (std::count(left_bound_ids.begin(), left_bound_ids.end(), llt.rightBound().id()) < 1) { - for (const auto & pt : llt.rightBound()) { - rights.push_back(lanelet::Point3d(pt)); - } + + // check if shoulder lanelets which has LEFT bound same to RIGHT bound of lanelet exist + const auto right_shared_shoulder_it = find_bound_shared_shoulder( + llt.rightBound(), [](const auto & shoulder_llt) { return shoulder_llt.leftBound(); }); + if (right_shared_shoulder_it != shoulder_lanelets.end()) { + // if exist, add right bound of SHOULDER lanelet to rights + add_bound(right_shared_shoulder_it->rightBound(), rights); + } else if ( + // if not exist, add right bound of lanelet to rights + 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); diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp index 3ea6237f38501..3287267a00dfe 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -49,7 +49,8 @@ void set_color(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, doub void insert_marker_array( visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2); -lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets); +lanelet::ConstLanelet combine_lanelets_with_shoulder( + const lanelet::ConstLanelets & lanelets, const lanelet::ConstLanelets & shoulder_lanelets); std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet); geometry_msgs::msg::Pose convertBasicPoint3dToPose( const lanelet::BasicPoint3d & point, const double lane_yaw); From d5fd32601349843a52999e6d4472d88abeb56daf Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Fri, 12 Jan 2024 05:21:58 +0100 Subject: [PATCH 230/276] build(probabilistic_occupancy_grid_map): move header files to the probabilistic_occupancy_grid_map folder to avoid conflicts (#5839) * build(probabilistic_occupancy_grid_map): move header files to the probabilistic_occupancy_grid_map folder to avoid conflicts Signed-off-by: Esteve Fernandez * style(pre-commit): autofix --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../cost_value.hpp | 6 +++--- .../fusion/single_frame_fusion_policy.hpp | 8 ++++---- .../fusion/synchronized_grid_map_fusion_node.hpp | 14 +++++++------- .../laserscan_based_occupancy_grid_map_node.hpp | 12 ++++++------ .../occupancy_grid_map.hpp | 6 +++--- .../occupancy_grid_map_base.hpp | 6 +++--- .../occupancy_grid_map_fixed.hpp | 8 ++++---- .../occupancy_grid_map_projective.hpp | 8 ++++---- .../pointcloud_based_occupancy_grid_map_node.hpp | 12 ++++++------ ...upancy_grid_map_binary_bayes_filter_updater.hpp | 8 ++++---- ...ancy_grid_map_log_odds_bayes_filter_updater.hpp | 12 ++++++------ .../occupancy_grid_map_updater_interface.hpp | 8 ++++---- .../utils/utils.hpp | 8 ++++---- .../src/fusion/single_frame_fusion_policy.cpp | 2 +- .../fusion/synchronized_grid_map_fusion_node.cpp | 6 +++--- .../laserscan_based_occupancy_grid_map_node.cpp | 6 +++--- .../occupancy_grid_map.cpp | 4 ++-- .../occupancy_grid_map_base.cpp | 6 +++--- .../occupancy_grid_map_fixed.cpp | 6 +++--- .../occupancy_grid_map_projective.cpp | 6 +++--- .../pointcloud_based_occupancy_grid_map_node.cpp | 10 +++++----- ...upancy_grid_map_binary_bayes_filter_updater.cpp | 4 ++-- ...ancy_grid_map_log_odds_bayes_filter_updater.cpp | 4 ++-- .../src/utils/utils.cpp | 2 +- .../test/cost_value_test.cpp | 4 ++-- .../test/fusion_policy_test.cpp | 7 ++++--- .../test/test_utils.cpp | 6 +++--- 27 files changed, 95 insertions(+), 94 deletions(-) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/cost_value.hpp (95%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/fusion/single_frame_fusion_policy.hpp (88%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/fusion/synchronized_grid_map_fusion_node.hpp (87%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp (84%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp (92%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp (92%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp (75%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp (78%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp (83%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp (75%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp (71%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/updater/occupancy_grid_map_updater_interface.hpp (78%) rename perception/probabilistic_occupancy_grid_map/include/{ => probabilistic_occupancy_grid_map}/utils/utils.hpp (93%) diff --git a/perception/probabilistic_occupancy_grid_map/include/cost_value.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/cost_value.hpp similarity index 95% rename from perception/probabilistic_occupancy_grid_map/include/cost_value.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/cost_value.hpp index e0f18cedcdff1..880297a1210ed 100644 --- a/perception/probabilistic_occupancy_grid_map/include/cost_value.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/cost_value.hpp @@ -48,8 +48,8 @@ * Author: Eitan Marder-Eppstein *********************************************************************/ -#ifndef COST_VALUE_HPP_ -#define COST_VALUE_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE_HPP_ #include @@ -103,4 +103,4 @@ static const CostTranslationTable cost_translation_table; static const InverseCostTranslationTable inverse_cost_translation_table; } // namespace occupancy_cost_value -#endif // COST_VALUE_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/fusion/single_frame_fusion_policy.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp similarity index 88% rename from perception/probabilistic_occupancy_grid_map/include/fusion/single_frame_fusion_policy.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp index 13829b4910d96..1f0553878ef5a 100644 --- a/perception/probabilistic_occupancy_grid_map/include/fusion/single_frame_fusion_policy.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_ -#define FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_ -#include "cost_value.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" #include #include @@ -63,4 +63,4 @@ unsigned char singleFrameOccupancyFusion( const std::vector & reliability); } // namespace fusion_policy -#endif // FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/fusion/synchronized_grid_map_fusion_node.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/synchronized_grid_map_fusion_node.hpp similarity index 87% rename from perception/probabilistic_occupancy_grid_map/include/fusion/synchronized_grid_map_fusion_node.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/synchronized_grid_map_fusion_node.hpp index 6bea5b2a16f72..8f09764688055 100644 --- a/perception/probabilistic_occupancy_grid_map/include/fusion/synchronized_grid_map_fusion_node.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/synchronized_grid_map_fusion_node.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_ -#define FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_ -#include "fusion/single_frame_fusion_policy.hpp" -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp" -#include "updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp" -#include "updater/occupancy_grid_map_updater_interface.hpp" +#include "probabilistic_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp" +#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp" +#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp" +#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp" #include #include @@ -124,4 +124,4 @@ class GridMapFusionNode : public rclcpp::Node } // namespace synchronized_grid_map_fusion -#endif // FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp similarity index 84% rename from perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp index 3a0f1f5ea7433..a8adea6e700e5 100644 --- a/perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ -#define LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ -#include "laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp" -#include "updater/occupancy_grid_map_binary_bayes_filter_updater.hpp" -#include "updater/occupancy_grid_map_updater_interface.hpp" +#include "probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp" +#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp" +#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp" #include #include @@ -102,4 +102,4 @@ class LaserscanBasedOccupancyGridMapNode : public rclcpp::Node } // namespace occupancy_grid_map -#endif // LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp similarity index 92% rename from perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp index a9bbc3fda6ab4..d2210cf9c348a 100644 --- a/perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp @@ -49,8 +49,8 @@ * David V. Lu!! *********************************************************************/ -#ifndef LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_ -#define LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_ #include #include @@ -91,4 +91,4 @@ class OccupancyGridMap : public nav2_costmap_2d::Costmap2D } // namespace costmap_2d -#endif // LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp similarity index 92% rename from perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp index 8f8e1e503d388..f01b2d74e160b 100644 --- a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp @@ -49,8 +49,8 @@ * David V. Lu!! *********************************************************************/ -#ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_ -#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_ #include #include @@ -92,4 +92,4 @@ class OccupancyGridMapInterface : public nav2_costmap_2d::Costmap2D } // namespace costmap_2d -#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp similarity index 75% rename from perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp index 5755cd2c889be..298f327d632d7 100644 --- a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_ -#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_ -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" +#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" namespace costmap_2d { @@ -44,4 +44,4 @@ class OccupancyGridMapFixedBlindSpot : public OccupancyGridMapInterface } // namespace costmap_2d -#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp similarity index 78% rename from perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp index bc278772e9737..67b51d6184c8c 100644 --- a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_ -#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_ -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" +#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" #include @@ -52,4 +52,4 @@ class OccupancyGridMapProjectiveBlindSpot : public OccupancyGridMapInterface } // namespace costmap_2d -#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp similarity index 83% rename from perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp index e34899bb98b0c..93486e0ca56af 100644 --- a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ -#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" -#include "updater/occupancy_grid_map_binary_bayes_filter_updater.hpp" -#include "updater/occupancy_grid_map_updater_interface.hpp" +#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" +#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp" +#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp" #include #include @@ -95,4 +95,4 @@ class PointcloudBasedOccupancyGridMapNode : public rclcpp::Node } // namespace occupancy_grid_map -#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp similarity index 75% rename from perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp index d8f3cb6556bf2..3a921035ef219 100644 --- a/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_ -#define UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_ -#include "updater/occupancy_grid_map_updater_interface.hpp" +#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp" #include #include @@ -39,4 +39,4 @@ class OccupancyGridMapBBFUpdater : public OccupancyGridMapUpdaterInterface } // namespace costmap_2d -#endif // UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp similarity index 71% rename from perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp index 306f8988acab7..f9f100f285d38 100644 --- a/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_ -#define UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_ -#include "fusion/single_frame_fusion_policy.hpp" -#include "updater/occupancy_grid_map_updater_interface.hpp" -#include "utils/utils.hpp" +#include "probabilistic_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp" +#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp" +#include "probabilistic_occupancy_grid_map/utils/utils.hpp" #include #include @@ -45,4 +45,4 @@ class OccupancyGridMapLOBFUpdater : public OccupancyGridMapUpdaterInterface } // namespace costmap_2d -#endif // UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_updater_interface.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp similarity index 78% rename from perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_updater_interface.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp index 9305313ddc2fc..e85edf2245ef3 100644 --- a/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_updater_interface.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_ -#define UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_ -#include "cost_value.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" #include #include @@ -38,4 +38,4 @@ class OccupancyGridMapUpdaterInterface : public nav2_costmap_2d::Costmap2D } // namespace costmap_2d -#endif // UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/utils/utils.hpp similarity index 93% rename from perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp rename to perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/utils/utils.hpp index 46bd14b843dae..0950272dac470 100644 --- a/perception/probabilistic_occupancy_grid_map/include/utils/utils.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/utils/utils.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef UTILS__UTILS_HPP_ -#define UTILS__UTILS_HPP_ +#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_ +#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_ -#include "cost_value.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" #include #include @@ -119,4 +119,4 @@ bool extractCommonPointCloud( unsigned char getApproximateOccupancyState(const unsigned char & value); } // namespace utils -#endif // UTILS__UTILS_HPP_ +#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/src/fusion/single_frame_fusion_policy.cpp b/perception/probabilistic_occupancy_grid_map/src/fusion/single_frame_fusion_policy.cpp index 75e8791a04bca..6ac681eff4916 100644 --- a/perception/probabilistic_occupancy_grid_map/src/fusion/single_frame_fusion_policy.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/fusion/single_frame_fusion_policy.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "fusion/single_frame_fusion_policy.hpp" +#include "probabilistic_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp" namespace fusion_policy { diff --git a/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp b/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp index 6738286ae5592..a88e65e712ac1 100644 --- a/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "fusion/synchronized_grid_map_fusion_node.hpp" +#include "probabilistic_occupancy_grid_map/fusion/synchronized_grid_map_fusion_node.hpp" -#include "cost_value.hpp" -#include "utils/utils.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" +#include "probabilistic_occupancy_grid_map/utils/utils.hpp" namespace synchronized_grid_map_fusion { diff --git a/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp b/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp index b4505eedddd21..777c180fe1a3a 100644 --- a/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp" +#include "probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp" -#include "cost_value.hpp" -#include "utils/utils.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" +#include "probabilistic_occupancy_grid_map/utils/utils.hpp" #include diff --git a/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp b/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp index 59f562cb58f35..3d02be9ca7156 100644 --- a/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp @@ -49,9 +49,9 @@ * David V. Lu!! *********************************************************************/ -#include "laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp" +#include "probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp" -#include "cost_value.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" #include diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.cpp index 8652cfa34d96c..3d176e41583a0 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.cpp @@ -49,10 +49,10 @@ * David V. Lu!! *********************************************************************/ -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" +#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" -#include "cost_value.hpp" -#include "utils/utils.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" +#include "probabilistic_occupancy_grid_map/utils/utils.hpp" #include #include diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp index 56aeea30e0773..00b3e42fdf392 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp" +#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp" -#include "cost_value.hpp" -#include "utils/utils.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" +#include "probabilistic_occupancy_grid_map/utils/utils.hpp" #include #include diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp index 20a5770e37fdb..64b76a2488e24 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp" +#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp" -#include "cost_value.hpp" -#include "utils/utils.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" +#include "probabilistic_occupancy_grid_map/utils/utils.hpp" #include #include diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp index f6369602b8890..82da92da7f146 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp" +#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp" -#include "cost_value.hpp" -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp" -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp" -#include "utils/utils.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" +#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp" +#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp" +#include "probabilistic_occupancy_grid_map/utils/utils.hpp" #include #include diff --git a/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp b/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp index 16de17b1c2e61..40f538a64f6e9 100644 --- a/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "updater/occupancy_grid_map_binary_bayes_filter_updater.hpp" +#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp" -#include "cost_value.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" #include diff --git a/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_log_odds_bayes_filter_updater.cpp b/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_log_odds_bayes_filter_updater.cpp index e45f3d0686fbc..f3e306f262bf0 100644 --- a/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_log_odds_bayes_filter_updater.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_log_odds_bayes_filter_updater.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp" +#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp" -#include "cost_value.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" #include diff --git a/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp b/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp index b876004d89b0a..8009a503167ea 100644 --- a/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "utils/utils.hpp" +#include "probabilistic_occupancy_grid_map/utils/utils.hpp" #include diff --git a/perception/probabilistic_occupancy_grid_map/test/cost_value_test.cpp b/perception/probabilistic_occupancy_grid_map/test/cost_value_test.cpp index baf94fabfd2a1..c41c809a92b0c 100644 --- a/perception/probabilistic_occupancy_grid_map/test/cost_value_test.cpp +++ b/perception/probabilistic_occupancy_grid_map/test/cost_value_test.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "cost_value.hpp" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" -#include "gtest/gtest.h" +#include // Test the CostTranslationTable and InverseCostTranslationTable functions using occupancy_cost_value::cost_translation_table; diff --git a/perception/probabilistic_occupancy_grid_map/test/fusion_policy_test.cpp b/perception/probabilistic_occupancy_grid_map/test/fusion_policy_test.cpp index 2501a361fba58..6b3dc8a2ebcef 100644 --- a/perception/probabilistic_occupancy_grid_map/test/fusion_policy_test.cpp +++ b/perception/probabilistic_occupancy_grid_map/test/fusion_policy_test.cpp @@ -12,9 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "cost_value.hpp" -#include "fusion/single_frame_fusion_policy.hpp" -#include "gtest/gtest.h" +#include "probabilistic_occupancy_grid_map/cost_value.hpp" +#include "probabilistic_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp" + +#include // Test the log-odds update rule TEST(FusionPolicyTest, TestLogOddsUpdateRule) diff --git a/perception/probabilistic_occupancy_grid_map/test/test_utils.cpp b/perception/probabilistic_occupancy_grid_map/test/test_utils.cpp index 367dcee807e7b..4bc3dca0a67bd 100644 --- a/perception/probabilistic_occupancy_grid_map/test/test_utils.cpp +++ b/perception/probabilistic_occupancy_grid_map/test/test_utils.cpp @@ -12,6 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. +// autoware +#include "probabilistic_occupancy_grid_map/utils/utils.hpp" + #include #include @@ -21,9 +24,6 @@ #include #include -// autoware -#include "utils/utils.hpp" - // create pointcloud function pcl::PointCloud createPCLPointCloudWithIteratedHeight(const size_t width) { From 806137321e07bdb1bea0450341d35932f4a83db4 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 12 Jan 2024 13:33:30 +0900 Subject: [PATCH 231/276] feat(crosswalk): change the TTC formula (#6033) * change params * change the TTC formula Signed-off-by: Yuki Takagi --- .../config/crosswalk.param.yaml | 6 +++--- .../src/scene_crosswalk.cpp | 7 +++++-- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index 240963309e9a2..273db320f1027 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -16,7 +16,7 @@ # For the case where the crosswalk width is very wide far_object_threshold: 10.0 # [m] If objects cross X meters behind the stop line, the stop position is determined according to the object position (stop_distance_from_object meters before the object). # For the case where the stop position is determined according to the object position. - stop_distance_from_object: 2.0 # [m] the vehicle decelerates to be able to stop in front of object with margin + stop_distance_from_object: 3.0 # [m] the vehicle decelerates to be able to stop in front of object with margin # params for ego's slow down velocity. These params are not used for the case of "enable_rtc: false". slow_down: @@ -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: [6.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) + ego_pass_first_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_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: [10.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) @@ -62,7 +62,7 @@ # param for target object filtering object_filtering: - crosswalk_attention_range: 1.0 # [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk + crosswalk_attention_range: 2.0 # [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk vehicle_object_cross_angle_threshold: 0.5 # [rad] threshold judging object is crossing walkway as a pedestrian or passing over as a vehicle target_object: unknown: true # [-] whether to look and stop by UNKNOWN objects diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 7175cd0895fc0..acb88a214b0c0 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -766,7 +766,6 @@ CollisionPoint CrosswalkModule::createCollisionPoint( const std::optional object_crosswalk_passage_direction) const { constexpr double min_ego_velocity = 1.38; // [m/s] - const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y); const auto velocity = std::max(planner_param_.min_object_velocity, estimated_velocity); @@ -774,8 +773,12 @@ CollisionPoint CrosswalkModule::createCollisionPoint( CollisionPoint collision_point{}; collision_point.collision_point = nearest_collision_point; collision_point.crosswalk_passage_direction = object_crosswalk_passage_direction; + + // The decision of whether the ego vehicle or the pedestrian goes first is determined by the logic + // for ego_pass_first or yield; even the decision for ego_pass_later does not affect this sense. + // Hence, here, we use the length that would be appropriate for the ego_pass_first judge. collision_point.time_to_collision = - std::max(0.0, dist_ego2cp - planner_param_.stop_distance_from_object - base_link2front) / + std::max(0.0, dist_ego2cp - planner_data_->vehicle_info_.min_longitudinal_offset_m) / std::max(ego_vel.x, min_ego_velocity); collision_point.time_to_vehicle = std::max(0.0, dist_obj2cp) / velocity; From 42069db044b6742fee9bd98247c7c09bcced3ab7 Mon Sep 17 00:00:00 2001 From: Phoebe Wu Date: Fri, 12 Jan 2024 17:05:03 +0800 Subject: [PATCH 232/276] refactor(shape_estimation): rework parameters (#5330) * refactor(shape_estimation): rework parameters Signed-off-by: PhoebeWu21 * style(pre-commit): autofix * refactor(shape_estimation): rework parameters Signed-off-by: PhoebeWu21 * refactor(shape_estimation): rework parameters Signed-off-by: PhoebeWu21 --------- Signed-off-by: PhoebeWu21 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- perception/shape_estimation/CMakeLists.txt | 1 + perception/shape_estimation/README.md | 6 +- .../config/shape_estimation.param.yaml | 7 +++ .../launch/shape_estimation.launch.xml | 10 ++-- .../schema/shape_estimation.schema.json | 56 +++++++++++++++++++ perception/shape_estimation/src/node.cpp | 10 ++-- 6 files changed, 74 insertions(+), 16 deletions(-) create mode 100644 perception/shape_estimation/config/shape_estimation.param.yaml create mode 100644 perception/shape_estimation/schema/shape_estimation.schema.json diff --git a/perception/shape_estimation/CMakeLists.txt b/perception/shape_estimation/CMakeLists.txt index 5ae6002cd7c3b..8eb7a15b5a885 100644 --- a/perception/shape_estimation/CMakeLists.txt +++ b/perception/shape_estimation/CMakeLists.txt @@ -64,4 +64,5 @@ rclcpp_components_register_node(shape_estimation_node ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/perception/shape_estimation/README.md b/perception/shape_estimation/README.md index c50d66b546213..b635631381cc3 100644 --- a/perception/shape_estimation/README.md +++ b/perception/shape_estimation/README.md @@ -36,11 +36,7 @@ This node calculates a refined object shape (bounding box, cylinder, convex hull ## Parameters -| Name | Type | Default Value | Description | -| --------------------------- | ---- | ------------- | --------------------------------------------------- | -| `use_corrector` | bool | true | The flag to apply rule-based filter | -| `use_filter` | bool | true | The flag to apply rule-based corrector | -| `use_vehicle_reference_yaw` | bool | true | The flag to use vehicle reference yaw for corrector | +{{ json_to_markdown("perception/shape_estimation/schema/shape_estimation.schema.json") }} ## Assumptions / Known limits diff --git a/perception/shape_estimation/config/shape_estimation.param.yaml b/perception/shape_estimation/config/shape_estimation.param.yaml new file mode 100644 index 0000000000000..253516fffe0d4 --- /dev/null +++ b/perception/shape_estimation/config/shape_estimation.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + use_corrector: true + use_filter: true + use_vehicle_reference_yaw: false + use_vehicle_reference_shape_size: false + use_boost_bbox_optimizer: false diff --git a/perception/shape_estimation/launch/shape_estimation.launch.xml b/perception/shape_estimation/launch/shape_estimation.launch.xml index 8e90e3ea57cc0..65d1944417cc0 100644 --- a/perception/shape_estimation/launch/shape_estimation.launch.xml +++ b/perception/shape_estimation/launch/shape_estimation.launch.xml @@ -1,18 +1,16 @@ - - + + + - - - - + diff --git a/perception/shape_estimation/schema/shape_estimation.schema.json b/perception/shape_estimation/schema/shape_estimation.schema.json new file mode 100644 index 0000000000000..d81bfa636a923 --- /dev/null +++ b/perception/shape_estimation/schema/shape_estimation.schema.json @@ -0,0 +1,56 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Shape Estimation Node", + "type": "object", + "definitions": { + "shape_estimation": { + "type": "object", + "properties": { + "use_corrector": { + "type": "boolean", + "description": "The flag to apply rule-based corrector.", + "default": "true" + }, + "use_filter": { + "type": "boolean", + "description": "The flag to apply rule-based filter", + "default": "true" + }, + "use_vehicle_reference_yaw": { + "type": "boolean", + "description": "The flag to use vehicle reference yaw for corrector", + "default": "false" + }, + "use_vehicle_reference_shape_size": { + "type": "boolean", + "description": "The flag to use vehicle reference shape size", + "default": "false" + }, + "use_boost_bbox_optimizer": { + "type": "boolean", + "description": "The flag to use boost bbox optimizer", + "default": "false" + } + }, + "required": [ + "use_corrector", + "use_filter", + "use_vehicle_reference_yaw", + "use_vehicle_reference_shape_size", + "use_boost_bbox_optimizer" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/shape_estimation" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/shape_estimation/src/node.cpp b/perception/shape_estimation/src/node.cpp index 987cf8106c99e..624ca604d8fbf 100644 --- a/perception/shape_estimation/src/node.cpp +++ b/perception/shape_estimation/src/node.cpp @@ -42,11 +42,11 @@ ShapeEstimationNode::ShapeEstimationNode(const rclcpp::NodeOptions & node_option "input", rclcpp::QoS{1}, std::bind(&ShapeEstimationNode::callback, this, _1)); pub_ = create_publisher("objects", rclcpp::QoS{1}); - bool use_corrector = declare_parameter("use_corrector", true); - bool use_filter = declare_parameter("use_filter", true); - use_vehicle_reference_yaw_ = declare_parameter("use_vehicle_reference_yaw", true); - use_vehicle_reference_shape_size_ = declare_parameter("use_vehicle_reference_shape_size", true); - bool use_boost_bbox_optimizer = declare_parameter("use_boost_bbox_optimizer", false); + bool use_corrector = declare_parameter("use_corrector"); + bool use_filter = declare_parameter("use_filter"); + use_vehicle_reference_yaw_ = declare_parameter("use_vehicle_reference_yaw"); + use_vehicle_reference_shape_size_ = declare_parameter("use_vehicle_reference_shape_size"); + bool use_boost_bbox_optimizer = declare_parameter("use_boost_bbox_optimizer"); RCLCPP_INFO(this->get_logger(), "using boost shape estimation : %d", use_boost_bbox_optimizer); estimator_ = std::make_unique(use_corrector, use_filter, use_boost_bbox_optimizer); From 98baaf4af9abb508577f51c26a162c063c9f6b35 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Fri, 12 Jan 2024 18:05:46 +0900 Subject: [PATCH 233/276] feat(landmark_manager): add get_landmarrks func (#6063) Signed-off-by: yamato-ando Co-authored-by: yamato-ando --- .../landmark_manager/landmark_manager.hpp | 2 ++ .../landmark_manager/src/landmark_manager.cpp | 16 ++++++++++++++++ 2 files changed, 18 insertions(+) diff --git a/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp b/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp index 7e78ed713dddc..c2b0751d91f9a 100644 --- a/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp +++ b/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp @@ -44,6 +44,8 @@ class LandmarkManager const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, const std::string & target_subtype); + [[nodiscard]] std::vector get_landmarks() const; + [[nodiscard]] visualization_msgs::msg::MarkerArray get_landmarks_as_marker_array_msg() const; [[nodiscard]] geometry_msgs::msg::Pose calculate_new_self_pose( diff --git a/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp index 7ddd66efea0a6..57bfcde461af6 100644 --- a/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp +++ b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp @@ -83,6 +83,22 @@ void LandmarkManager::parse_landmarks( } } +std::vector LandmarkManager::get_landmarks() const +{ + std::vector landmarks; + + landmark_manager::Landmark landmark; + for (const auto & [landmark_id_str, landmark_poses] : landmarks_map_) { + for (const auto & pose : landmark_poses) { + landmark.id = landmark_id_str; + landmark.pose = pose; + landmarks.push_back(landmark); + } + } + + return landmarks; +} + visualization_msgs::msg::MarkerArray LandmarkManager::get_landmarks_as_marker_array_msg() const { int32_t id = 0; From 8ff11175c10f01f31297338fd9e365d3638746ae Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Fri, 12 Jan 2024 18:41:54 +0900 Subject: [PATCH 234/276] feat(perception_rviz_plugin): visualize object heading direction on 3d bounding box (#6035) * feat(autoware_auto_perception_rviz_plugin): visualize object heading Signed-off-by: Taekjin LEE * feat(autoware_auto_perception_rviz_plugin): visualize heading only it is available Signed-off-by: Taekjin LEE * feat(autoware_auto_perception_rviz_plugin): 2d visualization implemented Signed-off-by: Taekjin LEE * feat(autoware_auto_perception_rviz_plugin): integrating repeating codes Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../object_polygon_detail.hpp | 18 +- .../object_polygon_display_base.hpp | 11 +- .../detected_objects_display.cpp | 4 +- .../object_polygon_detail.cpp | 259 ++++++++---------- .../predicted_objects_display.cpp | 2 +- .../tracked_objects_display.cpp | 4 +- 6 files changed, 142 insertions(+), 156 deletions(-) diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp index b661010c19a4d..deaa6be90b5f6 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp @@ -83,13 +83,15 @@ AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::Sha get_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, - const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width); + const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width, + const bool & is_orientation_available = true); AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr get_2d_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, - const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width); + const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width, + const bool & is_orientation_available = true); /// \brief Convert the given polygon into a marker representing the shape in 3d /// \param centroid Centroid position of the shape in Object.header.frame_id frame @@ -139,14 +141,26 @@ get_path_confidence_marker_ptr( const autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, const std_msgs::msg::ColorRGBA & path_confidence_color); +AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_line_list_from_points( + const double point_list[][3], const int point_pairs[][2], const int & num_pairs, + std::vector & points); + AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_bounding_box_line_list( const autoware_auto_perception_msgs::msg::Shape & shape, std::vector & points); +AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_bounding_box_direction_line_list( + const autoware_auto_perception_msgs::msg::Shape & shape, + std::vector & points); + AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_2d_bounding_box_bottom_line_list( const autoware_auto_perception_msgs::msg::Shape & shape, std::vector & points); +AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_2d_bounding_box_bottom_direction_line_list( + const autoware_auto_perception_msgs::msg::Shape & shape, + std::vector & points); + AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_cylinder_line_list( const autoware_auto_perception_msgs::msg::Shape & shape, std::vector & points); diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp index 223611520b2fc..240cbdc9efc5b 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp @@ -170,14 +170,16 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase std::optional get_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, - const ClassificationContainerT & labels, const double & line_width) const + const ClassificationContainerT & labels, const double & line_width, + const bool & is_orientation_available) const { const std_msgs::msg::ColorRGBA color_rgba = get_color_rgba(labels); if (m_display_type_property->getOptionInt() == 0) { - return detail::get_shape_marker_ptr(shape_msg, centroid, orientation, color_rgba, line_width); + return detail::get_shape_marker_ptr( + shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available); } else if (m_display_type_property->getOptionInt() == 1) { return detail::get_2d_shape_marker_ptr( - shape_msg, centroid, orientation, color_rgba, line_width); + shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available); } else { return std::nullopt; } @@ -187,7 +189,8 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase visualization_msgs::msg::Marker::SharedPtr get_2d_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, - const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width); + const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width, + const bool & is_orientation_available); /// \brief Convert given shape msg into a Marker to visualize label name /// \tparam ClassificationContainerT List type with ObjectClassificationMsg diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp index 5dcdce791c585..db57e0e59a1ce 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp @@ -38,7 +38,9 @@ void DetectedObjectsDisplay::processMessage(DetectedObjects::ConstSharedPtr msg) auto shape_marker = get_shape_marker_ptr( object.shape, object.kinematics.pose_with_covariance.pose.position, object.kinematics.pose_with_covariance.pose.orientation, object.classification, - get_line_width()); + get_line_width(), + object.kinematics.orientation_availability == + autoware_auto_perception_msgs::msg::DetectedObjectKinematics::AVAILABLE); if (shape_marker) { auto shape_marker_ptr = shape_marker.value(); shape_marker_ptr->header = msg->header; diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp index d87541b7840a9..84321559f3541 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp @@ -262,7 +262,8 @@ visualization_msgs::msg::Marker::SharedPtr get_existence_probability_marker_ptr( visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, - const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width) + const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width, + const bool & is_orientation_available) { auto marker_ptr = std::make_shared(); marker_ptr->ns = std::string("shape"); @@ -271,6 +272,9 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr( if (shape_msg.type == Shape::BOUNDING_BOX) { marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; calc_bounding_box_line_list(shape_msg, marker_ptr->points); + if (is_orientation_available) { + calc_bounding_box_direction_line_list(shape_msg, marker_ptr->points); + } } else if (shape_msg.type == Shape::CYLINDER) { marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; calc_cylinder_line_list(shape_msg, marker_ptr->points); @@ -294,7 +298,8 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr( visualization_msgs::msg::Marker::SharedPtr get_2d_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, - const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width) + const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width, + const bool & is_orientation_available) { auto marker_ptr = std::make_shared(); marker_ptr->ns = std::string("shape"); @@ -303,6 +308,9 @@ visualization_msgs::msg::Marker::SharedPtr get_2d_shape_marker_ptr( if (shape_msg.type == Shape::BOUNDING_BOX) { marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; calc_2d_bounding_box_bottom_line_list(shape_msg, marker_ptr->points); + if (is_orientation_available) { + calc_2d_bounding_box_bottom_direction_line_list(shape_msg, marker_ptr->points); + } } else if (shape_msg.type == Shape::CYLINDER) { marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; calc_2d_cylinder_bottom_line_list(shape_msg, marker_ptr->points); @@ -323,163 +331,120 @@ visualization_msgs::msg::Marker::SharedPtr get_2d_shape_marker_ptr( return marker_ptr; } +void calc_line_list_from_points( + const double point_list[][3], const int point_pairs[][2], const int & num_pairs, + std::vector & points) +{ + geometry_msgs::msg::Point point; + for (int i = 0; i < num_pairs; ++i) { + point.x = point_list[point_pairs[i][0]][0]; + point.y = point_list[point_pairs[i][0]][1]; + point.z = point_list[point_pairs[i][0]][2]; + points.push_back(point); + point.x = point_list[point_pairs[i][1]][0]; + point.y = point_list[point_pairs[i][1]][1]; + point.z = point_list[point_pairs[i][1]][2]; + points.push_back(point); + } +} + void calc_bounding_box_line_list( const autoware_auto_perception_msgs::msg::Shape & shape, std::vector & points) { + const double length_half = shape.dimensions.x / 2.0; + const double width_half = shape.dimensions.y / 2.0; + const double height_half = shape.dimensions.z / 2.0; + geometry_msgs::msg::Point point; + + // bounding box corner points + // top and bottom surface, clockwise + const double point_list[8][3] = { + {length_half, width_half, height_half}, {length_half, -width_half, height_half}, + {-length_half, -width_half, height_half}, {-length_half, width_half, height_half}, + {length_half, width_half, -height_half}, {length_half, -width_half, -height_half}, + {-length_half, -width_half, -height_half}, {-length_half, width_half, -height_half}, + }; + const int point_pairs[12][2] = { + {0, 1}, {1, 2}, {2, 3}, {3, 0}, {4, 5}, {5, 6}, {6, 7}, {7, 4}, {0, 4}, {1, 5}, {2, 6}, {3, 7}, + }; + calc_line_list_from_points(point_list, point_pairs, 12, points); +} + +void calc_bounding_box_direction_line_list( + const autoware_auto_perception_msgs::msg::Shape & shape, + std::vector & points) +{ + // direction triangle + const double length_half = shape.dimensions.x / 2.0; + const double width_half = shape.dimensions.y / 2.0; + const double height_half = shape.dimensions.z / 2.0; + const double triangle_size_half = shape.dimensions.y / 1.4; geometry_msgs::msg::Point point; - point.x = shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - point.x = shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - point.x = shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = -shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = -shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - - // up surface - point.x = shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - point.x = shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = -shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = shape.dimensions.z / 2.0; - points.push_back(point); - - // down surface - point.x = shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - point.x = shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = -shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); + + // triangle-shaped direction indicator + const double point_list[6][3] = { + {length_half, 0, height_half}, + {length_half - triangle_size_half, width_half, height_half}, + {length_half - triangle_size_half, -width_half, height_half}, + {length_half, 0, -height_half}, + {length_half, width_half, height_half}, + {length_half, -width_half, height_half}, + }; + const int point_pairs[5][2] = { + {0, 1}, {1, 2}, {0, 2}, {3, 4}, {3, 5}, + }; + calc_line_list_from_points(point_list, point_pairs, 5, points); } void calc_2d_bounding_box_bottom_line_list( const autoware_auto_perception_msgs::msg::Shape & shape, std::vector & points) { + const double length_half = shape.dimensions.x / 2.0; + const double width_half = shape.dimensions.y / 2.0; + const double height_half = shape.dimensions.z / 2.0; geometry_msgs::msg::Point point; - // down surface - point.x = shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - point.x = shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = -shape.dimensions.x / 2.0; - point.y = shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - - point.x = shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); - point.x = -shape.dimensions.x / 2.0; - point.y = -shape.dimensions.y / 2.0; - point.z = -shape.dimensions.z / 2.0; - points.push_back(point); + + // bounding box corner points + // top surface, clockwise + const double point_list[4][3] = { + {length_half, width_half, -height_half}, + {length_half, -width_half, -height_half}, + {-length_half, -width_half, -height_half}, + {-length_half, width_half, -height_half}, + }; + const int point_pairs[4][2] = { + {0, 1}, + {1, 2}, + {2, 3}, + {3, 0}, + }; + calc_line_list_from_points(point_list, point_pairs, 4, points); +} + +void calc_2d_bounding_box_bottom_direction_line_list( + const autoware_auto_perception_msgs::msg::Shape & shape, + std::vector & points) +{ + const double length_half = shape.dimensions.x / 2.0; + const double width_half = shape.dimensions.y / 2.0; + const double height_half = shape.dimensions.z / 2.0; + const double triangle_size_half = shape.dimensions.y / 1.4; + geometry_msgs::msg::Point point; + + // triangle-shaped direction indicator + const double point_list[6][3] = { + {length_half, 0, -height_half}, + {length_half - triangle_size_half, width_half, -height_half}, + {length_half - triangle_size_half, -width_half, -height_half}, + }; + const int point_pairs[3][2] = { + {0, 1}, + {1, 2}, + {0, 2}, + }; + calc_line_list_from_points(point_list, point_pairs, 3, points); } void calc_cylinder_line_list( diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp index 438d70f052b4a..aa9eded82a88e 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp @@ -77,7 +77,7 @@ std::vector PredictedObjectsDisplay: auto shape_marker = get_shape_marker_ptr( object.shape, object.kinematics.initial_pose_with_covariance.pose.position, object.kinematics.initial_pose_with_covariance.pose.orientation, object.classification, - get_line_width()); + get_line_width(), true); if (shape_marker) { auto shape_marker_ptr = shape_marker.value(); shape_marker_ptr->header = msg->header; diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp index 75b094b49a762..fb53dbe1c2b8d 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp @@ -59,7 +59,9 @@ void TrackedObjectsDisplay::processMessage(TrackedObjects::ConstSharedPtr msg) // Get marker for shape auto shape_marker = get_shape_marker_ptr( object.shape, object.kinematics.pose_with_covariance.pose.position, - object.kinematics.pose_with_covariance.pose.orientation, object.classification, line_width); + object.kinematics.pose_with_covariance.pose.orientation, object.classification, line_width, + object.kinematics.orientation_availability == + autoware_auto_perception_msgs::msg::DetectedObjectKinematics::AVAILABLE); if (shape_marker) { auto shape_marker_ptr = shape_marker.value(); shape_marker_ptr->header = msg->header; From 2c7d0ece575397a427eb97e5024e0f75e50c0af5 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 14 Jan 2024 23:37:39 +0900 Subject: [PATCH 235/276] fix(motion_utils): add guard to calcCurvature (#6070) * fix(motion_utils): add guard to calcCurvature Signed-off-by: kosuke55 * style(pre-commit): autofix --------- Signed-off-by: kosuke55 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/motion_utils/trajectory/trajectory.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp index d81f75815ecc6..b9136bc4002e3 100644 --- a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp @@ -952,7 +952,10 @@ calcArcLength>( template std::vector calcCurvature(const T & points) { - std::vector curvature_vec(points.size()); + std::vector curvature_vec(points.size(), 0.0); + if (points.size() < 3) { + return curvature_vec; + } for (size_t i = 1; i < points.size() - 1; ++i) { const auto p1 = tier4_autoware_utils::getPoint(points.at(i - 1)); From ad049e3b3b596b8b3ff57928d90a4b64cd452c5a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 15 Jan 2024 09:40:51 +0900 Subject: [PATCH 236/276] feat(geography_utils): add mgrs code in projector (#5990) Signed-off-by: Takayuki Murooka --- common/geography_utils/src/lanelet2_projector.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/common/geography_utils/src/lanelet2_projector.cpp b/common/geography_utils/src/lanelet2_projector.cpp index 3e982ac2ccf4d..532606248cd1f 100644 --- a/common/geography_utils/src/lanelet2_projector.cpp +++ b/common/geography_utils/src/lanelet2_projector.cpp @@ -34,6 +34,7 @@ std::unique_ptr get_lanelet2_projector(const MapProjectorInf } else if (projector_info.projector_type == MapProjectorInfo::MGRS) { lanelet::projection::MGRSProjector projector{}; + projector.setMGRSCode(projector_info.mgrs_grid); return std::make_unique(projector); } else if (projector_info.projector_type == MapProjectorInfo::TRANSVERSE_MERCATOR) { From d2bb615c92be5394dcb3658e524dba77d5a01c3b Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 15 Jan 2024 18:10:15 +0900 Subject: [PATCH 237/276] feat(mpc): calculate mpc predicted trajectory in the world coordinate to improve accuracy (#5576) * remake Signed-off-by: Takamasa Horibe * remove maybe_unused in decleration Signed-off-by: Takamasa Horibe * support two predicted trajectories in world and Frenet coordinate Signed-off-by: Takamasa Horibe * fix test Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../include/mpc_lateral_controller/mpc.hpp | 30 +-- .../mpc_lateral_controller.hpp | 2 +- .../mpc_lateral_controller/mpc_trajectory.hpp | 6 + .../mpc_lateral_controller/mpc_utils.hpp | 15 ++ .../vehicle_model_bicycle_dynamics.hpp | 10 + .../vehicle_model_bicycle_kinematics.hpp | 10 + ...icle_model_bicycle_kinematics_no_delay.hpp | 10 + .../vehicle_model/vehicle_model_interface.hpp | 46 +++- .../lateral_controller_defaults.param.yaml | 2 + control/mpc_lateral_controller/src/mpc.cpp | 64 +++--- .../src/mpc_lateral_controller.cpp | 90 ++++---- .../src/mpc_trajectory.cpp | 16 ++ .../mpc_lateral_controller/src/mpc_utils.cpp | 26 +++ .../vehicle_model_bicycle_dynamics.cpp | 44 ++++ .../vehicle_model_bicycle_kinematics.cpp | 81 +++++++ ...icle_model_bicycle_kinematics_no_delay.cpp | 78 +++++++ .../vehicle_model/vehicle_model_interface.cpp | 8 +- .../mpc_lateral_controller/test/test_mpc.cpp | 205 ++++++++++-------- .../param/lateral/mpc.param.yaml | 2 + 19 files changed, 560 insertions(+), 185 deletions(-) diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp index 186481e92cdc4..2e83c5ab847c4 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp @@ -221,6 +221,7 @@ class MPC double m_min_prediction_length = 5.0; // Minimum prediction distance. + rclcpp::Publisher::SharedPtr m_debug_frenet_predicted_trajectory_pub; /** * @brief Get variables for MPC calculation. * @param trajectory The reference trajectory. @@ -333,6 +334,19 @@ class MPC const MPCMatrix & m, const MatrixXd & x0, const MatrixXd & Uex, const double u_filtered, const float current_steer, const double predict_dt) const; + /** + * @brief calculate predicted trajectory + * @param mpc_matrix The MPC matrix used in the mpc problem. + * @param x0 initial state used in the mpc problem. + * @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. + * @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; + /** * @brief Check if the MPC matrix has any invalid values. * @param m The MPC matrix to check. @@ -352,18 +366,6 @@ class MPC : m_param.nominal_weight; } - /** - * @brief Calculate the predicted trajectory for the ego vehicle based on the MPC result. - * @param mpc_resampled_reference_trajectory The resampled reference trajectory. - * @param mpc_matrix The MPC matrix used for optimization. - * @param x0_delayed The delayed initial state vector. - * @param Uex The optimized input vector. - * @return The predicted trajectory. - */ - Trajectory calcPredictedTrajectory( - const MPCTrajectory & mpc_resampled_reference_trajectory, const MPCMatrix & mpc_matrix, - const VectorXd & x0_delayed, const VectorXd & Uex) const; - /** * @brief Generate diagnostic data for debugging purposes. * @param reference_trajectory The reference trajectory. @@ -424,8 +426,10 @@ 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 + //!< Constructor. - MPC() = default; + explicit MPC(rclcpp::Node & node); /** * @brief Calculate control command using the MPC algorithm. diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp index 441101abfc243..92b01247105c6 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp @@ -91,7 +91,7 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase // trajectory buffer for detecting new trajectory std::deque m_trajectory_buffer; - MPC m_mpc; // MPC object for trajectory following. + std::unique_ptr m_mpc; // MPC object for trajectory following. // Check is mpc output converged bool m_is_mpc_history_filled{false}; diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_trajectory.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_trajectory.hpp index f77ef72608edd..7e1c7ebdf1348 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_trajectory.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_trajectory.hpp @@ -85,6 +85,12 @@ class MPCTrajectory */ size_t size() const; + /** + * @brief get trajectory point at index i + * @return trajectory point at index i + */ + MPCTrajectoryPoint at(const size_t i) const; + /** * @return true if the components sizes are all 0 or are inconsistent */ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_utils.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_utils.hpp index 036e6a32a9b83..9062ff1ea34e3 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_utils.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_utils.hpp @@ -92,6 +92,13 @@ Trajectory convertToAutowareTrajectory(const MPCTrajectory & input); */ void calcMPCTrajectoryArcLength(const MPCTrajectory & trajectory, std::vector & arc_length); +/** + * @brief calculate the arc length of the given trajectory + * @param [in] trajectory trajectory for which to calculate the arc length + * @return total arc length + */ +double calcMPCTrajectoryArcLength(const MPCTrajectory & trajectory); + /** * @brief resample the given trajectory with the given fixed interval * @param [in] input trajectory to resample @@ -194,6 +201,14 @@ double calcStopDistance(const Trajectory & current_trajectory, const int origin) void extendTrajectoryInYawDirection( const double yaw, const double interval, const bool is_forward_shift, MPCTrajectory & traj); +/** + * @brief clip trajectory size by length + * @param [in] trajectory original trajectory + * @param [in] length clip length + * @return clipped trajectory + */ +MPCTrajectory clipTrajectoryByLength(const MPCTrajectory & trajectory, const double length); + /** * @brief Updates the value of a parameter with the given name. * @tparam T The type of the parameter value. diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp index 29cab73826f31..488a3c7ab8be2 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp @@ -103,6 +103,16 @@ class DynamicsBicycleModel : public VehicleModelInterface std::string modelName() override { return "dynamics"; }; + MPCTrajectory calculatePredictedTrajectoryInWorldCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d, + const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const override; + + MPCTrajectory calculatePredictedTrajectoryInFrenetCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d, + const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const override; + private: double m_lf; //!< @brief length from center of mass to front wheel [m] double m_lr; //!< @brief length from center of mass to rear wheel [m] diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp index fb113d5e30df7..e2f66e95ab0e3 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp @@ -91,6 +91,16 @@ class KinematicsBicycleModel : public VehicleModelInterface std::string modelName() override { return "kinematics"; }; + MPCTrajectory calculatePredictedTrajectoryInWorldCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d, + const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const override; + + MPCTrajectory calculatePredictedTrajectoryInFrenetCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d, + const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const override; + private: double m_steer_lim; //!< @brief steering angle limit [rad] double m_steer_tau; //!< @brief steering time constant for 1d-model [s] diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp index 93d84caa89992..b503ad8eb1d13 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp @@ -87,6 +87,16 @@ class KinematicsBicycleModelNoDelay : public VehicleModelInterface std::string modelName() override { return "kinematics_no_delay"; }; + MPCTrajectory calculatePredictedTrajectoryInWorldCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d, + const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const override; + + MPCTrajectory calculatePredictedTrajectoryInFrenetCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d, + const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const override; + private: double m_steer_lim; //!< @brief steering angle limit [rad] }; diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp index 808ec1b7def2c..68806ff5a00dc 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp @@ -15,6 +15,8 @@ #ifndef MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_ #define MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_ +#include "mpc_lateral_controller/mpc_trajectory.hpp" + #include #include @@ -55,25 +57,25 @@ class VehicleModelInterface * @brief get state x dimension * @return state dimension */ - int getDimX(); + int getDimX() const; /** * @brief get input u dimension * @return input dimension */ - int getDimU(); + int getDimU() const; /** * @brief get output y dimension * @return output dimension */ - int getDimY(); + int getDimY() const; /** * @brief get wheelbase of the vehicle * @return wheelbase value [m] */ - double getWheelbase(); + double getWheelbase() const; /** * @brief set velocity @@ -109,6 +111,42 @@ class VehicleModelInterface * @brief returns model name e.g. kinematics, dynamics */ virtual std::string modelName() = 0; + + /** + * @brief Calculate the predicted trajectory for the ego vehicle based on the MPC result in world + * coordinate + * @param a_d The MPC A matrix used for optimization. + * @param b_d The MPC B matrix used for optimization. + * @param c_d The MPC C matrix used for optimization. + * @param w_d The MPC W matrix used for optimization. + * @param x0 initial state vector. + * @param Uex The optimized input vector. + * @param reference_trajectory The resampled reference trajectory. + * @param dt delta time used in the optimization + * @return The predicted trajectory. + */ + virtual MPCTrajectory calculatePredictedTrajectoryInWorldCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d, + const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const = 0; + + /** + * @brief Calculate the predicted trajectory for the ego vehicle based on the MPC result in Frenet + * Coordinate + * @param a_d The MPC A matrix used for optimization. + * @param b_d The MPC B matrix used for optimization. + * @param c_d The MPC C matrix used for optimization. + * @param w_d The MPC W matrix used for optimization. + * @param x0 initial state vector. + * @param Uex The optimized input vector. + * @param reference_trajectory The resampled reference trajectory. + * @param dt delta time used in the optimization + * @return The predicted trajectory. + */ + virtual MPCTrajectory calculatePredictedTrajectoryInFrenetCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d, + const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const = 0; }; } // namespace autoware::motion::control::mpc_lateral_controller #endif // MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_ diff --git a/control/mpc_lateral_controller/param/lateral_controller_defaults.param.yaml b/control/mpc_lateral_controller/param/lateral_controller_defaults.param.yaml index 59d3f759c9c2f..182458d532c8a 100644 --- a/control/mpc_lateral_controller/param/lateral_controller_defaults.param.yaml +++ b/control/mpc_lateral_controller/param/lateral_controller_defaults.param.yaml @@ -83,3 +83,5 @@ mass_rr: 600.0 cf: 155494.663 cr: 155494.663 + + debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate diff --git a/control/mpc_lateral_controller/src/mpc.cpp b/control/mpc_lateral_controller/src/mpc.cpp index 153c2ae61d076..8fa95f4b3b87b 100644 --- a/control/mpc_lateral_controller/src/mpc.cpp +++ b/control/mpc_lateral_controller/src/mpc.cpp @@ -17,6 +17,7 @@ #include "interpolation/linear_interpolation.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "mpc_lateral_controller/mpc_utils.hpp" +#include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/math/unit_conversion.hpp" #include @@ -28,6 +29,12 @@ using tier4_autoware_utils::calcDistance2d; using tier4_autoware_utils::normalizeRadian; using tier4_autoware_utils::rad2deg; +MPC::MPC(rclcpp::Node & node) +{ + m_debug_frenet_predicted_trajectory_pub = node.create_publisher( + "~/debug/predicted_trajectory_in_frenet_coordinate", rclcpp::QoS(1)); +} + bool MPC::calculateMPC( const SteeringReport & current_steer, const Odometry & current_kinematics, AckermannLateralCommand & ctrl_cmd, Trajectory & predicted_trajectory, @@ -97,9 +104,9 @@ bool MPC::calculateMPC( m_raw_steer_cmd_pprev = m_raw_steer_cmd_prev; m_raw_steer_cmd_prev = Uex(0); - // calculate predicted trajectory + /* calculate predicted trajectory */ predicted_trajectory = - calcPredictedTrajectory(mpc_resampled_ref_trajectory, mpc_matrix, x0_delayed, Uex); + calculatePredictedTrajectory(mpc_matrix, x0, Uex, mpc_resampled_ref_trajectory, prediction_dt); // prepare diagnostic message diagnostic = @@ -108,30 +115,6 @@ bool MPC::calculateMPC( return true; } -Trajectory MPC::calcPredictedTrajectory( - const MPCTrajectory & mpc_resampled_ref_trajectory, const MPCMatrix & mpc_matrix, - const VectorXd & x0_delayed, const VectorXd & Uex) const -{ - const VectorXd Xex = mpc_matrix.Aex * x0_delayed + mpc_matrix.Bex * Uex + mpc_matrix.Wex; - MPCTrajectory mpc_predicted_traj; - const auto & traj = mpc_resampled_ref_trajectory; - for (int i = 0; i < m_param.prediction_horizon; ++i) { - const int DIM_X = m_vehicle_model_ptr->getDimX(); - const double lat_error = Xex(i * DIM_X); - const double yaw_error = Xex(i * DIM_X + 1); - const double x = traj.x.at(i) - std::sin(traj.yaw.at(i)) * lat_error; - const double y = traj.y.at(i) + std::cos(traj.yaw.at(i)) * lat_error; - const double z = traj.z.at(i); - const double yaw = traj.yaw.at(i) + yaw_error; - const double vx = traj.vx.at(i); - const double k = traj.k.at(i); - const double smooth_k = traj.smooth_k.at(i); - const double relative_time = traj.relative_time.at(i); - mpc_predicted_traj.push_back(x, y, z, yaw, vx, k, smooth_k, relative_time); - } - return MPCUtils::convertToAutowareTrajectory(mpc_predicted_traj); -} - Float32MultiArrayStamped MPC::generateDiagData( const MPCTrajectory & reference_trajectory, const MPCData & mpc_data, const MPCMatrix & mpc_matrix, const AckermannLateralCommand & ctrl_cmd, const VectorXd & Uex, @@ -794,6 +777,35 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory( return steer_rate_limits; } +Trajectory MPC::calculatePredictedTrajectory( + const MPCMatrix & mpc_matrix, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const +{ + const auto 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); + + // do not over the reference trajectory + const auto predicted_length = MPCUtils::calcMPCTrajectoryArcLength(reference_trajectory); + const auto clipped_trajectory = + MPCUtils::clipTrajectoryByLength(predicted_mpc_trajectory, predicted_length); + + 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); + const auto frenet_clipped = MPCUtils::convertToAutowareTrajectory( + MPCUtils::clipTrajectoryByLength(frenet, predicted_length)); + m_debug_frenet_predicted_trajectory_pub->publish(frenet_clipped); + } + + return predicted_trajectory; +} + bool MPC::isValid(const MPCMatrix & m) const { if ( diff --git a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp index 3d19104112a71..7eca1481ba921 100644 --- a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -42,7 +42,9 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) const auto dp_bool = [&](const std::string & s) { return node.declare_parameter(s); }; const auto dp_double = [&](const std::string & s) { return node.declare_parameter(s); }; - m_mpc.m_ctrl_period = node.get_parameter("ctrl_period").as_double(); + m_mpc = std::make_unique(node); + + m_mpc->m_ctrl_period = node.get_parameter("ctrl_period").as_double(); auto & p_filt = m_trajectory_filtering_param; p_filt.enable_path_smoothing = dp_bool("enable_path_smoothing"); @@ -52,10 +54,10 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) p_filt.traj_resample_dist = dp_double("traj_resample_dist"); p_filt.extend_trajectory_for_end_yaw_control = dp_bool("extend_trajectory_for_end_yaw_control"); - m_mpc.m_admissible_position_error = dp_double("admissible_position_error"); - m_mpc.m_admissible_yaw_error_rad = dp_double("admissible_yaw_error_rad"); - m_mpc.m_use_steer_prediction = dp_bool("use_steer_prediction"); - m_mpc.m_param.steer_tau = dp_double("vehicle_model_steer_tau"); + m_mpc->m_admissible_position_error = dp_double("admissible_position_error"); + m_mpc->m_admissible_yaw_error_rad = dp_double("admissible_yaw_error_rad"); + m_mpc->m_use_steer_prediction = dp_bool("use_steer_prediction"); + m_mpc->m_param.steer_tau = dp_double("vehicle_model_steer_tau"); /* stop state parameters */ m_stop_state_entry_ego_speed = dp_double("stop_state_entry_ego_speed"); @@ -70,7 +72,7 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); const double wheelbase = vehicle_info.wheel_base_m; constexpr double deg2rad = static_cast(M_PI) / 180.0; - m_mpc.m_steer_lim = vehicle_info.max_steer_angle_rad; + m_mpc->m_steer_lim = vehicle_info.max_steer_angle_rad; // steer rate limit depending on curvature const auto steer_rate_lim_dps_list_by_curvature = @@ -78,7 +80,7 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) const auto curvature_list_for_steer_rate_lim = node.declare_parameter>("curvature_list_for_steer_rate_lim"); for (size_t i = 0; i < steer_rate_lim_dps_list_by_curvature.size(); ++i) { - m_mpc.m_steer_rate_lim_map_by_curvature.emplace_back( + m_mpc->m_steer_rate_lim_map_by_curvature.emplace_back( curvature_list_for_steer_rate_lim.at(i), steer_rate_lim_dps_list_by_curvature.at(i) * deg2rad); } @@ -89,26 +91,26 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) const auto velocity_list_for_steer_rate_lim = node.declare_parameter>("velocity_list_for_steer_rate_lim"); for (size_t i = 0; i < steer_rate_lim_dps_list_by_velocity.size(); ++i) { - m_mpc.m_steer_rate_lim_map_by_velocity.emplace_back( + m_mpc->m_steer_rate_lim_map_by_velocity.emplace_back( velocity_list_for_steer_rate_lim.at(i), steer_rate_lim_dps_list_by_velocity.at(i) * deg2rad); } /* vehicle model setup */ auto vehicle_model_ptr = - createVehicleModel(wheelbase, m_mpc.m_steer_lim, m_mpc.m_param.steer_tau, node); - m_mpc.setVehicleModel(vehicle_model_ptr); + createVehicleModel(wheelbase, m_mpc->m_steer_lim, m_mpc->m_param.steer_tau, node); + m_mpc->setVehicleModel(vehicle_model_ptr); /* QP solver setup */ - m_mpc.setVehicleModel(vehicle_model_ptr); + m_mpc->setVehicleModel(vehicle_model_ptr); auto qpsolver_ptr = createQPSolverInterface(node); - m_mpc.setQPSolver(qpsolver_ptr); + m_mpc->setQPSolver(qpsolver_ptr); /* delay compensation */ { const double delay_tmp = dp_double("input_delay"); - const double delay_step = std::round(delay_tmp / m_mpc.m_ctrl_period); - m_mpc.m_param.input_delay = delay_step * m_mpc.m_ctrl_period; - m_mpc.m_input_buffer = std::deque(static_cast(delay_step), 0.0); + const double delay_step = std::round(delay_tmp / m_mpc->m_ctrl_period); + m_mpc->m_param.input_delay = delay_step * m_mpc->m_ctrl_period; + m_mpc->m_input_buffer = std::deque(static_cast(delay_step), 0.0); } /* steering offset compensation */ @@ -120,7 +122,7 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) { const double steering_lpf_cutoff_hz = dp_double("steering_lpf_cutoff_hz"); const double error_deriv_lpf_cutoff_hz = dp_double("error_deriv_lpf_cutoff_hz"); - m_mpc.initializeLowPassFilters(steering_lpf_cutoff_hz, error_deriv_lpf_cutoff_hz); + m_mpc->initializeLowPassFilters(steering_lpf_cutoff_hz, error_deriv_lpf_cutoff_hz); } // ego nearest index search @@ -129,8 +131,10 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) }; m_ego_nearest_dist_threshold = check_and_get_param("ego_nearest_dist_threshold"); m_ego_nearest_yaw_threshold = check_and_get_param("ego_nearest_yaw_threshold"); - m_mpc.ego_nearest_dist_threshold = m_ego_nearest_dist_threshold; - m_mpc.ego_nearest_yaw_threshold = m_ego_nearest_yaw_threshold; + 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_pub_predicted_traj = node.create_publisher("~/output/predicted_trajectory", 1); m_pub_debug_values = @@ -144,10 +148,10 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) m_set_param_res = node.add_on_set_parameters_callback(std::bind(&MpcLateralController::paramCallback, this, _1)); - m_mpc.initializeSteeringPredictor(); + m_mpc->initializeSteeringPredictor(); - m_mpc.setLogger(logger_); - m_mpc.setClock(clock_); + m_mpc->setLogger(logger_); + m_mpc->setClock(clock_); } MpcLateralController::~MpcLateralController() @@ -244,7 +248,7 @@ trajectory_follower::LateralOutput MpcLateralController::run( m_is_ctrl_cmd_prev_initialized = true; } - const bool is_mpc_solved = m_mpc.calculateMPC( + const bool is_mpc_solved = m_mpc->calculateMPC( m_current_steering, m_current_kinematic_state, ctrl_cmd, predicted_traj, debug_values); // reset previous MPC result @@ -253,7 +257,7 @@ trajectory_follower::LateralOutput MpcLateralController::run( // After the recovery, the previous value of the optimization may deviate greatly from // the actual steer angle, and it may make the optimization result unstable. if (!is_mpc_solved) { - m_mpc.resetPrevResult(m_current_steering); + m_mpc->resetPrevResult(m_current_steering); } else { setSteeringToHistory(ctrl_cmd); } @@ -284,11 +288,11 @@ trajectory_follower::LateralOutput MpcLateralController::run( if (isStoppedState()) { // Reset input buffer - for (auto & value : m_mpc.m_input_buffer) { + for (auto & value : m_mpc->m_input_buffer) { value = m_ctrl_cmd_prev.steering_tire_angle; } // Use previous command value as previous raw steer command - m_mpc.m_raw_steer_cmd_prev = m_ctrl_cmd_prev.steering_tire_angle; + m_mpc->m_raw_steer_cmd_prev = m_ctrl_cmd_prev.steering_tire_angle; return createLateralOutput(m_ctrl_cmd_prev, false); } @@ -323,15 +327,15 @@ bool MpcLateralController::isReady(const trajectory_follower::InputData & input_ m_current_kinematic_state = input_data.current_odometry; m_current_steering = input_data.current_steering; - if (!m_mpc.hasVehicleModel()) { + if (!m_mpc->hasVehicleModel()) { info_throttle("MPC does not have a vehicle model"); return false; } - if (!m_mpc.hasQPSolver()) { + if (!m_mpc->hasQPSolver()) { info_throttle("MPC does not have a QP solver"); return false; } - if (m_mpc.m_reference_trajectory.empty()) { + if (m_mpc->m_reference_trajectory.empty()) { info_throttle("trajectory size is zero."); return false; } @@ -354,7 +358,7 @@ void MpcLateralController::setTrajectory( return; } - m_mpc.setReferenceTrajectory(msg, m_trajectory_filtering_param, current_kinematics); + m_mpc->setReferenceTrajectory(msg, m_trajectory_filtering_param, current_kinematics); // update trajectory buffer to check the trajectory shape change. m_trajectory_buffer.push_back(m_current_trajectory); @@ -504,12 +508,12 @@ bool MpcLateralController::isMpcConverged() void MpcLateralController::declareMPCparameters(rclcpp::Node & node) { - m_mpc.m_param.prediction_horizon = node.declare_parameter("mpc_prediction_horizon"); - m_mpc.m_param.prediction_dt = node.declare_parameter("mpc_prediction_dt"); + m_mpc->m_param.prediction_horizon = node.declare_parameter("mpc_prediction_horizon"); + m_mpc->m_param.prediction_dt = node.declare_parameter("mpc_prediction_dt"); const auto dp = [&](const auto & param) { return node.declare_parameter(param); }; - auto & nw = m_mpc.m_param.nominal_weight; + auto & nw = m_mpc->m_param.nominal_weight; nw.lat_error = dp("mpc_weight_lat_error"); nw.heading_error = dp("mpc_weight_heading_error"); nw.heading_error_squared_vel = dp("mpc_weight_heading_error_squared_vel"); @@ -521,7 +525,7 @@ void MpcLateralController::declareMPCparameters(rclcpp::Node & node) nw.terminal_lat_error = dp("mpc_weight_terminal_lat_error"); nw.terminal_heading_error = dp("mpc_weight_terminal_heading_error"); - auto & lcw = m_mpc.m_param.low_curvature_weight; + auto & lcw = m_mpc->m_param.low_curvature_weight; lcw.lat_error = dp("mpc_low_curvature_weight_lat_error"); lcw.heading_error = dp("mpc_low_curvature_weight_heading_error"); lcw.heading_error_squared_vel = dp("mpc_low_curvature_weight_heading_error_squared_vel"); @@ -530,12 +534,12 @@ void MpcLateralController::declareMPCparameters(rclcpp::Node & node) lcw.lat_jerk = dp("mpc_low_curvature_weight_lat_jerk"); lcw.steer_rate = dp("mpc_low_curvature_weight_steer_rate"); lcw.steer_acc = dp("mpc_low_curvature_weight_steer_acc"); - m_mpc.m_param.low_curvature_thresh_curvature = dp("mpc_low_curvature_thresh_curvature"); + m_mpc->m_param.low_curvature_thresh_curvature = dp("mpc_low_curvature_thresh_curvature"); - m_mpc.m_param.zero_ff_steer_deg = dp("mpc_zero_ff_steer_deg"); - m_mpc.m_param.acceleration_limit = dp("mpc_acceleration_limit"); - m_mpc.m_param.velocity_time_constant = dp("mpc_velocity_time_constant"); - m_mpc.m_param.min_prediction_length = dp("mpc_min_prediction_length"); + m_mpc->m_param.zero_ff_steer_deg = dp("mpc_zero_ff_steer_deg"); + m_mpc->m_param.acceleration_limit = dp("mpc_acceleration_limit"); + m_mpc->m_param.velocity_time_constant = dp("mpc_velocity_time_constant"); + m_mpc->m_param.min_prediction_length = dp("mpc_min_prediction_length"); } rcl_interfaces::msg::SetParametersResult MpcLateralController::paramCallback( @@ -546,7 +550,7 @@ rcl_interfaces::msg::SetParametersResult MpcLateralController::paramCallback( result.reason = "success"; // strong exception safety wrt MPCParam - MPCParam param = m_mpc.m_param; + MPCParam param = m_mpc->m_param; auto & nw = param.nominal_weight; auto & lcw = param.low_curvature_weight; @@ -587,15 +591,15 @@ rcl_interfaces::msg::SetParametersResult MpcLateralController::paramCallback( // initialize input buffer update_param(parameters, "input_delay", param.input_delay); - const double delay_step = std::round(param.input_delay / m_mpc.m_ctrl_period); - const double delay = delay_step * m_mpc.m_ctrl_period; + const double delay_step = std::round(param.input_delay / m_mpc->m_ctrl_period); + const double delay = delay_step * m_mpc->m_ctrl_period; if (param.input_delay != delay) { param.input_delay = delay; - m_mpc.m_input_buffer = std::deque(static_cast(delay_step), 0.0); + m_mpc->m_input_buffer = std::deque(static_cast(delay_step), 0.0); } // transaction succeeds, now assign values - m_mpc.m_param = param; + m_mpc->m_param = param; } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { result.successful = false; result.reason = e.what(); diff --git a/control/mpc_lateral_controller/src/mpc_trajectory.cpp b/control/mpc_lateral_controller/src/mpc_trajectory.cpp index 3c799722494b9..b7fed942375e8 100644 --- a/control/mpc_lateral_controller/src/mpc_trajectory.cpp +++ b/control/mpc_lateral_controller/src/mpc_trajectory.cpp @@ -58,6 +58,22 @@ MPCTrajectoryPoint MPCTrajectory::back() return p; } +MPCTrajectoryPoint MPCTrajectory::at(const size_t i) const +{ + MPCTrajectoryPoint p; + + p.x = x.at(i); + p.y = y.at(i); + p.z = z.at(i); + p.yaw = yaw.at(i); + p.vx = vx.at(i); + p.k = k.at(i); + p.smooth_k = smooth_k.at(i); + p.relative_time = relative_time.at(i); + + return p; +} + void MPCTrajectory::clear() { x.clear(); diff --git a/control/mpc_lateral_controller/src/mpc_utils.cpp b/control/mpc_lateral_controller/src/mpc_utils.cpp index d3fc5fba0b014..01a81d9015b47 100644 --- a/control/mpc_lateral_controller/src/mpc_utils.cpp +++ b/control/mpc_lateral_controller/src/mpc_utils.cpp @@ -89,6 +89,15 @@ void calcMPCTrajectoryArcLength(const MPCTrajectory & trajectory, std::vector resampleMPCTrajectoryByDistance( const MPCTrajectory & input, const double resample_interval_dist, const size_t nearest_seg_idx, const double ego_offset_to_segment) @@ -458,5 +467,22 @@ void extendTrajectoryInYawDirection( } } +MPCTrajectory clipTrajectoryByLength(const MPCTrajectory & trajectory, const double length) +{ + MPCTrajectory clipped_trajectory; + clipped_trajectory.push_back(trajectory.at(0)); + + double current_length = 0.0; + for (size_t i = 1; i < trajectory.size(); ++i) { + current_length += calcDistance3d(trajectory, i, i - 1); + if (current_length > length) { + break; + } + clipped_trajectory.push_back(trajectory.at(i)); + } + + return clipped_trajectory; +} + } // namespace MPCUtils } // namespace autoware::motion::control::mpc_lateral_controller diff --git a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp b/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp index 576907e79da4b..2467b1f0c2311 100644 --- a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp +++ b/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp @@ -86,4 +86,48 @@ void DynamicsBicycleModel::calculateReferenceInput(Eigen::MatrixXd & u_ref) m_lr * m_mass / (2 * m_cf * m_wheelbase) - m_lf * m_mass / (2 * m_cr * m_wheelbase); u_ref(0, 0) = m_wheelbase * m_curvature + Kv * vel * vel * m_curvature; } + +MPCTrajectory DynamicsBicycleModel::calculatePredictedTrajectoryInWorldCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, + [[maybe_unused]] const Eigen::MatrixXd & c_d, const Eigen::MatrixXd & w_d, + const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, [[maybe_unused]] const double dt) const +{ + RCLCPP_ERROR( + rclcpp::get_logger("control.trajectory_follower.lateral_controller"), + "Predicted trajectory calculation in world coordinate is not supported in dynamic model. " + "Calculate in the Frenet coordinate instead."); + return calculatePredictedTrajectoryInFrenetCoordinate( + a_d, b_d, c_d, w_d, x0, Uex, reference_trajectory, dt); +} + +MPCTrajectory DynamicsBicycleModel::calculatePredictedTrajectoryInFrenetCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, + [[maybe_unused]] const Eigen::MatrixXd & c_d, const Eigen::MatrixXd & w_d, + const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, [[maybe_unused]] const double dt) const +{ + // state = [e, de, th, dth] + // e : lateral error + // de : derivative of lateral error + // th : heading angle error + // dth : derivative of heading angle error + // steer : steering angle (input) + + Eigen::VectorXd Xex = a_d * x0 + b_d * Uex + w_d; + MPCTrajectory mpc_predicted_trajectory; + const auto DIM_X = getDimX(); + const auto & t = reference_trajectory; + + for (size_t i = 0; i < reference_trajectory.size(); ++i) { + const auto lateral_error = Xex(i * DIM_X); // model dependent + const auto yaw_error = Xex(i * DIM_X + 2); // model dependent + const auto x = t.x.at(i) - std::sin(t.yaw.at(i)) * lateral_error; + const auto y = t.y.at(i) + std::cos(t.yaw.at(i)) * lateral_error; + const auto yaw = t.yaw.at(i) + yaw_error; + mpc_predicted_trajectory.push_back( + x, y, t.z.at(i), yaw, t.vx.at(i), t.k.at(i), t.smooth_k.at(i), t.relative_time.at(i)); + } + return mpc_predicted_trajectory; +} } // namespace autoware::motion::control::mpc_lateral_controller diff --git a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp b/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp index 35bef667125c5..cd52dd4f79314 100644 --- a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp +++ b/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp @@ -68,4 +68,85 @@ void KinematicsBicycleModel::calculateReferenceInput(Eigen::MatrixXd & u_ref) { u_ref(0, 0) = std::atan(m_wheelbase * m_curvature); } + +MPCTrajectory KinematicsBicycleModel::calculatePredictedTrajectoryInWorldCoordinate( + [[maybe_unused]] const Eigen::MatrixXd & a_d, [[maybe_unused]] const Eigen::MatrixXd & b_d, + [[maybe_unused]] const Eigen::MatrixXd & c_d, [[maybe_unused]] const Eigen::MatrixXd & w_d, + const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const +{ + // Calculate predicted state in world coordinate since there is modeling errors in Frenet + // Relative coordinate x = [lat_err, yaw_err, steer] + // World coordinate x = [x, y, yaw, steer] + + const auto & t = reference_trajectory; + + // create initial state in the world coordinate + Eigen::VectorXd state_w = [&]() { + Eigen::VectorXd state = Eigen::VectorXd::Zero(4); + const auto lateral_error_0 = x0(0); + const auto yaw_error_0 = x0(1); + state(0, 0) = t.x.at(0) - std::sin(t.yaw.at(0)) * lateral_error_0; // world-x + state(1, 0) = t.y.at(0) + std::cos(t.yaw.at(0)) * lateral_error_0; // world-y + state(2, 0) = t.yaw.at(0) + yaw_error_0; // world-yaw + state(3, 0) = x0(2); // steering + return state; + }(); + + // update state in the world coordinate + const auto updateState = [&]( + const Eigen::VectorXd & state_w, const Eigen::MatrixXd & input, + const double dt, const double velocity) { + const auto yaw = state_w(2); + const auto steer = state_w(3); + const auto desired_steer = input(0); + + Eigen::VectorXd dstate = Eigen::VectorXd::Zero(4); + dstate(0) = velocity * std::cos(yaw); + dstate(1) = velocity * std::sin(yaw); + dstate(2) = velocity * std::tan(steer) / m_wheelbase; + dstate(3) = -(steer - desired_steer) / m_steer_tau; + + // Note: don't do "return state_w + dstate * dt", which does not work due to the lazy evaluation + // in Eigen. + const Eigen::VectorXd next_state = state_w + dstate * dt; + return next_state; + }; + + MPCTrajectory mpc_predicted_trajectory; + const auto DIM_U = getDimU(); + + for (size_t i = 0; i < reference_trajectory.size(); ++i) { + state_w = updateState(state_w, Uex.block(i * DIM_U, 0, DIM_U, 1), dt, t.vx.at(i)); + mpc_predicted_trajectory.push_back( + state_w(0), state_w(1), t.z.at(i), state_w(2), t.vx.at(i), t.k.at(i), t.smooth_k.at(i), + t.relative_time.at(i)); + } + return mpc_predicted_trajectory; +} + +MPCTrajectory KinematicsBicycleModel::calculatePredictedTrajectoryInFrenetCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, + [[maybe_unused]] const Eigen::MatrixXd & c_d, const Eigen::MatrixXd & w_d, + const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, [[maybe_unused]] const double dt) const +{ + // Relative coordinate x = [lat_err, yaw_err, steer] + + Eigen::VectorXd Xex = a_d * x0 + b_d * Uex + w_d; + MPCTrajectory mpc_predicted_trajectory; + const auto DIM_X = getDimX(); + const auto & t = reference_trajectory; + + for (size_t i = 0; i < reference_trajectory.size(); ++i) { + const auto lateral_error = Xex(i * DIM_X); // model dependent + const auto yaw_error = Xex(i * DIM_X + 1); // model dependent + const auto x = t.x.at(i) - std::sin(t.yaw.at(i)) * lateral_error; + const auto y = t.y.at(i) + std::cos(t.yaw.at(i)) * lateral_error; + const auto yaw = t.yaw.at(i) + yaw_error; + mpc_predicted_trajectory.push_back( + x, y, t.z.at(i), yaw, t.vx.at(i), t.k.at(i), t.smooth_k.at(i), t.relative_time.at(i)); + } + return mpc_predicted_trajectory; +} } // namespace autoware::motion::control::mpc_lateral_controller diff --git a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp b/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp index 1536beba9cd00..8f4510510aca9 100644 --- a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp +++ b/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp @@ -59,4 +59,82 @@ void KinematicsBicycleModelNoDelay::calculateReferenceInput(Eigen::MatrixXd & u_ { u_ref(0, 0) = std::atan(m_wheelbase * m_curvature); } + +MPCTrajectory KinematicsBicycleModelNoDelay::calculatePredictedTrajectoryInWorldCoordinate( + [[maybe_unused]] const Eigen::MatrixXd & a_d, [[maybe_unused]] const Eigen::MatrixXd & b_d, + [[maybe_unused]] const Eigen::MatrixXd & c_d, [[maybe_unused]] const Eigen::MatrixXd & w_d, + const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, const double dt) const +{ + // Calculate predicted state in world coordinate since there is modeling errors in Frenet + // Relative coordinate x = [lat_err, yaw_err] + // World coordinate x = [x, y, yaw] + + const auto & t = reference_trajectory; + + // create initial state in the world coordinate + Eigen::VectorXd state_w = [&]() { + Eigen::VectorXd state = Eigen::VectorXd::Zero(3); + const auto lateral_error_0 = x0(0); + const auto yaw_error_0 = x0(1); + state(0, 0) = t.x.at(0) - std::sin(t.yaw.at(0)) * lateral_error_0; // world-x + state(1, 0) = t.y.at(0) + std::cos(t.yaw.at(0)) * lateral_error_0; // world-y + state(2, 0) = t.yaw.at(0) + yaw_error_0; // world-yaw + return state; + }(); + + // update state in the world coordinate + const auto updateState = [&]( + const Eigen::VectorXd & state_w, const Eigen::MatrixXd & input, + const double dt, const double velocity) { + const auto yaw = state_w(2); + const auto steer = input(0); + + Eigen::VectorXd dstate = Eigen::VectorXd::Zero(3); + dstate(0) = velocity * std::cos(yaw); + dstate(1) = velocity * std::sin(yaw); + dstate(2) = velocity * std::tan(steer) / m_wheelbase; + + // Note: don't do "return state_w + dstate * dt", which does not work due to the lazy evaluation + // in Eigen. + const Eigen::VectorXd next_state = state_w + dstate * dt; + return next_state; + }; + + MPCTrajectory mpc_predicted_trajectory; + const auto DIM_U = getDimU(); + for (size_t i = 0; i < t.size(); ++i) { + state_w = updateState(state_w, Uex.block(i * DIM_U, 0, DIM_U, 1), dt, t.vx.at(i)); + mpc_predicted_trajectory.push_back( + state_w(0), state_w(1), t.z.at(i), state_w(2), t.vx.at(i), t.k.at(i), t.smooth_k.at(i), + t.relative_time.at(i)); + } + + return mpc_predicted_trajectory; +} + +MPCTrajectory KinematicsBicycleModelNoDelay::calculatePredictedTrajectoryInFrenetCoordinate( + const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, + [[maybe_unused]] const Eigen::MatrixXd & c_d, const Eigen::MatrixXd & w_d, + const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex, + const MPCTrajectory & reference_trajectory, [[maybe_unused]] const double dt) const +{ + // Relative coordinate x = [lat_err, yaw_err] + + Eigen::VectorXd Xex = a_d * x0 + b_d * Uex + w_d; + MPCTrajectory mpc_predicted_trajectory; + const auto DIM_X = getDimX(); + const auto & t = reference_trajectory; + + for (size_t i = 0; i < reference_trajectory.size(); ++i) { + const auto lateral_error = Xex(i * DIM_X); // model dependent + const auto yaw_error = Xex(i * DIM_X + 1); // model dependent + const auto x = t.x.at(i) - std::sin(t.yaw.at(i)) * lateral_error; + const auto y = t.y.at(i) + std::cos(t.yaw.at(i)) * lateral_error; + const auto yaw = t.yaw.at(i) + yaw_error; + mpc_predicted_trajectory.push_back( + x, y, t.z.at(i), yaw, t.vx.at(i), t.k.at(i), t.smooth_k.at(i), t.relative_time.at(i)); + } + return mpc_predicted_trajectory; +} } // namespace autoware::motion::control::mpc_lateral_controller diff --git a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_interface.cpp b/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_interface.cpp index 97e3f2742f546..f54a5e325bead 100644 --- a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_interface.cpp +++ b/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_interface.cpp @@ -20,19 +20,19 @@ VehicleModelInterface::VehicleModelInterface(int dim_x, int dim_u, int dim_y, do : m_dim_x(dim_x), m_dim_u(dim_u), m_dim_y(dim_y), m_wheelbase(wheelbase) { } -int VehicleModelInterface::getDimX() +int VehicleModelInterface::getDimX() const { return m_dim_x; } -int VehicleModelInterface::getDimU() +int VehicleModelInterface::getDimU() const { return m_dim_u; } -int VehicleModelInterface::getDimY() +int VehicleModelInterface::getDimY() const { return m_dim_y; } -double VehicleModelInterface::getWheelbase() +double VehicleModelInterface::getWheelbase() const { return m_wheelbase; } diff --git a/control/mpc_lateral_controller/test/test_mpc.cpp b/control/mpc_lateral_controller/test/test_mpc.cpp index dade035daf26c..ba145b5dd146c 100644 --- a/control/mpc_lateral_controller/test/test_mpc.cpp +++ b/control/mpc_lateral_controller/test/test_mpc.cpp @@ -19,6 +19,7 @@ #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp" #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp" #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" +#include "rclcpp/rclcpp.hpp" #include "autoware_auto_control_msgs/msg/ackermann_lateral_command.hpp" #include "autoware_auto_planning_msgs/msg/trajectory.hpp" @@ -48,6 +49,22 @@ using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; using tier4_debug_msgs::msg::Float32MultiArrayStamped; +TrajectoryPoint makePoint(const double x, const double y, const float vx) +{ + TrajectoryPoint p; + p.pose.position.x = x; + p.pose.position.y = y; + p.longitudinal_velocity_mps = vx; + return p; +} + +nav_msgs::msg::Odometry makeOdometry(const geometry_msgs::msg::Pose & pose, const double velocity) +{ + nav_msgs::msg::Odometry odometry; + odometry.pose.pose = pose; + odometry.twist.twist.linear.x = velocity; + return odometry; +} class MPCTest : public ::testing::Test { protected: @@ -86,16 +103,7 @@ class MPCTest : public ::testing::Test TrajectoryFilteringParam trajectory_param; - TrajectoryPoint makePoint(const double x, const double y, const float vx) - { - TrajectoryPoint p; - p.pose.position.x = x; - p.pose.position.y = y; - p.longitudinal_velocity_mps = vx; - return p; - } - - void SetUp() override + void initParam() { param.prediction_horizon = 50; param.prediction_dt = 0.1; @@ -168,259 +176,268 @@ class MPCTest : public ::testing::Test mpc.setReferenceTrajectory(dummy_straight_trajectory, trajectory_param, current_kinematics); } - nav_msgs::msg::Odometry makeOdometry(const geometry_msgs::msg::Pose & pose, const double velocity) + void SetUp() override { - nav_msgs::msg::Odometry odometry; - odometry.pose.pose = pose; - odometry.twist.twist.linear.x = velocity; - return odometry; + rclcpp::init(0, nullptr); + initParam(); } + + void TearDown() override { rclcpp::shutdown(); } }; // class MPCTest /* cppcheck-suppress syntaxError */ TEST_F(MPCTest, InitializeAndCalculate) { - MPC mpc; - EXPECT_FALSE(mpc.hasVehicleModel()); - EXPECT_FALSE(mpc.hasQPSolver()); + auto node = rclcpp::Node("mpc_test_node", rclcpp::NodeOptions{}); + auto mpc = std::make_unique(node); + EXPECT_FALSE(mpc->hasVehicleModel()); + EXPECT_FALSE(mpc->hasQPSolver()); std::shared_ptr vehicle_model_ptr = std::make_shared(wheelbase, steer_limit, steer_tau); - mpc.setVehicleModel(vehicle_model_ptr); - ASSERT_TRUE(mpc.hasVehicleModel()); + mpc->setVehicleModel(vehicle_model_ptr); + ASSERT_TRUE(mpc->hasVehicleModel()); std::shared_ptr qpsolver_ptr = std::make_shared(); - mpc.setQPSolver(qpsolver_ptr); - ASSERT_TRUE(mpc.hasQPSolver()); + mpc->setQPSolver(qpsolver_ptr); + ASSERT_TRUE(mpc->hasQPSolver()); // Init parameters and reference trajectory - initializeMPC(mpc); + initializeMPC(*mpc); // Calculate MPC AckermannLateralCommand ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, InitializeAndCalculateRightTurn) { - MPC mpc; - EXPECT_FALSE(mpc.hasVehicleModel()); - EXPECT_FALSE(mpc.hasQPSolver()); + auto node = rclcpp::Node("mpc_test_node", rclcpp::NodeOptions{}); + auto mpc = std::make_unique(node); + EXPECT_FALSE(mpc->hasVehicleModel()); + EXPECT_FALSE(mpc->hasQPSolver()); std::shared_ptr vehicle_model_ptr = std::make_shared(wheelbase, steer_limit, steer_tau); - mpc.setVehicleModel(vehicle_model_ptr); - ASSERT_TRUE(mpc.hasVehicleModel()); + mpc->setVehicleModel(vehicle_model_ptr); + ASSERT_TRUE(mpc->hasVehicleModel()); std::shared_ptr qpsolver_ptr = std::make_shared(); - mpc.setQPSolver(qpsolver_ptr); - ASSERT_TRUE(mpc.hasQPSolver()); + mpc->setQPSolver(qpsolver_ptr); + ASSERT_TRUE(mpc->hasQPSolver()); // Init parameters and reference trajectory - initializeMPC(mpc); + initializeMPC(*mpc); const auto current_kinematics = makeOdometry(dummy_right_turn_trajectory.points.front().pose, 0.0); - mpc.setReferenceTrajectory(dummy_right_turn_trajectory, trajectory_param, current_kinematics); + mpc->setReferenceTrajectory(dummy_right_turn_trajectory, trajectory_param, current_kinematics); // Calculate MPC AckermannLateralCommand ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, OsqpCalculate) { - MPC mpc; - initializeMPC(mpc); + auto node = rclcpp::Node("mpc_test_node", rclcpp::NodeOptions{}); + auto mpc = std::make_unique(node); + initializeMPC(*mpc); const auto current_kinematics = makeOdometry(dummy_straight_trajectory.points.front().pose, 0.0); - mpc.setReferenceTrajectory(dummy_straight_trajectory, trajectory_param, current_kinematics); + mpc->setReferenceTrajectory(dummy_straight_trajectory, trajectory_param, current_kinematics); std::shared_ptr vehicle_model_ptr = std::make_shared(wheelbase, steer_limit, steer_tau); - mpc.setVehicleModel(vehicle_model_ptr); - ASSERT_TRUE(mpc.hasVehicleModel()); + mpc->setVehicleModel(vehicle_model_ptr); + ASSERT_TRUE(mpc->hasVehicleModel()); std::shared_ptr qpsolver_ptr = std::make_shared(logger); - mpc.setQPSolver(qpsolver_ptr); - ASSERT_TRUE(mpc.hasQPSolver()); + mpc->setQPSolver(qpsolver_ptr); + ASSERT_TRUE(mpc->hasQPSolver()); // Calculate MPC AckermannLateralCommand ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; const auto odom = makeOdometry(pose_zero, default_velocity); - EXPECT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, OsqpCalculateRightTurn) { - MPC mpc; - initializeMPC(mpc); + auto node = rclcpp::Node("mpc_test_node", rclcpp::NodeOptions{}); + auto mpc = std::make_unique(node); + initializeMPC(*mpc); const auto current_kinematics = makeOdometry(dummy_right_turn_trajectory.points.front().pose, 0.0); - mpc.setReferenceTrajectory(dummy_right_turn_trajectory, trajectory_param, current_kinematics); + mpc->setReferenceTrajectory(dummy_right_turn_trajectory, trajectory_param, current_kinematics); std::shared_ptr vehicle_model_ptr = std::make_shared(wheelbase, steer_limit, steer_tau); - mpc.setVehicleModel(vehicle_model_ptr); - ASSERT_TRUE(mpc.hasVehicleModel()); + mpc->setVehicleModel(vehicle_model_ptr); + ASSERT_TRUE(mpc->hasVehicleModel()); std::shared_ptr qpsolver_ptr = std::make_shared(logger); - mpc.setQPSolver(qpsolver_ptr); - ASSERT_TRUE(mpc.hasQPSolver()); + mpc->setQPSolver(qpsolver_ptr); + ASSERT_TRUE(mpc->hasQPSolver()); // Calculate MPC AckermannLateralCommand ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, KinematicsNoDelayCalculate) { - MPC mpc; - initializeMPC(mpc); + auto node = rclcpp::Node("mpc_test_node", rclcpp::NodeOptions{}); + auto mpc = std::make_unique(node); + initializeMPC(*mpc); std::shared_ptr vehicle_model_ptr = std::make_shared(wheelbase, steer_limit); - mpc.setVehicleModel(vehicle_model_ptr); - ASSERT_TRUE(mpc.hasVehicleModel()); + mpc->setVehicleModel(vehicle_model_ptr); + ASSERT_TRUE(mpc->hasVehicleModel()); std::shared_ptr qpsolver_ptr = std::make_shared(); - mpc.setQPSolver(qpsolver_ptr); - ASSERT_TRUE(mpc.hasQPSolver()); + mpc->setQPSolver(qpsolver_ptr); + ASSERT_TRUE(mpc->hasQPSolver()); // Init filters - mpc.initializeLowPassFilters(steering_lpf_cutoff_hz, error_deriv_lpf_cutoff_hz); + mpc->initializeLowPassFilters(steering_lpf_cutoff_hz, error_deriv_lpf_cutoff_hz); // Init trajectory const auto current_kinematics = makeOdometry(dummy_straight_trajectory.points.front().pose, 0.0); - mpc.setReferenceTrajectory(dummy_straight_trajectory, trajectory_param, current_kinematics); + mpc->setReferenceTrajectory(dummy_straight_trajectory, trajectory_param, current_kinematics); // Calculate MPC AckermannLateralCommand ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, KinematicsNoDelayCalculateRightTurn) { - MPC mpc; - initializeMPC(mpc); + auto node = rclcpp::Node("mpc_test_node", rclcpp::NodeOptions{}); + auto mpc = std::make_unique(node); + initializeMPC(*mpc); const auto current_kinematics = makeOdometry(dummy_right_turn_trajectory.points.front().pose, 0.0); - mpc.setReferenceTrajectory(dummy_right_turn_trajectory, trajectory_param, current_kinematics); + mpc->setReferenceTrajectory(dummy_right_turn_trajectory, trajectory_param, current_kinematics); std::shared_ptr vehicle_model_ptr = std::make_shared(wheelbase, steer_limit); - mpc.setVehicleModel(vehicle_model_ptr); - ASSERT_TRUE(mpc.hasVehicleModel()); + mpc->setVehicleModel(vehicle_model_ptr); + ASSERT_TRUE(mpc->hasVehicleModel()); std::shared_ptr qpsolver_ptr = std::make_shared(); - mpc.setQPSolver(qpsolver_ptr); - ASSERT_TRUE(mpc.hasQPSolver()); + mpc->setQPSolver(qpsolver_ptr); + ASSERT_TRUE(mpc->hasQPSolver()); // Init filters - mpc.initializeLowPassFilters(steering_lpf_cutoff_hz, error_deriv_lpf_cutoff_hz); + mpc->initializeLowPassFilters(steering_lpf_cutoff_hz, error_deriv_lpf_cutoff_hz); // Calculate MPC AckermannLateralCommand ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, DynamicCalculate) { - MPC mpc; - initializeMPC(mpc); + auto node = rclcpp::Node("mpc_test_node", rclcpp::NodeOptions{}); + auto mpc = std::make_unique(node); + initializeMPC(*mpc); std::shared_ptr vehicle_model_ptr = std::make_shared(wheelbase, mass_fl, mass_fr, mass_rl, mass_rr, cf, cr); - mpc.setVehicleModel(vehicle_model_ptr); - ASSERT_TRUE(mpc.hasVehicleModel()); + mpc->setVehicleModel(vehicle_model_ptr); + ASSERT_TRUE(mpc->hasVehicleModel()); std::shared_ptr qpsolver_ptr = std::make_shared(); - mpc.setQPSolver(qpsolver_ptr); - ASSERT_TRUE(mpc.hasQPSolver()); + mpc->setQPSolver(qpsolver_ptr); + ASSERT_TRUE(mpc->hasQPSolver()); // Calculate MPC AckermannLateralCommand ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, MultiSolveWithBuffer) { - MPC mpc; + auto node = rclcpp::Node("mpc_test_node", rclcpp::NodeOptions{}); + auto mpc = std::make_unique(node); std::shared_ptr vehicle_model_ptr = std::make_shared(wheelbase, steer_limit, steer_tau); - mpc.setVehicleModel(vehicle_model_ptr); + mpc->setVehicleModel(vehicle_model_ptr); std::shared_ptr qpsolver_ptr = std::make_shared(); - mpc.setQPSolver(qpsolver_ptr); + mpc->setQPSolver(qpsolver_ptr); // Init parameters and reference trajectory - initializeMPC(mpc); + initializeMPC(*mpc); - mpc.m_input_buffer = {0.0, 0.0, 0.0}; + mpc->m_input_buffer = {0.0, 0.0, 0.0}; // Calculate MPC AckermannLateralCommand ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); - EXPECT_EQ(mpc.m_input_buffer.size(), size_t(3)); - ASSERT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); - EXPECT_EQ(mpc.m_input_buffer.size(), size_t(3)); - ASSERT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); - EXPECT_EQ(mpc.m_input_buffer.size(), size_t(3)); - ASSERT_TRUE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); - EXPECT_EQ(mpc.m_input_buffer.size(), size_t(3)); + EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); } TEST_F(MPCTest, FailureCases) { - MPC mpc; + auto node = rclcpp::Node("mpc_test_node", rclcpp::NodeOptions{}); + auto mpc = std::make_unique(node); std::shared_ptr vehicle_model_ptr = std::make_shared(wheelbase, steer_limit, steer_tau); - mpc.setVehicleModel(vehicle_model_ptr); + mpc->setVehicleModel(vehicle_model_ptr); std::shared_ptr qpsolver_ptr = std::make_shared(); - mpc.setQPSolver(qpsolver_ptr); + mpc->setQPSolver(qpsolver_ptr); // Init parameters and reference trajectory - initializeMPC(mpc); + initializeMPC(*mpc); // Calculate MPC with a pose too far from the trajectory Pose pose_far; @@ -430,10 +447,10 @@ TEST_F(MPCTest, FailureCases) Trajectory pred_traj; Float32MultiArrayStamped diag; const auto odom = makeOdometry(pose_far, default_velocity); - EXPECT_FALSE(mpc.calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_FALSE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); // Calculate MPC with a fast velocity to make the prediction go further than the reference path - EXPECT_FALSE(mpc.calculateMPC( + EXPECT_FALSE(mpc->calculateMPC( neutral_steer, makeOdometry(pose_far, default_velocity + 10.0), ctrl_cmd, pred_traj, diag)); } } // namespace autoware::motion::control::mpc_lateral_controller diff --git a/control/trajectory_follower_node/param/lateral/mpc.param.yaml b/control/trajectory_follower_node/param/lateral/mpc.param.yaml index 4222082d40deb..9998b6aadf656 100644 --- a/control/trajectory_follower_node/param/lateral/mpc.param.yaml +++ b/control/trajectory_follower_node/param/lateral/mpc.param.yaml @@ -74,3 +74,5 @@ update_steer_threshold: 0.035 average_num: 1000 steering_offset_limit: 0.02 + + debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate From 04bef8b7631d43ed88a2a090ea2649ef723db9a7 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Mon, 15 Jan 2024 11:09:27 +0100 Subject: [PATCH 238/276] fix(autoware_auto_perception_rviz_plugin): move headers to a separate directory (#5921) * fix(autoware_auto_perception_rviz_plugin): move headers to a separate directory Signed-off-by: Esteve Fernandez * style(pre-commit): autofix * fix(autoware_auto_perception_rviz_plugin): fix include Signed-off-by: Esteve Fernandez * style(pre-commit): autofix * fix(autoware_auto_perception_rviz_plugin): fix header paths in CMakeLists.txt Signed-off-by: Esteve Fernandez --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CMakeLists.txt | 14 +++++++------- .../common/color_alpha_property.hpp | 9 +++++---- .../object_detection/detected_objects_display.hpp | 8 ++++---- .../object_detection/object_polygon_detail.hpp | 9 +++++---- .../object_polygon_display_base.hpp | 12 ++++++------ .../object_detection/predicted_objects_display.hpp | 8 ++++---- .../object_detection/tracked_objects_display.hpp | 8 ++++---- .../visibility_control.hpp | 6 +++--- .../src/common/color_alpha_property.cpp | 2 +- .../object_detection/detected_objects_display.cpp | 2 +- .../src/object_detection/object_polygon_detail.cpp | 3 ++- .../object_detection/predicted_objects_display.cpp | 2 +- .../object_detection/tracked_objects_display.cpp | 2 +- 13 files changed, 44 insertions(+), 41 deletions(-) rename common/autoware_auto_perception_rviz_plugin/include/{ => autoware_auto_perception_rviz_plugin}/common/color_alpha_property.hpp (84%) rename common/autoware_auto_perception_rviz_plugin/include/{ => autoware_auto_perception_rviz_plugin}/object_detection/detected_objects_display.hpp (76%) rename common/autoware_auto_perception_rviz_plugin/include/{ => autoware_auto_perception_rviz_plugin}/object_detection/object_polygon_detail.hpp (97%) rename common/autoware_auto_perception_rviz_plugin/include/{ => autoware_auto_perception_rviz_plugin}/object_detection/object_polygon_display_base.hpp (97%) rename common/autoware_auto_perception_rviz_plugin/include/{ => autoware_auto_perception_rviz_plugin}/object_detection/predicted_objects_display.hpp (92%) rename common/autoware_auto_perception_rviz_plugin/include/{ => autoware_auto_perception_rviz_plugin}/object_detection/tracked_objects_display.hpp (89%) rename common/autoware_auto_perception_rviz_plugin/include/{ => autoware_auto_perception_rviz_plugin}/visibility_control.hpp (89%) diff --git a/common/autoware_auto_perception_rviz_plugin/CMakeLists.txt b/common/autoware_auto_perception_rviz_plugin/CMakeLists.txt index dd5f88d4caae8..8d0469e78c3ac 100644 --- a/common/autoware_auto_perception_rviz_plugin/CMakeLists.txt +++ b/common/autoware_auto_perception_rviz_plugin/CMakeLists.txt @@ -13,18 +13,18 @@ set(OD_PLUGIN_LIB_SRC ) set(OD_PLUGIN_LIB_HEADERS - include/visibility_control.hpp + include/autoware_auto_perception_rviz_plugin/visibility_control.hpp ) set(OD_PLUGIN_LIB_HEADERS_TO_WRAP - include/object_detection/detected_objects_display.hpp - include/object_detection/tracked_objects_display.hpp - include/object_detection/predicted_objects_display.hpp + include/autoware_auto_perception_rviz_plugin/object_detection/detected_objects_display.hpp + include/autoware_auto_perception_rviz_plugin/object_detection/tracked_objects_display.hpp + include/autoware_auto_perception_rviz_plugin/object_detection/predicted_objects_display.hpp ) set(COMMON_HEADERS - include/common/color_alpha_property.hpp - include/object_detection/object_polygon_detail.hpp - include/object_detection/object_polygon_display_base.hpp + include/autoware_auto_perception_rviz_plugin/common/color_alpha_property.hpp + include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp + include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp ) set(COMMON_SRC diff --git a/common/autoware_auto_perception_rviz_plugin/include/common/color_alpha_property.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/common/color_alpha_property.hpp similarity index 84% rename from common/autoware_auto_perception_rviz_plugin/include/common/color_alpha_property.hpp rename to common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/common/color_alpha_property.hpp index 8c43192a26bd6..10dc46e55ec70 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/common/color_alpha_property.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/common/color_alpha_property.hpp @@ -11,13 +11,14 @@ // WITHOUT 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 COMMON__COLOR_ALPHA_PROPERTY_HPP_ -#define COMMON__COLOR_ALPHA_PROPERTY_HPP_ +#ifndef AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__COMMON__COLOR_ALPHA_PROPERTY_HPP_ +#define AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__COMMON__COLOR_ALPHA_PROPERTY_HPP_ + +#include "autoware_auto_perception_rviz_plugin/visibility_control.hpp" #include #include #include -#include #include @@ -55,4 +56,4 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ColorAlphaProperty } // namespace rviz_plugins } // namespace autoware -#endif // COMMON__COLOR_ALPHA_PROPERTY_HPP_ +#endif // AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__COMMON__COLOR_ALPHA_PROPERTY_HPP_ diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/detected_objects_display.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/detected_objects_display.hpp similarity index 76% rename from common/autoware_auto_perception_rviz_plugin/include/object_detection/detected_objects_display.hpp rename to common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/detected_objects_display.hpp index 67dac25c796bb..97479fb68ca9b 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/detected_objects_display.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/detected_objects_display.hpp @@ -11,10 +11,10 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBJECT_DETECTION__DETECTED_OBJECTS_DISPLAY_HPP_ -#define OBJECT_DETECTION__DETECTED_OBJECTS_DISPLAY_HPP_ +#ifndef AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__DETECTED_OBJECTS_DISPLAY_HPP_ +#define AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__DETECTED_OBJECTS_DISPLAY_HPP_ -#include +#include "autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp" #include @@ -43,4 +43,4 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC DetectedObjectsDisplay } // namespace rviz_plugins } // namespace autoware -#endif // OBJECT_DETECTION__DETECTED_OBJECTS_DISPLAY_HPP_ +#endif // AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__DETECTED_OBJECTS_DISPLAY_HPP_ diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp similarity index 97% rename from common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp rename to common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp index deaa6be90b5f6..b3ee4a33b28c9 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp @@ -12,12 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. /// \brief This file defines some helper functions used by ObjectPolygonDisplayBase class -#ifndef OBJECT_DETECTION__OBJECT_POLYGON_DETAIL_HPP_ -#define OBJECT_DETECTION__OBJECT_POLYGON_DETAIL_HPP_ +#ifndef AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__OBJECT_POLYGON_DETAIL_HPP_ +#define AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__OBJECT_POLYGON_DETAIL_HPP_ + +#include "autoware_auto_perception_rviz_plugin/visibility_control.hpp" #include #include -#include #include #include @@ -252,4 +253,4 @@ AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC } // namespace rviz_plugins } // namespace autoware -#endif // OBJECT_DETECTION__OBJECT_POLYGON_DETAIL_HPP_ +#endif // AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__OBJECT_POLYGON_DETAIL_HPP_ diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp similarity index 97% rename from common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp rename to common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp index 240cbdc9efc5b..a0a21406ba416 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp @@ -11,19 +11,19 @@ // WITHOUT 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 OBJECT_DETECTION__OBJECT_POLYGON_DISPLAY_BASE_HPP_ -#define OBJECT_DETECTION__OBJECT_POLYGON_DISPLAY_BASE_HPP_ +#ifndef AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__OBJECT_POLYGON_DISPLAY_BASE_HPP_ +#define AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__OBJECT_POLYGON_DISPLAY_BASE_HPP_ -#include "common/color_alpha_property.hpp" +#include "autoware_auto_perception_rviz_plugin/common/color_alpha_property.hpp" +#include "autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp" +#include "autoware_auto_perception_rviz_plugin/visibility_control.hpp" -#include #include #include #include #include #include #include -#include #include #include @@ -449,4 +449,4 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase } // namespace rviz_plugins } // namespace autoware -#endif // OBJECT_DETECTION__OBJECT_POLYGON_DISPLAY_BASE_HPP_ +#endif // AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__OBJECT_POLYGON_DISPLAY_BASE_HPP_ diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/predicted_objects_display.hpp similarity index 92% rename from common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp rename to common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/predicted_objects_display.hpp index 2896286970217..775c18db6ba5c 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/predicted_objects_display.hpp @@ -11,10 +11,10 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBJECT_DETECTION__PREDICTED_OBJECTS_DISPLAY_HPP_ -#define OBJECT_DETECTION__PREDICTED_OBJECTS_DISPLAY_HPP_ +#ifndef AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__PREDICTED_OBJECTS_DISPLAY_HPP_ +#define AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__PREDICTED_OBJECTS_DISPLAY_HPP_ -#include +#include "autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp" #include @@ -153,4 +153,4 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay } // namespace rviz_plugins } // namespace autoware -#endif // OBJECT_DETECTION__PREDICTED_OBJECTS_DISPLAY_HPP_ +#endif // AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__PREDICTED_OBJECTS_DISPLAY_HPP_ diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/tracked_objects_display.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/tracked_objects_display.hpp similarity index 89% rename from common/autoware_auto_perception_rviz_plugin/include/object_detection/tracked_objects_display.hpp rename to common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/tracked_objects_display.hpp index a4cf8a703dff1..4e86a5ee93fd8 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/tracked_objects_display.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/tracked_objects_display.hpp @@ -11,10 +11,10 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBJECT_DETECTION__TRACKED_OBJECTS_DISPLAY_HPP_ -#define OBJECT_DETECTION__TRACKED_OBJECTS_DISPLAY_HPP_ +#ifndef AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__TRACKED_OBJECTS_DISPLAY_HPP_ +#define AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__TRACKED_OBJECTS_DISPLAY_HPP_ -#include +#include "autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp" #include @@ -114,4 +114,4 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC TrackedObjectsDisplay } // namespace rviz_plugins } // namespace autoware -#endif // OBJECT_DETECTION__TRACKED_OBJECTS_DISPLAY_HPP_ +#endif // AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__OBJECT_DETECTION__TRACKED_OBJECTS_DISPLAY_HPP_ diff --git a/common/autoware_auto_perception_rviz_plugin/include/visibility_control.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/visibility_control.hpp similarity index 89% rename from common/autoware_auto_perception_rviz_plugin/include/visibility_control.hpp rename to common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/visibility_control.hpp index bce7351572375..47cb8383fdada 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/visibility_control.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/visibility_control.hpp @@ -14,8 +14,8 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#ifndef VISIBILITY_CONTROL_HPP_ -#define VISIBILITY_CONTROL_HPP_ +#ifndef AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__VISIBILITY_CONTROL_HPP_ +#define AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__VISIBILITY_CONTROL_HPP_ #if defined(__WIN32) #if defined(AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_BUILDING_DLL) || \ @@ -40,4 +40,4 @@ #error "Unsupported Build Configuration" #endif // defined(_WINDOWS) -#endif // VISIBILITY_CONTROL_HPP_ +#endif // AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN__VISIBILITY_CONTROL_HPP_ diff --git a/common/autoware_auto_perception_rviz_plugin/src/common/color_alpha_property.cpp b/common/autoware_auto_perception_rviz_plugin/src/common/color_alpha_property.cpp index 57a42c95f9d34..b3e542a02243b 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/common/color_alpha_property.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/common/color_alpha_property.cpp @@ -14,7 +14,7 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include "common/color_alpha_property.hpp" +#include "autoware_auto_perception_rviz_plugin/common/color_alpha_property.hpp" #include diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp index db57e0e59a1ce..932ea87ccf5ad 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp @@ -14,7 +14,7 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include +#include "autoware_auto_perception_rviz_plugin/object_detection/detected_objects_display.hpp" #include diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp index 84321559f3541..97d7212d4f0ce 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp @@ -12,9 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License.. +#include "autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp" + #include #include -#include #include diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp index aa9eded82a88e..a9074f9e1bc1a 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include "autoware_auto_perception_rviz_plugin/object_detection/predicted_objects_display.hpp" #include #include diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp index fb53dbe1c2b8d..54dfb9edf889a 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp @@ -14,7 +14,7 @@ // // Co-developed by Tier IV, Inc. and Apex.AI, Inc. -#include +#include "autoware_auto_perception_rviz_plugin/object_detection/tracked_objects_display.hpp" #include From 4b231a915d67e874894ada5cd4e7b993a6ef10d3 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 15 Jan 2024 19:59:36 +0900 Subject: [PATCH 239/276] perf(bpp): reduce computational cost (#6054) * pref(avoidance): don't use boost union_ Signed-off-by: satoshi-ota * perf(avoidance): reduce frequency to call calcSignedArcLength Signed-off-by: satoshi-ota * perf(turn_signal): reduce frequency to call calcSignedArcLength Signed-off-by: satoshi-ota * perf(static_drivable_area_expansion): don't use calcDistance2d Signed-off-by: satoshi-ota * fix(static_drivable_area_expansion): rename and fix return value consistency Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../data_structs.hpp | 2 +- .../behavior_path_avoidance_module/scene.hpp | 13 ++-- .../src/debug.cpp | 7 ++- .../src/scene.cpp | 62 +++++++++++-------- .../src/utils.cpp | 45 +++++--------- .../src/turn_signal_decider.cpp | 18 +++--- .../static_drivable_area.cpp | 17 +++-- 7 files changed, 84 insertions(+), 80 deletions(-) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index 1d1494b7719c3..86e1608501831 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -588,7 +588,7 @@ struct ShiftLineData */ struct DebugData { - geometry_msgs::msg::Polygon detection_area; + std::vector detection_areas; lanelet::ConstLineStrings3d bounds; diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp index 889d48c481b6f..0bb480bfa26b1 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp @@ -112,13 +112,12 @@ class AvoidanceModule : public SceneModuleInterface */ void updateRegisteredRTCStatus(const PathWithLaneId & path) { - const Point ego_position = planner_data_->self_odometry->pose.pose.position; + const auto ego_idx = planner_data_->findEgoIndex(path.points); for (const auto & left_shift : left_shift_array_) { const double start_distance = - calcSignedArcLength(path.points, ego_position, left_shift.start_pose.position); - const double finish_distance = - calcSignedArcLength(path.points, ego_position, left_shift.finish_pose.position); + calcSignedArcLength(path.points, ego_idx, left_shift.start_pose.position); + const double finish_distance = start_distance + left_shift.relative_longitudinal; rtc_interface_ptr_map_.at("left")->updateCooperateStatus( left_shift.uuid, true, start_distance, finish_distance, clock_->now()); if (finish_distance > -1.0e-03) { @@ -130,9 +129,8 @@ class AvoidanceModule : public SceneModuleInterface for (const auto & right_shift : right_shift_array_) { const double start_distance = - calcSignedArcLength(path.points, ego_position, right_shift.start_pose.position); - const double finish_distance = - calcSignedArcLength(path.points, ego_position, right_shift.finish_pose.position); + calcSignedArcLength(path.points, ego_idx, right_shift.start_pose.position); + const double finish_distance = start_distance + right_shift.relative_longitudinal; rtc_interface_ptr_map_.at("right")->updateCooperateStatus( right_shift.uuid, true, start_distance, finish_distance, clock_->now()); if (finish_distance > -1.0e-03) { @@ -399,6 +397,7 @@ class AvoidanceModule : public SceneModuleInterface UUID uuid; Pose start_pose; Pose finish_pose; + double relative_longitudinal{0.0}; }; using RegisteredShiftLineArray = std::vector; diff --git a/planning/behavior_path_avoidance_module/src/debug.cpp b/planning/behavior_path_avoidance_module/src/debug.cpp index ee97efe37d440..f088b9228d964 100644 --- a/planning/behavior_path_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_avoidance_module/src/debug.cpp @@ -608,10 +608,15 @@ MarkerArray createDebugMarkerArray( addShiftGrad(debug.total_backward_grad, debug.total_shift, "grad_backward", 0.4, 0.2, 0.9); } + // detection area + size_t i = 0; + for (const auto & detection_area : debug.detection_areas) { + add(createPolygonMarkerArray(detection_area, "detection_area", i++, 0.16, 1.0, 0.69, 0.1)); + } + // misc { add(createPathMarkerArray(path, "centerline_resampled", 0, 0.0, 0.9, 0.5)); - add(createPolygonMarkerArray(debug.detection_area, "detection_area", 0L, 0.16, 1.0, 0.69, 0.1)); add(createDrivableBounds(data, "drivable_bound", 1.0, 0.0, 0.42)); add(laneletsAsTriangleMarkerArray( "drivable_lanes", transformToLanelets(data.drivable_lanes), diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 61941eeee6f00..c94243451ed2b 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -703,18 +703,6 @@ bool AvoidanceModule::isSafePath( return true; // if safety check is disabled, it always return safe. } - const bool limit_to_max_velocity = false; - const auto ego_predicted_path_params = - std::make_shared( - parameters_->ego_predicted_path_params); - const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(shifted_path.path.points); - const auto ego_predicted_path_for_front_object = utils::path_safety_checker::createPredictedPath( - ego_predicted_path_params, shifted_path.path.points, getEgoPose(), getEgoSpeed(), ego_seg_idx, - true, limit_to_max_velocity); - const auto ego_predicted_path_for_rear_object = utils::path_safety_checker::createPredictedPath( - ego_predicted_path_params, shifted_path.path.points, getEgoPose(), getEgoSpeed(), ego_seg_idx, - false, limit_to_max_velocity); - const auto ego_idx = planner_data_->findEgoIndex(shifted_path.path.points); const auto is_right_shift = [&]() -> std::optional { for (size_t i = ego_idx; i < shifted_path.shift_length.size(); i++) { @@ -741,6 +729,22 @@ bool AvoidanceModule::isSafePath( const auto safety_check_target_objects = utils::avoidance::getSafetyCheckTargetObjects( avoid_data_, planner_data_, parameters_, is_right_shift.value(), debug); + if (safety_check_target_objects.empty()) { + return true; + } + + const bool limit_to_max_velocity = false; + const auto ego_predicted_path_params = + std::make_shared( + parameters_->ego_predicted_path_params); + const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(shifted_path.path.points); + const auto ego_predicted_path_for_front_object = utils::path_safety_checker::createPredictedPath( + ego_predicted_path_params, shifted_path.path.points, getEgoPose(), getEgoSpeed(), ego_seg_idx, + true, limit_to_max_velocity); + const auto ego_predicted_path_for_rear_object = utils::path_safety_checker::createPredictedPath( + ego_predicted_path_params, shifted_path.path.points, getEgoPose(), getEgoSpeed(), ego_seg_idx, + false, limit_to_max_velocity); + for (const auto & object : safety_check_target_objects) { auto current_debug_data = utils::path_safety_checker::createObjectDebug(object); @@ -793,15 +797,16 @@ PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & orig const auto longest_dist_to_shift_point = [&]() { double max_dist = 0.0; - for (const auto & pnt : path_shifter_.getShiftLines()) { - max_dist = std::max( - max_dist, calcSignedArcLength(previous_path.points, pnt.start.position, getEgoPosition())); + auto lines = path_shifter_.getShiftLines(); + if (lines.empty()) { + return max_dist; } - for (const auto & sp : generator_.getRawRegisteredShiftLine()) { - max_dist = std::max( - max_dist, calcSignedArcLength(previous_path.points, sp.start.position, getEgoPosition())); - } - return max_dist; + std::sort(lines.begin(), lines.end(), [](const auto & a, const auto & b) { + return a.start_idx < b.start_idx; + }); + return std::max( + max_dist, + calcSignedArcLength(previous_path.points, lines.front().start.position, getEgoPosition())); }(); const auto extra_margin = 10.0; // Since distance does not consider arclength, but just line. @@ -1029,11 +1034,14 @@ void AvoidanceModule::updatePathShifter(const AvoidLineArray & shift_lines) const auto sl = helper_->getMainShiftLine(shift_lines); const auto sl_front = shift_lines.front(); const auto sl_back = shift_lines.back(); + const auto relative_longitudinal = sl_back.end_longitudinal - sl_front.start_longitudinal; if (helper_->getRelativeShiftToPath(sl) > 0.0) { - left_shift_array_.push_back({uuid_map_.at("left"), sl_front.start, sl_back.end}); + left_shift_array_.push_back( + {uuid_map_.at("left"), sl_front.start, sl_back.end, relative_longitudinal}); } else if (helper_->getRelativeShiftToPath(sl) < 0.0) { - right_shift_array_.push_back({uuid_map_.at("right"), sl_front.start, sl_back.end}); + right_shift_array_.push_back( + {uuid_map_.at("right"), sl_front.start, sl_back.end, relative_longitudinal}); } uuid_map_.at("left") = generateUUID(); @@ -1150,15 +1158,19 @@ bool AvoidanceModule::isValidShiftLine( const size_t start_idx = shift_lines.front().start_idx; const size_t end_idx = shift_lines.back().end_idx; + const auto path = shifter_for_validate.getReferencePath(); + const auto left_bound = lanelet::utils::to2D(avoid_data_.left_bound); + const auto right_bound = lanelet::utils::to2D(avoid_data_.right_bound); for (size_t i = start_idx; i <= end_idx; ++i) { - const auto p = getPoint(shifter_for_validate.getReferencePath().points.at(i)); + const auto p = getPoint(path.points.at(i)); lanelet::BasicPoint2d basic_point{p.x, p.y}; const auto shift_length = proposed_shift_path.shift_length.at(i); - const auto bound = shift_length > 0.0 ? avoid_data_.left_bound : avoid_data_.right_bound; const auto THRESHOLD = minimum_distance + std::abs(shift_length); - if (boost::geometry::distance(basic_point, lanelet::utils::to2D(bound)) < THRESHOLD) { + if ( + boost::geometry::distance(basic_point, (shift_length > 0.0 ? left_bound : right_bound)) < + THRESHOLD) { RCLCPP_DEBUG_THROTTLE( getLogger(), *clock_, 1000, "following latest new shift line may cause deviation from drivable area."); diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index f72f8279d4351..4c09962840907 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -1892,11 +1892,12 @@ std::pair separateObjectsByPath( max_offset = std::max(max_offset, offset); } + const double MARGIN = is_running ? 1.0 : 0.0; // [m] const auto detection_area = - createVehiclePolygon(planner_data->parameters.vehicle_info, max_offset); + createVehiclePolygon(planner_data->parameters.vehicle_info, max_offset + MARGIN); const auto ego_idx = planner_data->findEgoIndex(path.points); - Polygon2d attention_area; + std::vector detection_areas; for (size_t i = 0; i < path.points.size() - 1; ++i) { const auto & p_ego_front = path.points.at(i).point.pose; const auto & p_ego_back = path.points.at(i + 1).point.pose; @@ -1906,41 +1907,27 @@ std::pair separateObjectsByPath( break; } - const auto ego_one_step_polygon = createOneStepPolygon(p_ego_front, p_ego_back, detection_area); - - std::vector unions; - boost::geometry::union_(attention_area, ego_one_step_polygon, unions); - if (!unions.empty()) { - attention_area = unions.front(); - boost::geometry::correct(attention_area); - } + detection_areas.push_back(createOneStepPolygon(p_ego_front, p_ego_back, detection_area)); } - // expand detection area width only when the module is running. - if (is_running) { - constexpr int PER_CIRCLE = 36; - constexpr double MARGIN = 1.0; // [m] - boost::geometry::strategy::buffer::distance_symmetric distance_strategy(MARGIN); - boost::geometry::strategy::buffer::join_round join_strategy(PER_CIRCLE); - boost::geometry::strategy::buffer::end_round end_strategy(PER_CIRCLE); - boost::geometry::strategy::buffer::point_circle circle_strategy(PER_CIRCLE); - boost::geometry::strategy::buffer::side_straight side_strategy; - boost::geometry::model::multi_polygon result; - // Create the buffer of a multi polygon - boost::geometry::buffer( - attention_area, result, distance_strategy, side_strategy, join_strategy, end_strategy, - circle_strategy); - if (!result.empty()) { - attention_area = result.front(); + std::for_each(detection_areas.begin(), detection_areas.end(), [&](const auto & detection_area) { + debug.detection_areas.push_back(toMsg(detection_area, data.reference_pose.position.z)); + }); + + const auto within_detection_area = [&](const auto & obj_polygon) { + for (const auto & detection_area : detection_areas) { + if (!boost::geometry::disjoint(obj_polygon, detection_area)) { + return true; + } } - } - debug.detection_area = toMsg(attention_area, data.reference_pose.position.z); + return false; + }; const auto objects = planner_data->dynamic_object->objects; std::for_each(objects.begin(), objects.end(), [&](const auto & object) { const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); - if (boost::geometry::disjoint(obj_polygon, attention_area)) { + if (!within_detection_area(obj_polygon)) { other_objects.objects.push_back(object); } else { target_objects.objects.push_back(object); diff --git a/planning/behavior_path_planner_common/src/turn_signal_decider.cpp b/planning/behavior_path_planner_common/src/turn_signal_decider.cpp index 44358dfa84e4e..6ddc0df4eebf4 100644 --- a/planning/behavior_path_planner_common/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner_common/src/turn_signal_decider.cpp @@ -415,15 +415,7 @@ TurnSignalInfo TurnSignalDecider::use_prior_turn_signal( const double dist_to_original_desired_start = get_distance(original_desired_start_point) - base_link2front_; - const double dist_to_original_desired_end = get_distance(original_desired_end_point); - const double dist_to_original_required_start = - get_distance(original_required_start_point) - base_link2front_; - const double dist_to_original_required_end = get_distance(original_required_end_point); const double dist_to_new_desired_start = get_distance(new_desired_start_point) - base_link2front_; - const double dist_to_new_desired_end = get_distance(new_desired_end_point); - const double dist_to_new_required_start = - get_distance(new_required_start_point) - base_link2front_; - const double dist_to_new_required_end = get_distance(new_required_end_point); // If we still do not reach the desired front point we ignore it if (dist_to_original_desired_start > 0.0 && dist_to_new_desired_start > 0.0) { @@ -435,6 +427,9 @@ TurnSignalInfo TurnSignalDecider::use_prior_turn_signal( return original_signal; } + const double dist_to_original_desired_end = get_distance(original_desired_end_point); + const double dist_to_new_desired_end = get_distance(new_desired_end_point); + // If we already passed the desired end point, return the other signal if (dist_to_original_desired_end < 0.0 && dist_to_new_desired_end < 0.0) { TurnSignalInfo empty_signal_info; @@ -445,6 +440,13 @@ TurnSignalInfo TurnSignalDecider::use_prior_turn_signal( return original_signal; } + const double dist_to_original_required_start = + get_distance(original_required_start_point) - base_link2front_; + const double dist_to_original_required_end = get_distance(original_required_end_point); + const double dist_to_new_required_start = + get_distance(new_required_start_point) - base_link2front_; + const double dist_to_new_required_end = get_distance(new_required_end_point); + if (dist_to_original_desired_start <= dist_to_new_desired_start) { const auto enable_prior = use_prior_turn_signal( dist_to_original_required_start, dist_to_original_required_end, dist_to_new_required_start, diff --git a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 44c3025a8c5d5..03fae6864fe50 100644 --- a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -208,26 +208,25 @@ std::optional> intersectBound( return std::nullopt; } -double calcDistanceFromPointToSegment( +double calcSquaredDistanceFromPointToSegment( const geometry_msgs::msg::Point & segment_start_point, const geometry_msgs::msg::Point & segment_end_point, const geometry_msgs::msg::Point & target_point) { + using tier4_autoware_utils::calcSquaredDistance2d; + const auto & a = segment_start_point; const auto & b = segment_end_point; const auto & p = target_point; const double dot_val = (b.x - a.x) * (p.x - a.x) + (b.y - a.y) * (p.y - a.y); - const double squared_segment_length = tier4_autoware_utils::calcSquaredDistance2d(a, b); + const double squared_segment_length = calcSquaredDistance2d(a, b); if (0 <= dot_val && dot_val <= squared_segment_length) { - const double numerator = std::abs((p.x - a.x) * (a.y - b.y) - (p.y - a.y) * (a.x - b.x)); - const double denominator = std::sqrt(std::pow(a.x - b.x, 2) + std::pow(a.y - b.y, 2)); - return numerator / denominator; + return calcSquaredDistance2d(p, a) - dot_val * dot_val / squared_segment_length; } // target_point is outside the segment. - return std::min( - tier4_autoware_utils::calcDistance2d(a, p), tier4_autoware_utils::calcDistance2d(b, p)); + return std::min(calcSquaredDistance2d(a, p), calcSquaredDistance2d(b, p)); } PolygonPoint transformBoundFrenetCoordinate( @@ -238,8 +237,8 @@ PolygonPoint transformBoundFrenetCoordinate( // find wrong nearest index. std::vector dist_to_bound_segment_vec; for (size_t i = 0; i < bound_points.size() - 1; ++i) { - const double dist_to_bound_segment = - calcDistanceFromPointToSegment(bound_points.at(i), bound_points.at(i + 1), target_point); + const double dist_to_bound_segment = calcSquaredDistanceFromPointToSegment( + bound_points.at(i), bound_points.at(i + 1), target_point); dist_to_bound_segment_vec.push_back(dist_to_bound_segment); } From b7d29be2dee1fc60a3f2308a5171b81ce8aeeb60 Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Tue, 16 Jan 2024 00:09:14 +0900 Subject: [PATCH 240/276] fix(image_projection_based_fusion): re-organize the parameters for image projection fusion (#6075) re-organize the parameters for image projection fusion Signed-off-by: Shunsuke Miura --- .../camera_lidar_fusion_based_detection.launch.xml | 9 +++------ ...a_lidar_radar_fusion_based_detection.launch.xml | 6 +++--- .../detection/detection.launch.xml | 11 +++-------- .../launch/perception.launch.xml | 14 ++++++-------- 4 files changed, 15 insertions(+), 25 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 227aac50d6d90..10d1ac034d457 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -12,9 +12,6 @@ - - - @@ -113,6 +110,7 @@ + @@ -167,9 +165,7 @@ - - - + @@ -305,6 +301,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index 65caad54876ff..c227298c932d9 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -139,6 +139,7 @@ + @@ -193,9 +194,7 @@ - - - + @@ -344,6 +343,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml index 0649d8c5d5116..68d5ea944e6cb 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -34,11 +34,6 @@ - - - - - @@ -65,14 +60,14 @@ - - - + + + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 1b5753fb4d5c4..87616b9ccb122 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -10,6 +10,9 @@ + + + @@ -99,11 +102,6 @@ description="options: `ped_traffic_light_classifier_mobilenetv2_batch_*` or `ped_traffic_light_classifier_efficientNet_b1_batch_*`. The batch number must be either one of 1, 4, 6" /> - - - - - @@ -177,6 +175,9 @@ + + + @@ -190,9 +191,6 @@ - - - From 98b1531e20e594932817264e007815f15fc186ca Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 16 Jan 2024 10:09:47 +0900 Subject: [PATCH 241/276] fix(ekf_localizer): fixed timer in ekf_localizer (#6066) Fixed timer in ekf_localizer Signed-off-by: Shintaro Sakoda --- .../include/ekf_localizer/ekf_localizer.hpp | 4 +- .../ekf_localizer/src/ekf_localizer.cpp | 46 ++++++++++--------- 2 files changed, 26 insertions(+), 24 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index ba18b7dadd599..6925e8b63c66b 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -199,7 +199,7 @@ class EKFLocalizer : public rclcpp::Node /** * @brief update predict frequency */ - void updatePredictFrequency(); + void updatePredictFrequency(const rclcpp::Time & current_time); /** * @brief get transform from frame_id @@ -219,7 +219,7 @@ class EKFLocalizer : public rclcpp::Node /** * @brief publish diagnostics message */ - void publishDiagnostics(); + void publishDiagnostics(const rclcpp::Time & current_time); /** * @brief update simple1DFilter diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index b3ee3665cf45e..f77481d45a534 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -104,14 +104,14 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti /* * updatePredictFrequency */ -void EKFLocalizer::updatePredictFrequency() +void EKFLocalizer::updatePredictFrequency(const rclcpp::Time & current_time) { if (last_predict_time_) { - if (get_clock()->now() < *last_predict_time_) { + if (current_time < *last_predict_time_) { warning_->warn("Detected jump back in time"); } else { /* Measure dt */ - ekf_dt_ = (get_clock()->now() - *last_predict_time_).seconds(); + ekf_dt_ = (current_time - *last_predict_time_).seconds(); DEBUG_INFO( get_logger(), "[EKF] update ekf_dt_ to %f seconds (= %f hz)", ekf_dt_, 1 / ekf_dt_); @@ -133,7 +133,7 @@ void EKFLocalizer::updatePredictFrequency() proc_cov_yaw_d_ = std::pow(params_.proc_stddev_yaw_c * ekf_dt_, 2.0); } } - last_predict_time_ = std::make_shared(get_clock()->now()); + last_predict_time_ = std::make_shared(current_time); } /* @@ -141,17 +141,19 @@ void EKFLocalizer::updatePredictFrequency() */ void EKFLocalizer::timerCallback() { + const rclcpp::Time current_time = this->now(); + if (!is_activated_) { warning_->warnThrottle( "The node is not activated. Provide initial pose to pose_initializer", 2000); - publishDiagnostics(); + publishDiagnostics(current_time); return; } DEBUG_INFO(get_logger(), "========================= timer called ========================="); /* update predict frequency with measured timer rate */ - updatePredictFrequency(); + updatePredictFrequency(current_time); /* predict model in EKF */ stop_watch_.tic(); @@ -175,7 +177,7 @@ void EKFLocalizer::timerCallback() stop_watch_.tic(); // save the initial size because the queue size can change in the loop - const auto t_curr = this->now(); + const auto t_curr = current_time; const size_t n = pose_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto pose = pose_queue_.pop_increment_age(); @@ -210,7 +212,7 @@ void EKFLocalizer::timerCallback() stop_watch_.tic(); // save the initial size because the queue size can change in the loop - const auto t_curr = this->now(); + const auto t_curr = current_time; const size_t n = twist_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto twist = twist_queue_.pop_increment_age(); @@ -228,15 +230,15 @@ void EKFLocalizer::timerCallback() const double roll = roll_filter_.get_x(); const double pitch = pitch_filter_.get_x(); const geometry_msgs::msg::PoseStamped current_ekf_pose = - ekf_module_->getCurrentPose(this->now(), z, roll, pitch, false); + ekf_module_->getCurrentPose(current_time, z, roll, pitch, false); const geometry_msgs::msg::PoseStamped current_biased_ekf_pose = - ekf_module_->getCurrentPose(this->now(), z, roll, pitch, true); + ekf_module_->getCurrentPose(current_time, z, roll, pitch, true); const geometry_msgs::msg::TwistStamped current_ekf_twist = - ekf_module_->getCurrentTwist(this->now()); + ekf_module_->getCurrentTwist(current_time); /* publish ekf result */ publishEstimateResult(current_ekf_pose, current_biased_ekf_pose, current_ekf_twist); - publishDiagnostics(); + publishDiagnostics(current_time); } /* @@ -256,10 +258,12 @@ void EKFLocalizer::timerTFCallback() 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 = tier4_autoware_utils::pose2transform( - ekf_module_->getCurrentPose(this->now(), z, roll, pitch, false), "base_link"); - transform_stamped.header.stamp = this->now(); + ekf_module_->getCurrentPose(current_time, z, roll, pitch, false), "base_link"); + transform_stamped.header.stamp = current_time; tf_br_->sendTransform(transform_stamped); } @@ -340,15 +344,13 @@ void EKFLocalizer::publishEstimateResult( const geometry_msgs::msg::PoseStamped & current_biased_ekf_pose, const geometry_msgs::msg::TwistStamped & current_ekf_twist) { - rclcpp::Time current_time = this->now(); - /* publish latest pose */ pub_pose_->publish(current_ekf_pose); pub_biased_pose_->publish(current_biased_ekf_pose); /* publish latest pose with covariance */ geometry_msgs::msg::PoseWithCovarianceStamped pose_cov; - pose_cov.header.stamp = current_time; + pose_cov.header.stamp = current_ekf_pose.header.stamp; pose_cov.header.frame_id = current_ekf_pose.header.frame_id; pose_cov.pose.pose = current_ekf_pose.pose; pose_cov.pose.covariance = ekf_module_->getCurrentPoseCovariance(); @@ -363,7 +365,7 @@ void EKFLocalizer::publishEstimateResult( /* publish latest twist with covariance */ geometry_msgs::msg::TwistWithCovarianceStamped twist_cov; - twist_cov.header.stamp = current_time; + twist_cov.header.stamp = current_ekf_twist.header.stamp; twist_cov.header.frame_id = current_ekf_twist.header.frame_id; twist_cov.twist.twist = current_ekf_twist.twist; twist_cov.twist.covariance = ekf_module_->getCurrentTwistCovariance(); @@ -371,13 +373,13 @@ void EKFLocalizer::publishEstimateResult( /* publish yaw bias */ tier4_debug_msgs::msg::Float64Stamped yawb; - yawb.stamp = current_time; + yawb.stamp = current_ekf_twist.header.stamp; yawb.data = ekf_module_->getYawBias(); pub_yaw_bias_->publish(yawb); /* publish latest odometry */ nav_msgs::msg::Odometry odometry; - odometry.header.stamp = current_time; + odometry.header.stamp = current_ekf_pose.header.stamp; odometry.header.frame_id = current_ekf_pose.header.frame_id; odometry.child_frame_id = "base_link"; odometry.pose = pose_cov.pose; @@ -385,7 +387,7 @@ void EKFLocalizer::publishEstimateResult( pub_odom_->publish(odometry); } -void EKFLocalizer::publishDiagnostics() +void EKFLocalizer::publishDiagnostics(const rclcpp::Time & current_time) { std::vector diag_status_array; @@ -421,7 +423,7 @@ void EKFLocalizer::publishDiagnostics() diag_merged_status.hardware_id = this->get_name(); diagnostic_msgs::msg::DiagnosticArray diag_msg; - diag_msg.header.stamp = this->now(); + diag_msg.header.stamp = current_time; diag_msg.status.push_back(diag_merged_status); pub_diag_->publish(diag_msg); } From edc5c1a0f59f00337858cb7e6833abc5f7c14ed3 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 16 Jan 2024 10:28:36 +0900 Subject: [PATCH 242/276] feat(goal_planner): output objects of interest (#6077) Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 7 +++++++ .../utils/path_safety_checker/safety_check.cpp | 15 +++++++-------- 2 files changed, 14 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 7bd97b3775bad..a13efd543d61c 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1957,6 +1957,13 @@ void GoalPlannerModule::setDebugData() } add(showPredictedPath(goal_planner_data_.collision_check, "ego_predicted_path")); add(showPolygon(goal_planner_data_.collision_check, "ego_and_target_polygon_relation")); + + // set objects of interest + for (const auto & [uuid, data] : goal_planner_data_.collision_check) { + const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; + setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color); + } + utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); // visualize safety status maker diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index bf93e71ab3591..e209e8dba36be 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -453,16 +453,15 @@ bool checkSafetyWithIntegralPredictedPolygon( for (const auto & path : object.predicted_paths) { for (const auto & pose_with_poly : path.path) { if (boost::geometry::overlaps(ego_integral_polygon, pose_with_poly.poly)) { - { - debug_pair.second.ego_predicted_path = ego_predicted_path; // raw path - debug_pair.second.obj_predicted_path = path.path; // raw path - debug_pair.second.extended_obj_polygon = pose_with_poly.poly; - debug_pair.second.extended_ego_polygon = - ego_integral_polygon; // time filtered extended polygon - updateCollisionCheckDebugMap(debug_map, debug_pair, false); - } + debug_pair.second.ego_predicted_path = ego_predicted_path; // raw path + debug_pair.second.obj_predicted_path = path.path; // raw path + debug_pair.second.extended_obj_polygon = pose_with_poly.poly; + debug_pair.second.extended_ego_polygon = + ego_integral_polygon; // time filtered extended polygon + updateCollisionCheckDebugMap(debug_map, debug_pair, /*is_safe=*/false); return false; } + updateCollisionCheckDebugMap(debug_map, debug_pair, /*is_safe=*/true); } } } From db927fbc6ad822c22f37b86d5f82860d3b5e274b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 16 Jan 2024 10:29:04 +0900 Subject: [PATCH 243/276] feat(start_planner): output objects of interest (#6078) * feat(start_planner): output objects of interest Signed-off-by: kosuke55 * style(pre-commit): autofix --------- Signed-off-by: kosuke55 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../start_planner_module.hpp | 2 +- .../src/start_planner_module.cpp | 9 ++++++++- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index 41a80e59d56bf..7b463f4fadf80 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -254,7 +254,7 @@ class StartPlannerModule : public SceneModuleInterface void onFreespacePlannerTimer(); bool planFreespacePath(); - void setDebugData() const; + void setDebugData(); void logPullOutStatus(rclcpp::Logger::Level log_level = rclcpp::Logger::Level::Info) const; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index d523f57125679..9ad7f72d6af4e 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -1325,7 +1325,7 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons } } -void StartPlannerModule::setDebugData() const +void StartPlannerModule::setDebugData() { using marker_utils::addFootprintMarker; using marker_utils::createFootprintMarkerArray; @@ -1432,6 +1432,13 @@ void StartPlannerModule::setDebugData() const add(showSafetyCheckInfo(start_planner_data_.collision_check, "object_debug_info")); add(showPredictedPath(start_planner_data_.collision_check, "ego_predicted_path")); add(showPolygon(start_planner_data_.collision_check, "ego_and_target_polygon_relation")); + + // set objects of interest + for (const auto & [uuid, data] : start_planner_data_.collision_check) { + const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; + setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color); + } + initializeCollisionCheckDebugMap(start_planner_data_.collision_check); } From 751032f96039ad040ff1a6ba0a90e6ad9f4878a6 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 16 Jan 2024 10:39:46 +0900 Subject: [PATCH 244/276] feat(perception_rviz_plugin): rviz object covariances (#6074) * feat: visualize yaw rate, yaw std Signed-off-by: Taekjin LEE * feat: discrete yaw covariance marker Signed-off-by: Taekjin LEE * feat: add yaw covariance to detected object Signed-off-by: Taekjin LEE * feat: visualize twist covariance, yaw only Signed-off-by: Taekjin LEE * feat: discrete yaw rate marker Signed-off-by: Taekjin LEE * fix: property order Signed-off-by: Taekjin LEE * chore: parameter order change Signed-off-by: Taekjin LEE * feat: position covariance as ellipse Signed-off-by: Taekjin LEE * feat: twist covariance Signed-off-by: Taekjin LEE * chore: pose covariance marker renamed Signed-off-by: Taekjin LEE * fix: velocity covariance minimum alpha Signed-off-by: Taekjin LEE * chore: refactoring Signed-off-by: Taekjin LEE * feat: add option for interval coefficients Signed-off-by: Taekjin LEE * fix: confidence interval (1D) and confidence region (2D) Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../object_polygon_detail.hpp | 36 +- .../object_polygon_display_base.hpp | 131 +++++++- .../detected_objects_display.cpp | 53 +++ .../object_polygon_detail.cpp | 309 +++++++++++++++--- .../predicted_objects_display.cpp | 72 +++- .../tracked_objects_display.cpp | 63 +++- 6 files changed, 592 insertions(+), 72 deletions(-) diff --git a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp index b3ee4a33b28c9..5f9da8531d2ab 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp @@ -17,6 +17,8 @@ #include "autoware_auto_perception_rviz_plugin/visibility_control.hpp" +#include +#include #include #include @@ -113,8 +115,14 @@ get_uuid_marker_ptr( const std_msgs::msg::ColorRGBA & color_rgba); AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr -get_pose_with_covariance_marker_ptr( - const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance); +get_pose_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const double & confidence_interval_coefficient); + +AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr +get_yaw_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, const double & length, + const double & confidence_interval_coefficient, const double & line_width); AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr get_velocity_text_marker_ptr( @@ -131,6 +139,23 @@ get_twist_marker_ptr( const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, const double & line_width); +AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr +get_twist_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, + const double & confidence_interval_coefficient); + +AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr +get_yaw_rate_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, const double & line_width); + +AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr +get_yaw_rate_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, + const double & confidence_interval_coefficient, const double & line_width); + AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr get_predicted_path_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape, @@ -142,10 +167,17 @@ get_path_confidence_marker_ptr( const autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, const std_msgs::msg::ColorRGBA & path_confidence_color); +AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_arc_line_strip( + const double start_angle, const double end_angle, const double radius, + std::vector & points); + AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_line_list_from_points( const double point_list[][3], const int point_pairs[][2], const int & num_pairs, std::vector & points); +AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_covariance_eigen_vectors( + const Eigen::Matrix2d & matrix, double & sigma1, double & sigma2, double & yaw); + AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC void calc_bounding_box_line_list( const autoware_auto_perception_msgs::msg::Shape & shape, std::vector & points); diff --git a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp index a0a21406ba416..4290fdff49bb3 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp @@ -64,14 +64,22 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase // m_display_type_property{"Polygon Type", "3d", "Type of the polygon to display object", this}, m_display_label_property{"Display Label", true, "Enable/disable label visualization", this}, m_display_uuid_property{"Display UUID", true, "Enable/disable uuid visualization", this}, - m_display_pose_with_covariance_property{ - "Display PoseWithCovariance", true, "Enable/disable pose with covariance visualization", - this}, m_display_velocity_text_property{ "Display Velocity", true, "Enable/disable velocity text visualization", this}, m_display_acceleration_text_property{ "Display Acceleration", true, "Enable/disable acceleration text visualization", this}, + m_display_pose_covariance_property{ + "Display Pose Covariance", true, "Enable/disable pose covariance visualization", this}, + m_display_yaw_covariance_property{ + "Display Yaw Covariance", false, "Enable/disable yaw covariance visualization", this}, m_display_twist_property{"Display Twist", true, "Enable/disable twist visualization", this}, + m_display_twist_covariance_property{ + "Display Twist Covariance", false, "Enable/disable twist covariance visualization", this}, + m_display_yaw_rate_property{ + "Display Yaw Rate", false, "Enable/disable yaw rate visualization", this}, + m_display_yaw_rate_covariance_property{ + "Display Yaw Rate Covariance", false, "Enable/disable yaw rate covariance visualization", + this}, m_display_predicted_paths_property{ "Display Predicted Paths", true, "Enable/disable predicted paths visualization", this}, m_display_path_confidence_property{ @@ -96,6 +104,13 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase "Visualization Type", "Normal", "Simplicity of the polygon to display object.", this); m_simple_visualize_mode_property->addOption("Normal", 0); m_simple_visualize_mode_property->addOption("Simple", 1); + // Confidence interval property + m_confidence_interval_property = new rviz_common::properties::EnumProperty( + "Confidence Interval", "95%", "Confidence interval of state estimations.", this); + m_confidence_interval_property->addOption("70%", 0); + m_confidence_interval_property->addOption("85%", 1); + m_confidence_interval_property->addOption("95%", 2); + m_confidence_interval_property->addOption("99%", 3); // iterate over default values to create and initialize the properties. for (const auto & map_property_it : detail::kDefaultObjectPropertyValues) { @@ -238,11 +253,23 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase } } - std::optional get_pose_with_covariance_marker_ptr( + std::optional get_pose_covariance_marker_ptr( const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance) const { - if (m_display_pose_with_covariance_property.getBool()) { - return detail::get_pose_with_covariance_marker_ptr(pose_with_covariance); + if (m_display_pose_covariance_property.getBool()) { + return detail::get_pose_covariance_marker_ptr(pose_with_covariance, get_confidence_region()); + } else { + return std::nullopt; + } + } + + std::optional get_yaw_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, const double & length, + const double & line_width) const + { + if (m_display_yaw_covariance_property.getBool()) { + return detail::get_yaw_covariance_marker_ptr( + pose_with_covariance, length, get_confidence_interval(), line_width); } else { return std::nullopt; } @@ -286,6 +313,44 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase } } + std::optional get_twist_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance) const + { + if (m_display_twist_covariance_property.getBool()) { + return detail::get_twist_covariance_marker_ptr( + pose_with_covariance, twist_with_covariance, get_confidence_region()); + } else { + return std::nullopt; + } + } + + std::optional get_yaw_rate_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, + const double & line_width) const + { + if (m_display_yaw_rate_property.getBool()) { + return detail::get_yaw_rate_marker_ptr( + pose_with_covariance, twist_with_covariance, line_width); + } else { + return std::nullopt; + } + } + + std::optional get_yaw_rate_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, + const double & line_width) const + { + if (m_display_yaw_rate_covariance_property.getBool()) { + return detail::get_yaw_rate_covariance_marker_ptr( + pose_with_covariance, twist_with_covariance, get_confidence_interval(), line_width); + } else { + return std::nullopt; + } + } + std::optional get_predicted_path_marker_ptr( const unique_identifier_msgs::msg::UUID & uuid, const autoware_auto_perception_msgs::msg::Shape & shape, @@ -408,6 +473,46 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase double get_line_width() { return m_line_width_property.getFloat(); } + double get_confidence_interval() const + { + switch (m_confidence_interval_property->getOptionInt()) { + case 0: + // 70% + return 1.036; + case 1: + // 85% + return 1.440; + case 2: + // 95% + return 1.960; + case 3: + // 99% + return 2.576; + default: + return 1.960; + } + } + + double get_confidence_region() const + { + switch (m_confidence_interval_property->getOptionInt()) { + case 0: + // 70% + return 1.552; + case 1: + // 85% + return 1.802; + case 2: + // 95% + return 2.448; + case 3: + // 99% + return 3.035; + default: + return 2.448; + } + } + private: // All rviz plugins should have this. Should be initialized with pointer to this class MarkerCommon m_marker_common; @@ -419,18 +524,28 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase rviz_common::properties::EnumProperty * m_display_type_property; // Property to choose simplicity of visualization polygon rviz_common::properties::EnumProperty * m_simple_visualize_mode_property; + // Property to set confidence interval of state estimations + rviz_common::properties::EnumProperty * m_confidence_interval_property; // Property to enable/disable label visualization rviz_common::properties::BoolProperty m_display_label_property; // Property to enable/disable uuid visualization rviz_common::properties::BoolProperty m_display_uuid_property; - // Property to enable/disable pose with covariance visualization - rviz_common::properties::BoolProperty m_display_pose_with_covariance_property; // Property to enable/disable velocity text visualization rviz_common::properties::BoolProperty m_display_velocity_text_property; // Property to enable/disable acceleration text visualization rviz_common::properties::BoolProperty m_display_acceleration_text_property; + // Property to enable/disable pose with covariance visualization + rviz_common::properties::BoolProperty m_display_pose_covariance_property; + // Property to enable/disable yaw covariance visualization + rviz_common::properties::BoolProperty m_display_yaw_covariance_property; // Property to enable/disable twist visualization rviz_common::properties::BoolProperty m_display_twist_property; + // Property to enable/disable twist covariance visualization + rviz_common::properties::BoolProperty m_display_twist_covariance_property; + // Property to enable/disable yaw rate visualization + rviz_common::properties::BoolProperty m_display_yaw_rate_property; + // Property to enable/disable yaw rate covariance visualization + rviz_common::properties::BoolProperty m_display_yaw_rate_covariance_property; // Property to enable/disable predicted paths visualization rviz_common::properties::BoolProperty m_display_predicted_paths_property; // Property to enable/disable predicted path confidence visualization diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp index 932ea87ccf5ad..53e935fa1850a 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp @@ -59,6 +59,27 @@ void DetectedObjectsDisplay::processMessage(DetectedObjects::ConstSharedPtr msg) add_marker(label_marker_ptr); } + // Get marker for pose covariance + auto pose_with_covariance_marker = + get_pose_covariance_marker_ptr(object.kinematics.pose_with_covariance); + if (pose_with_covariance_marker) { + auto marker_ptr = pose_with_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = id++; + add_marker(marker_ptr); + } + + // Get marker for yaw covariance + auto yaw_covariance_marker = get_yaw_covariance_marker_ptr( + object.kinematics.pose_with_covariance, object.shape.dimensions.x * 0.65, + get_line_width() * 0.5); + if (yaw_covariance_marker) { + auto marker_ptr = yaw_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = id++; + add_marker(marker_ptr); + } + // Get marker for existence probability geometry_msgs::msg::Point existence_probability_position; existence_probability_position.x = object.kinematics.pose_with_covariance.pose.position.x + 0.5; @@ -99,6 +120,38 @@ void DetectedObjectsDisplay::processMessage(DetectedObjects::ConstSharedPtr msg) twist_marker_ptr->id = id++; add_marker(twist_marker_ptr); } + + // Get marker for twist covariance + auto twist_covariance_marker = get_twist_covariance_marker_ptr( + object.kinematics.pose_with_covariance, object.kinematics.twist_with_covariance); + if (twist_covariance_marker) { + auto marker_ptr = twist_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = id++; + add_marker(marker_ptr); + } + + // Get marker for yaw rate + auto yaw_rate_marker = get_yaw_rate_marker_ptr( + object.kinematics.pose_with_covariance, object.kinematics.twist_with_covariance, + get_line_width() * 0.4); + if (yaw_rate_marker) { + auto marker_ptr = yaw_rate_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = id++; + add_marker(marker_ptr); + } + + // Get marker for yaw rate covariance + auto yaw_rate_covariance_marker = get_yaw_rate_covariance_marker_ptr( + object.kinematics.pose_with_covariance, object.kinematics.twist_with_covariance, + get_line_width() * 0.3); + if (yaw_rate_covariance_marker) { + auto marker_ptr = yaw_rate_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = id++; + add_marker(marker_ptr); + } } } diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp index 97d7212d4f0ce..11a0bbbe57d53 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp @@ -101,17 +101,16 @@ visualization_msgs::msg::Marker::SharedPtr get_twist_marker_ptr( marker_ptr->action = visualization_msgs::msg::Marker::MODIFY; marker_ptr->pose = pose_with_covariance.pose; - geometry_msgs::msg::Point pt_s; - pt_s.x = 0.0; - pt_s.y = 0.0; - pt_s.z = 0.0; - marker_ptr->points.push_back(pt_s); - - geometry_msgs::msg::Point pt_e; - pt_e.x = twist_with_covariance.twist.linear.x; - pt_e.y = twist_with_covariance.twist.linear.y; - pt_e.z = twist_with_covariance.twist.linear.z; - marker_ptr->points.push_back(pt_e); + // velocity line + geometry_msgs::msg::Point point; + point.x = 0.0; + point.y = 0.0; + point.z = 0.0; + marker_ptr->points.push_back(point); + point.x = twist_with_covariance.twist.linear.x; + point.y = twist_with_covariance.twist.linear.y; + point.z = twist_with_covariance.twist.linear.z; + marker_ptr->points.push_back(point); marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5); marker_ptr->color.a = 0.999; @@ -122,6 +121,168 @@ visualization_msgs::msg::Marker::SharedPtr get_twist_marker_ptr( return marker_ptr; } +visualization_msgs::msg::Marker::SharedPtr get_twist_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, + const double & confidence_interval_coefficient) +{ + auto marker_ptr = std::make_shared(); + marker_ptr->type = visualization_msgs::msg::Marker::CYLINDER; + marker_ptr->ns = std::string("twist covariance"); + marker_ptr->action = visualization_msgs::msg::Marker::MODIFY; + marker_ptr->pose = pose_with_covariance.pose; + + // position is the tip of the velocity vector + const double velocity = std::sqrt( + twist_with_covariance.twist.linear.x * twist_with_covariance.twist.linear.x + + twist_with_covariance.twist.linear.y * twist_with_covariance.twist.linear.y); + const double velocity_angle = + std::atan2(twist_with_covariance.twist.linear.y, twist_with_covariance.twist.linear.x); + const double pos_yaw_angle = 2.0 * std::atan2( + pose_with_covariance.pose.orientation.z, + pose_with_covariance.pose.orientation.w); // [rad] + marker_ptr->pose.position.x += velocity * std::cos(pos_yaw_angle + velocity_angle); + marker_ptr->pose.position.y += velocity * std::sin(pos_yaw_angle + velocity_angle); + + // velocity covariance + // extract eigen values and eigen vectors + Eigen::Matrix2d eigen_twist_covariance; + eigen_twist_covariance << twist_with_covariance.covariance[0], + twist_with_covariance.covariance[1], twist_with_covariance.covariance[6], + twist_with_covariance.covariance[7]; + double phi, sigma1, sigma2; + calc_covariance_eigen_vectors(eigen_twist_covariance, sigma1, sigma2, phi); + phi = pos_yaw_angle + phi; + double area = sigma1 * sigma2; + double alpha = std::min(0.5, 1.0 / area); + alpha = std::max(0.1, alpha); + + // ellipse orientation + marker_ptr->pose.orientation.x = 0.0; + marker_ptr->pose.orientation.y = 0.0; + marker_ptr->pose.orientation.z = std::sin(phi / 2.0); + marker_ptr->pose.orientation.w = std::cos(phi / 2.0); + + // ellipse size + marker_ptr->scale.x = sigma1 * confidence_interval_coefficient; + marker_ptr->scale.y = sigma2 * confidence_interval_coefficient; + marker_ptr->scale.z = 0.05; + + marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5); + marker_ptr->color.a = alpha; + marker_ptr->color.r = 1.0; + marker_ptr->color.g = 0.2; + marker_ptr->color.b = 0.4; + + return marker_ptr; +} + +visualization_msgs::msg::Marker::SharedPtr get_yaw_rate_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, const double & line_width) +{ + auto marker_ptr = std::make_shared(); + marker_ptr->type = visualization_msgs::msg::Marker::LINE_STRIP; + marker_ptr->ns = std::string("yaw rate"); + marker_ptr->scale.x = line_width; + marker_ptr->action = visualization_msgs::msg::Marker::MODIFY; + marker_ptr->pose = pose_with_covariance.pose; + + // yaw rate + const double yaw_rate = twist_with_covariance.twist.angular.z; + const double velocity = std::sqrt( + twist_with_covariance.twist.linear.x * twist_with_covariance.twist.linear.x + + twist_with_covariance.twist.linear.y * twist_with_covariance.twist.linear.y + + twist_with_covariance.twist.linear.z * twist_with_covariance.twist.linear.z); + const double velocity_angle = + std::atan2(twist_with_covariance.twist.linear.y, twist_with_covariance.twist.linear.x); + const double yaw_mark_length = velocity * 0.8; + + geometry_msgs::msg::Point point; + // first point + point.x = 0; + point.y = 0; + point.z = 0; + marker_ptr->points.push_back(point); + // yaw rate arc + calc_arc_line_strip( + velocity_angle, velocity_angle + yaw_rate, yaw_mark_length, marker_ptr->points); + // last point + point.x = 0; + point.y = 0; + point.z = 0; + marker_ptr->points.push_back(point); + + marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5); + marker_ptr->color.a = 0.9; + marker_ptr->color.r = 1.0; + marker_ptr->color.g = 0.0; + marker_ptr->color.b = 0.0; + + return marker_ptr; +} + +visualization_msgs::msg::Marker::SharedPtr get_yaw_rate_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, + const double & confidence_interval_coefficient, const double & line_width) +{ + auto marker_ptr = std::make_shared(); + marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; + marker_ptr->ns = std::string("yaw rate covariance"); + marker_ptr->scale.x = line_width; + marker_ptr->action = visualization_msgs::msg::Marker::MODIFY; + marker_ptr->pose = pose_with_covariance.pose; + + // yaw rate covariance + const double yaw_rate_covariance = twist_with_covariance.covariance[35]; + const double yaw_rate_sigma = std::sqrt(yaw_rate_covariance) * confidence_interval_coefficient; + const double yaw_rate = twist_with_covariance.twist.angular.z; + const double velocity = std::sqrt( + twist_with_covariance.twist.linear.x * twist_with_covariance.twist.linear.x + + twist_with_covariance.twist.linear.y * twist_with_covariance.twist.linear.y + + twist_with_covariance.twist.linear.z * twist_with_covariance.twist.linear.z); + const double velocity_angle = + std::atan2(twist_with_covariance.twist.linear.y, twist_with_covariance.twist.linear.x); + const double yaw_mark_length = velocity * 0.8; + const double bar_width = std::max(velocity * 0.05, 0.1); + const double velocity_yaw_angle = velocity_angle + yaw_rate; + const double velocity_yaw_p_sigma_angle = velocity_yaw_angle + yaw_rate_sigma; + const double velocity_yaw_n_sigma_angle = velocity_yaw_angle - yaw_rate_sigma; + + const double point_list[7][3] = { + {yaw_mark_length * std::cos(velocity_yaw_angle), yaw_mark_length * std::sin(velocity_yaw_angle), + 0}, + {yaw_mark_length * std::cos(velocity_yaw_p_sigma_angle), + yaw_mark_length * std::sin(velocity_yaw_p_sigma_angle), 0}, + {yaw_mark_length * std::cos(velocity_yaw_n_sigma_angle), + yaw_mark_length * std::sin(velocity_yaw_n_sigma_angle), 0}, + {(yaw_mark_length + bar_width) * std::cos(velocity_yaw_p_sigma_angle), + (yaw_mark_length + bar_width) * std::sin(velocity_yaw_p_sigma_angle), 0}, + {(yaw_mark_length - bar_width) * std::cos(velocity_yaw_p_sigma_angle), + (yaw_mark_length - bar_width) * std::sin(velocity_yaw_p_sigma_angle), 0}, + {(yaw_mark_length + bar_width) * std::cos(velocity_yaw_n_sigma_angle), + (yaw_mark_length + bar_width) * std::sin(velocity_yaw_n_sigma_angle), 0}, + {(yaw_mark_length - bar_width) * std::cos(velocity_yaw_n_sigma_angle), + (yaw_mark_length - bar_width) * std::sin(velocity_yaw_n_sigma_angle), 0}, + }; + const int point_pairs[4][2] = { + {0, 1}, + {0, 2}, + {3, 4}, + {5, 6}, + }; + calc_line_list_from_points(point_list, point_pairs, 4, marker_ptr->points); + + marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5); + marker_ptr->color.a = 0.9; + marker_ptr->color.r = 1.0; + marker_ptr->color.g = 0.2; + marker_ptr->color.b = 0.4; + + return marker_ptr; +} + visualization_msgs::msg::Marker::SharedPtr get_velocity_text_marker_ptr( const geometry_msgs::msg::Twist & twist, const geometry_msgs::msg::Point & vis_pos, const std_msgs::msg::ColorRGBA & color_rgba) @@ -164,47 +325,117 @@ visualization_msgs::msg::Marker::SharedPtr get_acceleration_text_marker_ptr( return marker_ptr; } -visualization_msgs::msg::Marker::SharedPtr get_pose_with_covariance_marker_ptr( - const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance) +void calc_arc_line_strip( + const double start_angle, const double end_angle, const double radius, + std::vector & points) +{ + geometry_msgs::msg::Point point; + // arc points + const double maximum_delta_angle = 10.0 * M_PI / 180.0; + const int num_points = + std::max(3, static_cast(std::abs(end_angle - start_angle) / maximum_delta_angle)); + for (int i = 0; i < num_points; ++i) { + const double angle = start_angle + (end_angle - start_angle) * static_cast(i) / + static_cast(num_points - 1); + point.x = radius * std::cos(angle); + point.y = radius * std::sin(angle); + point.z = 0; + points.push_back(point); + } +} + +void calc_covariance_eigen_vectors( + const Eigen::Matrix2d & matrix, double & sigma1, double & sigma2, double & yaw) +{ + Eigen::SelfAdjointEigenSolver solver(matrix); + Eigen::Vector2d eigen_values = solver.eigenvalues(); + // eigen values + sigma1 = std::sqrt(eigen_values.x()); + sigma2 = std::sqrt(eigen_values.y()); + // orientation of covariance ellipse + Eigen::Vector2d e1 = solver.eigenvectors().col(0); + yaw = std::atan2(e1.y(), e1.x()); +} + +visualization_msgs::msg::Marker::SharedPtr get_pose_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, + const double & confidence_interval_coefficient) { auto marker_ptr = std::make_shared(); - marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; + marker_ptr->type = visualization_msgs::msg::Marker::CYLINDER; marker_ptr->ns = std::string("position covariance"); - marker_ptr->scale.x = 0.03; marker_ptr->action = visualization_msgs::msg::Marker::MODIFY; marker_ptr->pose = pose_with_covariance.pose; + + // position covariance + // extract eigen values and eigen vectors + Eigen::Matrix2d eigen_pose_covariance; + eigen_pose_covariance << pose_with_covariance.covariance[0], pose_with_covariance.covariance[1], + pose_with_covariance.covariance[6], pose_with_covariance.covariance[7]; + double yaw, sigma1, sigma2; + calc_covariance_eigen_vectors(eigen_pose_covariance, sigma1, sigma2, yaw); + + // ellipse orientation marker_ptr->pose.orientation.x = 0.0; marker_ptr->pose.orientation.y = 0.0; - marker_ptr->pose.orientation.z = 0.0; - marker_ptr->pose.orientation.w = 1.0; + marker_ptr->pose.orientation.z = std::sin(yaw / 2.0); + marker_ptr->pose.orientation.w = std::cos(yaw / 2.0); + + // ellipse size + marker_ptr->scale.x = sigma1 * confidence_interval_coefficient; + marker_ptr->scale.y = sigma2 * confidence_interval_coefficient; + marker_ptr->scale.z = 0.05; + + // ellipse color density + double area = sigma1 * sigma2; + double alpha = std::min(0.5, 3.0 / area); + alpha = std::max(0.1, alpha); + + // marker configuration + marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5); + marker_ptr->color.a = alpha; + marker_ptr->color.r = 1.0; + marker_ptr->color.g = 1.0; + marker_ptr->color.b = 1.0; + return marker_ptr; +} + +visualization_msgs::msg::Marker::SharedPtr get_yaw_covariance_marker_ptr( + const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, const double & length, + const double & confidence_interval_coefficient, const double & line_width) +{ + auto marker_ptr = std::make_shared(); + marker_ptr->type = visualization_msgs::msg::Marker::LINE_STRIP; + marker_ptr->ns = std::string("yaw covariance"); + marker_ptr->scale.x = line_width; + marker_ptr->action = visualization_msgs::msg::Marker::MODIFY; + marker_ptr->pose = pose_with_covariance.pose; geometry_msgs::msg::Point point; - Eigen::Matrix2d eigen_pose_with_covariance; - eigen_pose_with_covariance << pose_with_covariance.covariance[0], - pose_with_covariance.covariance[1], pose_with_covariance.covariance[6], - pose_with_covariance.covariance[7]; - Eigen::SelfAdjointEigenSolver solver(eigen_pose_with_covariance); - double sigma1 = 2.448 * std::sqrt(solver.eigenvalues().x()); // 2.448 sigma is 95% - double sigma2 = 2.448 * std::sqrt(solver.eigenvalues().y()); // 2.448 sigma is 95% - Eigen::Vector2d e1 = solver.eigenvectors().col(0); - Eigen::Vector2d e2 = solver.eigenvectors().col(1); - point.x = -e1.x() * sigma1; - point.y = -e1.y() * sigma1; - point.z = 0; - marker_ptr->points.push_back(point); - point.x = e1.x() * sigma1; - point.y = e1.y() * sigma1; - point.z = 0; - marker_ptr->points.push_back(point); - point.x = -e2.x() * sigma2; - point.y = -e2.y() * sigma2; + + // orientation covariance + double yaw_vector_length = std::max(length, 1.0); + double yaw_sigma = + std::sqrt(pose_with_covariance.covariance[35]) * confidence_interval_coefficient; + // get arc points + if (yaw_sigma > M_PI) { + yaw_vector_length = 1.0; + } + // first point + point.x = 0; + point.y = 0; point.z = 0; marker_ptr->points.push_back(point); - point.x = e2.x() * sigma2; - point.y = e2.y() * sigma2; + // arc points + calc_arc_line_strip(-yaw_sigma, yaw_sigma, yaw_vector_length, marker_ptr->points); + // last point + point.x = 0; + point.y = 0; point.z = 0; marker_ptr->points.push_back(point); + + // marker configuration marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.5); - marker_ptr->color.a = 0.999; + marker_ptr->color.a = 0.9; marker_ptr->color.r = 1.0; marker_ptr->color.g = 1.0; marker_ptr->color.b = 1.0; diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp index a9074f9e1bc1a..24b21a15732c3 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp @@ -79,10 +79,10 @@ std::vector PredictedObjectsDisplay: object.kinematics.initial_pose_with_covariance.pose.orientation, object.classification, get_line_width(), true); if (shape_marker) { - auto shape_marker_ptr = shape_marker.value(); - shape_marker_ptr->header = msg->header; - shape_marker_ptr->id = uuid_to_marker_id(object.object_id); - markers.push_back(shape_marker_ptr); + auto marker_ptr = shape_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + markers.push_back(marker_ptr); } // Get marker for label @@ -90,10 +90,10 @@ std::vector PredictedObjectsDisplay: object.kinematics.initial_pose_with_covariance.pose.position, object.kinematics.initial_pose_with_covariance.pose.orientation, object.classification); if (label_marker) { - auto label_marker_ptr = label_marker.value(); - label_marker_ptr->header = msg->header; - label_marker_ptr->id = uuid_to_marker_id(object.object_id); - markers.push_back(label_marker_ptr); + auto marker_ptr = label_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + markers.push_back(marker_ptr); } // Get marker for id @@ -111,14 +111,25 @@ std::vector PredictedObjectsDisplay: markers.push_back(id_marker_ptr); } - // Get marker for pose with covariance + // Get marker for pose covariance auto pose_with_covariance_marker = - get_pose_with_covariance_marker_ptr(object.kinematics.initial_pose_with_covariance); + get_pose_covariance_marker_ptr(object.kinematics.initial_pose_with_covariance); if (pose_with_covariance_marker) { - auto pose_with_covariance_marker_ptr = pose_with_covariance_marker.value(); - pose_with_covariance_marker_ptr->header = msg->header; - pose_with_covariance_marker_ptr->id = uuid_to_marker_id(object.object_id); - markers.push_back(pose_with_covariance_marker_ptr); + auto marker_ptr = pose_with_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + markers.push_back(marker_ptr); + } + + // Get marker for yaw covariance + auto yaw_covariance_marker = get_yaw_covariance_marker_ptr( + object.kinematics.initial_pose_with_covariance, object.shape.dimensions.x * 0.65, + get_line_width() * 0.5); + if (yaw_covariance_marker) { + auto marker_ptr = yaw_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + markers.push_back(marker_ptr); } // Get marker for existence probability @@ -181,6 +192,39 @@ std::vector PredictedObjectsDisplay: markers.push_back(twist_marker_ptr); } + // Get marker for twist covariance + auto twist_covariance_marker = get_twist_covariance_marker_ptr( + object.kinematics.initial_pose_with_covariance, + object.kinematics.initial_twist_with_covariance); + if (twist_covariance_marker) { + auto marker_ptr = twist_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + markers.push_back(marker_ptr); + } + + // Get marker for yaw rate + auto yaw_rate_marker = get_yaw_rate_marker_ptr( + object.kinematics.initial_pose_with_covariance, + object.kinematics.initial_twist_with_covariance, get_line_width() * 0.4); + if (yaw_rate_marker) { + auto marker_ptr = yaw_rate_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + add_marker(marker_ptr); + } + + // Get marker for twist covariance + auto yaw_rate_covariance_marker = get_yaw_rate_covariance_marker_ptr( + object.kinematics.initial_pose_with_covariance, + object.kinematics.initial_twist_with_covariance, get_line_width() * 0.3); + if (yaw_rate_covariance_marker) { + auto marker_ptr = yaw_rate_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + markers.push_back(marker_ptr); + } + // Add marker for each candidate path int32_t path_count = 0; for (const auto & predicted_path : object.kinematics.predicted_paths) { diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp index 54dfb9edf889a..504b51f850444 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp @@ -55,11 +55,11 @@ void TrackedObjectsDisplay::processMessage(TrackedObjects::ConstSharedPtr msg) for (const auto & object : msg->objects) { // Filter by object dynamic status if (!is_object_to_show(showing_dynamic_status, object)) continue; - const auto line_width = get_line_width(); // Get marker for shape auto shape_marker = get_shape_marker_ptr( object.shape, object.kinematics.pose_with_covariance.pose.position, - object.kinematics.pose_with_covariance.pose.orientation, object.classification, line_width, + object.kinematics.pose_with_covariance.pose.orientation, object.classification, + get_line_width(), object.kinematics.orientation_availability == autoware_auto_perception_msgs::msg::DetectedObjectKinematics::AVAILABLE); if (shape_marker) { @@ -95,15 +95,27 @@ void TrackedObjectsDisplay::processMessage(TrackedObjects::ConstSharedPtr msg) add_marker(id_marker_ptr); } - // Get marker for pose with covariance + // Get marker for pose covariance auto pose_with_covariance_marker = - get_pose_with_covariance_marker_ptr(object.kinematics.pose_with_covariance); + get_pose_covariance_marker_ptr(object.kinematics.pose_with_covariance); if (pose_with_covariance_marker) { - auto pose_with_covariance_marker_ptr = pose_with_covariance_marker.value(); - pose_with_covariance_marker_ptr->header = msg->header; - pose_with_covariance_marker_ptr->id = uuid_to_marker_id(object.object_id); - add_marker(pose_with_covariance_marker_ptr); + auto marker_ptr = pose_with_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + add_marker(marker_ptr); } + + // Get marker for yaw covariance + auto yaw_covariance_marker = get_yaw_covariance_marker_ptr( + object.kinematics.pose_with_covariance, object.shape.dimensions.x * 0.65, + get_line_width() * 0.5); + if (yaw_covariance_marker) { + auto marker_ptr = yaw_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + add_marker(marker_ptr); + } + // Get marker for existence probability geometry_msgs::msg::Point existence_probability_position; existence_probability_position.x = object.kinematics.pose_with_covariance.pose.position.x + 0.5; @@ -150,13 +162,46 @@ void TrackedObjectsDisplay::processMessage(TrackedObjects::ConstSharedPtr msg) // Get marker for twist auto twist_marker = get_twist_marker_ptr( - object.kinematics.pose_with_covariance, object.kinematics.twist_with_covariance, line_width); + object.kinematics.pose_with_covariance, object.kinematics.twist_with_covariance, + get_line_width()); if (twist_marker) { auto twist_marker_ptr = twist_marker.value(); twist_marker_ptr->header = msg->header; twist_marker_ptr->id = uuid_to_marker_id(object.object_id); add_marker(twist_marker_ptr); } + + // Get marker for twist covariance + auto twist_covariance_marker = get_twist_covariance_marker_ptr( + object.kinematics.pose_with_covariance, object.kinematics.twist_with_covariance); + if (twist_covariance_marker) { + auto marker_ptr = twist_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + add_marker(marker_ptr); + } + + // Get marker for yaw rate + auto yaw_rate_marker = get_yaw_rate_marker_ptr( + object.kinematics.pose_with_covariance, object.kinematics.twist_with_covariance, + get_line_width() * 0.4); + if (yaw_rate_marker) { + auto marker_ptr = yaw_rate_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + add_marker(marker_ptr); + } + + // Get marker for twist covariance + auto yaw_rate_covariance_marker = get_yaw_rate_covariance_marker_ptr( + object.kinematics.pose_with_covariance, object.kinematics.twist_with_covariance, + get_line_width() * 0.5); + if (yaw_rate_covariance_marker) { + auto marker_ptr = yaw_rate_covariance_marker.value(); + marker_ptr->header = msg->header; + marker_ptr->id = uuid_to_marker_id(object.object_id); + add_marker(marker_ptr); + } } } From 4d4b6ae6911f8fb6c699219538e0aa7f64e02ba0 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 16 Jan 2024 11:10:14 +0900 Subject: [PATCH 245/276] feat(static_centerline_optimizer): get behavior_velocity_planner's path interval from yaml (#6071) * feat(static_centerline_optimizer): get behavior_velocity_planner's path interval from yaml Signed-off-by: Takayuki Murooka * fix test Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../launch/static_centerline_optimizer.launch.xml | 5 +++++ planning/static_centerline_optimizer/package.xml | 1 + .../src/static_centerline_optimizer_node.cpp | 7 +++++-- .../test/test_static_centerline_optimizer.test.py | 4 ++++ 4 files changed, 15 insertions(+), 2 deletions(-) diff --git a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml index f8b96ca0db146..37a9abc47bfeb 100644 --- a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml +++ b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml @@ -21,6 +21,10 @@ name="behavior_path_planner_param" default="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml" /> + + diff --git a/planning/static_centerline_optimizer/package.xml b/planning/static_centerline_optimizer/package.xml index 51bd9e87d6ba2..17191868b7418 100644 --- a/planning/static_centerline_optimizer/package.xml +++ b/planning/static_centerline_optimizer/package.xml @@ -19,6 +19,7 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs behavior_path_planner + behavior_velocity_planner geometry_msgs global_parameter_loader interpolation diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index f2d9dc68a8cdc..d98341ecb2e23 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -425,6 +425,10 @@ std::vector StaticCenterlineOptimizerNode::plan_path( const double behavior_path_interval = has_parameter("output_path_interval") ? get_parameter("output_path_interval").as_double() : declare_parameter("output_path_interval"); + const double behavior_vel_interval = + has_parameter("behavior_output_path_interval") + ? get_parameter("behavior_output_path_interval").as_double() + : declare_parameter("behavior_output_path_interval"); // extract path with lane id from lanelets const auto raw_path_with_lane_id = [&]() { @@ -439,8 +443,7 @@ std::vector StaticCenterlineOptimizerNode::plan_path( // convert path with lane id to path const auto raw_path = [&]() { const auto non_resampled_path = convert_to_path(raw_path_with_lane_id); - // NOTE: The behavior_velocity_planner resamples with the interval 1.0 somewhere. - return motion_utils::resamplePath(non_resampled_path, 1.0); + return motion_utils::resamplePath(non_resampled_path, behavior_vel_interval); }(); pub_raw_path_->publish(raw_path); RCLCPP_INFO(get_logger(), "Converted to path and published."); diff --git a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py b/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py index 141743deb007c..36bdfc732ed79 100644 --- a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py +++ b/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py @@ -56,6 +56,10 @@ def generate_test_description(): get_package_share_directory("behavior_path_planner"), "config/behavior_path_planner.param.yaml", ), + os.path.join( + get_package_share_directory("behavior_velocity_planner"), + "config/behavior_velocity_planner.param.yaml", + ), os.path.join( get_package_share_directory("path_smoother"), "config/elastic_band_smoother.param.yaml", From 963fcdf5b3e4708e6a43cf1a6dbdbcea11f6173a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 16 Jan 2024 13:15:48 +0900 Subject: [PATCH 246/276] feat(goal_planner): add scale buffer to calcModuleRequestLength (#6068) * feat(goal_planner): add scale buffer to calcModuleRequestLength Signed-off-by: kosuke55 * style(pre-commit): autofix --------- Signed-off-by: kosuke55 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/goal_planner_module.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index a13efd543d61c..9403ed7529678 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -440,8 +440,14 @@ double GoalPlannerModule::calcModuleRequestLength() const return parameters_->pull_over_minimum_request_length; } - const double minimum_request_length = - *min_stop_distance + parameters_->backward_goal_search_length + approximate_pull_over_distance_; + // The module is requested at a distance such that the ego can stop for the pull over start point + // closest to ego. When path planning, each start point is checked to see if it is possible to + // stop again. At that time, if the speed has changed over time, the path will be rejected if + // min_stop_distance is used as is, so scale is applied to provide a buffer. + constexpr double scale_factor_for_buffer = 1.2; + const double minimum_request_length = *min_stop_distance * scale_factor_for_buffer + + parameters_->backward_goal_search_length + + approximate_pull_over_distance_; return std::max(minimum_request_length, parameters_->pull_over_minimum_request_length); } From d87af6867c78ac13c925b9e16aff4dae40430e0c Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 16 Jan 2024 14:26:04 +0900 Subject: [PATCH 247/276] feat(avoidance): improve object detection area in order not to prevent endless loop (#6084) * perf(avoidance): reduce heavy process Signed-off-by: satoshi-ota * fix(avoidance): filter objects by precise lon distance Signed-off-by: satoshi-ota * refactor(avoidance): remove unused function Signed-off-by: satoshi-ota * feat(avoidance): improve detection area Signed-off-by: satoshi-ota * fix(avoidance): return shift line Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/scene.cpp | 6 +- .../behavior_path_avoidance_module/utils.hpp | 19 +- .../src/scene.cpp | 32 +-- .../src/shift_line_generator.cpp | 8 +- .../src/utils.cpp | 203 +++++++++++------- 5 files changed, 143 insertions(+), 125 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index b76a9e5645b48..6107314bc2824 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -187,7 +187,7 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData( } void AvoidanceByLaneChange::fillAvoidanceTargetObjects( - AvoidancePlanningData & data, DebugData & debug) const + AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const { const auto p = std::dynamic_pointer_cast(avoidance_parameters_); @@ -227,7 +227,9 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects( [&](const auto & object) { return createObjectData(data, object); }); } - utils::avoidance::filterTargetObjects(target_lane_objects, data, debug, planner_data_, p); + utils::avoidance::filterTargetObjects( + target_lane_objects, data, avoidance_parameters_->object_check_max_forward_distance, + planner_data_, p); } ObjectData AvoidanceByLaneChange::createObjectData( diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp index dc602edcc8b86..cbf68ada44abb 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp @@ -77,11 +77,6 @@ std::vector generateObstaclePolygonsForDrivableArea( const ObjectDataArray & objects, const std::shared_ptr & parameters, const double vehicle_width); -double getLongitudinalVelocity(const Pose & p_ref, const Pose & p_target, const double v); - -bool isCentroidWithinLanelets( - const PredictedObject & object, const lanelet::ConstLanelets & target_lanelets); - lanelet::ConstLanelets getAdjacentLane( const std::shared_ptr & planner_data, const std::shared_ptr & parameters, const bool is_right_shift); @@ -128,12 +123,7 @@ void compensateDetectionLost( ObjectDataArray & other_objects); void filterTargetObjects( - ObjectDataArray & objects, AvoidancePlanningData & data, DebugData & debug, - const std::shared_ptr & planner_data, - const std::shared_ptr & parameters); - -double getRoadShoulderDistance( - ObjectData & object, const AvoidancePlanningData & data, + ObjectDataArray & objects, AvoidancePlanningData & data, const double forward_detection_range, const std::shared_ptr & planner_data, const std::shared_ptr & parameters); @@ -157,9 +147,10 @@ std::vector getSafetyCheckTargetObjects( DebugData & debug); std::pair separateObjectsByPath( - const PathWithLaneId & path, const std::shared_ptr & planner_data, - const AvoidancePlanningData & data, const std::shared_ptr & parameters, - const double object_check_forward_distance, const bool is_running, DebugData & debug); + const PathWithLaneId & reference_path, const PathWithLaneId & spline_path, + const std::shared_ptr & planner_data, const AvoidancePlanningData & data, + const std::shared_ptr & parameters, + const double object_check_forward_distance, DebugData & debug); DrivableLanes generateExpandDrivableLanes( const lanelet::ConstLanelet & lanelet, const std::shared_ptr & planner_data, diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index c94243451ed2b..bc1d8c6d75424 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -287,21 +287,18 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat void AvoidanceModule::fillAvoidanceTargetObjects( AvoidancePlanningData & data, DebugData & debug) const { + using utils::avoidance::fillAvoidanceNecessity; using utils::avoidance::fillObjectStoppableJudge; using utils::avoidance::filterTargetObjects; using utils::avoidance::getTargetLanelets; - - // Add margin in order to prevent avoidance request chattering only when the module is running. - const auto is_running = getCurrentStatus() == ModuleStatus::RUNNING || - getCurrentStatus() == ModuleStatus::WAITING_APPROVAL; + using utils::avoidance::separateObjectsByPath; // Separate dynamic objects based on whether they are inside or outside of the expanded lanelets. - const auto sparse_resample_path = utils::resamplePathWithSpline( - helper_->getPreviousSplineShiftPath().path, parameters_->resample_interval_for_output); - const auto [object_within_target_lane, object_outside_target_lane] = - utils::avoidance::separateObjectsByPath( - sparse_resample_path, planner_data_, data, parameters_, helper_->getForwardDetectionRange(), - is_running, debug); + constexpr double MARGIN = 10.0; + const auto forward_detection_range = helper_->getForwardDetectionRange(); + const auto [object_within_target_lane, object_outside_target_lane] = separateObjectsByPath( + helper_->getPreviousReferencePath(), helper_->getPreviousSplineShiftPath().path, planner_data_, + data, parameters_, forward_detection_range + MARGIN, debug); for (const auto & object : object_outside_target_lane.objects) { ObjectData other_object; @@ -316,11 +313,13 @@ void AvoidanceModule::fillAvoidanceTargetObjects( } // Filter out the objects to determine the ones to be avoided. - filterTargetObjects(objects, data, debug, planner_data_, parameters_); + filterTargetObjects(objects, data, forward_detection_range, planner_data_, parameters_); // Calculate the distance needed to safely decelerate the ego vehicle to a stop line. + const auto & vehicle_width = planner_data_->parameters.vehicle_width; const auto feasible_stop_distance = helper_->getFeasibleDecelDistance(0.0, false); std::for_each(data.target_objects.begin(), data.target_objects.end(), [&, this](auto & o) { + fillAvoidanceNecessity(o, registered_objects_, vehicle_width, parameters_); o.to_stop_line = calcDistanceToStopLine(o); fillObjectStoppableJudge(o, registered_objects_, feasible_stop_distance, parameters_); }); @@ -380,21 +379,10 @@ ObjectData AvoidanceModule::createObjectData( utils::avoidance::fillInitialPose(object_data, detected_objects_); // Calc lateral deviation from path to target object. - object_data.to_centerline = - lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance; object_data.direction = calcLateralDeviation(object_closest_pose, object_pose.position) > 0.0 ? Direction::LEFT : Direction::RIGHT; - // Find the footprint point closest to the path, set to object_data.overhang_distance. - object_data.overhang_dist = utils::avoidance::calcEnvelopeOverhangDistance( - object_data, data.reference_path, object_data.overhang_pose.position); - - // Check whether the the ego should avoid the object. - const auto & vehicle_width = planner_data_->parameters.vehicle_width; - utils::avoidance::fillAvoidanceNecessity( - object_data, registered_objects_, vehicle_width, parameters_); - return object_data; } diff --git a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index dabb0d7257555..c20a8a73c955d 100644 --- a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -1101,8 +1101,8 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( const double variable_prepare_distance = std::max(nominal_prepare_distance - last_sl_distance, 0.0); - double prepare_distance_scaled = - std::clamp(nominal_prepare_distance, helper_->getMinimumPrepareDistance(), last_sl_distance); + double prepare_distance_scaled = std::max( + helper_->getMinimumPrepareDistance(), std::max(nominal_prepare_distance, last_sl_distance)); double avoid_distance_scaled = nominal_avoid_distance; if (remaining_distance < prepare_distance_scaled + avoid_distance_scaled) { const auto scale = (remaining_distance - last_sl_distance) / @@ -1122,7 +1122,7 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( al.end_idx = utils::avoidance::findPathIndexFromArclength(arclength_from_ego, prepare_distance_scaled); al.end = data.reference_path.points.at(al.end_idx).point.pose; - al.end_longitudinal = arclength_from_ego.at(al.end_idx); + al.end_longitudinal = prepare_distance_scaled; al.end_shift_length = last_sl.end_shift_length; al.start_shift_length = last_sl.end_shift_length; ret.push_back(al); @@ -1136,7 +1136,7 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( al.start_idx = utils::avoidance::findPathIndexFromArclength(arclength_from_ego, prepare_distance_scaled); al.start = data.reference_path.points.at(al.start_idx).point.pose; - al.start_longitudinal = arclength_from_ego.at(al.start_idx); + al.start_longitudinal = prepare_distance_scaled; al.end_idx = utils::avoidance::findPathIndexFromArclength( arclength_from_ego, prepare_distance_scaled + avoid_distance_scaled); al.end = data.reference_path.points.at(al.end_idx).point.pose; diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index 4c09962840907..c3d5467d680c6 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -175,7 +175,8 @@ geometry_msgs::msg::Polygon createVehiclePolygon( } Polygon2d createOneStepPolygon( - const geometry_msgs::msg::Pose & p_front, const geometry_msgs::msg::Pose & p_back, + const geometry_msgs::msg::Pose & p1, const geometry_msgs::msg::Pose & p2, + const geometry_msgs::msg::Pose & p3, const geometry_msgs::msg::Pose & p4, const geometry_msgs::msg::Polygon & base_polygon) { Polygon2d one_step_polygon{}; @@ -183,7 +184,7 @@ Polygon2d createOneStepPolygon( { geometry_msgs::msg::Polygon out_polygon{}; geometry_msgs::msg::TransformStamped geometry_tf{}; - geometry_tf.transform = pose2transform(p_front); + geometry_tf.transform = pose2transform(p1); tf2::doTransform(base_polygon, out_polygon, geometry_tf); for (const auto & p : out_polygon.points) { @@ -194,7 +195,29 @@ Polygon2d createOneStepPolygon( { geometry_msgs::msg::Polygon out_polygon{}; geometry_msgs::msg::TransformStamped geometry_tf{}; - geometry_tf.transform = pose2transform(p_back); + geometry_tf.transform = pose2transform(p2); + tf2::doTransform(base_polygon, out_polygon, geometry_tf); + + for (const auto & p : out_polygon.points) { + one_step_polygon.outer().push_back(Point2d(p.x, p.y)); + } + } + + { + geometry_msgs::msg::Polygon out_polygon{}; + geometry_msgs::msg::TransformStamped geometry_tf{}; + geometry_tf.transform = pose2transform(p3); + tf2::doTransform(base_polygon, out_polygon, geometry_tf); + + for (const auto & p : out_polygon.points) { + one_step_polygon.outer().push_back(Point2d(p.x, p.y)); + } + } + + { + geometry_msgs::msg::Polygon out_polygon{}; + geometry_msgs::msg::TransformStamped geometry_tf{}; + geometry_tf.transform = pose2transform(p4); tf2::doTransform(base_polygon, out_polygon, geometry_tf); for (const auto & p : out_polygon.points) { @@ -629,7 +652,7 @@ bool isForceAvoidanceTarget( } bool isSatisfiedWithCommonCondition( - ObjectData & object, const AvoidancePlanningData & data, + ObjectData & object, const AvoidancePlanningData & data, const double forward_detection_range, const std::shared_ptr & planner_data, const std::shared_ptr & parameters) { @@ -656,7 +679,7 @@ bool isSatisfiedWithCommonCondition( return false; } - if (object.longitudinal > parameters->object_check_max_forward_distance) { + if (object.longitudinal > forward_detection_range) { object.reason = AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD; return false; } @@ -741,6 +764,9 @@ bool isSatisfiedWithVehicleCondition( } // Object is on center line -> ignore. + const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; + object.to_centerline = + lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance; if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) { object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE; return false; @@ -817,6 +843,64 @@ std::optional getAvoidMargin( // Step3. nominal case. avoid margin is limited by soft constraint. return std::min(soft_lateral_distance_limit, max_avoid_margin); } + +double getRoadShoulderDistance( + ObjectData & object, const AvoidancePlanningData & data, + const std::shared_ptr & planner_data) +{ + using lanelet::utils::to2D; + using tier4_autoware_utils::Point2d; + + const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; + const auto object_closest_index = + findNearestIndex(data.reference_path.points, object_pose.position); + const auto object_closest_pose = data.reference_path.points.at(object_closest_index).point.pose; + + const auto rh = planner_data->route_handler; + if (!rh->getClosestLaneletWithinRoute(object_closest_pose, &object.overhang_lanelet)) { + return 0.0; + } + + const auto centerline_pose = + lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position); + const auto & p1_object = object.overhang_pose.position; + const auto p_tmp = + geometry_msgs::build().position(p1_object).orientation(centerline_pose.orientation); + const auto p2_object = + calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? 100.0 : -100.0), 0.0).position; + + // TODO(Satoshi OTA): check if the basic point is on right or left of bound. + const auto bound = isOnRight(object) ? data.left_bound : data.right_bound; + + std::vector intersects; + for (size_t i = 1; i < bound.size(); i++) { + const auto p1_bound = + geometry_msgs::build().x(bound[i - 1].x()).y(bound[i - 1].y()).z(bound[i - 1].z()); + const auto p2_bound = + geometry_msgs::build().x(bound[i].x()).y(bound[i].y()).z(bound[i].z()); + + const auto opt_intersect = + tier4_autoware_utils::intersect(p1_object, p2_object, p1_bound, p2_bound); + + if (!opt_intersect) { + continue; + } + + intersects.push_back(opt_intersect.value()); + } + + if (intersects.empty()) { + return 0.0; + } + + std::sort(intersects.begin(), intersects.end(), [&p1_object](const auto & a, const auto & b) { + return calcDistance2d(p1_object, a) < calcDistance2d(p1_object, b); + }); + + object.nearest_bound_point = intersects.front(); + + return calcDistance2d(p1_object, object.nearest_bound_point.value()); +} } // namespace filtering_utils bool isOnRight(const ObjectData & obj) @@ -1113,11 +1197,6 @@ std::vector generateObstaclePolygonsForDrivableArea( return obstacles_for_drivable_area; } -double getLongitudinalVelocity(const Pose & p_ref, const Pose & p_target, const double v) -{ - return v * std::cos(calcYawDeviation(p_ref, p_target)); -} - lanelet::ConstLanelets getTargetLanelets( const std::shared_ptr & planner_data, lanelet::ConstLanelets & route_lanelets, const double left_offset, const double right_offset) @@ -1517,67 +1596,8 @@ void compensateDetectionLost( } } -double getRoadShoulderDistance( - ObjectData & object, const AvoidancePlanningData & data, - const std::shared_ptr & planner_data, - [[maybe_unused]] const std::shared_ptr & parameters) -{ - using lanelet::utils::to2D; - using tier4_autoware_utils::Point2d; - - const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; - const auto object_closest_index = - findNearestIndex(data.reference_path.points, object_pose.position); - const auto object_closest_pose = data.reference_path.points.at(object_closest_index).point.pose; - - const auto rh = planner_data->route_handler; - if (!rh->getClosestLaneletWithinRoute(object_closest_pose, &object.overhang_lanelet)) { - return 0.0; - } - - const auto centerline_pose = - lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position); - const auto & p1_object = object.overhang_pose.position; - const auto p_tmp = - geometry_msgs::build().position(p1_object).orientation(centerline_pose.orientation); - const auto p2_object = - calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? 100.0 : -100.0), 0.0).position; - - // TODO(Satoshi OTA): check if the basic point is on right or left of bound. - const auto bound = isOnRight(object) ? data.left_bound : data.right_bound; - - std::vector intersects; - for (size_t i = 1; i < bound.size(); i++) { - const auto p1_bound = - geometry_msgs::build().x(bound[i - 1].x()).y(bound[i - 1].y()).z(bound[i - 1].z()); - const auto p2_bound = - geometry_msgs::build().x(bound[i].x()).y(bound[i].y()).z(bound[i].z()); - - const auto opt_intersect = - tier4_autoware_utils::intersect(p1_object, p2_object, p1_bound, p2_bound); - - if (!opt_intersect) { - continue; - } - - intersects.push_back(opt_intersect.value()); - } - - if (intersects.empty()) { - return 0.0; - } - - std::sort(intersects.begin(), intersects.end(), [&p1_object](const auto & a, const auto & b) { - return calcDistance2d(p1_object, a) < calcDistance2d(p1_object, b); - }); - - object.nearest_bound_point = intersects.front(); - - return calcDistance2d(p1_object, object.nearest_bound_point.value()); -} - void filterTargetObjects( - ObjectDataArray & objects, AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug, + ObjectDataArray & objects, AvoidancePlanningData & data, const double forward_detection_range, const std::shared_ptr & planner_data, const std::shared_ptr & parameters) { @@ -1592,12 +1612,16 @@ void filterTargetObjects( }; for (auto & o : objects) { - if (!filtering_utils::isSatisfiedWithCommonCondition(o, data, planner_data, parameters)) { + if (!filtering_utils::isSatisfiedWithCommonCondition( + o, data, forward_detection_range, planner_data, parameters)) { data.other_objects.push_back(o); continue; } - o.to_road_shoulder_distance = getRoadShoulderDistance(o, data, planner_data, parameters); + // Find the footprint point closest to the path, set to object_data.overhang_distance. + o.overhang_dist = + calcEnvelopeOverhangDistance(o, data.reference_path, o.overhang_pose.position); + o.to_road_shoulder_distance = filtering_utils::getRoadShoulderDistance(o, data, planner_data); o.avoid_margin = filtering_utils::getAvoidMargin(o, planner_data, parameters); if (filtering_utils::isNoNeedAvoidanceBehavior(o, parameters)) { @@ -1877,9 +1901,10 @@ std::vector getSafetyCheckTargetObjects( } std::pair separateObjectsByPath( - const PathWithLaneId & path, const std::shared_ptr & planner_data, - const AvoidancePlanningData & data, const std::shared_ptr & parameters, - const double object_check_forward_distance, const bool is_running, DebugData & debug) + const PathWithLaneId & reference_path, const PathWithLaneId & spline_path, + const std::shared_ptr & planner_data, const AvoidancePlanningData & data, + const std::shared_ptr & parameters, + const double object_check_forward_distance, DebugData & debug) { PredictedObjects target_objects; PredictedObjects other_objects; @@ -1892,22 +1917,34 @@ std::pair separateObjectsByPath( max_offset = std::max(max_offset, offset); } - const double MARGIN = is_running ? 1.0 : 0.0; // [m] const auto detection_area = - createVehiclePolygon(planner_data->parameters.vehicle_info, max_offset + MARGIN); - const auto ego_idx = planner_data->findEgoIndex(path.points); + createVehiclePolygon(planner_data->parameters.vehicle_info, max_offset); + const auto ego_idx = planner_data->findEgoIndex(reference_path.points); + const auto arc_length_array = + utils::calcPathArcLengthArray(reference_path, 0L, reference_path.points.size(), 1e-3); + double next_longitudinal_distance = 0.0; std::vector detection_areas; - for (size_t i = 0; i < path.points.size() - 1; ++i) { - const auto & p_ego_front = path.points.at(i).point.pose; - const auto & p_ego_back = path.points.at(i + 1).point.pose; + for (size_t i = 0; i < reference_path.points.size() - 1; ++i) { + const auto & p_reference_ego_front = reference_path.points.at(i).point.pose; + const auto & p_reference_ego_back = reference_path.points.at(i + 1).point.pose; + const auto & p_spline_ego_front = spline_path.points.at(i).point.pose; + const auto & p_spline_ego_back = spline_path.points.at(i + 1).point.pose; - const auto distance_from_ego = calcSignedArcLength(path.points, ego_idx, i); + const auto distance_from_ego = calcSignedArcLength(reference_path.points, ego_idx, i); if (distance_from_ego > object_check_forward_distance) { break; } - detection_areas.push_back(createOneStepPolygon(p_ego_front, p_ego_back, detection_area)); + if (arc_length_array.at(i) < next_longitudinal_distance) { + continue; + } + + detection_areas.push_back(createOneStepPolygon( + p_reference_ego_front, p_reference_ego_back, p_spline_ego_front, p_spline_ego_back, + detection_area)); + + next_longitudinal_distance += parameters->resample_interval_for_output; } std::for_each(detection_areas.begin(), detection_areas.end(), [&](const auto & detection_area) { From 6975bd86884d7b0ac4da2befe511f65861612189 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Tue, 16 Jan 2024 14:58:23 +0900 Subject: [PATCH 248/276] feat(ndt_scan_matcher): change coordinate of output_pose_covariance (#6065) * feat(ndt_scan_matcher): change coordinate of output_pose_covariance Signed-off-by: yamato-ando * style(pre-commit): autofix * Update localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp Co-authored-by: Kento Yabuuchi * 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> Co-authored-by: Kento Yabuuchi --- .../ndt_scan_matcher_core.hpp | 2 ++ .../src/ndt_scan_matcher_core.cpp | 32 ++++++++++++++++++- 2 files changed, 33 insertions(+), 1 deletion(-) 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 e9aa265c78f34..71895c59ec37d 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 @@ -127,6 +127,8 @@ class NDTScanMatcher : public rclcpp::Node const double & transform_probability, const double & nearest_voxel_transformation_likelihood); static int count_oscillation(const std::vector & result_pose_msg_array); + std::array rotate_covariance( + const std::array & src_covariance, const Eigen::Matrix3d & rotation) const; std::array estimate_covariance( const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, const rclcpp::Time & sensor_ros_time); 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 0f6fdbc15db26..942df03410165 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -486,7 +486,15 @@ void NDTScanMatcher::callback_sensor_points( } // covariance estimation - std::array ndt_covariance = output_pose_covariance_; + const Eigen::Quaterniond map_to_base_link_quat = Eigen::Quaterniond( + result_pose_msg.orientation.w, result_pose_msg.orientation.x, result_pose_msg.orientation.y, + result_pose_msg.orientation.z); + const Eigen::Matrix3d map_to_base_link_rotation = + map_to_base_link_quat.normalized().toRotationMatrix(); + + std::array ndt_covariance = + rotate_covariance(output_pose_covariance_, map_to_base_link_rotation); + if (is_converged && use_cov_estimation_) { const auto estimated_covariance = estimate_covariance(ndt_result, initial_pose_matrix, sensor_ros_time); @@ -766,6 +774,28 @@ int NDTScanMatcher::count_oscillation( return max_oscillation_cnt; } +std::array NDTScanMatcher::rotate_covariance( + const std::array & src_covariance, const Eigen::Matrix3d & rotation) const +{ + std::array ret_covariance = src_covariance; + + Eigen::Matrix3d src_cov; + src_cov << src_covariance[0], src_covariance[1], src_covariance[2], src_covariance[6], + src_covariance[7], src_covariance[8], src_covariance[12], src_covariance[13], + src_covariance[14]; + + Eigen::Matrix3d ret_cov; + ret_cov = rotation * src_cov * rotation.transpose(); + + for (Eigen::Index i = 0; i < 3; ++i) { + ret_covariance[i] = ret_cov(0, i); + ret_covariance[i + 6] = ret_cov(1, i); + ret_covariance[i + 12] = ret_cov(2, i); + } + + return ret_covariance; +} + std::array NDTScanMatcher::estimate_covariance( const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, const rclcpp::Time & sensor_ros_time) From cad877fa3ead0b3d84d15346ce8fc30eaf6f328e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 16 Jan 2024 23:32:19 +0900 Subject: [PATCH 249/276] feat(avoidance/goal_planner): execute avoidance and pull over simultaneously (#5979) * feat(avoidance/goal_planner): execute avoidance and pull over simultaneously Signed-off-by: kosuke55 Signed-off-by: kosuke55 * use utils Signed-off-by: kosuke55 * fix overlapped Signed-off-by: kosuke55 * reafactor(behavior_path_planner): move isAllowedGoalModification to common Signed-off-by: kosuke55 * fix readme Signed-off-by: kosuke55 * add goal modification condtion to avoidance Signed-off-by: kosuke55 * clean up * revert param Signed-off-by: kosuke55 * fix param Signed-off-by: kosuke55 * move dead line process Signed-off-by: kosuke55 * fix condition Signed-off-by: kosuke55 * fix crop Signed-off-by: kosuke55 * fix crop * fix typos Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../behavior_path_avoidance_module/README.md | 3 +- .../config/avoidance.param.yaml | 3 +- .../data_structs.hpp | 12 +- .../parameter_helper.hpp | 2 + .../src/shift_line_generator.cpp | 97 +++++++++-- .../src/utils.cpp | 20 ++- .../goal_planner_module.hpp | 4 + .../pull_over_planner_base.hpp | 7 + .../shift_pull_over.hpp | 2 + .../util.hpp | 17 +- .../src/goal_planner_module.cpp | 151 ++++++++++++------ .../src/manager.cpp | 6 +- .../src/shift_pull_over.cpp | 84 ++++++++-- .../src/util.cpp | 134 ++++++++++++++-- .../utils/utils.hpp | 7 + .../src/utils/utils.cpp | 82 ++++++++++ 16 files changed, 531 insertions(+), 100 deletions(-) diff --git a/planning/behavior_path_avoidance_module/README.md b/planning/behavior_path_avoidance_module/README.md index 20c0985f0f333..122ad7adcce9e 100644 --- a/planning/behavior_path_avoidance_module/README.md +++ b/planning/behavior_path_avoidance_module/README.md @@ -833,7 +833,8 @@ namespace: `avoidance.target_filtering.` | object_ignore_section_crosswalk_behind_distance | [m] | double | If the back distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | | object_check_forward_distance | [m] | double | Forward distance to search the avoidance target. | 150.0 | | object_check_backward_distance | [m] | double | Backward distance to search the avoidance target. | 2.0 | -| object_check_goal_distance | [m] | double | Backward distance to search the avoidance target. | 20.0 | +| object_check_goal_distance | [m] | double | If the distance between object and goal position is less than this parameter, the module do not return center line. | 20.0 | +| object_check_return_pose_distance | [m] | double | If the distance between object and return position is less than this parameter, the module do not return center line. | 20.0 | | object_check_shiftable_ratio | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.6 | | object_check_min_road_shoulder_width | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder target. | 0.5 | | object_last_seen_threshold | [s] | double | For the compensation of the detection lost. The object is registered once it is observed as an avoidance target. When the detection loses, the timer will start and the object will be un-registered when the time exceeds this limit. | 2.0 | diff --git a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml index 2d38cebd591f5..b300de2236fcf 100644 --- a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml +++ b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml @@ -122,7 +122,8 @@ motorcycle: true # [-] pedestrian: true # [-] # detection range - object_check_goal_distance: 20.0 # [m] + object_check_goal_distance: 20.0 # [m] + object_check_return_pose_distance: 20.0 # [m] # filtering parking objects threshold_distance_object_is_on_center: 1.0 # [m] object_check_shiftable_ratio: 0.6 # [-] diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index 86e1608501831..9b5ae3cb4db9e 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -164,10 +164,14 @@ struct AvoidanceParameters double object_check_backward_distance{0.0}; double object_check_yaw_deviation{0.0}; - // if the distance between object and goal position is less than this parameter, the module ignore - // the object. + // if the distance between object and goal position is less than this parameter, the module do not + // return center line. double object_check_goal_distance{0.0}; + // if the distance between object and return position is less than this parameter, the module do + // not return center line. + double object_check_return_pose_distance{0.0}; + // use in judge whether the vehicle is parking object on road shoulder double object_check_shiftable_ratio{0.0}; @@ -462,14 +466,14 @@ using AvoidLineArray = std::vector; struct AvoidOutline { - AvoidOutline(AvoidLine avoid_line, AvoidLine return_line) + AvoidOutline(AvoidLine avoid_line, const std::optional return_line) : avoid_line{std::move(avoid_line)}, return_line{std::move(return_line)} { } AvoidLine avoid_line{}; - AvoidLine return_line{}; + std::optional return_line{}; AvoidLineArray middle_lines{}; }; diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index b9af50ce76eb5..9f2fdf7ab96d9 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -122,6 +122,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.object_check_goal_distance = getOrDeclareParameter(*node, ns + "object_check_goal_distance"); + p.object_check_return_pose_distance = + getOrDeclareParameter(*node, ns + "object_check_return_pose_distance"); p.threshold_distance_object_is_on_center = getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); p.object_check_shiftable_ratio = diff --git a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index c20a8a73c955d..6196b3e209d11 100644 --- a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -81,7 +81,9 @@ AvoidLineArray toArray(const AvoidOutlines & outlines) AvoidLineArray ret{}; for (const auto & outline : outlines) { ret.push_back(outline.avoid_line); - ret.push_back(outline.return_line); + if (outline.return_line.has_value()) { + ret.push_back(outline.return_line.value()); + } std::for_each( outline.middle_lines.begin(), outline.middle_lines.end(), @@ -341,7 +343,30 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( al_return.object_on_right = utils::avoidance::isOnRight(o); } - if (is_valid_shift_line(al_avoid) && is_valid_shift_line(al_return)) { + const bool skip_return_shift = [&]() { + if (!utils::isAllowedGoalModification(data_->route_handler)) { + return false; + } + const auto goal_pose = data_->route_handler->getGoalPose(); + const double goal_longitudinal_distance = + motion_utils::calcSignedArcLength(data.reference_path.points, 0, goal_pose.position); + const bool is_return_shift_to_goal = + std::abs(al_return.end_longitudinal - goal_longitudinal_distance) < + parameters_->object_check_return_pose_distance; + if (is_return_shift_to_goal) { + return true; + } + const auto & object_pos = o.object.kinematics.initial_pose_with_covariance.pose.position; + const bool has_object_near_goal = + tier4_autoware_utils::calcDistance2d(goal_pose.position, object_pos) < + parameters_->object_check_goal_distance; + return has_object_near_goal; + }(); + + if (skip_return_shift) { + // if the object is close to goal or ego is about to return near GOAL, do not return + 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 { o.reason = "InvalidShiftLine"; @@ -637,35 +662,43 @@ AvoidOutlines ShiftLineGenerator::applyMergeProcess( auto & next_outline = outlines.at(i); const auto & return_line = last_outline.return_line; - const auto & avoid_line = next_outline.avoid_line; + if (!return_line.has_value()) { + ret.push_back(outlines.at(i)); + break; + } - if (no_conflict(return_line, avoid_line)) { + const auto & avoid_line = next_outline.avoid_line; + if (no_conflict(return_line.value(), avoid_line)) { ret.push_back(outlines.at(i)); continue; } - const auto merged_shift_line = merge(return_line, avoid_line, generateUUID()); + const auto merged_shift_line = merge(return_line.value(), avoid_line, generateUUID()); if (!helper_->isComfortable(AvoidLineArray{merged_shift_line})) { ret.push_back(outlines.at(i)); continue; } - if (same_side_shift(return_line, avoid_line)) { + if (same_side_shift(return_line.value(), avoid_line)) { last_outline.middle_lines.push_back(merged_shift_line); last_outline.return_line = next_outline.return_line; debug.step1_merged_shift_line.push_back(merged_shift_line); continue; } - if (within(return_line, avoid_line.end_idx) && within(avoid_line, return_line.start_idx)) { + if ( + within(return_line.value(), avoid_line.end_idx) && + within(avoid_line, return_line->start_idx)) { last_outline.middle_lines.push_back(merged_shift_line); last_outline.return_line = next_outline.return_line; debug.step1_merged_shift_line.push_back(merged_shift_line); continue; } - if (within(return_line, avoid_line.start_idx) && within(avoid_line, return_line.end_idx)) { + if ( + within(return_line.value(), avoid_line.start_idx) && + within(avoid_line, return_line->end_idx)) { last_outline.middle_lines.push_back(merged_shift_line); last_outline.return_line = next_outline.return_line; debug.step1_merged_shift_line.push_back(merged_shift_line); @@ -686,7 +719,10 @@ AvoidOutlines ShiftLineGenerator::applyFillGapProcess( for (auto & outline : ret) { if (outline.middle_lines.empty()) { - const auto new_line = fill(outline.avoid_line, outline.return_line, generateUUID()); + const auto new_line = + outline.return_line.has_value() + ? fill(outline.avoid_line, outline.return_line.value(), generateUUID()) + : outline.avoid_line; outline.middle_lines.push_back(new_line); debug.step1_filled_shift_line.push_back(new_line); } @@ -701,8 +737,11 @@ AvoidOutlines ShiftLineGenerator::applyFillGapProcess( helper_->alignShiftLinesOrder(outline.middle_lines, false); - if (outline.middle_lines.back().end_longitudinal < outline.return_line.start_longitudinal) { - const auto new_line = fill(outline.middle_lines.back(), outline.return_line, generateUUID()); + if ( + outline.return_line.has_value() && + outline.middle_lines.back().end_longitudinal < outline.return_line->start_longitudinal) { + const auto new_line = + fill(outline.middle_lines.back(), outline.return_line.value(), generateUUID()); outline.middle_lines.push_back(new_line); debug.step1_filled_shift_line.push_back(new_line); } @@ -973,6 +1012,20 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( const bool has_candidate_point = !ret.empty(); const bool has_registered_point = last_.has_value(); + if (utils::isAllowedGoalModification(data_->route_handler)) { + const auto has_object_near_goal = + std::any_of(data.target_objects.begin(), data.target_objects.end(), [&](const auto & o) { + return tier4_autoware_utils::calcDistance2d( + data_->route_handler->getGoalPose().position, + o.object.kinematics.initial_pose_with_covariance.pose.position) < + parameters_->object_check_goal_distance; + }); + if (has_object_near_goal) { + RCLCPP_DEBUG(rclcpp::get_logger(""), "object near goal exists so skip adding return shift"); + return ret; + } + } + const auto exist_unavoidable_object = std::any_of( data.target_objects.begin(), data.target_objects.end(), [](const auto & o) { return !o.is_avoidable && o.longitudinal > 0.0; }); @@ -1027,6 +1080,21 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( } } + // if last shift line is near the objects, do not add return shift. + if (utils::isAllowedGoalModification(data_->route_handler)) { + const bool has_last_shift_near_goal = + std::any_of(data.target_objects.begin(), data.target_objects.end(), [&](const auto & o) { + return tier4_autoware_utils::calcDistance2d( + last_sl.end.position, + o.object.kinematics.initial_pose_with_covariance.pose.position) < + parameters_->object_check_goal_distance; + }); + if (has_last_shift_near_goal) { + RCLCPP_DEBUG(rclcpp::get_logger(""), "last shift line is near the objects"); + return ret; + } + } + // There already is a shift point candidates to go back to center line, but it could be too sharp // due to detection noise or timing. // Here the return-shift from ego is added for the in case. @@ -1070,8 +1138,11 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( return ret; } - const auto remaining_distance = std::min( - arclength_from_ego.back() - parameters_->dead_line_buffer_for_goal, data.to_return_point); + const auto remaining_distance = + utils::isAllowedGoalModification(data_->route_handler) + ? data.to_return_point + : std::min( + arclength_from_ego.back() - parameters_->dead_line_buffer_for_goal, data.to_return_point); // If the avoidance point has already been set, the return shift must be set after the point. const auto last_sl_distance = data.arclength_from_ego.at(last_sl.end_idx); diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index c3d5467d680c6..80aeb2bf0dccf 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -700,11 +700,13 @@ bool isSatisfiedWithCommonCondition( return false; } - if ( - object.longitudinal + object.length / 2 + parameters->object_check_goal_distance > - to_goal_distance) { - object.reason = "TooNearToGoal"; - return false; + if (!utils::isAllowedGoalModification(planner_data->route_handler)) { + if ( + object.longitudinal + object.length / 2 + parameters->object_check_goal_distance > + to_goal_distance) { + object.reason = "TooNearToGoal"; + return false; + } } return true; @@ -1686,7 +1688,9 @@ void fillAdditionalInfoFromLongitudinal( { for (auto & outline : outlines) { fillAdditionalInfoFromLongitudinal(data, outline.avoid_line); - fillAdditionalInfoFromLongitudinal(data, outline.return_line); + if (outline.return_line.has_value()) { + fillAdditionalInfoFromLongitudinal(data, outline.return_line.value()); + } std::for_each(outline.middle_lines.begin(), outline.middle_lines.end(), [&](auto & line) { fillAdditionalInfoFromLongitudinal(data, line); @@ -2169,7 +2173,9 @@ double calcDistanceToReturnDeadLine( } // dead line for goal - if (parameters->enable_dead_line_for_goal) { + if ( + !utils::isAllowedGoalModification(planner_data->route_handler) && + parameters->enable_dead_line_for_goal) { if (planner_data->route_handler->isInGoalRouteSection(lanelets.back())) { const auto & ego_pos = planner_data->self_odometry->pose.pose.position; const auto to_goal_distance = diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index e90162c958be5..9fb9c17f1ca70 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -472,6 +472,10 @@ class GoalPlannerModule : public SceneModuleInterface // new turn signal TurnSignalInfo calcTurnSignalInfo() const; + std::optional last_previous_module_output_{}; + bool hasPreviousModulePathShapeChanged() const; + bool hasDeviatedFromLastPreviousModulePath() const; + // timer for generating pull over path candidates in a separate thread void onTimer(); void onFreespaceParkingTimer(); diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp index fe24d66ddc850..9700c44445a65 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp @@ -118,6 +118,11 @@ class PullOverPlannerBase } 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; @@ -131,6 +136,8 @@ class PullOverPlannerBase vehicle_info_util::VehicleInfo vehicle_info_; LinearRing2d vehicle_footprint_; GoalPlannerParameters parameters_; + + BehaviorModuleOutput previous_module_output_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp index bd19dc2e87de0..892ef7d5dd303 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp @@ -43,6 +43,8 @@ class ShiftPullOver : public PullOverPlannerBase protected: PathWithLaneId generateReferencePath( 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; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp index a7aec66f64363..294a5125a0d13 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp @@ -49,8 +49,21 @@ PredictedObjects filterObjectsByLateralDistance( const Pose & ego_pose, const double vehicle_width, const PredictedObjects & objects, const double distance_thresh, const bool filter_inside); -bool isAllowedGoalModification(const std::shared_ptr & route_handler); -bool checkOriginalGoalIsInShoulder(const std::shared_ptr & route_handler); +double calcLateralDeviationBetweenPaths( + const PathWithLaneId & reference_path, const PathWithLaneId & target_path); +bool isReferencePath( + const PathWithLaneId & reference_path, const PathWithLaneId & target_path, + const double lateral_deviation_thresh); + +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); +PathWithLaneId extendPath( + const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path, + const double extend_length); +PathWithLaneId extendPath( + const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path, + const Pose & extend_pose); // debug MarkerArray createPullOverAreaMarkerArray( diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 9403ed7529678..3f765c99cffa9 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -136,11 +136,34 @@ void GoalPlannerModule::updateOccupancyGrid() occupancy_grid_map_->setMap(*(planner_data_->occupancy_grid)); } +bool GoalPlannerModule::hasPreviousModulePathShapeChanged() const +{ + if (!last_previous_module_output_) { + return true; + } + + const auto current_path = getPreviousModuleOutput().path; + + // the terminal distance is far + return calcDistance2d( + last_previous_module_output_->path.points.back().point, + current_path.points.back().point) > 0.3; +} + +bool GoalPlannerModule::hasDeviatedFromLastPreviousModulePath() const +{ + if (!last_previous_module_output_) { + return true; + } + return std::abs(motion_utils::calcLateralOffset( + last_previous_module_output_->path.points, + planner_data_->self_odometry->pose.pose.position)) > 0.3; +} + // generate pull over candidate paths void GoalPlannerModule::onTimer() { - // already generated pull over candidate paths - if (!thread_safe_data_.get_pull_over_path_candidates().empty()) { + if (getCurrentStatus() == ModuleStatus::IDLE) { return; } @@ -149,16 +172,30 @@ void GoalPlannerModule::onTimer() return; } - if ( - !planner_data_ || - !goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (!planner_data_ || !utils::isAllowedGoalModification(planner_data_->route_handler)) { return; } - if (getCurrentStatus() == ModuleStatus::IDLE) { + // check if new pull over path candidates are needed to be generated + const bool need_update = std::invoke([&]() { + if (thread_safe_data_.get_pull_over_path_candidates().empty()) { + return true; + } + if (hasPreviousModulePathShapeChanged()) { + RCLCPP_ERROR(getLogger(), "has previous module path shape changed"); + return true; + } + if (hasDeviatedFromLastPreviousModulePath() && !hasDecidedPath()) { + RCLCPP_ERROR(getLogger(), "has deviated from last previous module path"); + return true; + } + return false; + }); + if (!need_update) { return; } + const auto previous_module_output = getPreviousModuleOutput(); const auto goal_candidates = thread_safe_data_.get_goal_candidates(); // generate valid pull over path candidates and calculate closest start pose @@ -173,8 +210,9 @@ void GoalPlannerModule::onTimer() const std::shared_ptr & planner, const GoalCandidate & goal_candidate) { planner->setPlannerData(planner_data_); + planner->setPreviousModuleOutput(previous_module_output); auto pull_over_path = planner->plan(goal_candidate.goal_pose); - if (pull_over_path && isCrossingPossible(*pull_over_path)) { + if (pull_over_path) { pull_over_path->goal_id = goal_candidate.id; pull_over_path->id = path_candidates.size(); path_candidates.push_back(*pull_over_path); @@ -188,9 +226,21 @@ void GoalPlannerModule::onTimer() } } }; + + // todo: currently non centerline input path is supported only by shift pull over + const bool is_center_line_input_path = goal_planner_utils::isReferencePath( + previous_module_output.reference_path, previous_module_output.path, 0.1); + RCLCPP_DEBUG( + getLogger(), "the input path of pull over planner is center line: %d", + is_center_line_input_path); + // plan candidate paths and set them to the member variable if (parameters_->path_priority == "efficient_path") { for (const auto & planner : pull_over_planners_) { + // todo: temporary skip NON SHIFT planner when input path is not center line + if (!is_center_line_input_path && planner->getPlannerType() != PullOverPlannerType::SHIFT) { + continue; + } for (const auto & goal_candidate : goal_candidates) { planCandidatePaths(planner, goal_candidate); } @@ -198,6 +248,10 @@ void GoalPlannerModule::onTimer() } else if (parameters_->path_priority == "close_goal") { for (const auto & goal_candidate : goal_candidates) { for (const auto & planner : pull_over_planners_) { + // todo: temporary skip NON SHIFT planner when input path is not center line + if (!is_center_line_input_path && planner->getPlannerType() != PullOverPlannerType::SHIFT) { + continue; + } planCandidatePaths(planner, goal_candidate); } } @@ -213,7 +267,10 @@ void GoalPlannerModule::onTimer() const std::lock_guard lock(mutex_); thread_safe_data_.set_pull_over_path_candidates(path_candidates); thread_safe_data_.set_closest_start_pose(closest_start_pose); + RCLCPP_INFO(getLogger(), "generated %lu pull over path candidates", path_candidates.size()); } + + last_previous_module_output_ = previous_module_output; } void GoalPlannerModule::onFreespaceParkingTimer() @@ -225,7 +282,7 @@ void GoalPlannerModule::onFreespaceParkingTimer() return; } // fixed goal planner do not use freespace planner - if (!goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (!utils::isAllowedGoalModification(planner_data_->route_handler)) { return; } @@ -354,7 +411,9 @@ bool GoalPlannerModule::isExecutionRequested() const // check if goal_pose is in current_lanes. lanelet::ConstLanelet current_lane{}; - const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_); + // const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_); + 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) { @@ -384,14 +443,14 @@ bool GoalPlannerModule::isExecutionRequested() const // if goal modification is not allowed // 1) goal_pose is in current_lanes, plan path to the original fixed goal // 2) goal_pose is NOT in current_lanes, do not execute goal_planner - if (!goal_planner_utils::isAllowedGoalModification(route_handler)) { + if (!utils::isAllowedGoalModification(route_handler)) { return goal_is_in_current_lanes; } // if goal arc coordinates can be calculated, check if goal is in request_length const double self_to_goal_arc_length = utils::getSignedDistance(current_pose, goal_pose, current_lanes); - const double request_length = goal_planner_utils::isAllowedGoalModification(route_handler) + const double request_length = utils::isAllowedGoalModification(route_handler) ? calcModuleRequestLength() : parameters_->pull_over_minimum_request_length; if (self_to_goal_arc_length < 0.0 || self_to_goal_arc_length > request_length) { @@ -402,7 +461,7 @@ bool GoalPlannerModule::isExecutionRequested() const // if goal modification is not allowed // 1) goal_pose is in current_lanes, plan path to the original fixed goal // 2) goal_pose is NOT in current_lanes, do not execute goal_planner - if (!goal_planner_utils::isAllowedGoalModification(route_handler)) { + if (!utils::isAllowedGoalModification(route_handler)) { return goal_is_in_current_lanes; } @@ -591,7 +650,7 @@ GoalCandidates GoalPlannerModule::generateGoalCandidates() const { // calculate goal candidates const auto & route_handler = planner_data_->route_handler; - if (goal_planner_utils::isAllowedGoalModification(route_handler)) { + if (utils::isAllowedGoalModification(route_handler)) { return goal_searcher_->search(); } @@ -609,7 +668,7 @@ GoalCandidates GoalPlannerModule::generateGoalCandidates() const BehaviorModuleOutput GoalPlannerModule::plan() { - if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (utils::isAllowedGoalModification(planner_data_->route_handler)) { return planPullOver(); } @@ -1100,7 +1159,7 @@ void GoalPlannerModule::updatePreviousData(const BehaviorModuleOutput & output) BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() { - if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (utils::isAllowedGoalModification(planner_data_->route_handler)) { return planPullOverAsCandidate(); } @@ -1159,11 +1218,15 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const return PathWithLaneId{}; } - // generate reference path - const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; - const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); - const double s_end = s_current + common_parameters.forward_path_length; - auto reference_path = route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); + // extend previous module path to generate reference path for stop path + const auto reference_path = std::invoke([&]() -> PathWithLaneId { + const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; + const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); + const double s_end = s_current + common_parameters.forward_path_length; + return route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); + }); + const auto extended_prev_path = goal_planner_utils::extendPath( + getPreviousModuleOutput().path, reference_path, common_parameters.forward_path_length); // 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 @@ -1171,7 +1234,7 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const const auto closest_goal_candidate = goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()); const auto decel_pose = calcLongitudinalOffsetPose( - reference_path.points, closest_goal_candidate.goal_pose.position, + extended_prev_path.points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); // if not approved stop road lane. @@ -1199,7 +1262,7 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const } // if stop pose is closer than min_stop_distance, stop as soon as possible - const double ego_to_stop_distance = calcSignedArcLengthFromEgo(reference_path, *stop_pose); + const double ego_to_stop_distance = calcSignedArcLengthFromEgo(extended_prev_path, *stop_pose); const auto min_stop_distance = calcFeasibleDecelDistance( planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, 0.0); const double eps_vel = 0.01; @@ -1210,55 +1273,43 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const } // slow down for turn signal, insert stop point to stop_pose - decelerateForTurnSignal(*stop_pose, reference_path); + auto stop_path = extended_prev_path; + decelerateForTurnSignal(*stop_pose, stop_path); stop_pose_ = *stop_pose; // for debug wall marker // slow down before the search area. if (decel_pose) { - decelerateBeforeSearchStart(*decel_pose, reference_path); - return reference_path; + decelerateBeforeSearchStart(*decel_pose, stop_path); + return stop_path; } - // if already passed the decel pose, set pull_over_velocity to reference_path. + // if already passed the decel pose, set pull_over_velocity to stop_path. const auto min_decel_distance = calcFeasibleDecelDistance( planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, pull_over_velocity); - for (auto & p : reference_path.points) { - const double distance_from_ego = calcSignedArcLengthFromEgo(reference_path, p.point.pose); + for (auto & p : stop_path.points) { + const double distance_from_ego = calcSignedArcLengthFromEgo(stop_path, p.point.pose); if (min_decel_distance && distance_from_ego < *min_decel_distance) { continue; } p.point.longitudinal_velocity_mps = std::min(p.point.longitudinal_velocity_mps, static_cast(pull_over_velocity)); } - return reference_path; + return stop_path; } PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() const { - const auto & route_handler = planner_data_->route_handler; - const auto & current_pose = planner_data_->self_odometry->pose.pose; - const auto & common_parameters = planner_data_->parameters; - - // generate stop reference path - const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length, - /*forward_only_in_route*/ false); - - const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; - const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); - const double s_end = s_current + common_parameters.forward_path_length; - auto stop_path = route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); - // calc minimum stop distance under maximum deceleration const auto min_stop_distance = calcFeasibleDecelDistance( planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, 0.0); if (!min_stop_distance) { - return stop_path; + return getPreviousModuleOutput().path; } // set stop point + auto stop_path = getPreviousModuleOutput().path; + const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto stop_idx = motion_utils::insertStopPoint(current_pose, *min_stop_distance, stop_path.points); if (stop_idx) { @@ -1887,7 +1938,7 @@ void GoalPlannerModule::setDebugData() } tier4_autoware_utils::appendMarkerArray(added, &debug_marker_); }; - if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (utils::isAllowedGoalModification(planner_data_->route_handler)) { // Visualize pull over areas const auto color = hasDecidedPath() ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green @@ -1900,6 +1951,14 @@ void GoalPlannerModule::setDebugData() add(goal_planner_utils::createGoalCandidatesMarkerArray(goal_candidates, color)); } + // Visualize previous module output + add(createPathMarkerArray( + getPreviousModuleOutput().path, "previous_module_path", 0, 1.0, 0.0, 0.0)); + if (last_previous_module_output_.has_value()) { + add(createPathMarkerArray( + last_previous_module_output_.value().path, "last_previous_module_path", 0, 0.0, 1.0, 1.0)); + } + // Visualize path and related pose if (thread_safe_data_.foundPullOverPath()) { add(createPoseMarkerArray( diff --git a/planning/behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_goal_planner_module/src/manager.cpp index 3079361253c31..8608d6cce2c81 100644 --- a/planning/behavior_path_goal_planner_module/src/manager.cpp +++ b/planning/behavior_path_goal_planner_module/src/manager.cpp @@ -419,7 +419,7 @@ bool GoalPlannerModuleManager::isAlwaysExecutableModule() const { // enable AlwaysExecutable whenever goal modification is not allowed // because only minor path refinements are made for fixed goals - if (!goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (!utils::isAllowedGoalModification(planner_data_->route_handler)) { return true; } @@ -434,7 +434,7 @@ bool GoalPlannerModuleManager::isSimultaneousExecutableAsApprovedModule() const // enable SimultaneousExecutable whenever goal modification is not allowed // because only minor path refinements are made for fixed goals - if (!goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (!utils::isAllowedGoalModification(planner_data_->route_handler)) { return true; } @@ -449,7 +449,7 @@ bool GoalPlannerModuleManager::isSimultaneousExecutableAsCandidateModule() const // enable SimultaneousExecutable whenever goal modification is not allowed // because only minor path refinements are made for fixed goals - if (!goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (!utils::isAllowedGoalModification(planner_data_->route_handler)) { return true; } diff --git a/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp index 712da5aa03a4e..b168da61e6239 100644 --- a/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -46,10 +46,10 @@ std::optional ShiftPullOver::plan(const Pose & goal_pose) const int shift_sampling_num = parameters_.shift_sampling_num; const double jerk_resolution = std::abs(max_jerk - min_jerk) / shift_sampling_num; - // get road and shoulder lanes - const auto road_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_search_length, forward_search_length, + const auto road_lanes = utils::getExtendedCurrentLanesFromPath( + previous_module_output_.path, planner_data_, backward_search_length, forward_search_length, /*forward_only_in_route*/ false); + const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( *route_handler, left_side_parking_, backward_search_length, forward_search_length); if (road_lanes.empty() || pull_over_lanes.empty()) { @@ -99,6 +99,31 @@ PathWithLaneId ShiftPullOver::generateReferencePath( return road_lane_reference_path; } +std::optional ShiftPullOver::cropPrevModulePath( + const PathWithLaneId & prev_module_path, const Pose & shift_end_pose) const +{ + // clip previous module path to shift end pose nearest segment index + const size_t shift_end_idx = + motion_utils::findNearestSegmentIndex(prev_module_path.points, shift_end_pose.position); + std::vector clipped_points{ + prev_module_path.points.begin(), prev_module_path.points.begin() + shift_end_idx}; + if (clipped_points.empty()) { + return std::nullopt; + } + + // add projected shift end pose to clipped points + PathPointWithLaneId projected_point = clipped_points.back(); + const double offset = motion_utils::calcSignedArcLength( + prev_module_path.points, shift_end_idx, shift_end_pose.position); + projected_point.point.pose = + tier4_autoware_utils::calcOffsetPose(clipped_points.back().point.pose, offset, 0, 0); + clipped_points.push_back(projected_point); + auto clipped_prev_module_path = prev_module_path; + clipped_prev_module_path.points = clipped_points; + + return clipped_prev_module_path; +} + std::optional ShiftPullOver::generatePullOverPath( const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, const Pose & goal_pose, const double lateral_jerk) const @@ -106,33 +131,55 @@ std::optional ShiftPullOver::generatePullOverPath( const double pull_over_velocity = parameters_.pull_over_velocity; const double after_shift_straight_distance = parameters_.after_shift_straight_distance; + // shift end pose is longitudinal offset from goal pose to improve parking angle accuracy const Pose shift_end_pose = tier4_autoware_utils::calcOffsetPose(goal_pose, -after_shift_straight_distance, 0, 0); - // generate road lane reference path to shift end + // 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); + const auto prev_module_path = utils::resamplePathWithSpline( + previous_module_output_.path, parameters_.center_line_path_interval); + const auto prev_module_path_terminal_pose = prev_module_path.points.back().point.pose; + + // process previous module path for path shifter input path + // case1) extend path if shift end pose is behind of previous module path terminal pose + // case2) crop path if shift end pose is ahead of previous module path terminal pose + const auto processed_prev_module_path = std::invoke([&]() -> std::optional { + const bool extend_previous_module_path = + lanelet::utils::getArcCoordinates(road_lanes, shift_end_pose).length > + lanelet::utils::getArcCoordinates(road_lanes, prev_module_path_terminal_pose).length; + if (extend_previous_module_path) { // case1 + return goal_planner_utils::extendPath( + prev_module_path, road_lane_reference_path_to_shift_end, shift_end_pose); + } else { // case2 + return goal_planner_utils::cropPath(prev_module_path, shift_end_pose); + } + }); + if (!processed_prev_module_path || processed_prev_module_path->points.empty()) { + return {}; + } // calculate shift length - const Pose & shift_end_pose_road_lane = - road_lane_reference_path_to_shift_end.points.back().point.pose; + const Pose & shift_end_pose_prev_module_path = + processed_prev_module_path->points.back().point.pose; const double shift_end_road_to_target_distance = - tier4_autoware_utils::inverseTransformPoint(shift_end_pose.position, shift_end_pose_road_lane) + tier4_autoware_utils::inverseTransformPoint( + shift_end_pose.position, shift_end_pose_prev_module_path) .y; // calculate shift start pose on road lane const double pull_over_distance = PathShifter::calcLongitudinalDistFromJerk( shift_end_road_to_target_distance, lateral_jerk, pull_over_velocity); const double before_shifted_pull_over_distance = calcBeforeShiftedArcLength( - road_lane_reference_path_to_shift_end, pull_over_distance, shift_end_road_to_target_distance); + processed_prev_module_path.value(), pull_over_distance, shift_end_road_to_target_distance); const auto shift_start_pose = motion_utils::calcLongitudinalOffsetPose( - road_lane_reference_path_to_shift_end.points, shift_end_pose_road_lane.position, + processed_prev_module_path->points, shift_end_pose_prev_module_path.position, -before_shifted_pull_over_distance); - if (!shift_start_pose) return {}; // set path shifter and generate shifted path PathShifter path_shifter{}; - path_shifter.setPath(road_lane_reference_path_to_shift_end); + path_shifter.setPath(processed_prev_module_path.value()); ShiftLine shift_line{}; shift_line.start = *shift_start_pose; shift_line.end = shift_end_pose; @@ -140,7 +187,9 @@ std::optional ShiftPullOver::generatePullOverPath( path_shifter.addShiftLine(shift_line); ShiftedPath shifted_path{}; const bool offset_back = true; // offset front side from reference path - if (!path_shifter.generate(&shifted_path, offset_back)) return {}; + if (!path_shifter.generate(&shifted_path, offset_back)) { + return {}; + } shifted_path.path.points = motion_utils::removeOverlapPoints(shifted_path.path.points); motion_utils::insertOrientation(shifted_path.path.points, true); @@ -208,8 +257,13 @@ std::optional ShiftPullOver::generatePullOverPath( pull_over_path.pairs_terminal_velocity_and_accel.push_back(std::make_pair(pull_over_velocity, 0)); pull_over_path.start_pose = path_shifter.getShiftLines().front().start; pull_over_path.end_pose = path_shifter.getShiftLines().front().end; - pull_over_path.debug_poses.push_back(shift_end_pose_road_lane); + pull_over_path.debug_poses.push_back(shift_end_pose_prev_module_path); pull_over_path.debug_poses.push_back(actual_shift_end_pose); + pull_over_path.debug_poses.push_back(goal_pose); + pull_over_path.debug_poses.push_back(shift_end_pose); + pull_over_path.debug_poses.push_back( + road_lane_reference_path_to_shift_end.points.back().point.pose); + pull_over_path.debug_poses.push_back(prev_module_path_terminal_pose); // check if the parking path will leave lanes const auto drivable_lanes = @@ -218,8 +272,10 @@ std::optional ShiftPullOver::generatePullOverPath( 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); if (lane_departure_checker_.checkPathWillLeaveLane( - utils::transformToLanelets(expanded_lanes), pull_over_path.getParkingPath())) { + utils::transformToLanelets(combined_drivable), pull_over_path.getParkingPath())) { return {}; } diff --git a/planning/behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_goal_planner_module/src/util.cpp index 1a1e66f85b403..dfdaa2a3a18c1 100644 --- a/planning/behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_goal_planner_module/src/util.cpp @@ -196,22 +196,138 @@ MarkerArray createGoalCandidatesMarkerArray( return marker_array; } -bool isAllowedGoalModification(const std::shared_ptr & route_handler) +double calcLateralDeviationBetweenPaths( + const PathWithLaneId & reference_path, const PathWithLaneId & target_path) { - return route_handler->isAllowedGoalModification() || checkOriginalGoalIsInShoulder(route_handler); + double lateral_deviation = 0.0; + for (const auto & target_point : target_path.points) { + const size_t nearest_index = + motion_utils::findNearestIndex(reference_path.points, target_point.point.pose.position); + lateral_deviation = std::max( + lateral_deviation, + std::abs(tier4_autoware_utils::calcLateralDeviation( + reference_path.points[nearest_index].point.pose, target_point.point.pose.position))); + } + return lateral_deviation; +} + +bool isReferencePath( + const PathWithLaneId & reference_path, const PathWithLaneId & target_path, + const double lateral_deviation_threshold) +{ + return calcLateralDeviationBetweenPaths(reference_path, target_path) < + lateral_deviation_threshold; +} + +std::optional cropPath(const PathWithLaneId & path, const Pose & end_pose) +{ + const size_t end_idx = motion_utils::findNearestSegmentIndex(path.points, end_pose.position); + std::vector clipped_points{ + path.points.begin(), path.points.begin() + end_idx}; + if (clipped_points.empty()) { + return std::nullopt; + } + + // add projected end pose to clipped points + PathPointWithLaneId projected_point = clipped_points.back(); + const double offset = motion_utils::calcSignedArcLength(path.points, end_idx, end_pose.position); + projected_point.point.pose = + tier4_autoware_utils::calcOffsetPose(clipped_points.back().point.pose, offset, 0, 0); + clipped_points.push_back(projected_point); + auto clipped_path = path; + clipped_path.points = clipped_points; + + return clipped_path; +} + +PathWithLaneId cropForwardPoints( + const PathWithLaneId & path, const size_t target_seg_idx, const double forward_length) +{ + const auto & points = path.points; + + double sum_length = 0; + for (size_t i = target_seg_idx + 1; i < points.size(); ++i) { + const double seg_length = tier4_autoware_utils::calcDistance2d(points.at(i), points.at(i - 1)); + if (forward_length < sum_length + seg_length) { + const auto cropped_points = + std::vector{points.begin() + target_seg_idx, points.begin() + i}; + PathWithLaneId cropped_path = path; + cropped_path.points = cropped_points; + + // add precise end pose to cropped points + const double remaining_length = forward_length - sum_length; + const Pose precise_end_pose = + calcOffsetPose(cropped_path.points.back().point.pose, remaining_length, 0, 0); + if (remaining_length < 0.1) { + // if precise_end_pose is too close, replace the last point + cropped_path.points.back().point.pose = precise_end_pose; + } else { + auto precise_end_point = cropped_path.points.back(); + precise_end_point.point.pose = precise_end_pose; + cropped_path.points.push_back(precise_end_point); + } + return cropped_path; + } + sum_length += seg_length; + } + + // if forward_length is too long, return points after target_seg_idx + const auto cropped_points = + std::vector{points.begin() + target_seg_idx, points.end()}; + PathWithLaneId cropped_path = path; + cropped_path.points = cropped_points; + return cropped_path; } -bool checkOriginalGoalIsInShoulder(const std::shared_ptr & route_handler) +PathWithLaneId extendPath( + const PathWithLaneId & target_path, const PathWithLaneId & reference_path, + const double extend_length) { - const Pose & goal_pose = route_handler->getOriginalGoalPose(); - const auto shoulder_lanes = route_handler->getShoulderLanelets(); + const auto & target_terminal_pose = target_path.points.back().point.pose; + + // generate clipped road lane reference path from previous module path terminal pose to shift end + const size_t target_path_terminal_idx = + motion_utils::findNearestSegmentIndex(reference_path.points, target_terminal_pose.position); - lanelet::ConstLanelet closest_shoulder_lane{}; - if (lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &closest_shoulder_lane)) { - return lanelet::utils::isInLanelet(goal_pose, closest_shoulder_lane, 0.1); + PathWithLaneId clipped_path = + cropForwardPoints(reference_path, target_path_terminal_idx, extend_length); + + // shift clipped path to previous module path terminal pose + const double lateral_shift_from_reference_path = + motion_utils::calcLateralOffset(reference_path.points, target_terminal_pose.position); + for (auto & p : clipped_path.points) { + p.point.pose = + tier4_autoware_utils::calcOffsetPose(p.point.pose, 0, lateral_shift_from_reference_path, 0); } - return false; + auto extended_path = target_path; + const auto start_point = + std::find_if(clipped_path.points.begin(), clipped_path.points.end(), [&](const auto & p) { + const bool is_forward = + tier4_autoware_utils::inverseTransformPoint(p.point.pose.position, target_terminal_pose).x > + 0.0; + const bool is_close = tier4_autoware_utils::calcDistance2d( + p.point.pose.position, target_terminal_pose.position) < 0.1; + return is_forward && !is_close; + }); + std::copy(start_point, clipped_path.points.end(), std::back_inserter(extended_path.points)); + + extended_path.points = motion_utils::removeOverlapPoints(extended_path.points); + + return extended_path; +} + +PathWithLaneId extendPath( + const PathWithLaneId & target_path, const PathWithLaneId & reference_path, + const Pose & extend_pose) +{ + const auto & target_terminal_pose = target_path.points.back().point.pose; + const size_t target_path_terminal_idx = + motion_utils::findNearestSegmentIndex(reference_path.points, target_terminal_pose.position); + const double extend_distance = motion_utils::calcSignedArcLength( + reference_path.points, target_path_terminal_idx, extend_pose.position); + + return extendPath(target_path, reference_path, extend_distance); } } // namespace behavior_path_planner::goal_planner_utils diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp index 01b2880f4362a..dcee7696933dd 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp @@ -221,6 +221,9 @@ PathWithLaneId refinePathForGoal( 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); + bool isInLanelets(const Pose & pose, const lanelet::ConstLanelets & lanes); bool isInLaneletWithYawThreshold( @@ -303,6 +306,10 @@ lanelet::ConstLanelets getExtendedCurrentLanes( const std::shared_ptr & planner_data, const double backward_length, const double forward_length, const bool forward_only_in_route); +lanelet::ConstLanelets getExtendedCurrentLanesFromPath( + const PathWithLaneId & path, const std::shared_ptr & planner_data, + const double backward_length, const double forward_length, const bool forward_only_in_route); + lanelet::ConstLanelets calcLaneAroundPose( const std::shared_ptr route_handler, const geometry_msgs::msg::Pose & pose, const double forward_length, const double backward_length, diff --git a/planning/behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner_common/src/utils/utils.cpp index e6f9ce21cebf7..308cf9c4fed2c 100644 --- a/planning/behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/utils.cpp @@ -1450,6 +1450,70 @@ lanelet::ConstLanelets getExtendedCurrentLanes( return extendLanes(planner_data->route_handler, getCurrentLanes(planner_data)); } +lanelet::ConstLanelets getExtendedCurrentLanesFromPath( + const PathWithLaneId & path, const std::shared_ptr & planner_data, + const double backward_length, const double forward_length, const bool forward_only_in_route) +{ + auto lanes = getCurrentLanesFromPath(path, planner_data); + + if (lanes.empty()) return lanes; + const auto start_lane = lanes.front(); + double forward_length_sum = 0.0; + double backward_length_sum = 0.0; + + while (backward_length_sum < backward_length) { + auto extended_lanes = extendPrevLane(planner_data->route_handler, lanes); + if (extended_lanes.empty()) { + return lanes; + } + // loop check + // if current map lanes is looping and has a very large value for backward_length, + // the extending process will not finish. + if (extended_lanes.front().id() == start_lane.id()) { + return lanes; + } + + if (extended_lanes.size() > lanes.size()) { + backward_length_sum += lanelet::utils::getLaneletLength2d(extended_lanes.front()); + } else { + break; // no more previous lanes to add + } + lanes = extended_lanes; + } + + while (forward_length_sum < forward_length) { + auto extended_lanes = extendNextLane(planner_data->route_handler, lanes); + if (extended_lanes.empty()) { + return lanes; + } + // loop check + // if current map lanes is looping and has a very large value for forward_length, + // the extending process will not finish. + if (extended_lanes.back().id() == start_lane.id()) { + return lanes; + } + + if (extended_lanes.size() > lanes.size()) { + forward_length_sum += lanelet::utils::getLaneletLength2d(extended_lanes.back()); + } else { + break; // no more next lanes to add + } + + // stop extending when the lane outside of the route is reached + // if forward_length is a very large value, set it to true, + // as it may continue to extend forever. + if (forward_only_in_route) { + if (!planner_data->route_handler->isRouteLanelet(extended_lanes.back())) { + return lanes; + } + } + + lanes = extended_lanes; + } + + return lanes; +} + lanelet::ConstLanelets calcLaneAroundPose( const std::shared_ptr route_handler, const Pose & pose, const double forward_length, const double backward_length, const double dist_threshold, const double yaw_threshold) @@ -1551,4 +1615,22 @@ std::string convertToSnakeCase(const std::string & input_str) } return output_str; } + +bool isAllowedGoalModification(const std::shared_ptr & route_handler) +{ + return route_handler->isAllowedGoalModification() || checkOriginalGoalIsInShoulder(route_handler); +} + +bool checkOriginalGoalIsInShoulder(const std::shared_ptr & route_handler) +{ + const Pose & goal_pose = route_handler->getOriginalGoalPose(); + const auto shoulder_lanes = route_handler->getShoulderLanelets(); + + lanelet::ConstLanelet closest_shoulder_lane{}; + if (lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &closest_shoulder_lane)) { + return lanelet::utils::isInLanelet(goal_pose, closest_shoulder_lane, 0.1); + } + + return false; +} } // namespace behavior_path_planner::utils From 775ff32403a315870edbc885dc87658e23d9ac91 Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Wed, 17 Jan 2024 11:40:35 +0900 Subject: [PATCH 250/276] feat(yabloc): add yabloc trigger service to suspend and restart the estimation (#6076) * change arg default value Signed-off-by: Kento Yabuuchi * add yabloc_trigger_service Signed-off-by: Kento Yabuuchi * fix misc Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- .../launch/image_processing.launch.xml | 2 +- .../yabloc/yabloc_particle_filter/README.md | 6 +++ .../prediction/predictor.hpp | 9 ++++ .../launch/yabloc_particle_filter.launch.xml | 3 ++ .../src/prediction/predictor.cpp | 41 ++++++++++++++++++- 5 files changed, 59 insertions(+), 2 deletions(-) diff --git a/localization/yabloc/yabloc_image_processing/launch/image_processing.launch.xml b/localization/yabloc/yabloc_image_processing/launch/image_processing.launch.xml index aa6fc10ee6667..a0cad16302c2b 100644 --- a/localization/yabloc/yabloc_image_processing/launch/image_processing.launch.xml +++ b/localization/yabloc/yabloc_image_processing/launch/image_processing.launch.xml @@ -1,7 +1,7 @@ - + diff --git a/localization/yabloc/yabloc_particle_filter/README.md b/localization/yabloc/yabloc_particle_filter/README.md index 41ab7b1b10039..d42ce4647bc95 100644 --- a/localization/yabloc/yabloc_particle_filter/README.md +++ b/localization/yabloc/yabloc_particle_filter/README.md @@ -46,6 +46,12 @@ This package contains some executable nodes related to particle filter. | `prediction_rate` | double | frequency of forecast updates, in Hz | | `cov_xx_yy` | vector\ | the covariance of initial pose | +### Services + +| Name | Type | Description | +| -------------------- | ------------------------ | ------------------------------------------------ | +| `yabloc_trigger_srv` | `std_srvs::srv::SetBool` | activation and deactivation of yabloc estimation | + ## gnss_particle_corrector ### Purpose diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/predictor.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/predictor.hpp index c7794a2be9f51..e02393ee14db6 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/predictor.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/predictor.hpp @@ -27,6 +27,7 @@ #include #include #include +#include #include #include @@ -46,6 +47,7 @@ class Predictor : public rclcpp::Node using TwistCovStamped = geometry_msgs::msg::TwistWithCovarianceStamped; using TwistStamped = geometry_msgs::msg::TwistStamped; using Marker = visualization_msgs::msg::Marker; + using SetBool = std_srvs::srv::SetBool; Predictor(); @@ -62,6 +64,7 @@ class Predictor : public rclcpp::Node const std::vector cov_xx_yy_; // Subscriber + rclcpp::Subscription::SharedPtr ekf_pose_sub_; rclcpp::Subscription::SharedPtr initialpose_sub_; rclcpp::Subscription::SharedPtr twist_cov_sub_; rclcpp::Subscription::SharedPtr particles_sub_; @@ -73,11 +76,15 @@ class Predictor : public rclcpp::Node rclcpp::Publisher::SharedPtr pose_cov_pub_; rclcpp::Publisher::SharedPtr marker_pub_; std::unique_ptr tf2_broadcaster_; + // Server + rclcpp::Service::SharedPtr yabloc_trigger_server_; // Timer callback rclcpp::TimerBase::SharedPtr timer_; float ground_height_{0}; + bool yabloc_activated_{true}; + PoseCovStamped::ConstSharedPtr latest_ekf_pose_ptr_{nullptr}; std::optional particle_array_opt_{std::nullopt}; std::optional latest_twist_opt_{std::nullopt}; @@ -92,6 +99,8 @@ class Predictor : public rclcpp::Node void on_twist_cov(const TwistCovStamped::ConstSharedPtr twist); void on_weighted_particles(const ParticleArray::ConstSharedPtr weighted_particles); void on_timer(); + void on_trigger_service( + SetBool::Request::ConstSharedPtr request, SetBool::Response::SharedPtr response); // void initialize_particles(const PoseCovStamped & initialpose); diff --git a/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml b/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml index f38264b828d34..5dd483f142174 100644 --- a/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml +++ b/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml @@ -16,6 +16,9 @@ + + + diff --git a/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp b/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp index b16905ba19b41..764ef88bbde18 100644 --- a/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp @@ -52,7 +52,12 @@ Predictor::Predictor() auto on_initial = std::bind(&Predictor::on_initial_pose, this, _1); auto on_twist_cov = std::bind(&Predictor::on_twist_cov, this, _1); auto on_particle = std::bind(&Predictor::on_weighted_particles, this, _1); - auto on_height = [this](std_msgs::msg::Float32 m) -> void { this->ground_height_ = m.data; }; + auto on_height = [this](std_msgs::msg::Float32::ConstSharedPtr msg) -> void { + this->ground_height_ = msg->data; + }; + auto on_ekf_pose = [this](PoseCovStamped::ConstSharedPtr msg) -> void { + this->latest_ekf_pose_ptr_ = msg; + }; initialpose_sub_ = create_subscription("~/input/initialpose", 1, on_initial); particles_sub_ = @@ -60,6 +65,7 @@ Predictor::Predictor() height_sub_ = create_subscription("~/input/height", 10, on_height); twist_cov_sub_ = create_subscription("~/input/twist_with_covariance", 10, on_twist_cov); + ekf_pose_sub_ = create_subscription("~/input/ekf_pose", 10, on_ekf_pose); // Timer callback const double prediction_rate = declare_parameter("prediction_rate"); @@ -67,12 +73,41 @@ Predictor::Predictor() timer_ = rclcpp::create_timer( this, this->get_clock(), rclcpp::Rate(prediction_rate).period(), std::move(on_timer)); + // Service server + using std::placeholders::_2; + auto on_trigger_service = std::bind(&Predictor::on_trigger_service, this, _1, _2); + yabloc_trigger_server_ = create_service("~/yabloc_trigger_srv", on_trigger_service); + // Optional modules if (declare_parameter("visualize", false)) { visualizer_ptr_ = std::make_unique(*this); } } +void Predictor::on_trigger_service( + SetBool::Request::ConstSharedPtr request, SetBool::Response::SharedPtr response) +{ + if (request->data) { + RCLCPP_INFO_STREAM(get_logger(), "yabloc particle filter is activated"); + } else { + RCLCPP_INFO_STREAM(get_logger(), "yabloc particle filter is deactivated"); + } + + const bool before_activated_ = yabloc_activated_; + yabloc_activated_ = request->data; + response->success = true; + + if (yabloc_activated_ && (!before_activated_)) { + RCLCPP_INFO_STREAM(get_logger(), "restart particle filter"); + if (latest_ekf_pose_ptr_) { + on_initial_pose(latest_ekf_pose_ptr_); + } else { + yabloc_activated_ = false; + response->success = false; + } + } +} + void Predictor::on_initial_pose(const PoseCovStamped::ConstSharedPtr initialpose) { // Publish initial pose marker @@ -181,6 +216,10 @@ void Predictor::on_timer() { // ========================================================================== // Pre-check section + // Return if yabloc is not activated + if (!yabloc_activated_) { + return; + } // Return if particle_array is not initialized yet if (!particle_array_opt_.has_value()) { return; From 498e338ac3e73ab07c2d0bfd6d0bfd89c205acde Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 17 Jan 2024 14:21:43 +0900 Subject: [PATCH 251/276] feat(goal_planner): exclude goals located laterally in no_parking_areas (#6095) Signed-off-by: kosuke55 --- .../behavior_path_goal_planner_module/src/goal_searcher.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp index bf359be3de18b..31f99e8ea5aa1 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -170,11 +170,13 @@ GoalCandidates GoalSearcher::search() transformVector(vehicle_footprint_, tier4_autoware_utils::pose2transform(search_pose)); if (isInAreas(transformed_vehicle_footprint, getNoParkingAreaPolygons(pull_over_lanes))) { - continue; + // break here to exclude goals located laterally in no_parking_areas + break; } if (isInAreas(transformed_vehicle_footprint, getNoStoppingAreaPolygons(pull_over_lanes))) { - continue; + // break here to exclude goals located laterally in no_stopping_areas + break; } if (LaneDepartureChecker::isOutOfLane(lanes, transformed_vehicle_footprint)) { From a219a7e6f5f77e8f9b32744b71921ff7cdd418c0 Mon Sep 17 00:00:00 2001 From: Makoto Kurihara Date: Wed, 17 Jan 2024 16:12:32 +0900 Subject: [PATCH 252/276] chore(mission_planner): add logs for reroute safety check (#6096) * chore(mission_planner): add logs for reroute safety check Signed-off-by: Makoto Kurihara * style(pre-commit): autofix --------- Signed-off-by: Makoto Kurihara Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../mission_planner/src/mission_planner/mission_planner.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 9ee874928d7d1..e0181065150fd 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -731,6 +731,7 @@ bool MissionPlanner::check_reroute_safety( const LaneletRoute & original_route, const LaneletRoute & target_route) { if (original_route.segments.empty() || target_route.segments.empty() || !map_ptr_ || !odometry_) { + RCLCPP_ERROR(get_logger(), "Check reroute safety failed. Route, map or odometry is not set."); return false; } @@ -803,6 +804,8 @@ bool MissionPlanner::check_reroute_safety( return std::nullopt; }); if (!start_idx_opt.has_value()) { + RCLCPP_ERROR( + get_logger(), "Check reroute safety failed. Cannot find the start index of the route."); return false; } const size_t start_idx = start_idx_opt.value(); @@ -838,6 +841,7 @@ bool MissionPlanner::check_reroute_safety( // get closest lanelet in start lanelets lanelet::ConstLanelet closest_lanelet; if (!lanelet::utils::query::getClosestLanelet(start_lanelets, current_pose, &closest_lanelet)) { + RCLCPP_ERROR(get_logger(), "Check reroute safety failed. Cannot find the closest lanelet."); return false; } From e09b95e8b1995db41ac32e25b41f560a1522a0d2 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 17 Jan 2024 17:43:45 +0900 Subject: [PATCH 253/276] fix(AbLC, lane_change): fix module name inconsistency (#6090) * fix(AbLC): rename Signed-off-by: satoshi-ota * fix(AbLC, LC): fix duplicated rtc setting Signed-off-by: satoshi-ota * fix(bpp): fix module name inconsistency Signed-off-by: satoshi-ota * fix(AbLC): rename Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- ..._lc.param.yaml => avoidance_by_lane_change.param.yaml} | 0 .../manager.hpp | 2 +- .../src/manager.cpp | 2 +- .../test/test_behavior_path_planner_node_interface.cpp | 2 +- .../include/behavior_path_lane_change_module/manager.hpp | 2 ++ planning/behavior_path_lane_change_module/src/manager.cpp | 8 ++++++-- .../config/scene_module_manager.param.yaml | 2 +- planning/behavior_path_planner/src/planner_manager.cpp | 8 +++----- 8 files changed, 15 insertions(+), 11 deletions(-) rename planning/behavior_path_avoidance_by_lane_change_module/config/{avoidance_by_lc.param.yaml => avoidance_by_lane_change.param.yaml} (100%) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml similarity index 100% rename from planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml rename to planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp index d996555365166..75fa67e7fe1a3 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp @@ -35,7 +35,7 @@ class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager public: AvoidanceByLaneChangeModuleManager() : LaneChangeModuleManager( - "avoidance_by_lc", route_handler::Direction::NONE, + "avoidance_by_lane_change", route_handler::Direction::NONE, LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) { } diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 3f810710ef37b..4bdcb51f1eab5 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -37,7 +37,7 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) initInterface(node, {"left", "right"}); // init lane change manager - LaneChangeModuleManager::init(node); + LaneChangeModuleManager::initParams(node); const auto avoidance_params = getParameter(node); AvoidanceByLCParameters p(avoidance_params); diff --git a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 581aafa6c860c..1167fa4414752 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -70,7 +70,7 @@ std::shared_ptr generateNode() ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + "/config/avoidance.param.yaml", ament_index_cpp::get_package_share_directory("behavior_path_avoidance_by_lane_change_module") + - "/config/avoidance_by_lc.param.yaml"}); + "/config/avoidance_by_lane_change.param.yaml"}); return std::make_shared(node_options); } diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp index b34f691bd2b0d..31561b6210591 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp @@ -45,6 +45,8 @@ class LaneChangeModuleManager : public SceneModuleManagerInterface void updateModuleParams(const std::vector & parameters) override; protected: + void initParams(rclcpp::Node * node); + std::shared_ptr parameters_; Direction direction_; diff --git a/planning/behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_lane_change_module/src/manager.cpp index e4405a31a360d..0a56c17d89fd0 100644 --- a/planning/behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_lane_change_module/src/manager.cpp @@ -29,10 +29,14 @@ namespace behavior_path_planner void LaneChangeModuleManager::init(rclcpp::Node * node) { - using tier4_autoware_utils::getOrDeclareParameter; - // init manager interface initInterface(node, {""}); + initParams(node); +} + +void LaneChangeModuleManager::initParams(rclcpp::Node * node) +{ + using tier4_autoware_utils::getOrDeclareParameter; LaneChangeParameters p{}; diff --git a/planning/behavior_path_planner/config/scene_module_manager.param.yaml b/planning/behavior_path_planner/config/scene_module_manager.param.yaml index 91e34c0e91931..439e08fd7e94f 100644 --- a/planning/behavior_path_planner/config/scene_module_manager.param.yaml +++ b/planning/behavior_path_planner/config/scene_module_manager.param.yaml @@ -67,7 +67,7 @@ priority: 4 max_module_size: 1 - avoidance_by_lc: + avoidance_by_lane_change: enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 262de4764fcfe..a1d0a82be38b1 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -859,11 +859,9 @@ void PlannerManager::resetRootLanelet(const std::shared_ptr & data) // when lane change module is running, don't update root lanelet. const bool is_lane_change_running = std::invoke([&]() { - const auto lane_change_itr = - std::find_if(approved_module_ptrs_.begin(), approved_module_ptrs_.end(), [](const auto & m) { - return m->name().find("lane_change") != std::string::npos || - m->name().find("avoidance_by_lc") != std::string::npos; - }); + const auto lane_change_itr = std::find_if( + approved_module_ptrs_.begin(), approved_module_ptrs_.end(), + [](const auto & m) { return m->isRootLaneletToBeUpdated(); }); return lane_change_itr != approved_module_ptrs_.end(); }); if (is_lane_change_running) { From b801f8e893b96c30fe6479db8b9c2e5e63ef09db Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 17 Jan 2024 18:14:36 +0900 Subject: [PATCH 254/276] fix(avoidance): fix detection area issue in avoidance module (#6097) * fix(avoidance): fix invalid vector access Signed-off-by: satoshi-ota * fix(avoidance): fix detection area Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/utils.cpp | 25 +++++++++++++------ 1 file changed, 17 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index 80aeb2bf0dccf..3a9b5db283304 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -1913,6 +1913,10 @@ std::pair separateObjectsByPath( PredictedObjects target_objects; PredictedObjects other_objects; + if (reference_path.points.empty() || spline_path.points.empty()) { + return std::make_pair(target_objects, other_objects); + } + double max_offset = 0.0; for (const auto & object_parameter : parameters->object_parameters) { const auto p = object_parameter.second; @@ -1925,16 +1929,15 @@ std::pair separateObjectsByPath( createVehiclePolygon(planner_data->parameters.vehicle_info, max_offset); const auto ego_idx = planner_data->findEgoIndex(reference_path.points); const auto arc_length_array = - utils::calcPathArcLengthArray(reference_path, 0L, reference_path.points.size(), 1e-3); + utils::calcPathArcLengthArray(reference_path, 0L, reference_path.points.size(), 0.0); - double next_longitudinal_distance = 0.0; - std::vector detection_areas; - for (size_t i = 0; i < reference_path.points.size() - 1; ++i) { - const auto & p_reference_ego_front = reference_path.points.at(i).point.pose; - const auto & p_reference_ego_back = reference_path.points.at(i + 1).point.pose; - const auto & p_spline_ego_front = spline_path.points.at(i).point.pose; - const auto & p_spline_ego_back = spline_path.points.at(i + 1).point.pose; + const auto points_size = std::min(reference_path.points.size(), spline_path.points.size()); + std::vector detection_areas; + Pose p_reference_ego_front = reference_path.points.front().point.pose; + Pose p_spline_ego_front = spline_path.points.front().point.pose; + double next_longitudinal_distance = parameters->resample_interval_for_output; + for (size_t i = 0; i < points_size; ++i) { const auto distance_from_ego = calcSignedArcLength(reference_path.points, ego_idx, i); if (distance_from_ego > object_check_forward_distance) { break; @@ -1944,10 +1947,16 @@ std::pair separateObjectsByPath( continue; } + const auto & p_reference_ego_back = reference_path.points.at(i).point.pose; + const auto & p_spline_ego_back = spline_path.points.at(i).point.pose; + detection_areas.push_back(createOneStepPolygon( p_reference_ego_front, p_reference_ego_back, p_spline_ego_front, p_spline_ego_back, detection_area)); + p_reference_ego_front = p_reference_ego_back; + p_spline_ego_front = p_spline_ego_back; + next_longitudinal_distance += parameters->resample_interval_for_output; } From d73554e8a29cc0a135d65161cdf296f09a72f411 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Wed, 17 Jan 2024 20:21:13 +0900 Subject: [PATCH 255/276] chore: add localization & mapping maintainers (#6085) * Added lm maintainers Signed-off-by: Shintaro SAKODA * Add more Signed-off-by: Shintaro SAKODA * Fixed maintainer Signed-off-by: Shintaro SAKODA --------- Signed-off-by: Shintaro SAKODA --- launch/tier4_localization_launch/package.xml | 3 +++ localization/ekf_localizer/package.xml | 5 +++++ localization/geo_pose_projector/package.xml | 6 ++++++ localization/gyro_odometer/package.xml | 5 +++++ .../ar_tag_based_localizer/package.xml | 3 +++ .../landmark_based_localizer/landmark_manager/package.xml | 3 +++ localization/localization_error_monitor/package.xml | 5 +++++ localization/localization_util/package.xml | 3 +++ localization/ndt_scan_matcher/package.xml | 4 ++++ localization/pose2twist/package.xml | 5 +++++ localization/pose_initializer/package.xml | 5 +++++ localization/pose_instability_detector/package.xml | 1 + localization/stop_filter/package.xml | 5 +++++ localization/tree_structured_parzen_estimator/package.xml | 3 +++ localization/twist2accel/package.xml | 5 +++++ localization/yabloc/yabloc_common/package.xml | 5 +++++ localization/yabloc/yabloc_image_processing/package.xml | 5 +++++ localization/yabloc/yabloc_monitor/package.xml | 5 +++++ localization/yabloc/yabloc_particle_filter/package.xml | 5 +++++ localization/yabloc/yabloc_pose_initializer/package.xml | 5 +++++ map/map_height_fitter/package.xml | 4 ++++ map/map_loader/package.xml | 3 +++ map/map_projection_loader/package.xml | 4 ++++ map/map_tf_generator/package.xml | 4 ++++ 24 files changed, 101 insertions(+) diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index c4de9c04dcaf2..9b4f727c9ce52 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -8,6 +8,9 @@ Koji Minoda Kento Yabuuchi Ryu Yamamoto + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda Apache License 2.0 Yamato Ando diff --git a/localization/ekf_localizer/package.xml b/localization/ekf_localizer/package.xml index 4101bae88b6e2..e9d756e547f26 100644 --- a/localization/ekf_localizer/package.xml +++ b/localization/ekf_localizer/package.xml @@ -9,6 +9,11 @@ Yamato Ando Takeshi Ishita Masahiro Sakamoto + Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 Takamasa Horibe diff --git a/localization/geo_pose_projector/package.xml b/localization/geo_pose_projector/package.xml index d424ff14b9c99..c0e2db59deb64 100644 --- a/localization/geo_pose_projector/package.xml +++ b/localization/geo_pose_projector/package.xml @@ -6,6 +6,12 @@ The geo_pose_projector package Yamato Ando Koji Minoda + Masahiro Sakamoto + Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 Koji Minoda diff --git a/localization/gyro_odometer/package.xml b/localization/gyro_odometer/package.xml index ad4a865a2014a..a0a982ddedc16 100644 --- a/localization/gyro_odometer/package.xml +++ b/localization/gyro_odometer/package.xml @@ -6,6 +6,11 @@ The gyro_odometer package as a ROS 2 node Yamato Ando Masahiro Sakamoto + Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 Yamato Ando diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index 857ec4f16f051..072479cc7aaf5 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -8,6 +8,9 @@ Masahiro Sakamoto Yamato Ando Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Ryu Yamamoto Apache License 2.0 ament_cmake diff --git a/localization/landmark_based_localizer/landmark_manager/package.xml b/localization/landmark_based_localizer/landmark_manager/package.xml index 2e0e252386d1f..be19de9334e84 100644 --- a/localization/landmark_based_localizer/landmark_manager/package.xml +++ b/localization/landmark_based_localizer/landmark_manager/package.xml @@ -8,6 +8,9 @@ Masahiro Sakamoto Yamato Ando Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Ryu Yamamoto Apache License 2.0 ament_cmake diff --git a/localization/localization_error_monitor/package.xml b/localization/localization_error_monitor/package.xml index 266ae6c848834..a1b352d911a0d 100644 --- a/localization/localization_error_monitor/package.xml +++ b/localization/localization_error_monitor/package.xml @@ -7,6 +7,11 @@ Yamato Ando Koji Minoda Masahiro Sakamoto + Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 Taichi Higashide diff --git a/localization/localization_util/package.xml b/localization/localization_util/package.xml index 20f9b160212b5..fa8da2aa1231a 100644 --- a/localization/localization_util/package.xml +++ b/localization/localization_util/package.xml @@ -8,6 +8,9 @@ Masahiro Sakamoto Shintaro Sakoda Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Ryu Yamamoto Apache License 2.0 Yamato Ando diff --git a/localization/ndt_scan_matcher/package.xml b/localization/ndt_scan_matcher/package.xml index dcfdd77cb5a18..0913ee04174f5 100644 --- a/localization/ndt_scan_matcher/package.xml +++ b/localization/ndt_scan_matcher/package.xml @@ -8,6 +8,10 @@ Kento Yabuuchi Koji Minoda Masahiro Sakamoto + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 Yamato Ando diff --git a/localization/pose2twist/package.xml b/localization/pose2twist/package.xml index 83bce5a718334..16c49bb51c218 100644 --- a/localization/pose2twist/package.xml +++ b/localization/pose2twist/package.xml @@ -6,6 +6,11 @@ The pose2twist package Yamato Ando Masahiro Sakamoto + Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 Yamato Ando diff --git a/localization/pose_initializer/package.xml b/localization/pose_initializer/package.xml index 1a1a8e48b7e3b..85c9c26bd6c8c 100644 --- a/localization/pose_initializer/package.xml +++ b/localization/pose_initializer/package.xml @@ -7,6 +7,11 @@ Yamato Ando Takagi, Isamu Masahiro Sakamoto + Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 Yamato Ando Takagi, Isamu diff --git a/localization/pose_instability_detector/package.xml b/localization/pose_instability_detector/package.xml index 7774407a7990d..bf57e5589b747 100644 --- a/localization/pose_instability_detector/package.xml +++ b/localization/pose_instability_detector/package.xml @@ -10,6 +10,7 @@ Taiki Yamada Ryu Yamamoto Shintaro Sakoda + NGUYEN Viet Anh Apache License 2.0 Shintaro Sakoda diff --git a/localization/stop_filter/package.xml b/localization/stop_filter/package.xml index b17809aaa9948..83eaf1b9fa821 100644 --- a/localization/stop_filter/package.xml +++ b/localization/stop_filter/package.xml @@ -7,6 +7,11 @@ Koji Minoda Yamato Ando Masahiro Sakamoto + Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 Koji Minoda diff --git a/localization/tree_structured_parzen_estimator/package.xml b/localization/tree_structured_parzen_estimator/package.xml index b699d5c69e610..96d2b9ecf54cc 100644 --- a/localization/tree_structured_parzen_estimator/package.xml +++ b/localization/tree_structured_parzen_estimator/package.xml @@ -8,6 +8,9 @@ Masahiro Sakamoto Shintaro Sakoda Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Ryu Yamamoto Apache License 2.0 Shintaro Sakoda diff --git a/localization/twist2accel/package.xml b/localization/twist2accel/package.xml index c44cd9d144566..08dacf9185769 100644 --- a/localization/twist2accel/package.xml +++ b/localization/twist2accel/package.xml @@ -7,6 +7,11 @@ Koji Minoda Yamato Ando Masahiro Sakamoto + Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 Koji Minoda diff --git a/localization/yabloc/yabloc_common/package.xml b/localization/yabloc/yabloc_common/package.xml index d7e94ebefa24b..710ec0aeb75f8 100644 --- a/localization/yabloc/yabloc_common/package.xml +++ b/localization/yabloc/yabloc_common/package.xml @@ -5,6 +5,11 @@ YabLoc common library Kento Yabuuchi Masahiro Sakamoto + Yamato Ando + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 ament_cmake_ros diff --git a/localization/yabloc/yabloc_image_processing/package.xml b/localization/yabloc/yabloc_image_processing/package.xml index ffdcea25b4b6d..209f09fdaa7ac 100644 --- a/localization/yabloc/yabloc_image_processing/package.xml +++ b/localization/yabloc/yabloc_image_processing/package.xml @@ -6,6 +6,11 @@ YabLoc image processing package Kento Yabuuchi Masahiro Sakamoto + Yamato Ando + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 ament_cmake diff --git a/localization/yabloc/yabloc_monitor/package.xml b/localization/yabloc/yabloc_monitor/package.xml index 8c92c3c6a4303..22a5d0eded6b6 100644 --- a/localization/yabloc/yabloc_monitor/package.xml +++ b/localization/yabloc/yabloc_monitor/package.xml @@ -7,6 +7,11 @@ Kento Yabuuchi Koji Minoda Masahiro Sakamoto + Yamato Ando + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 ament_cmake_ros diff --git a/localization/yabloc/yabloc_particle_filter/package.xml b/localization/yabloc/yabloc_particle_filter/package.xml index aabb6009c2148..5db4aa0c29e88 100644 --- a/localization/yabloc/yabloc_particle_filter/package.xml +++ b/localization/yabloc/yabloc_particle_filter/package.xml @@ -6,6 +6,11 @@ YabLoc particle filter package Kento Yabuuchi Masahiro Sakamoto + Yamato Ando + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 ament_cmake_ros diff --git a/localization/yabloc/yabloc_pose_initializer/package.xml b/localization/yabloc/yabloc_pose_initializer/package.xml index 4e3ca1c1e61d1..e9921db50093e 100644 --- a/localization/yabloc/yabloc_pose_initializer/package.xml +++ b/localization/yabloc/yabloc_pose_initializer/package.xml @@ -5,6 +5,11 @@ The pose initializer Kento Yabuuchi Masahiro Sakamoto + Yamato Ando + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 ament_cmake_ros diff --git a/map/map_height_fitter/package.xml b/map/map_height_fitter/package.xml index 2dc864b0cb925..85258a8e54b22 100644 --- a/map/map_height_fitter/package.xml +++ b/map/map_height_fitter/package.xml @@ -8,6 +8,10 @@ Yamato Ando Masahiro Sakamoto Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 Takagi, Isamu diff --git a/map/map_loader/package.xml b/map/map_loader/package.xml index c8fcce6f7002f..0103c7d2b74a7 100644 --- a/map/map_loader/package.xml +++ b/map/map_loader/package.xml @@ -9,6 +9,9 @@ Koji Minoda Masahiro Sakamoto Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda Apache License 2.0 diff --git a/map/map_projection_loader/package.xml b/map/map_projection_loader/package.xml index 76e40d4379de4..475881577bd58 100644 --- a/map/map_projection_loader/package.xml +++ b/map/map_projection_loader/package.xml @@ -8,6 +8,10 @@ Yamato Ando Masahiro Sakamoto Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 ament_cmake_auto diff --git a/map/map_tf_generator/package.xml b/map/map_tf_generator/package.xml index 6e266b0ad82f0..6f08da169309e 100644 --- a/map/map_tf_generator/package.xml +++ b/map/map_tf_generator/package.xml @@ -7,6 +7,10 @@ Yamato Ando Kento Yabuuchi Masahiro Sakamoto + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto Apache License 2.0 ament_cmake_auto From 53dc6a5b8b2f8141569b5131f3a9bb99ebd05f9e Mon Sep 17 00:00:00 2001 From: Ioannis Souflas Date: Wed, 17 Jan 2024 15:07:15 +0200 Subject: [PATCH 256/276] feat(obstacle_cruise_planner): add calculation of obstacle distance to ego (#6057) Add the arc length from the ego to the obstacle stop point to the stop_reasons topic. Signed-off-by: Ioannis Souflas Signed-off-by: karishma --- .../obstacle_cruise_planner/src/planner_interface.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index f00ad01efb0d9..f7ce218cf3ccf 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -37,19 +37,21 @@ StopSpeedExceeded createStopSpeedExceededMsg( } tier4_planning_msgs::msg::StopReasonArray makeStopReasonArray( - const rclcpp::Time & current_time, const geometry_msgs::msg::Pose & stop_pose, + const PlannerData & planner_data, const geometry_msgs::msg::Pose & stop_pose, const StopObstacle & stop_obstacle) { // create header std_msgs::msg::Header header; header.frame_id = "map"; - header.stamp = current_time; + header.stamp = planner_data.current_time; // create stop factor StopFactor stop_factor; stop_factor.stop_pose = stop_pose; geometry_msgs::msg::Point stop_factor_point = stop_obstacle.collision_point; stop_factor_point.z = stop_pose.position.z; + stop_factor.dist_to_stop_pose = motion_utils::calcSignedArcLength( + planner_data.traj_points, planner_data.ego_pose.position, stop_pose.position); stop_factor.stop_factor_points.emplace_back(stop_factor_point); // create stop reason stamped @@ -359,7 +361,7 @@ std::vector PlannerInterface::generateStopTrajectory( // Publish Stop Reason const auto stop_pose = output_traj_points.at(*zero_vel_idx).pose; const auto stop_reasons_msg = - makeStopReasonArray(planner_data.current_time, stop_pose, *closest_stop_obstacle); + makeStopReasonArray(planner_data, stop_pose, *closest_stop_obstacle); stop_reasons_pub_->publish(stop_reasons_msg); velocity_factors_pub_->publish(makeVelocityFactorArray(planner_data.current_time, stop_pose)); From 17aca88e96e24562f29dd80c8f025446ea843d61 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Wed, 17 Jan 2024 23:14:07 +0900 Subject: [PATCH 257/276] fix: rename `score_threshold` into `score_thresh` in config (#6098) Signed-off-by: karishma --- perception/tensorrt_yolo/config/yolov3.param.yaml | 2 +- perception/tensorrt_yolo/config/yolov4-tiny.param.yaml | 2 +- perception/tensorrt_yolo/config/yolov4.param.yaml | 2 +- perception/tensorrt_yolo/config/yolov5l.param.yaml | 2 +- perception/tensorrt_yolo/config/yolov5m.param.yaml | 2 +- perception/tensorrt_yolo/config/yolov5s.param.yaml | 2 +- perception/tensorrt_yolo/config/yolov5x.param.yaml | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/perception/tensorrt_yolo/config/yolov3.param.yaml b/perception/tensorrt_yolo/config/yolov3.param.yaml index 5ce50f3acfa96..d97505dae5020 100644 --- a/perception/tensorrt_yolo/config/yolov3.param.yaml +++ b/perception/tensorrt_yolo/config/yolov3.param.yaml @@ -3,7 +3,7 @@ num_anchors: 3 anchors: [116.0, 90.0, 156.0, 198.0, 373.0, 326.0, 30.0, 61.0, 62.0, 45.0, 59.0, 119.0, 10.0, 13.0, 16.0, 30.0, 33.0, 23.0] scale_x_y: [1.0, 1.0, 1.0] - score_threshold: 0.1 + score_thresh: 0.1 iou_thresh: 0.45 detections_per_im: 100 use_darknet_layer: true diff --git a/perception/tensorrt_yolo/config/yolov4-tiny.param.yaml b/perception/tensorrt_yolo/config/yolov4-tiny.param.yaml index 2ee53ee68f764..8071da9dcac06 100644 --- a/perception/tensorrt_yolo/config/yolov4-tiny.param.yaml +++ b/perception/tensorrt_yolo/config/yolov4-tiny.param.yaml @@ -3,7 +3,7 @@ num_anchors: 3 anchors: [81.0, 82.0, 135.0, 169.0, 344.0, 319.0, 23.0, 27.0, 37.0, 58.0, 81.0, 82.0] scale_x_y: [1.05, 1.05] - score_threshold: 0.1 + score_thresh: 0.1 iou_thresh: 0.45 detections_per_im: 100 use_darknet_layer: true diff --git a/perception/tensorrt_yolo/config/yolov4.param.yaml b/perception/tensorrt_yolo/config/yolov4.param.yaml index 6122af667c470..9edc0fc6ce708 100644 --- a/perception/tensorrt_yolo/config/yolov4.param.yaml +++ b/perception/tensorrt_yolo/config/yolov4.param.yaml @@ -3,7 +3,7 @@ num_anchors: 3 anchors: [12.0, 16.0, 19.0, 36.0, 40.0, 28.0, 36.0, 75.0, 76.0, 55.0, 72.0, 146.0, 142.0, 110.0, 192.0, 243.0, 459.0, 401.0] scale_x_y: [1.2, 1.1, 1.05] - score_threshold: 0.1 + score_thresh: 0.1 iou_thresh: 0.45 detections_per_im: 100 use_darknet_layer: true diff --git a/perception/tensorrt_yolo/config/yolov5l.param.yaml b/perception/tensorrt_yolo/config/yolov5l.param.yaml index 8a709d057594b..67ae862fc33af 100644 --- a/perception/tensorrt_yolo/config/yolov5l.param.yaml +++ b/perception/tensorrt_yolo/config/yolov5l.param.yaml @@ -3,7 +3,7 @@ num_anchors: 3 anchors: [10.0, 13.0, 16.0, 30.0, 33.0, 23.0, 30.0, 61.0, 62.0, 45.0, 59.0, 119.0, 116.0, 90.0, 156.0, 198.0, 373.0, 326.0] scale_x_y: [1.0, 1.0, 1.0] - score_threshold: 0.1 + score_thresh: 0.1 iou_thresh: 0.45 detections_per_im: 100 use_darknet_layer: false diff --git a/perception/tensorrt_yolo/config/yolov5m.param.yaml b/perception/tensorrt_yolo/config/yolov5m.param.yaml index 8a709d057594b..67ae862fc33af 100644 --- a/perception/tensorrt_yolo/config/yolov5m.param.yaml +++ b/perception/tensorrt_yolo/config/yolov5m.param.yaml @@ -3,7 +3,7 @@ num_anchors: 3 anchors: [10.0, 13.0, 16.0, 30.0, 33.0, 23.0, 30.0, 61.0, 62.0, 45.0, 59.0, 119.0, 116.0, 90.0, 156.0, 198.0, 373.0, 326.0] scale_x_y: [1.0, 1.0, 1.0] - score_threshold: 0.1 + score_thresh: 0.1 iou_thresh: 0.45 detections_per_im: 100 use_darknet_layer: false diff --git a/perception/tensorrt_yolo/config/yolov5s.param.yaml b/perception/tensorrt_yolo/config/yolov5s.param.yaml index 8a709d057594b..67ae862fc33af 100644 --- a/perception/tensorrt_yolo/config/yolov5s.param.yaml +++ b/perception/tensorrt_yolo/config/yolov5s.param.yaml @@ -3,7 +3,7 @@ num_anchors: 3 anchors: [10.0, 13.0, 16.0, 30.0, 33.0, 23.0, 30.0, 61.0, 62.0, 45.0, 59.0, 119.0, 116.0, 90.0, 156.0, 198.0, 373.0, 326.0] scale_x_y: [1.0, 1.0, 1.0] - score_threshold: 0.1 + score_thresh: 0.1 iou_thresh: 0.45 detections_per_im: 100 use_darknet_layer: false diff --git a/perception/tensorrt_yolo/config/yolov5x.param.yaml b/perception/tensorrt_yolo/config/yolov5x.param.yaml index 8a709d057594b..67ae862fc33af 100644 --- a/perception/tensorrt_yolo/config/yolov5x.param.yaml +++ b/perception/tensorrt_yolo/config/yolov5x.param.yaml @@ -3,7 +3,7 @@ num_anchors: 3 anchors: [10.0, 13.0, 16.0, 30.0, 33.0, 23.0, 30.0, 61.0, 62.0, 45.0, 59.0, 119.0, 116.0, 90.0, 156.0, 198.0, 373.0, 326.0] scale_x_y: [1.0, 1.0, 1.0] - score_threshold: 0.1 + score_thresh: 0.1 iou_thresh: 0.45 detections_per_im: 100 use_darknet_layer: false From af49451239fb970ef3e73bb61eb07e0c42996a04 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 18 Jan 2024 02:20:37 +0900 Subject: [PATCH 258/276] chore: update api package maintainers (#6086) * update api maintainers Signed-off-by: Takagi, Isamu * fix Signed-off-by: Takagi, Isamu --------- Signed-off-by: Takagi, Isamu Signed-off-by: karishma --- common/autoware_ad_api_specs/package.xml | 2 -- common/component_interface_specs/package.xml | 2 -- common/component_interface_tools/package.xml | 2 -- common/component_interface_utils/package.xml | 2 -- common/path_distance_calculator/package.xml | 2 -- common/tier4_api_utils/package.xml | 2 -- common/tier4_datetime_rviz_plugin/package.xml | 2 -- common/tier4_localization_rviz_plugin/package.xml | 2 -- launch/tier4_autoware_api_launch/package.xml | 2 -- system/component_state_monitor/package.xml | 2 -- system/default_ad_api/package.xml | 2 -- system/default_ad_api_helpers/ad_api_adaptors/package.xml | 2 -- system/default_ad_api_helpers/ad_api_visualizers/package.xml | 2 -- .../automatic_pose_initializer/package.xml | 2 -- 14 files changed, 28 deletions(-) diff --git a/common/autoware_ad_api_specs/package.xml b/common/autoware_ad_api_specs/package.xml index d4d82faf4ee78..0d14ccff758b0 100644 --- a/common/autoware_ad_api_specs/package.xml +++ b/common/autoware_ad_api_specs/package.xml @@ -5,8 +5,6 @@ 0.0.0 The autoware_ad_api_specs package Takagi, Isamu - yabuta - Kah Hooi Tan Ryohsuke Mitsudome Apache License 2.0 diff --git a/common/component_interface_specs/package.xml b/common/component_interface_specs/package.xml index 93f77c651869d..67279d0ae2b7f 100644 --- a/common/component_interface_specs/package.xml +++ b/common/component_interface_specs/package.xml @@ -5,8 +5,6 @@ 0.0.0 The component_interface_specs package Takagi, Isamu - yabuta - Kah Hooi Tan Yukihiro Saito Apache License 2.0 diff --git a/common/component_interface_tools/package.xml b/common/component_interface_tools/package.xml index ebf0684d0066c..cff1829473e86 100644 --- a/common/component_interface_tools/package.xml +++ b/common/component_interface_tools/package.xml @@ -5,8 +5,6 @@ 0.1.0 The component_interface_tools package Takagi, Isamu - yabuta - Kah Hooi Tan Apache License 2.0 ament_cmake_auto diff --git a/common/component_interface_utils/package.xml b/common/component_interface_utils/package.xml index dc82fda3f5c64..7a6a6d12880ad 100755 --- a/common/component_interface_utils/package.xml +++ b/common/component_interface_utils/package.xml @@ -5,8 +5,6 @@ 0.0.0 The component_interface_utils package Takagi, Isamu - yabuta - Kah Hooi Tan Yukihiro Saito Apache License 2.0 diff --git a/common/path_distance_calculator/package.xml b/common/path_distance_calculator/package.xml index b5e770a0ea624..e796bbd0d20f7 100644 --- a/common/path_distance_calculator/package.xml +++ b/common/path_distance_calculator/package.xml @@ -5,8 +5,6 @@ 0.0.0 The path_distance_calculator package Takagi, Isamu - yabuta - Kah Hooi Tan Apache License 2.0 ament_cmake diff --git a/common/tier4_api_utils/package.xml b/common/tier4_api_utils/package.xml index 091f512480150..d05b810caf904 100644 --- a/common/tier4_api_utils/package.xml +++ b/common/tier4_api_utils/package.xml @@ -5,8 +5,6 @@ 0.0.0 The tier4_api_utils package Takagi, Isamu - yabuta - Kah Hooi Tan Apache License 2.0 ament_cmake_auto diff --git a/common/tier4_datetime_rviz_plugin/package.xml b/common/tier4_datetime_rviz_plugin/package.xml index 6dc0c09b32a3b..82e1e82c61ba2 100644 --- a/common/tier4_datetime_rviz_plugin/package.xml +++ b/common/tier4_datetime_rviz_plugin/package.xml @@ -5,8 +5,6 @@ 0.0.0 The tier4_datetime_rviz_plugin package Takagi, Isamu - yabuta - Kah Hooi Tan Apache License 2.0 ament_cmake_auto diff --git a/common/tier4_localization_rviz_plugin/package.xml b/common/tier4_localization_rviz_plugin/package.xml index e103db19f1d43..f2482b2d45a3b 100644 --- a/common/tier4_localization_rviz_plugin/package.xml +++ b/common/tier4_localization_rviz_plugin/package.xml @@ -5,8 +5,6 @@ 0.1.0 The tier4_localization_rviz_plugin package Takagi, Isamu - yabuta - Kah Hooi Tan Takamasa Horibe Apache License 2.0 diff --git a/launch/tier4_autoware_api_launch/package.xml b/launch/tier4_autoware_api_launch/package.xml index 4d41ad0ac4a83..c55f1c8038e83 100644 --- a/launch/tier4_autoware_api_launch/package.xml +++ b/launch/tier4_autoware_api_launch/package.xml @@ -5,8 +5,6 @@ 0.0.0 The tier4_autoware_api_launch package Takagi, Isamu - yabuta - Kah Hooi Tan Ryohsuke Mitsudome Apache License 2.0 diff --git a/system/component_state_monitor/package.xml b/system/component_state_monitor/package.xml index 60d0fd0577ef0..16903fa216174 100644 --- a/system/component_state_monitor/package.xml +++ b/system/component_state_monitor/package.xml @@ -5,8 +5,6 @@ 0.1.0 The component_state_monitor package Takagi, Isamu - yabuta - Kah Hooi Tan Apache License 2.0 ament_cmake_auto diff --git a/system/default_ad_api/package.xml b/system/default_ad_api/package.xml index 6a9a22f39cdc4..4e691f7ab3192 100644 --- a/system/default_ad_api/package.xml +++ b/system/default_ad_api/package.xml @@ -5,8 +5,6 @@ 0.1.0 The default_ad_api package Takagi, Isamu - Kah Hooi Tan - yabuta Ryohsuke Mitsudome Yukihiro Saito Apache License 2.0 diff --git a/system/default_ad_api_helpers/ad_api_adaptors/package.xml b/system/default_ad_api_helpers/ad_api_adaptors/package.xml index e54a5faa6e1b7..785ff58db1f81 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/package.xml +++ b/system/default_ad_api_helpers/ad_api_adaptors/package.xml @@ -5,8 +5,6 @@ 0.1.0 The ad_api_adaptors package Takagi, Isamu - Kah Hooi Tan - yabuta Ryohsuke Mitsudome Yukihiro Saito Apache License 2.0 diff --git a/system/default_ad_api_helpers/ad_api_visualizers/package.xml b/system/default_ad_api_helpers/ad_api_visualizers/package.xml index 95961769813cd..75fd09a1335b1 100644 --- a/system/default_ad_api_helpers/ad_api_visualizers/package.xml +++ b/system/default_ad_api_helpers/ad_api_visualizers/package.xml @@ -5,8 +5,6 @@ 0.1.0 The ad_api_visualizers package Takagi, Isamu - Kah Hooi Tan - yabuta Ryohsuke Mitsudome Yukihiro Saito Apache License 2.0 diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml b/system/default_ad_api_helpers/automatic_pose_initializer/package.xml index 10f4abfe446fb..be192c3dade4b 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml +++ b/system/default_ad_api_helpers/automatic_pose_initializer/package.xml @@ -5,8 +5,6 @@ 0.1.0 The automatic_pose_initializer package Takagi, Isamu - Kah Hooi Tan - yabuta Ryohsuke Mitsudome Yukihiro Saito Apache License 2.0 From f70bbdc39e50971891a80df6b11c20b90d8606f0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 18 Jan 2024 05:55:13 +0900 Subject: [PATCH 259/276] feat(rviz_plugin): add string visualization plugin (#6100) Signed-off-by: satoshi-ota Signed-off-by: karishma --- common/tier4_debug_rviz_plugin/CMakeLists.txt | 2 + .../classes/StringStampedOverlayDisplay.png | Bin 0 -> 18815 bytes .../string_stamped.hpp | 107 ++++++++++ .../plugins/plugin_description.xml | 5 + .../src/string_stamped.cpp | 198 ++++++++++++++++++ 5 files changed, 312 insertions(+) create mode 100644 common/tier4_debug_rviz_plugin/icons/classes/StringStampedOverlayDisplay.png create mode 100644 common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/string_stamped.hpp create mode 100644 common/tier4_debug_rviz_plugin/src/string_stamped.cpp diff --git a/common/tier4_debug_rviz_plugin/CMakeLists.txt b/common/tier4_debug_rviz_plugin/CMakeLists.txt index 05cf35b93ef9f..02e65ad759ed6 100644 --- a/common/tier4_debug_rviz_plugin/CMakeLists.txt +++ b/common/tier4_debug_rviz_plugin/CMakeLists.txt @@ -12,7 +12,9 @@ add_definitions(-DQT_NO_KEYWORDS) ament_auto_add_library(tier4_debug_rviz_plugin SHARED include/tier4_debug_rviz_plugin/float32_multi_array_stamped_pie_chart.hpp include/tier4_debug_rviz_plugin/jsk_overlay_utils.hpp + include/tier4_debug_rviz_plugin/string_stamped.hpp src/float32_multi_array_stamped_pie_chart.cpp + src/string_stamped.cpp src/jsk_overlay_utils.cpp ) diff --git a/common/tier4_debug_rviz_plugin/icons/classes/StringStampedOverlayDisplay.png b/common/tier4_debug_rviz_plugin/icons/classes/StringStampedOverlayDisplay.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_debug_rviz_plugin/include/tier4_debug_rviz_plugin/string_stamped.hpp b/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/string_stamped.hpp new file mode 100644 index 0000000000000..0960875d7eee2 --- /dev/null +++ b/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/string_stamped.hpp @@ -0,0 +1,107 @@ +// 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. + +// Copyright (c) 2014, JSK Lab +// All rights reserved. +// +// Software License Agreement (BSD License) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of {copyright_holder} nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE.S SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#ifndef TIER4_DEBUG_RVIZ_PLUGIN__STRING_STAMPED_HPP_ +#define TIER4_DEBUG_RVIZ_PLUGIN__STRING_STAMPED_HPP_ + +#include +#include + +#ifndef Q_MOC_RUN +#include "tier4_debug_rviz_plugin/jsk_overlay_utils.hpp" + +#include +#include +#include +#include + +#endif + +#include + +namespace rviz_plugins +{ +class StringStampedOverlayDisplay +: public rviz_common::RosTopicDisplay + +{ + Q_OBJECT + +public: + StringStampedOverlayDisplay(); + ~StringStampedOverlayDisplay() override; + + void onInitialize() override; + void onEnable() override; + void onDisable() override; + +private Q_SLOTS: + void updateVisualization(); + +protected: + void update(float wall_dt, float ros_dt) override; + void processMessage(const tier4_debug_msgs::msg::StringStamped::ConstSharedPtr msg_ptr) override; + jsk_rviz_plugins::OverlayObject::Ptr overlay_; + rviz_common::properties::ColorProperty * property_text_color_; + rviz_common::properties::IntProperty * property_left_; + rviz_common::properties::IntProperty * property_top_; + rviz_common::properties::IntProperty * property_value_height_offset_; + rviz_common::properties::FloatProperty * property_value_scale_; + rviz_common::properties::IntProperty * property_font_size_; + rviz_common::properties::IntProperty * property_max_letter_num_; + // QImage hud_; + +private: + static constexpr int line_width_ = 2; + static constexpr int hand_width_ = 4; + + std::mutex mutex_; + tier4_debug_msgs::msg::StringStamped::ConstSharedPtr last_msg_ptr_; +}; +} // namespace rviz_plugins + +#endif // TIER4_DEBUG_RVIZ_PLUGIN__STRING_STAMPED_HPP_ diff --git a/common/tier4_debug_rviz_plugin/plugins/plugin_description.xml b/common/tier4_debug_rviz_plugin/plugins/plugin_description.xml index c1158465e1cf1..e18900afc8d84 100644 --- a/common/tier4_debug_rviz_plugin/plugins/plugin_description.xml +++ b/common/tier4_debug_rviz_plugin/plugins/plugin_description.xml @@ -4,4 +4,9 @@ base_class_type="rviz_common::Display"> Display drivable area of tier4_debug_msgs::msg::Float32MultiArrayStamped + + Display drivable area of tier4_debug_msgs::msg::StringStamped +
diff --git a/common/tier4_debug_rviz_plugin/src/string_stamped.cpp b/common/tier4_debug_rviz_plugin/src/string_stamped.cpp new file mode 100644 index 0000000000000..538dc0cbe7069 --- /dev/null +++ b/common/tier4_debug_rviz_plugin/src/string_stamped.cpp @@ -0,0 +1,198 @@ +// 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. + +// Copyright (c) 2014, JSK Lab +// All rights reserved. +// +// Software License Agreement (BSD License) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of {copyright_holder} nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE.S SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#include "tier4_debug_rviz_plugin/string_stamped.hpp" + +#include "tier4_debug_rviz_plugin/jsk_overlay_utils.hpp" + +#include +#include + +#include + +#include +#include +#include +#include + +namespace rviz_plugins +{ +StringStampedOverlayDisplay::StringStampedOverlayDisplay() +{ + const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL)); + + constexpr float hight_4k = 2160.0; + const float scale = static_cast(screen_info->height) / hight_4k; + const auto left = static_cast(std::round(1024 * scale)); + const auto top = static_cast(std::round(128 * scale)); + + property_text_color_ = new rviz_common::properties::ColorProperty( + "Text Color", QColor(25, 255, 240), "text color", this, SLOT(updateVisualization()), this); + property_left_ = new rviz_common::properties::IntProperty( + "Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this); + property_left_->setMin(0); + property_top_ = new rviz_common::properties::IntProperty( + "Top", top, "Top of the plotter window", this, SLOT(updateVisualization())); + property_top_->setMin(0); + + property_value_height_offset_ = new rviz_common::properties::IntProperty( + "Value height offset", 0, "Height offset of the plotter window", this, + SLOT(updateVisualization())); + property_font_size_ = new rviz_common::properties::IntProperty( + "Font Size", 15, "Font Size", this, SLOT(updateVisualization()), this); + property_font_size_->setMin(1); + property_max_letter_num_ = new rviz_common::properties::IntProperty( + "Max Letter Num", 100, "Max Letter Num", this, SLOT(updateVisualization()), this); + property_max_letter_num_->setMin(10); +} + +StringStampedOverlayDisplay::~StringStampedOverlayDisplay() +{ + if (initialized()) { + overlay_->hide(); + } +} + +void StringStampedOverlayDisplay::onInitialize() +{ + RTDClass::onInitialize(); + + static int count = 0; + rviz_common::UniformStringStream ss; + ss << "StringOverlayDisplayObject" << count++; + auto logger = context_->getRosNodeAbstraction().lock()->get_raw_node()->get_logger(); + overlay_.reset(new jsk_rviz_plugins::OverlayObject(scene_manager_, logger, ss.str())); + + overlay_->show(); + + const int texture_size = property_font_size_->getInt() * property_max_letter_num_->getInt(); + overlay_->updateTextureSize(texture_size, texture_size); + overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); + overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); +} + +void StringStampedOverlayDisplay::onEnable() +{ + subscribe(); + overlay_->show(); +} + +void StringStampedOverlayDisplay::onDisable() +{ + unsubscribe(); + reset(); + overlay_->hide(); +} + +void StringStampedOverlayDisplay::update(float wall_dt, float ros_dt) +{ + (void)wall_dt; + (void)ros_dt; + + std::lock_guard message_lock(mutex_); + if (!last_msg_ptr_) { + return; + } + + // Display + QColor background_color; + background_color.setAlpha(0); + jsk_rviz_plugins::ScopedPixelBuffer buffer = overlay_->getBuffer(); + QImage hud = buffer.getQImage(*overlay_); + hud.fill(background_color); + + QPainter painter(&hud); + painter.setRenderHint(QPainter::Antialiasing, true); + + const int w = overlay_->getTextureWidth() - line_width_; + const int h = overlay_->getTextureHeight() - line_width_; + + // text + QColor text_color(property_text_color_->getColor()); + text_color.setAlpha(255); + painter.setPen(QPen(text_color, static_cast(2), Qt::SolidLine)); + QFont font = painter.font(); + font.setPixelSize(property_font_size_->getInt()); + font.setBold(true); + painter.setFont(font); + + // same as above, but align on right side + painter.drawText( + 0, std::min(property_value_height_offset_->getInt(), h - 1), w, + std::max(h - property_value_height_offset_->getInt(), 1), Qt::AlignLeft | Qt::AlignTop, + last_msg_ptr_->data.c_str()); + painter.end(); + updateVisualization(); +} + +void StringStampedOverlayDisplay::processMessage( + const tier4_debug_msgs::msg::StringStamped::ConstSharedPtr msg_ptr) +{ + if (!isEnabled()) { + return; + } + + { + std::lock_guard message_lock(mutex_); + last_msg_ptr_ = msg_ptr; + } + + queueRender(); +} + +void StringStampedOverlayDisplay::updateVisualization() +{ + const int texture_size = property_font_size_->getInt() * property_max_letter_num_->getInt(); + overlay_->updateTextureSize(texture_size, texture_size); + overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); + overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); +} + +} // namespace rviz_plugins + +#include +PLUGINLIB_EXPORT_CLASS(rviz_plugins::StringStampedOverlayDisplay, rviz_common::Display) From 86022c98deb040f36d67f2118bac2f962017b4d8 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 18 Jan 2024 08:14:33 +0900 Subject: [PATCH 260/276] feat(behavior_path_planner): output manager internal state as topic (#6099) Signed-off-by: satoshi-ota Signed-off-by: karishma --- .../include/behavior_path_planner/planner_manager.hpp | 3 +++ .../behavior_path_planner/src/planner_manager.cpp | 11 +++++++---- 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index f6f95ae3b5e82..5e773eba96aee 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -46,6 +46,7 @@ using SceneModulePtr = std::shared_ptr; using SceneModuleManagerPtr = std::shared_ptr; using DebugPublisher = tier4_autoware_utils::DebugPublisher; using DebugDoubleMsg = tier4_debug_msgs::msg::Float64Stamped; +using DebugStringMsg = tier4_debug_msgs::msg::StringStamped; enum Action { ADD = 0, @@ -456,6 +457,8 @@ class PlannerManager std::unique_ptr debug_publisher_ptr_; + std::unique_ptr state_publisher_ptr_; + pluginlib::ClassLoader plugin_loader_; mutable rclcpp::Logger logger_; diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index a1d0a82be38b1..cbcec2e3095d3 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -40,6 +40,7 @@ PlannerManager::PlannerManager( { processing_time_.emplace("total_time", 0.0); debug_publisher_ptr_ = std::make_unique(&node, "~/debug"); + state_publisher_ptr_ = std::make_unique(&node, "~/debug"); } void PlannerManager::launchScenePlugin(rclcpp::Node & node, const std::string & name) @@ -908,10 +909,6 @@ void PlannerManager::resetRootLanelet(const std::shared_ptr & data) void PlannerManager::print() const { - if (!verbose_) { - return; - } - const auto get_status = [](const auto & m) { return magic_enum::enum_name(m->getCurrentStatus()); }; @@ -961,6 +958,12 @@ void PlannerManager::print() const << std::setw(21); } + state_publisher_ptr_->publish("internal_state", string_stream.str()); + + if (!verbose_) { + return; + } + RCLCPP_INFO_STREAM(logger_, string_stream.str()); } From 2355fde4d57181fc865478abfceed8d8c57fdbfd Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 18 Jan 2024 11:10:42 +0900 Subject: [PATCH 261/276] refactor(goal_planner): remove duplicated execution condition (#6087) Signed-off-by: kosuke55 Signed-off-by: karishma --- .../src/goal_planner_module.cpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 3f765c99cffa9..a13344ee87e7c 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -458,13 +458,6 @@ bool GoalPlannerModule::isExecutionRequested() const return false; } - // if goal modification is not allowed - // 1) goal_pose is in current_lanes, plan path to the original fixed goal - // 2) goal_pose is NOT in current_lanes, do not execute goal_planner - if (!utils::isAllowedGoalModification(route_handler)) { - return goal_is_in_current_lanes; - } - // if (A) or (B) is met execute pull over // (A) target lane is `road` and same to the current lanes // (B) target lane is `road_shoulder` and neighboring to the current lanes From ab4cc684a0dc75bb3bcf09c1c58e865ded361599 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 18 Jan 2024 12:58:32 +0900 Subject: [PATCH 262/276] fix(behavior_velocity_planner, behavior_path_planner): refresh raw traffic light id map every callback (#6061) Signed-off-by: Mamoru Sobue Signed-off-by: karishma --- .../src/behavior_path_planner_node.cpp | 1 + planning/behavior_velocity_planner/src/node.cpp | 14 +++++++++++--- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 9b3fbedc37203..3eb5eca5954fb 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -784,6 +784,7 @@ void BehaviorPathPlannerNode::onTrafficSignals(const TrafficSignalArray::ConstSh { std::lock_guard lock(mutex_pd_); + planner_data_->traffic_light_id_map.clear(); for (const auto & signal : msg->signals) { TrafficSignalStamped traffic_signal; traffic_signal.stamp = msg->stamp; diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index e2c29ef868257..9fa5634c6dd65 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -323,6 +323,11 @@ void BehaviorVelocityPlannerNode::onTrafficSignals( { std::lock_guard lock(mutex_); + // clear previous observation + planner_data_.traffic_light_id_map_raw_.clear(); + const auto traffic_light_id_map_last_observed_old = + planner_data_.traffic_light_id_map_last_observed_; + planner_data_.traffic_light_id_map_last_observed_.clear(); for (const auto & signal : msg->signals) { TrafficSignalStamped traffic_signal; traffic_signal.stamp = msg->stamp; @@ -334,9 +339,12 @@ void BehaviorVelocityPlannerNode::onTrafficSignals( }); // if the observation is UNKNOWN and past observation is available, only update the timestamp // and keep the body of the info - if ( - is_unknown_observation && - planner_data_.traffic_light_id_map_last_observed_.count(signal.traffic_signal_id) == 1) { + const auto old_data = traffic_light_id_map_last_observed_old.find(signal.traffic_signal_id); + if (is_unknown_observation && old_data != traffic_light_id_map_last_observed_old.end()) { + // copy last observation + planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id] = + old_data->second; + // update timestamp planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id].stamp = msg->stamp; } else { From 5da6e87dc8e575ae37576fbbc8fe37aa3822c0dc Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Thu, 18 Jan 2024 13:23:40 +0900 Subject: [PATCH 263/276] fix(radar_tracks_msgs_converter): change default parameter for twist compensation (#6080) Signed-off-by: scepter914 Signed-off-by: karishma --- perception/radar_tracks_msgs_converter/README.md | 2 +- .../launch/radar_tracks_msgs_converter.launch.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/radar_tracks_msgs_converter/README.md b/perception/radar_tracks_msgs_converter/README.md index fb8f117c82245..fa08eb08f521a 100644 --- a/perception/radar_tracks_msgs_converter/README.md +++ b/perception/radar_tracks_msgs_converter/README.md @@ -23,7 +23,7 @@ This package converts from [radar_msgs/msg/RadarTracks](https://github.com/ros-p - `new_frame_id` (string): The header frame of the output topic. - Default parameter is "base_link" - `use_twist_compensation` (bool): If the parameter is true, then the twist of the output objects' topic is compensated by ego vehicle motion. - - Default parameter is "false" + - Default parameter is "true" - `use_twist_yaw_compensation` (bool): If the parameter is true, then the ego motion compensation will also consider yaw motion of the ego vehicle. - Default parameter is "false" - `static_object_speed_threshold` (float): Specify the threshold for static object speed which determines the flag `is_stationary` [m/s]. diff --git a/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml b/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml index a6a3f394b1f40..cc2bb80c6f4f7 100644 --- a/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml +++ b/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml @@ -4,7 +4,7 @@ - + From 0b6c53889af98f00358996a1ada25a6bd7dc6d11 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 18 Jan 2024 14:28:40 +0900 Subject: [PATCH 264/276] fix(pointpainting): fix param path declaration (#6106) * fix(pointpainting): fix param path declaration Signed-off-by: kminoda * remove pointpainting_model_name Signed-off-by: kminoda * revert: revert unnecessary change Signed-off-by: kminoda --------- Signed-off-by: kminoda Signed-off-by: karishma --- .../detection/camera_lidar_fusion_based_detection.launch.xml | 2 ++ .../camera_lidar_radar_fusion_based_detection.launch.xml | 2 ++ launch/tier4_perception_launch/launch/perception.launch.xml | 3 +++ 3 files changed, 7 insertions(+) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 10d1ac034d457..d269144067e0e 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -267,6 +267,8 @@ + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index c227298c932d9..4838187ef8fbe 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -296,6 +296,8 @@ + + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 87616b9ccb122..4e9f0daafa736 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -34,6 +34,9 @@ + + + From 4000c7b980144b5ef513dea38a833e2e60d620f2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 18 Jan 2024 16:14:22 +0900 Subject: [PATCH 265/276] docs(crosswalk): update the document (#5583) * docs(crosswalk): update the document Signed-off-by: Takayuki Murooka * fix the spell Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka Signed-off-by: karishma --- .../README.md | 359 ++++++++++-------- .../docs/crosswalk_attention_range.svg | 229 ++++------- .../docs/crosswalk_module.svg | 98 +++++ .../docs/debug_markers.png | Bin 0 -> 220365 bytes .../docs/explicit_stop_line.svg | 71 ++++ .../docs/far_object_threshold.drawio.svg | 114 ++++++ .../docs/limitation.svg | 164 -------- .../docs/no-intension.svg | 193 ---------- .../docs/stop_line.svg | 149 -------- .../docs/stop_line_distance.svg | 170 --------- .../docs/stop_line_margin.svg | 204 ---------- .../docs/stop_margin.svg | 144 ------- .../docs/stuck_vehicle_attention_range.svg | 174 --------- .../docs/stuck_vehicle_detection.svg | 93 +++++ .../docs/ttc_vs_ttv.drawio.svg | 210 ++++++++++ .../docs/virtual_collision_point.svg | 157 +++----- .../docs/virtual_stop_line.svg | 73 ++++ .../docs/with_traffic_light.svg | 97 +++++ .../docs/without_traffic_light.svg | 67 ++++ 19 files changed, 1141 insertions(+), 1625 deletions(-) create mode 100644 planning/behavior_velocity_crosswalk_module/docs/crosswalk_module.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/debug_markers.png create mode 100644 planning/behavior_velocity_crosswalk_module/docs/explicit_stop_line.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/far_object_threshold.drawio.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/limitation.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/no-intension.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/stop_line.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/stop_line_distance.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/stop_line_margin.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/stop_margin.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_attention_range.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_detection.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/virtual_stop_line.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/with_traffic_light.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/without_traffic_light.svg diff --git a/planning/behavior_velocity_crosswalk_module/README.md b/planning/behavior_velocity_crosswalk_module/README.md index 5f82fe839fda6..37c3fb58049a6 100644 --- a/planning/behavior_velocity_crosswalk_module/README.md +++ b/planning/behavior_velocity_crosswalk_module/README.md @@ -1,204 +1,169 @@ -## Crosswalk +# Crosswalk -### Role +## Role -This module judges whether the ego should stop in front of the crosswalk in order to provide safe passage of pedestrians and bicycles based on object's behavior and surround traffic. +This module judges whether the ego should stop in front of the crosswalk in order to provide safe passage of crosswalk users such as pedestrians and bicycles based on the objects' behavior and surround traffic.
- ![example](docs/example.png){width=1000} -
crosswalk module
+ ![crosswalk_module](docs/crosswalk_module.svg){width=1100}
-### Activation Timing +## Features -The manager launch crosswalk scene modules when the reference path conflicts crosswalk lanelets. +### Yield -### Module Parameters +#### Target Object -#### Common parameters +The target object's type is filtered by the following parameters in the `object_filtering.target_object` namespace. -| Parameter | Type | Description | -| ----------------------------- | ---- | ------------------------------- | -| `common.show_processing_time` | bool | whether to show processing time | +| Parameter | Unit | Type | Description | +| ------------ | ---- | ---- | ---------------------------------------------- | +| `unknown` | [-] | bool | whether to look and stop by UNKNOWN objects | +| `pedestrian` | [-] | bool | whether to look and stop by PEDESTRIAN objects | +| `bicycle` | [-] | bool | whether to look and stop by BICYCLE objects | +| `motorcycle` | [-] | bool | whether to look and stop by MOTORCYCLE objects | -#### Parameters for input data +In order to detect crosswalk users crossing outside the crosswalk as well, the crosswalk module creates an attention area around the crosswalk shown as the yellow polygon in the figure. If the object's predicted path collides with the attention area, the object will be targeted for yield. -| Parameter | Type | Description | -| ------------------------------------ | ------ | ---------------------------------------------- | -| `common.traffic_light_state_timeout` | double | [s] timeout threshold for traffic light signal | +
+ ![crosswalk_attention_range](docs/crosswalk_attention_range.svg){width=600} +
-#### Parameters for stop position +The parameter is in the `object_filtering.target_object` namespace. -The crosswalk module determines a stop position at least `stop_distance_from_object` away from the object. +| Parameter | Unit | Type | Description | +| --------------------------- | ---- | ------ | ------------------------------------------------------------------------------------------------- | +| `crosswalk_attention_range` | [m] | double | the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk | -
- ![stop_distance_from_object](docs/stop_margin.svg){width=1000} -
stop margin
-
+#### Stop Position -The stop line is the reference point for the stopping position of the vehicle, but if there is no stop line in front of the crosswalk, the position `stop_distance_from_crosswalk` meters before the crosswalk is the virtual stop line for the vehicle. Then, if the stop position determined from `stop_distance_from_object` exists in front of the stop line determined from the HDMap or `stop_distance_from_crosswalk`, the actual stop position is determined according to `stop_distance_from_object` in principle, and vice versa. +First of all, `stop_distance_from_object [m]` is always kept at least between the ego and the target object for safety. -
- ![stop_line](docs/stop_line.svg){width=700} -
explicit stop line
-
+When the stop line exists in the lanelet map, the stop position is calculated based on the line. +When the stop line does **NOT** exist in the lanelet map, the stop position is calculated by keeping `stop_distance_from_crosswalk [m]` between the ego and the crosswalk. -
- ![stop_distance_from_crosswalk](docs/stop_line_distance.svg){width=700} -
virtual stop point
-
+
+ + + + + +
+
On the other hand, if pedestrian (bicycle) is crossing **wide** crosswalks seen in scramble intersections, and the pedestrian position is more than `far_object_threshold` meters away from the stop line, the actual stop position is determined to be `stop_distance_from_object` and pedestrian position, not at the stop line.
- ![far_object_threshold](docs/stop_line_margin.svg){width=1000} -
stop at wide crosswalk
+ ![far_object_threshold](docs/far_object_threshold.drawio.svg){width=700}
-See the workflow in algorithms section. +In the `stop_position` namespace, -| Parameter | Type | Description | -| -------------------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `stop_position.stop_distance_from_object` | double | [m] the vehicle decelerates to be able to stop in front of object with margin | -| `stop_position.stop_distance_from_crosswalk` | double | [m] make stop line away from crosswalk when no explicit stop line exists | -| `stop_position.far_object_threshold` | double | [m] if objects cross X meters behind the stop line, the stop position is determined according to the object position (stop_distance_from_object meters before the object) | -| `stop_position.stop_position_threshold` | double | [m] threshold for check whether the vehicle stop in front of crosswalk | +| Parameter | | Type | Description | +| ------------------------------ | --- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `stop_position_threshold` | [m] | double | If the ego vehicle has stopped near the stop line than this value, this module assumes itself to have achieved yielding. | +| `stop_distance_from_crosswalk` | [m] | double | make stop line away from crosswalk for the Lanelet2 map with no explicit stop lines | +| `far_object_threshold` | [m] | double | If objects cross X meters behind the stop line, the stop position is determined according to the object position (stop_distance_from_object meters before the object) for the case where the crosswalk width is very wide | +| `stop_distance_from_object` | [m] | double | the vehicle decelerates to be able to stop in front of object with margin | -#### Parameters for ego's slow down velocity +#### Yield decision -| Parameter | Type | Description | -| --------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------- | -| `slow_velocity` | double | [m/s] target vehicle velocity when module receive slow down command from FOA | -| `max_slow_down_jerk` | double | [m/sss] minimum jerk deceleration for safe brake | -| `max_slow_down_accel` | double | [m/ss] minimum accel deceleration for safe brake | -| `no_relax_velocity` | double | [m/s] if the current velocity is less than X m/s, ego always stops at the stop position(not relax deceleration constraints) | +The module makes a decision to yield only when the pedestrian traffic light is **GREEN** or **UNKNOWN**. +Calculating the collision point, the decision is based on the following variables. -#### Parameters for stuck vehicle +- TTC: Time-To-Collision which is the time for the **ego** to reach the virtual collision point. +- TTV: Time-To-Vehicle which is the time for the **object** to reach the virtual collision point. -If there are low speed or stop vehicle ahead of the crosswalk, and there is not enough space between the crosswalk and the vehicle (see following figure), closing the distance to that vehicle could cause Ego to be stuck on the crosswalk. So, in this situation, this module plans to stop before the crosswalk and wait until the vehicles move away, even if there are no pedestrians or bicycles. +Depending on the relative relationship between TTC and TTV, the ego's behavior at crosswalks can be classified into three categories based on [1] -
- ![stuck_vehicle_attention_range](docs/stuck_vehicle_attention_range.svg){width=1000} -
stuck vehicle attention range
-
+- A. **TTC >> TTV**: The object has enough time to cross before the ego. + - No stop planning. +- B. **TTC ≒ TTV**: There is a risk of collision. + - **Stop point is inserted in the ego's path**. +- C. **TTC << TTV**: Ego has enough time to cross before the object. + - No stop planning. -| Parameter | Type | Description | -| ------------------------------------------------ | ------ | ---------------------------------------------------------------------- | -| `stuck_vehicle.stuck_vehicle_velocity` | double | [m/s] maximum velocity threshold whether the vehicle is stuck | -| `stuck_vehicle.max_stuck_vehicle_lateral_offset` | double | [m] maximum lateral offset for stuck vehicle position should be looked | -| `stuck_vehicle.stuck_vehicle_attention_range` | double | [m] the detection area is defined as X meters behind the crosswalk | +
+ + + + + +
+
-#### Parameters for pass judge logic +The boundary of A and B is interpolated from `ego_pass_later_margin_x` and `ego_pass_later_margin_y`. In the case of the upper figure, `ego_pass_later_margin_x` is `{0, 1, 2}` and `ego_pass_later_margin_y` is `{1, 4, 6}` for example. +The same way, the boundary of B and C is calculated from `ego_pass_first_margin_x` and `ego_pass_first_margin_y`. In the case of the upper figure, `ego_pass_first_margin_x` is `{3, 5}` and `ego_pass_first_margin_y` is `{0, 1}` for example. -Also see algorithm section. +In the `pass_judge` namespace, -| Parameter | Type | Description | -| ------------------------------------------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| `pass_judge.ego_pass_first_margin` | double | [s] time margin for ego pass first situation | -| `pass_judge.ego_pass_later_margin` | double | [s] time margin for object pass first situation | -| `pass_judge.stop_object_velocity_threshold` | double | [m/s] velocity threshold for the module to judge whether the objects is stopped | -| `pass_judge.min_object_velocity` | double | [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV.) | -| `pass_judge.timeout_no_intention_to_walk` | double | [s] if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first. | -| `pass_judge.timeout_ego_stop_for_yield` | double | [s] the amount of time which ego should be stopping to query whether it yields or not. | +| Parameter | | Type | Description | +| ---------------------------------- | ----- | ------ | ----------------------------------------------------------------------------------------------------------------------------------------------- | +| `ego_pass_first_margin_x` | [[s]] | double | 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` | [[s]] | double | 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` | [s] | double | additional time margin for ego pass first situation to suppress chattering | +| `ego_pass_later_margin_x` | [[s]] | double | 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` | [[s]] | double | time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) | +| `ego_pass_later_additional_margin` | [s] | double | additional time margin for object pass first situation to suppress chattering | -#### Parameters for object filtering +### Smooth Yield Decision -As a countermeasure against pedestrians attempting to cross outside the crosswalk area, this module watches not only the crosswalk zebra area but also in front of and behind space of the crosswalk, and if there are pedestrians or bicycles attempting to pass through the watch area, this module judges whether ego should pass or stop. +When the object is stopped around the crosswalk but has no intention to walk, the ego will yield the object forever. +To prevent this dead lock behavior, the ego will cancel the yield depending on the situation. -
- ![crosswalk_attention_range](docs/crosswalk_attention_range.svg){width=1000} -
crosswalk attention range
-
+#### When there is no traffic light -This module mainly looks the following objects as target objects. There are also optional flags that enables the pass/stop decision for `motorcycle` and `unknown` objects. - -- pedestrian -- bicycle - -| Parameter | Type | Description | -| --------------------------- | ------ | ----------------------------------------------------------------------------------------------------- | -| `crosswalk_attention_range` | double | [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk | -| `target/unknown` | bool | whether to look and stop by UNKNOWN objects | -| `target/bicycle` | bool | whether to look and stop by BICYCLE objects | -| `target/motorcycle` | bool | whether to look and stop MOTORCYCLE objects | -| `target/pedestrian` | bool | whether to look and stop PEDESTRIAN objects | - -### Inner-workings / Algorithms - -#### Stop position - -The stop position is determined by the existence of the stop line defined by the HDMap, the positional relationship between the stop line and the pedestrians and bicycles, and each parameter. - -```plantuml -start -:calculate stop point from **stop_distance_from_object** (POINT-1); -if (There is the stop line in front of the crosswalk?) then (yes) - :calculate stop point from stop line (POINT-2.1); -else (no) - :calculate stop point from **stop_distance_from_crosswalk** (POINT-2.2); -endif -if (The distance ego to **POINT-1** is shorter than the distance ego to **POINT-2**) then (yes) - :ego stops at POINT-1; -else if (The distance ego to **POINT-1** is longer than the distance ego to **POINT-2** + **far_object_threshold**) then (yes) - :ego stops at POINT-1; -else (no) - :ego stops at POINT-2; -endif -end -``` +For the object stopped around the crosswalk but has no intention to walk (\*1), when the ego keeps stopping to yield for a certain time (\*2), the ego cancels the yield and start driving. -#### Pass judge logic +\*1: +The time is calculated by the interpolation of distance between the object and crosswalk with `distance_map_for_no_intention_to_walk` and `timeout_map_for_no_intention_to_walk`. -At first, this module determines whether the pedestrians or bicycles are likely to cross the crosswalk based on the color of the pedestrian traffic light signal related to the crosswalk. Only when the pedestrian traffic signal is **RED**, this module judges that the objects will not cross the crosswalk and skip the pass judge logic. +In the `pass_judge` namespace, -Secondly, this module makes a decision as to whether ego should stop in front of the crosswalk or pass through based on the relative relationship between TTC(Time-To-Collision) and TTV(Time-To-Vehicle). The TTC is the time it takes for ego to reach the virtual collision point, and the TTV is the time it takes for the object to reach the virtual collision point. +| Parameter | | Type | Description | +| --------------------------------------- | ----- | ------ | --------------------------------------------------------------------------------- | +| `distance_map_for_no_intention_to_walk` | [[m]] | double | distance map to calculate the timeout for no intention to walk with interpolation | +| `timeout_map_for_no_intention_to_walk` | [[s]] | double | timeout map to calculate the timeout for no intention to walk with interpolation | -
- ![virtual_collision_point](docs/virtual_collision_point.svg){width=1000} -
virtual collision point
-
+\*2: +In the `pass_judge` namespace, -Depending on the relative relationship between TTC and TTV, the ego's behavior at crosswalks can be classified into three categories. +| Parameter | | Type | Description | +| ---------------------------- | --- | ------ | ----------------------------------------------------------------------------------------------------------------------- | +| `timeout_ego_stop_for_yield` | [s] | double | If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough. | -1. **TTC >> TTV**: The objects have enough time to cross first before ego reaches the crosswalk. (Type-A) -2. **TTC ≒ TTV**: There is a risk of a near miss and collision between ego and objects at the virtual collision point. (Type-B) -3. **TTC << TTV**: Ego has enough time to path through the crosswalk before the objects reach the virtual collision point. (Type-C) +#### When there is traffic light -This module judges that ego is able to pass through the crosswalk without collision risk when the relative relationship between TTC and TTV is **Type-A** and **Type-C**. On the other hand, this module judges that ego needs to stop in front of the crosswalk prevent collision with objects in **Type-B** condition. The time margin can be set by parameters `ego_pass_first_margin` and `ego_pass_later_margin`. This logic is designed based on [1]. +For the object stopped around the crosswalk but has no intention to walk (\*1), the ego will cancel the yield without stopping. +This comes from the assumption that the object has no intention to walk since it is stopped even though the pedestrian traffic light is green. -
- ![ttc-ttv](docs/ttc-ttv.svg){width=1000} -
time-to-collision vs time-to-vehicle
-
+\*1: +The crosswalk user's intention to walk is calculated in the same way as `When there is no traffic light`. -This module uses the larger value of estimated object velocity and `min_object_velocity` in calculating TTV in order to avoid division by zero. - -```plantuml -start -if (Pedestrian's traffic light signal is **RED**?) then (yes) -else (no) - if (There are objects around the crosswalk?) then (yes) - :calculate TTC & TTV; - if (TTC < TTV + **ego_pass_first_margin** && TTV < TTC + **ego_pass_later_margin**) then (yes) - :STOP; - else (no) - :PASS; - endif - endif -endif -end -``` +
+ + + + + +
+
-#### Dead lock prevention +#### New Object Handling -If there are objects stop within a radius of `min_object_velocity * ego_pass_later_margin` meters from virtual collision point, this module judges that ego should stop based on the pass judge logic described above at all times. In such a situation, even if the pedestrian has no intention of crossing, ego continues the stop decision on the spot. So, this module has another logic for dead lock prevention, and if the object continues to stop for more than `timeout_no_intention_to_walk` seconds after ego stops in front of the crosswalk, this module judges that the object has no intention of crossing and switches from **STOP** state to **PASS** state. The parameter `stop_object_velocity_threshold` is used to judge whether the objects are stopped or not. In addition, if the object starts to move after the module judges that the object has no intention of crossing, this module judges whether ego should stop or not once again. +Due to the perception's limited performance where the tree or poll is recognized as a pedestrian or the tracking failure in the crowd or occlusion, even if the surrounding environment does not change, the new pedestrian (= the new ID's pedestrian) may suddenly appear unexpectedly. +When this happens when the ego is going to pass the crosswalk, the ego will stop suddenly. -
- ![no-intension](docs/no-intension.svg){width=1000} -
dead lock situation
-
+To fix this issue, the option `disable_yield_for_new_stopped_object` is prepared. +If set to true, the new stopped object will be ignored during the yield decision around the crosswalk with a traffic light. + +In the `pass_judge` namespace, + +| Parameter | | Type | Description | +| -------------------------------------- | --- | ---- | ------------------------------------------------------------------------------------------------ | +| `disable_yield_for_new_stopped_object` | [-] | bool | If set to true, the new stopped object will be ignored around the crosswalk with a traffic light | -#### Safety Slow Down Behavior +### Safety Slow Down Behavior In current autoware implementation if there are no target objects around a crosswalk, ego vehicle will not slow down for the crosswalk. However, if ego vehicle to slow down to a certain speed in @@ -207,27 +172,103 @@ it is instructed in [lanelet2_format_extension.md](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md) document. -### Limitations +| Parameter | | Type | Description | +| --------------------- | ------- | ------ | --------------------------------------------------------------------------------------------------------------------- | +| `slow_velocity` | [m/s] | double | target vehicle velocity when module receive slow down command from FOA | +| `max_slow_down_jerk` | [m/sss] | double | minimum jerk deceleration for safe brake | +| `max_slow_down_accel` | [m/ss] | double | minimum accel deceleration for safe brake | +| `no_relax_velocity` | [m/s] | double | if the current velocity is less than X m/s, ego always stops at the stop position(not relax deceleration constraints) | -When multiple crosswalks are nearby (such as intersection), this module may make a stop decision even at crosswalks where the object has no intention of crossing. +### Stuck Vehicle Detection + +The feature will make the ego not to stop on the crosswalk. +When there are low-speed or stopped vehicle ahead of the crosswalk, and there is not enough space between the crosswalk and the vehicle, the crosswalk module will plan to stop before the crosswalk even if there are no pedestrians or bicycles. + +`min_acc`, `min_jerk`, and `max_jerk` are met. If the ego cannot stop before the crosswalk with these parameters, the stop position will move forward. + +
+ ![stuck_vehicle_attention_range](docs/stuck_vehicle_detection.svg){width=600} +
+ +In the `stuck_vehicle` namespace, + +| Parameter | Unit | Type | Description | +| ---------------------------------- | ------- | ------ | ----------------------------------------------------------------------- | +| `stuck_vehicle_velocity` | [m/s] | double | maximum velocity threshold whether the target vehicle is stopped or not | +| `max_stuck_vehicle_lateral_offset` | [m] | double | maximum lateral offset of the target vehicle position | +| `stuck_vehicle_attention_range` | [m] | double | detection area length ahead of the crosswalk | +| `min_acc` | [m/ss] | double | minimum acceleration to stop | +| `min_jerk` | [m/sss] | double | minimum jerk to stop | +| `max_jerk` | [m/sss] | double | maximum jerk to stop | + +### Others + +In the `common` namespace, + +| Parameter | Unit | Type | Description | +| ----------------------------- | ---- | ------ | ----------------------------------------------------------------------------------------------------------------------------------------------- | +| `show_processing_time` | [-] | bool | whether to show processing time | +| `traffic_light_state_timeout` | [s] | double | timeout threshold for traffic light signal | +| `enable_rtc` | [-] | bool | if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc. | + +## Known Issues + +- The yield decision may be sometimes aggressive or conservative depending on the case. + - The main reason is that the crosswalk module does not know the ego's position in the future. The detailed ego's position will be determined after the whole planning. + - Currently the module assumes that the ego will move with a constant velocity. + +## Debugging + +### Visualization of debug markers + +`/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk` shows the following markers.
- ![limitation](docs/limitation.svg){width=1000} -
design limits
+ ![limitation](docs/debug_markers.png){width=1000}
-### Known Issues +- Yellow polygons + - Ego footprints' polygon to calculate the collision check. +- Pink polygons + - Object footprints' polygon to calculate the collision check. +- The color of crosswalk + - Considering the traffic light's color, red means the target crosswalk and white means the ignored crosswalk. +- Texts + - It shows the module id, TTC, TTV, and the module state. + +### Visualization of Time-To-Collision -### Debugging +```sh +ros2 run behavior_velocity_crosswalk_module time_to_collision_plotter.py +``` -By `ros2 run behavior_velocity_crosswalk_module time_to_collision_plotter.py`, you can visualize the following figure of the ego and pedestrian's time to collision. +enables you to visualize the following figure of the ego and pedestrian's time to collision. The label of each plot is `-`.
![limitation](docs/time_to_collision_plot.png){width=1000} -
Plot of time to collision
-### References/External links +## Trouble Shooting + +### Behavior + +- Q. The ego stopped around the crosswalk even though there were no crosswalk user objects. + - A. See [Stuck Vehicle Detection](https://autowarefoundation.github.io/autoware.universe/pr-5583/planning/behavior_velocity_crosswalk_module/#stuck-vehicle-detection). +- Q. The crosswalk virtual wall suddenly appeared resulting in the sudden stop. + - A. There may be a crosswalk user started moving when the ego was close to the crosswalk. +- Q. The crosswalk module decides to stop even when the pedestrian traffic light is red. + - A. The lanelet map may be incorrect. The pedestrian traffic light and the crosswalk have to be related. +- Q. In the planning simulation, the crosswalk module does the yield decision to stop on all the crosswalks. + - A. This is because the pedestrian traffic light is unknown by default. In this case, the crosswalk does the yield decision for safety. + +### Parameter Tuning + +- Q. The ego's yield behavior is too conservative. + - A. Tune `ego_pass_later_margin` described in [Yield Decision](https://autowarefoundation.github.io/autoware.universe/pr-5583/planning/behavior_velocity_crosswalk_module/#stuck-vehicle-detection) +- Q. The ego's yield behavior is too aggressive. + - A. Tune `ego_pass_later_margin` described in [Yield Decision](https://autowarefoundation.github.io/autoware.universe/pr-5583/planning/behavior_velocity_crosswalk_module/#stuck-vehicle-detection) + +## References/External links [1] 佐藤 みなみ, 早坂 祥一, 清水 政行, 村野 隆彦, 横断歩行者に対するドライバのリスク回避行動のモデル化, 自動車技術会論文集, 2013, 44 巻, 3 号, p. 931-936. diff --git a/planning/behavior_velocity_crosswalk_module/docs/crosswalk_attention_range.svg b/planning/behavior_velocity_crosswalk_module/docs/crosswalk_attention_range.svg index 270a61264fe66..26e6118756bd8 100644 --- a/planning/behavior_velocity_crosswalk_module/docs/crosswalk_attention_range.svg +++ b/planning/behavior_velocity_crosswalk_module/docs/crosswalk_attention_range.svg @@ -1,213 +1,132 @@ + - + - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -
+
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22%22%20style%3D%22endArrow%3Dclassic%3Bhtml%3D1%3Brounded%3D0%3BexitX%3D0.25%3BexitY%3D0%3BexitDx%3D0%3BexitDy%3D0%3BentryX%3D0.5%3BentryY%3D0.442%3BentryDx%3D0%3BentryDy%3D0%3BentryPerimeter%3D0%3B%22%20edge%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20width%3D%2250%22%20height%3D%2250%22%20relative%3D%221%22%20as%3D%22geometry%22%3E%3CmxPoint%20x%3D%22851%22%20y%3D%221780%22%20as%3D%22sourcePoint%22%2F%3E%3CmxPoint%20x%3D%22890.04%22%20y%3D%221780%22%20as%3D%22targetPoint%22%2F%3E%3C%2FmxGeometry%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - +
+ target
- %3CmxGraphModel%3E%3... + target - - - - - - -
-
- crosswalk_attention_range - [m] +
+ target
- crosswalk_attention_range [m] + target - - - - -
+
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - +
+ NOT + target
- %3Cmx... + NOT target - - -
+
-
- Module don't respond prediction path without attention range. -
-
-
- - Module don't respond predict... - - - - - - -
-
-
- Vehicle +
+ crosswalk_attention_range
- Vehicle + crosswalk_attention... - - + + + + diff --git a/planning/behavior_velocity_crosswalk_module/docs/crosswalk_module.svg b/planning/behavior_velocity_crosswalk_module/docs/crosswalk_module.svg new file mode 100644 index 0000000000000..18225f188fddf --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/crosswalk_module.svg @@ -0,0 +1,98 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_velocity_crosswalk_module/docs/debug_markers.png b/planning/behavior_velocity_crosswalk_module/docs/debug_markers.png new file mode 100644 index 0000000000000000000000000000000000000000..15645a340dca83a14ba136c0192849ed56ba887a GIT binary patch literal 220365 zcmY(r1yGdV`v+f|(%rcrAR)N2EG69`-5t{1CEa*m zzQ6yyGnZio*kOQk&htLcrw-w2DssAEwGV-0CV$hqy}&atcQhg3vA{k zU^kUofk0r80z?w#{%x<({xgwf=HX38GW+zi9Z)IxaJTR0P5SF{1b!HKKrpwwvDJ$g)#l4LQX>0uMR|z(lT-2SD;Oexz4lDU`rZ8E{e9D- z=D)6gR|h^FsLZ5=cEi z>Adoudr#ziFhiJ|hsUI5z%|&1gG5GBEUOFniTaC1vzT{2P8-4 z`m+=fTyNeWz2}REQhb_04LALLW<2t*6W@59v;EA=Gw>B*{Gq7oA}KptpD+=t{>O2LgS&J|)JHvAK>+8OnH-(bIdK(+H)XoXW&?fyylVtU4`s z*re-ZNmK~pfSBeuB@E1LqCC5g@^YApiw1D=RK7_q+pRkNxnuM_&I<))>vQC)=abtl z=^gMYOJMpPf5BF7j#^k?`f0zZmXC}xf3fXMQL58_E`|0FW4v7g{k?$w$3La2-kvyu zb_>5MidvP>5TPsW()fmi;TRj6n@~2=JHv<;bJv5paPOP*k4Bp(9#OHe_19ubVw@mw z`oLo?pU}^Zf!Mweo2;$J%f1|Em3bnqRzp`DynqM2(Gfm&5GqcMS|!_W4ZWV)X6c8gIwI zoyouZyRYf#Z9R#M+=7CeGpm1dV4ffay+@$9A8$|-3=moZXBU^;f&$8Tc|4O+v3;+J z9YPS8v>?2wtl{~H6}46ox`l<^^;N+o`gBUS*d+6zxYma|(S(2XS0dY(Fwl%;Fbbs~ z^XwghP!T~$7#_50i#8ln;{GZtasLhf48hhJe6#OQnFlT?Tg0e}Ehkx#VgF<{KSpL! z_MG+ZM4O3JjfoVjKuE8E4pIgQ=vBj~s`QG`K_(;QwDSb*IowIqDU_34dg%r_CHv|w z*y_If7m*O!XEt24q>&$+8Dr1lr?i@zw3s3S!pDe|&`3aa|L&R>y|<25yJkWOA{}dk zY-(i%yQL9fz^BJw@(&b={v~&_}*%@qhGWXQ6)R+uK0kw5DVReuW_s>OIN$d0n=i)R%W!nCfDZ=EsT{J_*v@PV>%#>U#RmXZ?%DkSQv2nQm>4itU((6*o zAu1(R)z!V}a{cOk0aTsend&Q8sSb5=N>=toeqy);E((MnermP(3#BKV#h^h3oF!uP z5uWcO-w~s3G@;eIuII8j<&N7(d_37LjcQfCt3Q(6Wveggi{ zS0hb%Mzc#xV4xnVr;-idSLzkL53EC4qnEt6B|gG+!+pc;gT7u?`uNY?zJ0TgmB&^1 z@~dv7k4NSmE{ugmJ)bxvBt(w`NizLOYu2N&y<5xsyrD7>Z{0s&+N&JNk-8{}5dh{9 z5s5M>Wzv_ojfzhkDoE7TgD~V$N(P69?FbafUct^B=HK|zmOd|Qpa6ZoawH9IHJF;T zkb%rs*-}>7&UQL~C+zw`GO~#BE9mMYVlVkno7~ma1ssGlP}0vM}nFrqLKB>~{MEBjI>d!0f*!s0A3&Gsg;4%DmgPDnmXW6fl%EBO? zI~Ws=9xAgTY$btgQyj#u32`&|WR80+gc%-n?L?G>-FyAu((h-OKf(24^Z1?~5pXl_ zb;lRGQ^ilzcw2S3e~;8Ge}$W;<~tBiyFdAH~5fws{dUTE69q(O|G*q#?s!FF0M)a07L><@a`D?vz99}2>e#hAuM8v3qA@;B01>|qij~anVJaXLp zAOr$vNup_=DWcD5Qf~eU@lccCuijZWymMY?G8J|;bCu9zPrZL3h(Whd3@bCB`b)}6 zCrY5qmqg#=NSy0qE0R^O!#3&MkhP^!!3v+7{N!D<@?>0QA}MTp(x%??%v#P4COA2z z)IMa`yMmW>_j}wmEdnWPdW&%tql&p7^7(s}pilH+ zIaYcYMY~HG1}vBVHKD@Ku$?M*3oVE_Tw&TFYqWjUVZUW!`*51$K#C^Y^BrSttIiej z`Xm4G#q9R41=Yt-o_uGDSRY!wySbpFid|ie6@M;s|B*FqJ-19p$6Y^V`&Hyb88rOw z%tzBZjOJtUHZ0YVw|4`4h7>+M=XwEbT8|C3Fs+Nvp2hmRQg zKKdvzk(TiR$fWeWoe6m*f6t74f@v+hIelWO{Dc7aB0t;U1r-%(u)1y7;_3}sn6%9V zO4I*UqAEh&rML~8;XWKt^Fpu`#bH&83=E{ik36Hz8mhmaOLqx8n5`}u3`V(Sp-*1u zdg_IAVKvRJ*4X7Xhpk+AN#wO?aN!C$i&-<0$WQxgnpk$Mt88Xvig=9fuX{$Met~5} zB^de#N!5xtfW2UK5Gc@Rg+67;IK5xRpvrODsU>!8sA@aXo9m`!m|d5Q3pQM7aNdz+ zsEJ>lK{-ccCI~np6p!9C-QQ}pPqssA;DTQcw!Vy8nBJXU>)4d{_4hvo8kc;+T6Z)K zpWEq-KUQOH!P~jZ+)8hR*Y5DU&})-uEvH;=AMc;>2DfZ+qnlZz5tsl*N!l(T*$Ief zRgwhi!nUiW1qAeX@^yRO0IsH?){lk=vSG$bNdm7k+Z_uz({0E6@84&JJPDx2ozE0| ze}v&`a-OfBcr;urcqQYdSrLS4`=`DKwxxB(GT<-Ou)>z=a1oBh2mfz>W22&+&HR%z z_hN`bMgLWhpsvXyjzMJ&Dt&TATCC5ctZV1C8Z?u1`-cR5jFP8l;^k@KGcyjR_t&_7 z``7nvkLq)rOia<^Gt*`{!*qYxMO~b@K2EdE77XCvO`yjf(IGxLIf)6jT6kN0>Z*g# zC_K7vmoPy@v0S-)xubkPLRr*EJvi69daYqfYvb)KkU!3uN~rD;ak+j~_WG%?L+>fySgab#agZ| zIq$BI<__Cd4!D8Ms_0b7F)*Qt0^m6Lix(p*LBYoM&skU7_Y-_)a8}3}u8^vk;}LN^ zU+-I6P1$+j*-Yh3aEo+1!K@*dHFsZfPSABQNs2okX~(tySy-pFUc_{RVmZe2S`Ikb^Se9%;?s1jZbf(P9?VikFE2OdEMKE0P}^T%=&A(GB1Rh< zvJ7vcsXtps?D=?H&W5s(kcc)yo!#WD-y)5CLKG2(E|ZoN(+ueYj`b!VNONyBSTWTh z`C4QR19l`>4G?0*N<21h7AqAn6++xDQ6;Yu?_+ZY67rPp4*?m_egFJg)}<$`JdOs3 zA=`tmZ%>A1Sz@h23^6v@U+(k;25cNGmkwcFniAvwrgLmnJq>8gVY>X=h9`X|>=Ax{ zhharrJHrlCk?a*RGBUEi^wy-b7Wr*xQwVrO<&soV+oIlyP()6?M8?av4V^f1)WNl< zW289uWf=nIcP0vIi-rzI^DB>LOp}>It?c|g;IXYnd@ zjLzceI==D=W^8Qzxp{&SyS@!Up^A;T%2^-HQa%ab%0OS*ci|M?YP9J2Co#nmI-}>P zp}e`QdGKa_a}SMDS7(d=yLIm0p?k4sfeUn40Q!a_iHL}babFHV#sQM^;o@L^Yk%LR zgIhT=Eh4ApToAwg7;JbG)$&TG_!k)auhxfs`>vQ*Ck`^p!Dl`RDtSly_P&%;B}Vr3 zw_{qwk=3Oi$DBacS4iLojm#nWB6wzb4o{EQ6|^VG1^Thh11My3oC-M~yX4nmk({!r z3kEHy=eM(WO%&@W)I-CKH$(7kEp27V8>`esVix!vPGxiBG9z--*+PPDpZbw-SBhv$ zt#3C+uRJN-$Q`wDx}MvfN7nAXWz$Tl3BR<+Wk`C0lahaYAeMiD50X!ay16(szIMHv zcuR$j%3-Scyo{bA&csT-o|VQPN4O3RP%)V*HjskYJ_-ODqVTie#o&S+ED7vimVhdu!7nXVV=@6&Rck06j}t#0x26Bvq>~wQT4e4-?8L#tp6x z%wcN!<}A=B&aVMxn9Bne@9s_>4v~sF4kgcJ>&edQrU#-@v zb#I=;P4&72i?{zWmsP?P%5#qRl=8$iQyAC{L+TQBHbG#&d_;pSo6h-9yLPL!wKRd} zI^S*vjswDbhj>gtV)ey#yVU2{mo@iH1@dJknni&Srvo5Y77v)(YLT^{xQ2qR{$X#h zBn%#-*!svRC>(G59wzif1#>^^w~Z_uU?>wQ&=a->Q;K|C$?uf-T z5<}FL?ueyDS-hL4j}|45x_HW zf+yGYOro0KO4fkLo#p+<_X5*aQzt39n+LG+8!{rz>P42APwU{TidFLw7IrW{UuM#h zO^!OxXV;m!k^HKduw=D-H-us-c~d6x1$Fefq^CDM?u4}%%kS_o)p{s{LThxopgzG- zcy9HNB>ipvQ3&i>a%{U|ReUc$pLuA}Ib$PB$ab3$t2Kft35W9o#o`pvV*+@R5!yn; zXS;|GYi_-pCz-cmr@L%@Jizw+a#)q^9~fAkt92^Iy@!12wkXe}N^#%j7#ALy|9pni z;Lp&4_x$;_o^>80TyZ(WZ6Uw@v)kzww6xhF2n$K=d&}+D$-|TFB*U?y2w!)(T#1YX zS;xTW%BFjgb@Kx#BqI>mgxBcITFbGz+AQ{)Ig}>m^;nGqb4a_w*idrv?PyxUXmn&a z+)UV$8(yQ1(0SUZdeNt4B6c@ZyrXB%N)7KEbn0@-SNaRJ?j_FkA_~Y17e=k zryxFJ`O@BQAx(L9IF$s{dJv{*AVC{%w!oP+^j)W6|7fQ*`W_uTTzm5Z)SeY?de`E) zVGA++wX293pewWegZ2wKpxgL!&4yesW?EmAko#{enIV`ksQ6jq9|O<~Bd zC^DFcv8#*@mlRd#m1V>#{-RqcpF?68()ygMlUn+EO`Z=`OA$dmh~?2L6M3kv2(^sY z{||$~`ffFNnucaqSn-2`4eDK&kJtOYW|0w)exNA?Q0gslO}_+&T#GjWeEqev^wX2; zx2kz#E?s1$I!}Sg&}Q#*LODe(3|I8fVw-qM=k|T<_&JSLrJy8h1|g>ULAmcgpNBfx z(_KvzUnVV-oI_Ob!e!U8XS%k~jfeG*?1+3{KliY8qUjH3ohTY*Hq=v!bJ9oqO6WOI z1I2D|ve=LCpXiWbW9P_W9gQx|TRm@wqfpUOTm{Y%R;B=fdpChd!?)!Hjyoc3u|FE; z4cSq7N?Es|au`Iju2VHwzUt*ZuPq8@vmu&sfZB%DbpHcN|zWUk&#l@jVg=`9(Obwl1~ zu=S%s8cQ$3|2=wxX8Zky7%+RfPEVaR(BKjas@-1LOU>N}jDSeczPh{9c`frC5&oE2rceF`@*MeQ_k zd#k-Y$c8q`koYwc717h906gMd@U96WdIES$n*kF>(O^I|$eu(?)`^^vIv|P!4c^(! zzE#;xg%Qy)n--Tgw5i4-`qxXrRx&SH#YL`;V7Gh&%;$)xa>PX6hs(_1l)TF;tbxw! zWsS_}K|S=x3Y20mQWV|YORRcGyjM4#Da$hy!|J6_x&+N|O1QCByEZWjZMv)f%bc z9sLHXLrW6*@K&BC`a}gl8R|;*Q#7u{Y$Toz3_@{8Xi`UV`;c)(!~=uO_9`=*1F1#^ zdj~+bcvgPyI0=uYPg{y42#rB5Le`=>=)6uAkz5H>g{8n5B}gH2ev$QEjm-+3VR#0v zC@h_UlkZo%IT%F=A65$Em}6fOY`%V`7~ys(JwIDzFKl)Z+9t%j2(W(R}3bZpb3TN#-6Tu?<=?@eh`?;wEo0l7Nhp=oUnX0&Z) z`3{~rq)Q6hmrsAnzPH;;YTtU-1$@(^3pcvYWZv76@1;VzXI-+)c*3g}JaHLSzO}$v zwO`s6Xv_zA!p=%RXV+l?3&_B{*-_VI&D>a4gwyv_u#(^-G+em|J^Nz&;-cZnxYo8O_U>pd3+b7X;LnxT$2NQS_FS zsiyY!ZS0|E301%N@12S57708m!rG9EA?uFIm~TmNMj6lPMtJ6xTqw8<2XX#?k=M;}ntH9V3qXksH!6NbZBf?+I}GEk9$6+Bvizv7}z zcmo5<&~uyN+Z%^~g8yoJ)?kg$T{RE;93bVRZGL7 z#+sx$*w6)9xi0Hs>h1cfv2TK9T+ZoPutvN*glIbjjrgbi$Lbg6X9=@br#S@~o8iIG z?IcY>78+mP*jwd)3zlr*|6fNYOMwjmriEbC;iDqlAKjN?wT|@oSXzL8(s_H^fDe5n zFC2R~HoT&RZ-A7zqd*gDrOU9~?s_9IU0pU^xY{)lc?X(>*4xesi2S=faX;OPFQK&_ zmWz*`6J_(S)1X0TQDc=Qma;Z|S5HJEy|!Pc`Z`gPC$+tc+Bd4U_U#l^*VY~6(2)%5 z+i*BH;kq2Ze^)Up9IpAX6Hd{|rY`JGb2{UYTURUQX>0L;LRYIr>VHjbfGd2L)V3*Cm$)k9biz;in8t1{ybDAu6oHaFusDK_OLu&J3kuz$fPg z+$(1xcG;^(vW!uOV{y>?>^e1nS%QiDzsRBTQ`48}q}t!^IZm5ql<*g-?Xz6tcJjg~ zlA9SC>qCbJ51&|kzjzA@lg(W*S-vi!Z;5?+Rm5au5u^}ZAH z_r)-PPXLnf6q~wG$tboRc4KMNS2{ry~*LKjz1>S+AOjXmJbdJEL76Mu}BVGW+{>Cf^o7 zH+Z&Mw=eJjo{pcCszqdzLHCO%n1)7ewsP3&mCrm&F|7`g7XYOg(Cq_(K1AhrQ6kvm zhuKO86zUDt@clui)(`dk&QIk!PmkR7zhsJbC^Z#R9bZXrIaimzzof|~6dGY?`U||G zVzg(yIm*nlfcM7@Q6^hBP@|6KgV1Owm-mRhD3@*7mkL_YVSD_RW7hTI;K~fj$+7cQ zQJSY0=i|01YMGq87me)_IfF>|)s1K&8vd-ITs5{D+Lda@Tof*g#WAlxw?Y*$w2>oD zvH9ENf{2yg`U6jpFn$gU7q%#hxY?s#QGeI(k9Gg7&;V`6Q5+K|Pxq zj2~zd^Us970h-;E%O8SiOmx;HMMMnIUPg_&e^0r?+o7K&V>I%zA})BME*rEo5U8yPil6B+G42 z1G*81VMCa(+rcGA&c?}A3oa&G7Y{-HM>o~_6t`c0>RfEb60sK;{q`jaMwy}D^=A)Q zXm0N1V5Y5M&@RcT4={@3frfi<2U!vWN)%}5VW$wb6cx1JpAoKl+r+;TuC`qtHEQlb z1b^Y=vBYkc>K6fa)C-}Qfh3g?4k+yp!^=H%Gu@4}k@Wh^0-{glS(f~{X2V>>P{6wr zv~gtJ+sGo+)B|Khbf>+U%6DN%wCu6Yi;r8SBiW>i1Xg5p#>$|lIT9ZjsmDKgBvJ8n z`W~&wfNsllilhvssSw6?t)8mcyiNdnkp`;yC(mS1+)S8HL-HFufF&`-9s2FpT=yBpI$Gqd zY#&-#Wr5HD%ur+>RQV}AV9=w0WTEHN;;S)h19HfZ#@!B)@;9|~B@ z94P>Q&twC0$F%?rlJ`V)C{x_#G6edS`EsF`0Y4~wdHDmVWo_-p5bO3QAqS!kH6U;B zzbwF)EQxxxKz$~eKlN_*^HUa>EnpmEOGNo(6l>zT7(YvTc-QKmCT}kTjq4`wo1M90 zpK#E!jgJGEh^mc*xm62$VgGC=3d6!k)9&K`Bv zdlA<{Eo3Xc%DrGe0pHOgWwybXd)^RiX!y3c{lg27ojDlU)l1<^10fklb*~!+Wb6jT zqy_z{0MXHzxfNg$OMcfG?)>W!eIe&*&7c*35av2a*nSZ%M4$;JHY?X1dM>8mpOh(8 z>Zg&FX+kO=f8>4qm;oQF9}pS1#Kk%FkzynH01&7k;@RSWfn21Rj8#D6xJXGycLGW7 z^Z|i8(bHo2?Al)`^7P=ovdJVBeWcsL+{nRdN|+**Ad(i9(fwrQ;5%liEBm1_T%nRS zULK2P0@Mhe-)WRE&iMahpj$(gcimn*?8Vi)H{mVfr&27#3pX#AGa}A9K1E+VIycA% zHM5Oo0~I|uDO=szmBX!cYuBnynm@anTY5c1NJF9%Y%UA)AGuD8zSwP6#mRP;6(l|& z{kvYtS!&)#YU?E_;xh#q2gvxE42%sIC|0F1qx z=Ki_j+V|nQAgl#1$VJuu>~jxY@C4hxaioM|k{mY1Abzm={YVdRdeer#3mb0uS4d^n^za3;o5?J{VA*QjFQ76(=|0;5W`QJ{!&r)K&+Im@VHHD)p4cp8_*6 z0DL-X2UEBBLG~!O5qf%litbm0&I0JtX&-(%M~H~GC{nSgIpvfE!C0j@X}p*t%bN|j z)i+K&_PsxR{>=3`F@1jb$t3l$x`g?97JBFZ0Qnoa8nrur(n-HT%EdgI)L6^GZ`i?) zQb=E67dp6VK5fg94+c%Pbsuoccw-)8&3nDXgmt;-Mp>D(DE{A{KBfGx9%!^rf zb-wuXVl|KEMXBVC@F~S)lk9!5uGHf@Z+{N}uO;-*t9*Mypoaz@jyYruSo$7|K%4Or zr(3-P`D(K`Kq+d0Vdw#GFvz#VYIIf1vl3)c^WxzDF34dzKjQ+*HqVdigdc#rs1wN8MMELT%1|1(PdXl4i{;0!QW^+c@V=T2u9!eA2zF< z6vrnNDs5L;5-lXhW<_Y^=H|NJ>{mNnpMKPy>cJH>$Pf3&=sj6~tQ>4<$T0mFXt;oX z`KQOhycUWkv6J%aJhc*(UCTl@PXNfpzZx3$rmv$uuU1y73(2(g?((0^2oR~ATzxUP z_l;Bh`JaZ`z5hf3nE7SGR#C^Q6PP5ysR5s}a4=qi?I)!mXO9~TN;JBFnX+-jMXZPx zO^a$8Sy0Rs;#AMKmq?zHOrAp1!PNBrv~0P%O009B!P*>XXiP;x(F%-?qxBRc>&4vQ zaTPLXG=|&4A?|g;SFQ*X*Urn2M-^kZh`l|VecBeUXY4?HV(l*IR=LV4JflT?FIgoz zCdTB;mzTiu$zQ$d7#}D8`Sa(T0o#*t%m?pGUbP*%O0;0mEk^Ahg)J zhM^GJaF{jg%8^T0$2GWb7vTR~x6|?Q@pbWU8znwAOwQqg~`u-WAm4b?Smj|+95T{Qk)Nw#4CX9oBK4y+g3eG}k zcnY$B9`>PHyFk-c7!a-I=jW3ne|{@0A#p92j|P*i_UMQy^J=s7D4D;_>2ZBXQ{2p! zGtJq~Rb>Ln33)-34Xw2a*k641!t&>dYR{!uX)P`W`eqo^$KE(vW|lqTqhRZn6y{Dw zdP{`PYMxrAJUv0=*@Sm277|E_N;sWk8QN_(uzhTec;-0czyGpPypJ$M=tJ=vElgEZrWrY6zi?bX@<2)ldkkS5O~KE zyKFf`xXb3j(XelS_xlJ42!xcDa)bEM&X$a*+GGFC#-f45FBg45;FnS?EtU;{sb<$* z_#;>%nU#MFz{(vGW%F9YcCdV-R_XN*ZQkA7a=u35Ag?Q=>(mqupu9g!Da%I zkJ}+bPcoU|#~3G=^!*Ekvh=ZZMMT9@HYrvzmhWQ_*g{USMgT_yKjkVJ-A!kWuGY_? zwhFz=(HKB>YB-yGfB8RIV*kSN%WozQ`fd(4$;;tG%XC5ePNTaCqviLDCK$M!xQbMzxo0VrD9P{fX+f$U@n2~ui4qz`Pa?&!VU0M^B7e#+X01og6}XWaq)L)IZ$G= zeUjMb5XM4K7qy{a(lHJqm`fSzV(G{HzfASJ>dYouGhb{9yMha2$U zA)$HB!Uv$PZg9CLkY}swASUf8s7e}4?kNvI$80t z^vZ3fIB0SlLtIu^j#Z~ID%Eh1>)!>OoO+LievB=)4i8)Gdr5i}<&HG{q-Al)+UdI3 z)>jiQ!7TW@c{XKaY4Ls3gxp(gJv2-aciE20ESR5CmouWLY%lU}eBU|{84Y%~4gj0& zmmPEYpA+{5`B_tW>tg{-A*96skXchP)n(Te)&%HU_5Y6o0&je{rXX$f<> zg)usM_FhX#RI1>wN?|OUI6D&q6Z!Yn787XclCkS(ds`K)FpRPA_y-`c6t{0+=4Vy139xl1Y0sMR{Eud_->qG(yn6rTrI|z}f4x zTCx2lt!-F7OlnyLt^7jkDQV&Dr#!N~Ks6q7U5G8*SCLFU{FuqV#jEPmG_5}Jn{o73 z6EF!(zBFS?x_(EG_CWH7>`!F&e+B=oWdy_<#caRVi#+viue+A+P2 zI>F)+jkptgQJz3#K}Df?DS$1xNSWvt!>mGSI)_=KJ{;k7q~v z-`(9YrSx?h3_Ym-gJYFLh5VX4GT^tUi-X10DgjSn$^KMKzt#-&V?oNr)%otB^Ln%1 zgs>U5e@Pq<0S0t`UqIc!P2n`^yluF=agx%JbG{4VIKj@uJ);cCz0Dtg{Pek<@q!jp z5&5VbCWUu3gjNJ4OWXSIE!*I`TuTGMA*zWM5K!O7o zR2+tsBrn)_whPv-u)TRlE*3gd>TLZGdCtu2oG!O~zo^?1)G$SK@nV0tNOgw zO#o_{u+cuc4?SGnsVs20_^@t6XvvUaIX#Hb*a_&ZbncB{tt5Jv2Uzo5-d=jM&HYJA z1Yu4S>{E>Rg`@erc|%|~_Nh}bSq-*`9G!cETaMHnA9ZiXZlyulf?ExfEHc2`X%X*c z`Ul7zi|?@cJ^ktXpYw9k(B(;R86ai%&ppvxtat1(%6Zcp1Nu?|j|62Pu)E8q91$sw zl+c`{%1WVdO>nR{UqsGQ`r_?tpNsm%*bt@NjEKK)*);VSROKNJo#N>>p=7u!IguQ^s{qe#|H-X2X@s-KBObj|qa zDB+s;a7HUUUj2F1x9Gt z-(RKAq_u*70IXxK^9IdS`+*!Bf2mb@x|cM{OgjkgGcPo%rvmZOkocW9kYl6P7WKA0 zv0gS>7|wE*c!vX_`j}I3s;g<|o}?7hyR`z}fX{1=bA*PeRv zk6Aq~eZ%*RSV=-E>}!#6=W7pTCe0+dZi|0dnnmU>dycL5tH5up!+)tCKKBm7C2Ja< zd@AAe9sQR9kk&!q$97R3t5n<0K5n^J2%e&~W`U!ee!ull(&8{z>q5=@S%$z{zGjok zPt$x-u>c~rq3+@Ye85%&rj9bxX)_F*?r+x}-K%h9jN*jOZ2jQ zaNq$PE-!bB73@|_1F(zT@yq+=dEb_d`tul8t0=`hoQ{CkCTJN@A(Gw5%Dp=7z>$+K zN5nDHYuZcEoQ0>rJsCC%=^w%Yz##j$VFw@&j0r%B1RC~46OaXdCdc{8X&GbECcQC9 z=A3Xb-XpII_f$vxs(IG*?inpgEHqpK=LhgRfK(n9dKj?C$9-o+Ri!=IOMJd#xTD)s z;6B39ZF?(^95!yA^b82wB;rmCh~_obn(7b`P4A^J!AU6&`r3kV{5*y$|K}LB=y3z{v&WDu?vA-Ubh8zKT@-%X*6vPhU zkNY&FQtVlEj)>7AWTFIbX>)6$OaG0(k1Z#_1u1>`E^cOi_qaFv6fX7;y^#cLj$rI- znY)dCdoE#N*4|u<01&P0RndpFYl2)eR{Z66(4^!iToqPi?TP=~zr3ol|K~okl47|_v7Y#xFh-uGqbF*dRwsmPf_8IO!nhTZ z4ddU(brL&&RiB&gg__RT+L=LiPWaDO?_^iE`NpdA9QG``KtbisI7@Ut&^wD^-VpRd z0+;G`3C7(5t%5X4&4eF6?O?1Jjm|7?{Fb#6z0XxRevO#k1qKEd`@}e3oSwcM#l_)+ z=z~ce9vXN+DEYcz?EMdZWNX%9+$Ix6w7`7H9R9w0x%Z7g!*TDsnJM5Dp%zEemd*Ys zvB!Qw+Fz$`9$$(4#QVE7Vo3N-B5}xQYI3lCt}p-pU9z04Y=xf(5YXRO+grtKm6=Ra z&kq8eT?p;>eN~BlNU_F6dG?#sU_S~rom6+A5=4i|F-s?;{Z z)!ZhYcUetlh2IOZ|2TFBE#2qX0GNQ1aIk1jkU@VS$*ZtNK-#eS;6auSLJ1@u4nV4egJp3mlpnYqm z-A9pB($7%jMbvOWw5ETTG?yh->L#p_H?608gEWK;Y&tQK+S`Z^{co8%1bk?RknKjV z3*Z`_NQFjetTu)ROc;weQU-GEp09Uv+w<9QD~-cf3slhIamL)B zxyt(?u>%MouGg8plaz*STP@Yx2SW?dxKWWonqu59N=5x@9Ly`q7MDsRF92bf5l>wAIp zj$m9ep@VYyL$h;~jyx9fw_JO0#gpsXu~O=o<+-)DW8#M)Ah}JOgd=C3QM~MRcX9lK zhjWwp!Pts$#<3#K-S!=mvW|O~_pL?@AoMzXAv#7+N3Fwc@)H4ZtoM>dCQZGLc#dhtg{QYRATihpy zkQ)rtdEG&%Mq=LaL1Hs(bhuan2ogUDtH+SSVGLzLS1Nv1;t} zXnr;p5R>Bg<-t8^#F&HQAPL5zHc85Q);G`i@_b%8LsDa?ZVh`XYdT6uY1MIiHShdcKW%QMQ9WqC+s4ii3M{^tCviN@p zJy<<%?PAYtXi;w*@UdFu$mOoOSV+Dd9Jrow>r97asLd>6sQZmZ>9BT|#Mp2KQt=JD2 zo>Xe2jWl+aK=;8p|K0;ZtXlo&5jlK!ZxgZkJ+!@>ljjYg(^3ZsCrE0gK8Z+y&FS`NgY2x98zRPyE5( zf<7ksR_JxacgQr{@kPzD(@ZeU{+d^n%4q489~Y?kt&W&{dS(#nd7e>j9nrMI1VF zYrVK98Bucvmi~)4szy+kb(ZQ=`Z&Om2eepSp|hESl4T%@_R2sA^Q#l$agl#!Cu zhzE20Sbh8KNRP7dRVG3sxE^z@xi=IgzhD&+JSV#tI~TgC<9h)d>ho|s@WU3E|F;D- zsFm9F^_eNvOk-d}#!;GIcXn3J-*{T4e*Tjl=rfoG*zY@#-fWR-NFg|`5~0562VA7f z>8DNU%Yj)ha4BqlN57R3pS*0!cxcQ*b4tn?D zt32%zgARZ=!~zs*a-LD%T*6bwT-cL9ErDJGq0!~z`c&c#AmZOkp+- zVq%=&x*XgobSp3zhF{m=7M+X=Opfa3Q zI3lj+B^Gg5Z&F8e#A!$)9bEeL45%ajbL?8PxaW7!DKlbwZ3>&~^YS+1#)8@7Ueo=* zSpdMQIK*ya`lo{kC{@JV{NeL*?pv#~Jzk8chF7kyZIdfV@Olj!bRz|*d_;phCx2e8 z4y`+?X=<{j9Y<=JJlvEo{*wRVl>E&!X)F=X34b^8S8G)o3Q^PF=1oesbmZ4l_eo%T2fV3DkDZ*HZ0WMm`2lx7DP+&ln?{!r z3ncfxz^RXJ|2>QjCF% z0#O%_a-4DgF2HxDd@Nu*h_0g1e62=O&%tkEfpe8FQ}{8^2ydiP6h_GY5X&qJO#(y7 zAN&KuJ1Gkb8Tw?>l&!Y(ph_X1TB0#dNGrcG?>&KrE^QjVY`>{%lz4`U4dV?EdYXBI zbCpTW`008olR=9Qkc6dU{T~e)WSD)@7jGH@cEJGI05Qr0vIjFZw*(xHm8Ehr}G+~pU9$F-5SPPxyyXH$s9yW?C-rLOV2OS638yP4S zaD|;!J-?u{|G9n`@$x~luF?AW z^iHl87MIjdC2%|IgT@nPATv)X z@Cl?wq}KD~`N!0AQ))A8qzWdcHx-IVJJ09S%g=I4d32-!TT=Y*kK1vzs8A26Ot`jN z$AQO!Bl*vO+&(>!6IR-W{V#q8+@5bV%9i^Y9k@j-3D*>2=)8F^-FZb6PEQz45BP{P z&1hBG)-V9cH~0DJ{btE16J8Ma@FDC`?oorQXr`c;#8J_?_4|qlUdxl}V?bofdH1vX z-JT%hX-I6NZNK1#Lbf>g* zOLup7y@TI-f9t+$xfXx9U_LW*&e`Yey(c)e>hr!4x=!_n(;ZU<;4F zlHP@Vi1T`atPhVjpWA`F?MfYf97zQ~GUZ=S5ztc+>@FpvpGy>QvY!_#ktOFSI`$}K zb7y)Eg;YiDN6wjQY%u^DF&OaXF|vuGR8olIPD$oOUnJ*_nay?~{rdoK0<-S2CTMxV z{yX&bany498CVQ>AIV7GC&b)*ij&1pDfM6f#{B{m-YBT3iSVUm)P9YJVFtt|)#?8FkA8WZXE>LbwMEV_bZu_=?!f z{C9}`)~y7GKtXUd#&@rHx61cG0dT8_cE&Bd-DF(dvFs#L$22D6dqDd$L8`8cV?8vy@(Gd4F5?|whCrm$W7By>dE(3w<2>1 z0^YtdkM7e08~?5e%NLGbK8;`cn#y*vJKbt0795x3TIPN#V6Lp1h}T!u4IC$A=9yw8 z%}80j_$GzZ0RgFTcr!x-n=+_Y&ih@%zB@|&Qxa8}AEf>1XY08TMV*AqtLG4P93J#; zm40uW*^6S!(-^>uSV_1V>-n98%|F&e&rvaz0L3gloF;`#GPelu64h!LeVdyn)T)rS z4t2uRiqJpRpslpr#UJXqUWq_{m!;jqwp@A3W-+~8?)h#scU7Pwxf-Xo{hUcM_Y9V7 zKbwB2LabI~TZuxnSZU>GKx?xh%}s$z`IkxtV?k0RL6C4#`1vbMyPSpo8fD)YVvt!) z4b`iid^G~|UTAL+cLV%9kB~K3Alt0{0d+i@*GFMpz-8@}hzqt-&F6_;s4aR&#mZO0^P>UnzTr znpb@RT?F^fSrDMfxr2Y$_5K)WlBR{Ai|utBGRATJ_<+{bq)_B(3;|vxRYPy&X=x&F zjD+1)?9`?3o_Mj*7nhl&hq);+`#X}#xJu#{Z;EG)>Y&@+o5h=gs!yMWA?$q2V(iew zS%HL_dI8m6dx^aW+44EJ!M&g`_6tGLNYSUFJ5-sLgQt|lpeJmuT1qk(2%%AM4`Co5 z78}(+_v<{AQ^Fcctm}(8>soo=*v(j8TRUVGuM*pWfC#dNKWcE$!=}qrDyrLkYWrid?>)MDdN7YC zOpmZ+9#I%PVDRRjwr>p72)=dHLxi4ZLh?-g&wZiWFhIcuLh4kDH&gRv)1yeke#_%! z*419c(8xTofQ_7t;r@P5MvFIFs@q!_p6#x=IammP^h%xzF7YqF+`#8WF)-6XExH*l zEakn?MKQ8X*PAv^lOI4xx!RWV?llUthH4em13oSuUp#OD0kg;HzN*fQ1YtPM7*5bjbKFjY%m^p0qBKQ>k;;$-AM$&;qAIyY)|q4mB&3+YK-mTMB0yI8 z?fo$HNcb@3eWL>dnJigs-1`- zHL`faxoFte_CHizn<7T8^HRv|)hYkeBChp(cUqi0e4nzyQ~4ueMxso-s1}0{oR%nH z$MTDR$NO%vrA^NJ=Djfa07ZQucU8lan+;Q3TmjhIs23R9;r4bpu&w_%f-#2@|ApC{ z0LqRV{U-`V&3u2X25qeEas@Kviw>7aa;{+|={xo(4}~HF6)kx{VNI`J+k+L&U0Q?v zfuR8R1q1V&!o#s2Tqv*Gm#;q*IjZA^l=*>2if?~mV*Ru5ip`;w%o9k9yET}X!ZHnx z6FE3;$NWwJoiA6OLC2JxLox1OcfA4=$T-&AJZ1{zi4}@`y;28_B(YoiKd#>PiZ7q$OR;oScX=DdC>3-Q1EcwBI?}Hceu1c~p(QU*LY>gW zzH2!`{G#r+X#7}G-4*Rq$@=E%<5T)sIrW2^+dpjomwzfD!MK3W;0%sQgZ(GKB;FZQ z1cou7VtEHf@r6Ik>k2EMs@f$-RotKT^|i&hDY|vC=fkVpjRcFo+Fr`fYa^sEnXlc9 zMx5LzTZ#mQy6pm8*+-8qlyZ_EHi@%p%SR9)(FU;fdcClNG)bm?i zUER;i_rc$6xzncQf;%&5URR9~59&91`;Ck!01Kzpy3N#Q!00N=<+vj4k&uKZ!Ec;t zvg^E|e#Gbm?{it^-;VJGz-oRL(TiTYmJNHSm48!aK~aG*xHBH*D2|%FVx2?oTbwI4 zG#O+ZZPvMGV07%R7aizybL`pDTOGJW=!i=z|LD@^;7x91;OLBbf9Q-O&PA-^A4|9r zFbfAY#)LJec%r<6(Xj1$FSg<(xLoD*HDGQ;jG*_;mLp`827*UO*d9e827&w^AS@VX z6w^n^<5eUWy`rYA{TC@GsZ32lA-|~6CU%2F*Uk=cy&Q>?*GD{i_BgQRhry(*9w&a# zRXm)u`9&)|@QT_m^ZMe&_X-YrS8DGo^Audfk1S%mi=eHb zM?yrR7E!h)dN3;oIF7~ruxv1~npV=eV^gJi&rUbhik0|Z#reIcFX?Og8Ca4xQedVFe57ZlyM&eK+xq^wG*LlD! z3ux&pOZwJd;*7iP>;i&PR^VBY{hp)~;PnH2=wDZFkR^c5yZ6*mYz6QO6u3Im!OfDV ze_jnb^B;2&cbvO#wyU%_Tm-Ph?Yb;FZVrOE%nz@6V=X&`{VMYGROks@1jhtXJX zMp0~iM<7}}!D1)89pkiR=Umc#r5;`a)ZFeDSHfG*cHnB$pVT^&K}DU2)(!G7x`zu* zkSoL=qSG;zwe%Ssvrv$Pty^@qLsrn}lgKcfW{Ypv;l5 zxJ|_DQn^0vxRjg-=Ah;IUx&BJ5$TsPG?mGsq~Qtu{keH~nz9};-H}vO zkUyJX&@d`Q##API0Rs#T64KHx&z2@-U?%eTgEc?Sl^FzVYyP;k_{$13VX6h3rZBx0 ztv(zd5xqE?1BVgDpL3|k5q4en)Zg($W$I9oWM60j1X+9SOAZ+?6%7tVg4xV}#7?oPgS5Uy{Q z-`g*yRg~v?V%RBjDR0K3N)s=Y(Cj&nJxO&~whLxb8qGhWLZau4pVOqcpAIc{Y;BpE zYUWSm6zl?0Q7zP<46o)slp~_Y-C!gk$K#2xD4W7D5r^yg#b1HMn>X!WF%Pf(d7n)V zbV_k?j-0E4|0mI48wggw(%hs^&;rwz5p!(CLY1IV8u&`n-|h3J=Vj*<723!+fGQ0r zvb|Mz8o0Al6Z$lDrYC3zzB}0yFXOwHtJ1K8 z;jD@lC3(&N>Afwy$%S-@RY<(KQgEKozGEZNI_WPJJ3~9nk!HNEXq|S>{IuPRPuSw9 zsHmJX4-+zkcCNY~wUg_<8s>c2jEfi9#(D-#5I!0;!^i5zO$k6sKUfsNTcp~WZ_~5Q z7#;fc9rLrN3S*(A^jZcI#MxJ#4j12z)Uql9@$Pk^wEj@)M-ID{=K$H&+AM~N2c`>@ z%LO&a>V`YdvWFsN7abYa1s@!c2xob!d6kDM7uF|m<`pqN2r>^j=GHIYtZ_OIG&lyc zE$BQs*+o;QtU&r=fxE*8Ppela*F5a1v`m-pKmN6OOUee=`FoUlI7d&DnNdlllw4d&XJV)iLOlczw9WxJO+6R>7+8UYh{?Des7^`t-XeQJ=O z0H(Yz*ytoOaMg#s3Bf{P2gUZ(S8xg~LtUoh$nFxHqP9a;8|f=wC9K{qKJpHxehi^g zEv~)5AvY(XR!uMsk*cjE;}Ul2h&Er7mdEnzu!L94NI=fyd9!unQVNDU2fgwA1G(YJ`m`FoAIKdre;xI~`3q5w}GD$7c z&Pkhb956&yK!5Ys;U0useipxs{bfz)L7$W^P9=I#G~SFzSMV!LxB6CcfJWTiXB47h zuxFgUeOe;Qs*QZt(LD?Y4e++d4}sreh92IHFHgwJPLEO9Y%S zs_3kqEFkzgutWqt{Fp!!Hhr7pweRw>cwF@L7~OJEEa%o{4-La8FiXe=lrkn;YvR;_ z(+=NsWE zv0Au0-A=#fZj1jrh?N@4$5Z>om|4#Hcvfg6ob^)4iDdn{E2P3tKb3RA<{M$LoO)bF z0qrSKD{aSwjJv>TAEfcOFUm)NQ2eyaTl09OMPp+%dU@!fZ!8Km6R zd!R5IetrrZIDtiu$8jevP^3#Ir}EcXHUmL3@l&w`8#zoOz21+JoDOowaLfCmvZZBsw&;bCvY8?aGQ!*M%i3>@;Fcw^ z@i6^8g>=ZAj+oHRtwp|!(T{>OKr3|$4h8rm5ep02V8~0)z+jdb4*1_cTDe1%m{hm~ zl$BMxZ(&wP^99S&!+drDiGg26ni9=$S<Z^f9^IJ?DF1Zeh-1)_r0~m5WNuiG? z&P!^Gq?XYBTlbHwJ7NBh|GHe)p+gwprtNtd)HqL+$kQ*4=K|V3lLJj8tT}8!>@(FB zNl&YXG8L`~iPig?FXT1zs-ksqUKuW&FTZfX557PAUMtU}-T24C&3`xtYMl0o8@Aw& z5Vo2xN3nqeY>)Y8iKH5j(a6#wvS!lAUsVpd29_D(-s&Dtx^LmRW$SYUB4;)OZ{I0rQmVn z#@KPf1hf@Dqq@~YxAWlN4`1g+zY)-q_w)ut9hOoU!IU7XSnrj~@QA2R~_6IGn7+sCewp{ldl{rrem>4-bjO#1}RH|}ohK-=)x zHNaC-l!x&CfIljL_T4i&gZMk{K*n-e|F!gbb+E?2FWC3XaUB^&?OywM-@^aLxIueZ z7XW$7`r1LZVO_V||B^dSj-t#_Z!A*6;tSz)W$~$#ZyH0 zK|w*$?Tcg36uSm13@xNRxVT&fjkucqmms0~%mg0#qY@HX=_p`n*4nn(aWvBRO_doS z6kE>(uFe9h<+neZ?^*luQ#AA4#qxgO`_PZHG5Jch;E<2f1i!puwoPU1ds^p?ARFjK z;nqlue~o=b0M*7;`nODS@-s9cNSodkg}@&HE5DH!H5iL?LX(*v)PZ4kRQsci;g*Q(g%dc;OLxp5_LZ)i- zt8)(Q{_AX@DSx%?sA0k6qBvan-C`U5O^EX1?~lB^;lOOnNqPZwYcncFD-2G*2?CZ`$QrK3b76c;Y~y3(P*~C37uTa_N-+r@Nsv(HuXt35H!n z@y~Jp)g^|&csHX&Hz!~l$uQl+k!)?+7Oi$~qP%jFdKPiY@MIYTeIwDU8p zw*J_{)%gH3)$>f8@DQPm?&qk!X1!Ijt4kWsqXJw9H>4Qr-->ILeo$@D zH@s-(Wkym-LJz1{E~-PmF+;M7XRwid$*#?$)eVdkSex-`Pc$n zwjkuOkZvybvpgoM?>9~uFn%}=Uk`NG68(_IHS=(pv^xOia-}b!95|78gm{Xk2AWtk&;}k*ror{3ovb;{8ZNt@k6Z&)`eCd0WpJGiCNK9PU{o zrespN3wNjNRmWarSNi5o`8(6DEk8i}+iP&KKg)H}btYzSk(`vR_Qex6!fO=0HiJ1& z9v?DuVr!(0B-h)QEluj~B{&3yGjo->GBq$~BMe#knI{o3puqsYB2swldGGmkM>ktU z^hA@(w^rV*wst_UBy9oRl{@z9!CM?xDF7_!T-V88eWO5_KoRu7#as3_NMwxU0!)a; z$K~7p+q%~(Czk2x<~TIECCc+Jl$Et;QZk3afa-5#^_^rLC*d^o=0M{cG2AhOeyZxZk&J! zRn#a^)3tLxu%i;<>-w8u(dO-N)TX~-2Rs~mayudWUq*OWwqCgg(`_Cl72cfh-~XgH z1i>w|afeJ>;U=bws@cmAV8r-43mh$B<7P7bTME(Rn(J8FGK0zq*0cFPU)gWpOYyh+6jY#fEDOsL2*aURcM=a^fG#Sxb^9O8XZ$ z7To2jWUuGaVM7Wg%-e@pEmy5!TCOK-0J-MV0LQ^f=7|L{8!~Rvxf(Yh}?KzF;=}9m==hk<|HWe3WJef9I!< z0QNxWlcwmc^ zr9@^bx&AK~K+bI4?%P=5dpoK0$@Z5}zjqs5tu1VF%}*yD&(hl7INRMp*--jffk zvn23=b?3HTubm-2=Bt#hJO^jBa+58vcpNZU%t?!_ zk@KF{kmTa40C_ENm#a)W)wp77lSMOUodM!fMD>Tq>Ccz79|pM>A1M%h`PE>buNWg* zqD;YC2Euf6(1*Xu?Q~9=wU%}MF&t9kfBF-0VYx zOvC)!LBEZS8A@mU(p5qZcy4Ag%dfRl(NX*_BwG0VP4L2uv!hs};S+{-JCO(O^;r9P zhCcHy9 z==n+@`R3aXb#?W@Uv$VX=*4mR%liAhdl|{FgK%CJg~DxNb4L`;Tjy%EjRfz1c>8-O z!618pDa!xy*=Ruin?}+=bm=OzPZ<;D+YW^iBmCbpTPsbte#g$Z)xXN+<-|U>OT1Qq zsT+>LdLyKyUj8OiTW@O3P7l?~AZUw=S-A z5Ig@m(&8epmRUk`ad3Fwl!C=YvInaxc$!WS1~Z^+&CZ~xuR{fO zdes*k(LoFTbi)9>vm`k;d7&Qbn!Y+Gqhne%S8oFYii?AJsRo!dw+sBcy-mLF^hH?Q zxcN#UvOy^Xt?TxktN_Mom3-NjWZS@7w&hx~<>I&;vnvu}`7?yhtS(cXrNH2B`{gLIew{$(OmIJnjme&L*(Uh8v z!op+{5)yp+)|XMvBm8O)5Xx$0v$x*HVUtqc@IDVzePjIEoOeS2n;gHnZ{^iw)$ux$ zH-3Z5;ZJ1okEeU@r%vZm6E?>}MfEqyV?$&`7#VArxf^u~Cq}CnHY`SHCbN+xcCr(2 zQedw@e_O_~E( zd3|ga(x8t1Zh`}$z`j_d4)pBuj5a_r)b~PRMy`4Bk$22ZG`V`YTEHBw%l0sf$3 zJQ?xZkXG2l1l=ajo4!N(6w-0P_1by`2bjufXe5e)QBSlFEiEks0>my~{@SD@3riNjgMF)wDZ=?h z+(kt3_wTRs&$T2UonyTI1TSBqV6!kOLH~63!a-LR9D|9GNJ5f*G$Cx-&v;KR?biQ> zt{uiie`TIILvAH2XpICThC)2ThMgKOdOh0re3TdsyWbE~5o02Q9l27dGXl!*uuEW} zQGq4mp~;t{I>?mh=F~k$S}O16y&vyuA0KXE~;-{`zb5cVbGkmlm znP0V?&A*9<$o4GXXBZJzuK?1`a_vE&6tiUAu+j?UzZ*uDHS!{N44);YWn{H=A)h9h z#V|AHozC2cHN3JiGYaBpUGN`&XFRjzARgX5&-?WY8%_-gF%g}z?4&F>N;W;0jP#Io z?nRjB*AqG=l3ulXXdMzy(0;EzSIY`2V4SE3v zSV;MlK2D_hp=o!;&`0E&Sz;{PPV%&$N)AyhmlVpwg_FA?5;E`|yb*MW0w$t_jNdX9 zlayqn+i$hLGpd!SJv%t=AJSjg1X~*v|KHYHH(wirr!88y9Z!nKwvN*$*4qfD)tPC? zs;aFSKF+&UzY>d3$Z**+pN*0<2SG@Zihr(j9u8~V_{+Fx1VTyR-LUcIC>A%<(i6LQ z^DdaG7K6?stw}DQ1CL_hYj4bm+8;y(DJdyf%{*b8J~%b{G(S&zUOQiFvT8=1mA7${ zdhf{XZLnse$|Ga{fSneHH<;7N17|r%D?P2?wlj; zn!#fdL5xoGm%U>*fs90)C93rkhjQlhW>kRwVoFL%IRzUmv(}Lh$0f|r=uUcH zla$3(4Fh5`!{UX^ptYs##qgNbS6L!yI^?<%+w7aYH}~q-oaf03o?g*5=d}f;r5G-Y zp6p%^r)gC6G!BA$w*{U060SS=>Sc;jQpm(esPb^xGu$(7ljz2dx>7}6+)-+t#{4r@ z&pK?<)C@>{VAJ>Ft49KN=gPXjwidt7Oj(=?5+iksNnNP2zZy_?&Lu3te=gtZvrJLOO^u-y(ghP*zZA{Txv_ZHZV&!iQ_bl340> z@7}^nzIO{D^ndBv^E{>1$F#8%KEKKQnf54q$NChjl9BIUSAoC4-Sr0tKx=z~sEQ5~ zehgBz36QFWT*3zL@=x-Mj?F$w{K>~~QEICwgS``#fJ~NPstAoWt-CO-**mH0_O{phD_uQ4nHCDae=<|L%6_L5=0 zu+*uY#2?Xg%K2#uO&=Pk5cy7S>IvniCFn%@*=65IO(*|vnZCU}Jpv*kaA+hvTkI`P z_Ahf$672@Ox#Ee_THnBfCC0pc8QJSK9E@1-l1(kd>56x;?B%j97U4>gH08U*xa)yc z`;0E6^m5`ahU)a(7X3B5PzVxNitLdm%ZOk9OUf03b^8#O&5HS?vge`Fkv%F=pWp0R z)y7>Gpu+5)6`*=~Q}ExXc$y!Wa8L5S%n+X|V&TUYvlPQ5YY5&b7pFYcg~Xb^u7l>x zebCjbiYT;N)-(}5cRHWC4ok@^DMWbZ!cR-qA4@?0XjU7HARa52=Ef`KpI2^3DZeNG z03terwaXk#ff~924UAHLou1VP!qM<*gUuuA9b#E`UQ+2WBUAX>W#SST0@W)o`o);H zqpf%$>}{GDvHOBm(_O<8ojTdFS7mo4e8nxVN%CJNY$_m;2?Qd?=3k>h5#Kr4xI=tw zH%&Ppv8Z&3!{3|ev96K}_1lzB5`CtGeN@jsGmWMpYTj?Kx6o_~U@MfY4&dO1!3C}fr#xtPJ5IAEo}7;zW=3~CHRs>;h>0uF@2z7V~SIZL9v zh6cg8*Ujy%-Ete8rliVh70M2b)?qRP!s^}xS&FBMEgb%?meKk&LqPRoz(EGb%K*(y z`t2(cuPeP4*}LWTfO~k{GLE;`+^bq6^M)+f%B40|R@gbik=ki+O}rtgj0_AwU#}b* zrj@hldD4@X#fvt1-u+NaKtOOu>)W++$8soF)~Nlhnv%!|DNyGZyTS?mFMp=@=&5W2 zw%`knRShK6=fb7V7`vMPSnlf&V0zED#Tz`I_2)=->Eif%o-^w3DYzttu2k~-<->d~ zp=llPCg>kHKHqJqHqe7hG|Gp+fY_3zW-kBT?>Kurl5cx#rRM83ySWmtk}S&b=GWw0 z)Ik!g1~G;Ga&o%qq>s(>pdbjVx~DqTXS~O`3{L zS?}$0kYZq9048-zADeEe8tm4xhTjQgjeINOw;`@>4=9OWb-glnbcg73r8m2?Wm`3Mx+1o|& z(P2R4bt1~rUYnep$jZxmaXIfo3K1vCu79h=NWw)J4O!{R%2Or`SoAd+>X+yb$#qo)?f#m;z2QCA+V`&jDKZMJORWjcm|I~w<1QtIxOBEV zlgnTJQnB$gLvq>5T}Wun&zFmvdsCPy4nJ6~?Wny+N-{YeWVV)VH4FLg*c?o3wj>Y~ zv#XRJ9<#!QjX~3oeRDkuN;*wTHFt&^EQ3zlZr?}lb>5347fK^ouonMyavNW|$r3== zv^Rd3aK))jVhUD8vr}IQD)do$qanV0ug`6at3fj98gN;$Yj$K-jGI!fUFNUFPYVs& zmNfeDIvX0}#4GXd+KXdjWB&m`t^M=i@?S%?i#0r9xV*Ii*3(~l^hn}CBN9;>yeehU zy~w_OmI*f}qd8Z1py&?#R28Ll&-E7)Yq5mOWNX2aI6OBe?HzEu$J4<=svsglyf4g# z$6~h{=Hy7-g6AgRj!0_sWkoGThh|+Uti!K2Zk)fs#LQ{DwDQkKLGN&!gmMAuSEl8y zCPlg?)HDc#LFJ@bt$`D&L$|FX-xK?6X%*Ghp27U8`NqH)^pdH4;s_K@L#TdFkXG=Vvi(;9$v@PCLWk>a{>@Ltkrs1>kXuBbHwsy%Q{`Vc z7bwWf;}4k)yF2|jrA;)yl+0idj!F3A!|0f_53LFne}AM~eyyHw$8Vz#;vc8RziF9Q znL=WTlZbbHaaHv~UD2)*hyxxTyofmM-!RIKtGTEpV8m_Ni$vh0 zN8bu$Ld>(>q=LW|)oX{s3L_|1M6xsEK#&7i;YS3hahH_P936@akzjUZ+z~ z&=!z$adOEhytVwZ-x!jASC-n@_iV$>WTO+Ql4aT4{n$Q~X3SM9FDejGb>grEPk-N! zviJ|0n=UWbA2Hm+XIE zf$QhkvS$Q$@wHse#uZkfPfW~QX;j<#FSG3_PM+YE1#Nc{oe`Q0$>;nsN>{v5J%%TJ zlM=-fu2@%kKlK7dkbM39nTFFO1ZbEcv<*wDdDY#8H&kY-nF0dYdUruSxg!w8>IS8} ziWrFEN~U4k$kVp^6$h+VKfi0GhWTL$Az)g`#YZ059pBBPq293!Qbb6#Fd3?Q_+@+s?p6DcZuGeBnny(=JIye>b@Ib0~Zt7nt3EqtY?S+k-bM%$?BbfoTnncbE3 zU672{E`x;ouWxa2c;IDs?1sRLBW>|(c?!FXF67km(|CVm=`6eW=%X85>rp06-W`P1 zg&v)d*6|`pcb}7D7T_(;ubEmT7$pkUzrtpg?n8 z8$XO)ggfuKS)-%M2d$vaO^ulH-)ZLCGmieDRQX041&}=-)-SqPtGpnWl)!6R{LJ2H zY%w->9#f~fqk|i#sqf#zQcpi-?sJpCWoO4Yuqu7hc7LF3+1^LD-qd6o*?bG}NZakW z$K~y=UZvV{vy!AtVk0OX;KV*`#h!e|i-~Twf@i3$6M#;7@req@jb?Sd{|$yyU)=2Q z*eU+QQNW_Grg-ptK2rBSeuPI}5Iu@079&69vu?HDW8%JM^m92GG3?A6@rR1^ChLOo z26JH`1GaBY4ZT*SxWBkBB-~6>9O#*B8-LB8- z!1p7sX=cKd70~v2A^xkRuzS#EPuNrIBLqJiNrCkp+gyxRx!}K2rc>g1x;4{>Weqkq zGMs0b_Slj7Z)4)2g9-q&BW>%JzAjinaVnnuOdY@Z-sZ7p4N~AVjx;%LiTwuvovT)* z*Tv(meAGECfd;Tl#=J_!&Vh)~X>aeM^vr)XIadsL$Fr#DdCOI21!lmp81gi(B(KtI zy}L5ol&)6^BJBcP~t*M(AFJ>4Q ziid0q3%Uu<{K1j$^+R(vQZ@H@^HphE{3)Dw3IJqhEu&%}7Y?&O!)iHSj&0L?ZajXA zs=|*XE*D#?YxX47R_%h3F zLxomND=*0l{Wh5VV-J4G*B)s!u#E}Cow}33YGiDG-Q_E|`JGXD5;)T!pI(3hU8Qh_$+v~jDv-C`CK@B_ z9@IaTxcoEum>n$T7-d6RpnQ))fwrq=zhnCgXNw#C)Miu(6@lzr=$rFfzr&MP(eRJp zeV{J5_opSJ?D`5Vy5l*vZ|AMQW*m?I^;^~JLg_b4^?Rp9OeE0UXyM%U@s-|MDHfjh|&)py??8oBme(~*`3#QL)6*9G+I%t|4%r~t!$4xK)0 zEQf-Yz6{tWpQJzJ5|%;A{Ip64o0E$Vz;%?j6Wj@x-{ptihqr3l&2u&j&A1mZklrvj z>LCXH%V8tOPfWF>xVte89$~?&I{SK*4VEW;;v#kW1vrPHT8;KHy z-zp*!5LgS!4VeKydh#=P`k-~_TeJ~1ufrg;^%79F;U$ZFKaBad*}(o0<7JZQzhEh< z(Jx`1ZqrQD9r-o*1PQOgVaqLuqx(&0%lSNCaJ>$1tt66$vQE?Q28Q<~|Gvn&VyssF zij+7^zBrc65{|X96Ad?A4jLV#_Mn13L=Rdm~<~Ve6poJ51Z|X724F|-kWMx-0 zRQyT7+qdQAEZ~V>T}Np(U-arJ^qyV#dZ}k+i&U2KmXp?~_}N-`wxf z;`ASS(5>qG0t){*X0MkMjK~FAIPUn0Uz6xVsd83q2WdU3O_|XM^B2{j%ngCN?_VF79;+_a^0IXm&+F2Emqp8_D#ksZcvSJu~jum^YUPMpImK z;00yKr$Iz2cZMbi#GrcQ(1j<&iEZ&hq>}g=V>SHffG;DvG(wPV7^=~A(a2w{)8s@`eVzBDvUWUD>T(uyy zgM&@K&6Em`AMUH2>7KJ;9W`Y=J5?@nKnNWBu;JCwYiC`haeqM=cIN)^-kbh!9mVCd zvKg@pWLq7R{uyGA9ge@g;ReKK31Qg-k;M6T`iqB&XqStS;vQ4wovTUhg$s>V<~s1a!Yg%@GVj=ld8&dOz9HzTwE9qm+5N z$+TQxK$Mhtm;UNKT;kuyc3Em{B#--$n$?Rc_SVg3qpSoT=1rmFz4lv;NLW+(PPk^! zWw<3}h;|L(VJf#@W)V@0;b!Z8;?J31l7fpGMYO314hdht0^Tyy8 z59aE$l{}t_-HjdUWNbceJp`2H*W-APoZuxFODGi=3E%G!9@SXw`Qs72P`b-t;fXrK8 z-=L4Cn1#5CD|A3;gYa%w33~+!XDswcK?BY4I_z{?mN()GhnVp+Y(^)*WnZ+^k%DfK z9Mku5Zh3K5S&rrVvcX*ZU)g(-vG%i&*|sf-4i&3UX5-r2^3DirZ22CjoiQ!$s$0^V3eA) zBW7kawnoRwx-`EWHa#4=Ue3`pPI|&y^h@dW_IFLU!dTMk_?gTuw0e^~VjOz7M?c^@ zg$m`%FG*or*p6M2wl=#g{_aCq6fwRb=ee)4SF6?4^5wtVwEf8CCg<&@>7l8entBeQ zKFHG4DJ;>3gS7DE>*r-;zyL4Qi(QUK&HXB>kwsv6#82e^?AbHDI%Jp~ zk9Q8mUAsJnMn<~8O!+IU0OvLl^Wr-NbDyk61HNye^JcbY#zq|;PW3RFzYfk7LybD}M2kExYXet+D5Rz6Nm6LRIA~V<)zU ztJGS(yXC-rC1PndT~|jus)Fj9CR5!_C?(^>4t@=L;$$wGN9zF2EFfF=7M8gw;7diB zWb8?z%7ul6J-sF$92^XJ4y&YFJtROBFd}I=X+pi3=`@A3TN>+}8QsQjh_A>PFEz8- z!~efrfRjPVavkP3Kk3+TishQL(c}BDok`=Q^wYSjXA?YAU|Q#ggo(TJyhJ>SCl({M z@-wi*>0&kG-#}%&K76Bk0u7YW;P~<+W(!K`k<3)h=^4U*eGM9ey|J-spK9V#4|ryS zvbw_u8B2o+e ztQXqOop2U&JrjDygo?7%he}v>IDc>Zndj)Hacid~uznQ#oyq3Pl%IoZ_O)!|QS0m< z$;piSyIil?9}f0*W4+28obLFbNq2PPakZt7ep3>D^~)v8jAm{|Nt)J&jm_fd`WtZ_ zFSfhbFTC0hx5O!XJHif5#M+!^Bviup=QWSG)sG&yAAS{!EFNJnMksXGIXN*rtPUOO zZN@d|`5{q%?e|`Pce*6p@x1GyUr1PCqqi6|k7zz3fHqseg zEarY1P4QhWcxOI@ZffO~>cV0{0WDr z%|RWK4g3pg-7Nj7h~}#)w1R(pIw~p&n)@3ew!K)0ohDxu$&J-`VSc_L;=_7}%}vCo z*#i*yYgp-3%!NgdSzNo7aS0SO2?Vm2dA%t2RPwP*XQVzlTizV9dOVrhSYlbe`9Z9dC)*X zn2?y#wrtBWWIJ@<{rgL3=$ZsnR7b__N_nu*oSYm5zP(I_XyJ~*?q2^q$PsRzitZd+ zkYfBzX}$-x3NFs_&z!!IN=wS5xL?9rBP@HLS1-YvwXGBbF2fkHf0mOvHrOo6TJGPG zm^Ht0DYEL2bYQOj`(ep@t`gHJr|)>7#~=ZEWjk5__HJP2ZPA}kD3fQb#Zx74mDd}i zNGLKg{86H)wKxnK-za(6xJuOC*;-+NDt$6Q?0CG1+xF}(_sU^19};Lj*wYy|LwHt51kCe^dCNV}e%#X%1ox4D$*XrHJ_|8!IUKA= zx!V7Ok@6vPfzy{f4gGQ;xdNzJp#9#G9oW#Wc=XtmNfsz2IXbO^j0`Gx=Nhg~-auXc z4av1UV%|qk{TVL!zpB}Gv~n1}`&lyt83R?AtgYnS&)jlJvv`{Lm}i@&E;NJ*UAA!(*wLR~@NnfMjdHH{XTRMf1j(-4 zlo)C514ndKZSnYXzXHM2{6XdPUJ|w4bN4}kb3t70$L$cNroe;LVH$;w!CacRwiLxf zx^+#6fAnD)K~oGZ_iMPjK{Z2aIy+I&enJ>rQK$*poGo_9Zg`ze@ownQeLs*lw7~n= z=ip#tFE`&FJR@s>ewE0hi}hePR5vopL4m?i(~O`-Qd$%jcJBK#3I*&FUCY(6a?x5s zh>+6lIgi_vi;%_fE4QzDQf6Twv^g)ww9&n;HY~-DZFo6DL$bz&#;j`$baf$M>m+!N zm?Uz(O|t*!x;~kDLE`RQ?OxNp>!)4PeS%GQG(@^5W^T{Y8+r|LS4hC*VlZjbCBaSC z9YVZ%qIzxcv?tfkw`Eq!#2@HCA?A(+VgDreST~VdUK2T(v-nK%fJWkRlLiAZVQ5mT zC?XQ%L(83p0h1qrrZ}kzFcxGgXCvT7 zGur$?@#mD@9VB)r`j2&uSn_1F++Od+u@cyPZP#VL$lcDD=^t2G1IyEdNrm#ny%d}0 ze*U)n_v33)Q6#5K?6Xb%)D|TaE7PeZRpJM^0Q9b^yeN8W)CjcInp^Kpgxa1%Qy6x{ zRqx|}mGN?w=@%Cn@gYl`b&)P;2pO zTEz3c*Q^D=XjSD@uUPV_titwt!M{#R)~TXyhA%262IqHTV>z=G&%FW28MRX`nEdIh z@1a2x3d>Sd=?aBqT}n@d6w5+l55vttouch$n)tP!C(2i~mpuN(I_*bO)V!Q-FE0`c zR)J^0SkMi+izj}X$HLduG^f?54Q{*Zofl831MGT&qugtDzM;dp+K(hCGbPKzeie9) z*6oW$>JfY?X#;w0E}j&7w7O8{*@HGS$_vjUoaW2B_gC{#U#WZOgw=(ej$7Iwv4vG* z9nZehX$;47%=pAE0%i5r<)XhsTjEk&kA5&+BVV_!a7hmPil-!VDBnvNog0+k-K^nh z#@9~i$l+_OdC97FnOmY9&`OSc9e+?W+3+g=l!|5ATl^1(&HW(p$;}2?&O-t>yIhSP z=5;cd!+iK*)mk3`24`k2vk&Z-tDW)W2rK^|Q)d|!W!Sat8B!WaDM6Z{1*E%?W=LtJ zC8Rs0MY_9(?rso}2I+2)?ymRtd7t-N-&+3AKeCv)@9Wz8+{bxtV?IJX7R@ES%rC9) zI9pe38YX=l1QzI^0Q4Zo8(A_pn?A>Dmt6E3D4Tbk`gXl(Dc7Gs+j7=lzvdYgAIfbL zHtlj)Nmrgc91>!=x9Kb1;Yj>P-xm9Ct54yJs(hymMhJxc7h5{0Bn7ag^f>wPT zU-`Z?xs?_XG1?Pu4sQ$Hg6Q#3m$W?4YUOBt>Lz(neAQP!KvubFtHc^%v^wqoN%gl~ zLQsBTG^6jhLdaj(^U;ilmhOpSe{_eR{Yy)j^vx4`1(|h^mGq)r?XH@q*`i=09M%k8 zeCK}SPyGY@x&EWZ0h597co1Q=_WYnk+X-0 zt1zH#4|x4zp}0C{WZhi8S&eY-a9|!zVQ#OqI;iBz!Xic+XPnl}8-9|(zl?bb%huZc zW@2EbQ}$saN6p&W+CF27qI&TN9Edc3<3%e&bAv*ZXa5m%H<5->{-5mqt>ui-;him* zfh9gZeto22WlK-7+cX3?iAZ@IeKX2SOYvx4ih7Mh`If{>9pMZHhbbp30!>)=8(KMQ6SXn}%xge#{!Jvy3 zt0S`Cwv9}<T6&=PZj0S+ zu{%$pmi z#bwqFXLfe=Yz15D>%Tp}xNvirz}aPs27Z0FVm~b><>XcCQvR-Nv8%xEd+?n_!+)}j z?)M`NGVhp1u%8T5uJm3XWnPEv7X)?4P7G+f3|@Kg}q);mxwi% z=werzYetSF{Q+t9DGxde{Wf_h+Hx8?Tyq`BceaQx0og3v+WV?6Cm5e3_3QH&57s9%x7jsPuL8SO7jM z5K$Qe34Ty+=yal={2L2a!V4ZYR#uq0h}@50b6D_0Ob*SsWnJT(NA#?lwm~x-Z4F95 z?Bl3>eXXRr@`1xQr6W~PXNYPrXC|735MjM=BU#7uHP&f-rXV7SZJHAdVxq%DS!mF& zknV}Va6DFBbRxk}?wQ#7MJ<;&T0paQP#J`CSN?wx)`d&a^jyBi#g1^DRuBk8Fl1&# z&Y@x4qMU3ipIqs1b9`!_ggChwDXi$DC}ES8LX3Kz4(P6iL?l^#e`tmTI;!}v&UmEQ zTy+lLN=AEp52E^tVOhUaN1C>0r?B)HmYCTjn5TlVVM4k%|RhA*T=S(?}~rtHZW-saY{!6Us~YY|Ke6W?2>cZi{ zXJ{-RHxAuJ1sOgBES~+{X#s)8TAx-g?+a3B=gKd;h2{tyJ7{B30G-3acR$6xi;viQ z5TObT0sdDf4$?OuhNL+3*ihmxI!uJrU{w^6ZAJn~!@?xRVTs@~_|BhX{5)uKz16;W ziN=UU$;QqzzXYV{?T8hO=(pwBVRsukByp^zo@sr{Xl=G1sR2)QreJvoLV8Vl}zB`On@EBy2Xz!KYeq zVL-wEUO?cxLHnIQ7#Fnx-M`U~!;_D=xuAJ%X>BbDw1ObiEE@nMcG3Hjs5&BX>iWj* zz9(L5!tk&@G++5MqVq3O?AAz#i5A0lJ@_nmYdz#ghcV(npspEzM^!8f8{%&em(E!i zbVG(_^5RGvJK{eKIH<01xsgko>@}dkJ8_ry0QP^71Pwl0XcA(;4wVT0ImK*&#Z#Ci z*tds0)tB^Cn0vKl`?`{1U!4Cf97qc)B`+Q*DTG|z=KR&ij(`87W)`3qfET~R6@3NN z_5{ZDOb5N@QCo6jFf`|UNVD?j7A4Lgd8ERvvIylxUsbF}I=1M05X_fT#1bI7=mZcS z$&!r)*YZICAPEb7v(^WvdO;@sqa)Z?4Fo=o<54tY{Pqy;J9$T3Fjhz^jtLoLH21Y6 zBa+f|Ni+v>5%@ww^q=K~k6-FecQw3JD0H{s%dL8}xZk28nU{FtgK`^uq$YY%J~N^@ zZv;k~`ehjZ64nEGxR*n8qvW=jnfgtfkXi$`!6Nvt&>zeoaUa#6R>GmbI}pwbM>V75 z!p5gdzmFn1v_i5(jVKnMc*>zf8dBwf&c|~T zF^2~~^0;EbmS2IEU3N}*!qbf)il8G2gd0eBLEj2I;hz&bsniZ`HSq&?3B^}W(Bd4^hMUt*`4NVRun41ask0R}GF2M?9k#j{HB7g%)vXoV};)@G+DHlQjAc z6ysH4FP{EIfEed}*Bb~2EhyI1q!PBRzoppQm4t)lqu2V5A8o?v4u6wpT5K3M+!j-e z=xiTNNlB?R>OpeXL4s|BqZPc554ki|jr&K4qEfPhEP?(79SJ@iiwg=aat$0ti`IHa zB1XP&$o33k0C`CneyUfWh67z^@&>*CEY#lejpTXuQ-|Lb-_=cFaqQWzHvX&&$QryI z!$7#wbU53&1^@Nqy>O*iVQ(y!H_7Jg(XDX55+LyEeRlmiX$p&z^PKZ|{c;(+3UnZh zj11T|oWu3Jy1te*^H~OYH}Eid>1yS``*NU?0RCNwrp`qs@E2KiF-{IxBiMza0^ak7 zvWt(*yGeb;y9$qA%ngC zRdP0Pn08;{m~XlpQ)Tie2_p&C&l!nlB&8;Y+gL=bdRzi@n?$XCHiuxwb;b=rcM{D6e4BcM1TCt1Vpg-el6i8vS-7SrzE4@Qc z3DE+@!<8@kb$;!1fv7i$V!&4hD)I!7>WS(Y6M8)jVm4vbEQqtvh*prcLnxUFw>bwcw_#|j$uJ(1L&&@YHLc+<5l+@ITnHkzac9Xl0NJZKIaSFIj z@$rTlB%}2JJt&PSP$uI?;cQ}9w@v~r!x=~Z(2|pCVv-;e~dh&4kx3LOi7}nD7+|93O9<>0%>!}Gxx~k$ZOkef z5?oh1gl!44c#6F*doQ;n;IJWh5Bc^6zccc(xI9r!u$Gz+3>T# zjLACzxt`eZOlX8T?`Nq{33GyK-d;G^EJA=}%&-j2=}J@&)+am-#Q65?82DddDKiw9 zRFQ%n4yT9hX;}vn#4}2qoID}fU7{Usz$j)Hp%}ESy6pf9vM;2?DX2!CI`hVq%msjL z%87mTl06tLOH+Za<6H-}ERi`%C?y(QtMF?;g6hT9u$*+HXKVx8G@#8Gp_TT)$5?!# z#%b~Tg$^~)jQodi14aOlh^;LvCK=!N`ucia2lA8>R3tS*KAHG`6LF^hZ4)HHFcALW z3sBv?6Xq5+2Q#n(_9gKhafa7>2)Et0;7)T+N*bEL3}<;B9{xffH4j`;7Q*&Q<2rH) zuS36JwldIf0^l2c?(cXau^E|J?>k3j`lS0K(>c9AK^~+1e3S09qTz)rYjX1w5b6iY z`l!&8s`QBP$>*Mmp0+&O^odz!l#OzESE@P{;)>5Aa&&Scz4u3TB@R;zf4{|eS9=@c z%B3kVauvDWn<-6B0=*#*kaM-lr`mxv z;&kRWB~c&{>;JFdAP@(t`V4thNnMe!kDnU8N}lwtWPzO8@uT3nKhkv)_GQMzz_sb0 zAS;L7`fk@3>v$Gb6Ck_uttX}Ydgkc=Ype>2I#$n`D*N@I$R#9v3L(~j8m|^9qTi&6 z40##!bL+bj__$m!S9(Bi9hA8F6rYJuK}W(5+)FP89pbX;%%omsQOR2Yw2b7a)&ySz z+U(?c*6T4)?me175RUwSf9EjJ)RDDgod&E7ppYkMm#>8e_*|yGEOSNhq!YpQ&jpGM#&klccObcPdM!OW5uzcDd#N!(+Y3 z`npc&h>1d?$L)L=THpy)Cm5>8YP!n#KaU!hmVf;&6&u9B?c}A~@_`f&CU>_4-l(-* zoUxv(cOnrS8TR2LJQlxD@C+;@fXJx-Kh!%f3vgm!6~_WBt4Y2IJu9=c#?B$dGawc^ z=DWoXeE;*Ob4hMpP7X9}TC?6Ai001^Ti|2{G#|{Qe@{W~L`Ys9_2>~4g19U)HGoTV_4WpSY4t{tT5XJSLc7b|${Gj<}LBImc{$>DuA=)ktmq0*6uK(0q7 zEv~|@c$3!kON9KHmWwQ0uH>7Q0tTiNnV(#)Wc6nR;0LmC`B?=J8j+BQS*`#+09QS~ zW1<3DI$D(|O>8yal$bO)@gPxbk)y-I?>+1&W{U5;HAMquHPO}9LmTw=kU?pqm*kH7 zSK8xy)ocQuyob)=MOO#2lVrN4T_JYVT)sMLY61Bl6La$NzGo!DoYgfn{>;t+d3A;j zXf8Tv_)JXIMIP;udkXw(L&GHZ2LYL<7_EiP%;+6~jY_e7rKgPEw$b=#(3Eto>+c4u0>Q&xwKelqw;F@#g!ZYK9^m6-47!G7FfV!o` zSoO^BgH{+0shqgF9D3u@vhJ)vA)7CzBZsQ!>HT)MT*=UKDTw^#8ZpT-MY-du@6(+rAJYXLJI7+K> zNd6mkxF_suq19p*hk2uSw8t+jCcvk8@B4ldxdP|3G^^S1FzOLvfLQEVbDYHyrkJMU z80dtqw(}#Ea}q7q&ps*zgF{bda#JI{(h#TL8rNN?Z zI_CpZ_G*vvW)pJYRq3iSVB3jZt#Zu40U~le_fr+NV`l5akYJ#Er9JWgV*$41+J4#R zOHC3y1k2rmWsOsXXQ zz>eC8%FNjtkIaSBWTsp6)n#87^(rxilw<9 z`U|HQFo(1EhXAC2{R9K%w>pK?0`cuZr{BMSi&pco-T&NECTsKr&z56Mig0N($@D5y z&+5_p4&t@gfTC_6#>KD`8J)7zT>xi>RTrZM$m#Q>6jWV(eWN#=9Uca_1TRzn$mGu+ zr~vL9r~cx9Xr2ES@@5S1BZq&;cet%Pip4^wKKVHBI(+QKxE&Mjh^*Q5I9+(2wY%8Y zd2@(sejhBomXT2~>rsD&<=XF#!P@#lfcaL~-}v*}x3_nZY@9s42_28`S4gTpPxtXx zaaoXhZO*dCrGz@xp(f>|*=m+*KK?wY*ZwEzF7CXf&wc$cXMGL(*WJqf!v%Uolv)aO z8;#p=?7UwcIydQ#TRM$fKHa#?Bn7XkLvxK?v88r-Gz`ePo-)02y$12Ub$#)U)DnadNIzJnvVGPfo)7%BhS`ZBO^(0?-@Xnf7s=YFH)~UH`J^$DQSGuIbLG$(TcOGUeWV$8&r`NIwfHgy5G2FIcn>&zJ^y+wRtRo# zjH(qd;=ekU!H{M!9ZXKq*bY3VWsMmTqTch8`S1V=gtK~I^m1Z`X_DKWQNFGeysh4l0jI22YB% zC?%IeL1|4dp*1m&BULsAJYj*K6CNu78FHBgs7=rV{Or>q@z2Lz@sLnw7%}>tmTo0F z?|h(Li(aF>iAZfdIJE8f?Mr6l=ci_Eo>`!d*VK0lbn$9gR!ntCx_MVK&tzGysr^j( zf`uCB|E!Pe_M-G1C|j*W83{mj_9ird&mQniNt&9{Vv-8@{(le-wEq?NmkcFpa;w^G zis;s}ZPZPy8)hN5042Wk)yBOKo<;T;?>Q~Bto8jpW>$Z2FJNtE14nU8+K-mmC&cIG zGlEB_O=ceZa@-Ge_d-{>?N)ur}$M zn905&`}W|w^{0{w)$**#WZug8KD%`>vu?5bdmxMnLq=v|Q>xy%{-8_4?^DWQPUHN=a@Fz$q7 z_Ji(F@c0Aca#Va_Kf!gt?XTt-uK-k+~1UU(emTVg>{;v`E zApPM%Z2FwvzkK3T{kk`PwVPwtmu^XjQh-x*iKnIT;UP+AyVrpx@s!yG3`MWJKeJ$d zwv!t}fzA@}SJfxM6}NxQx(>(mOp{y2z0I<$RDL-!D99Qcv}Y7L!aOWY=l9T<>c|X1 zQHzIPK4sB=`+h33b4nuk{u2`c;8Q{{tw|0NKf^2m8l_&Zn`LBQI2d63CCSb0K6#lC zqYCa3C4tjrA#BUEyPr9>;5G|`6a{K?^diE~Z=jvH@Q~T@JgE&d>at82<^RW|7xpHG zgJ!4c^KmeWDjgjVlTZ^K6EoP7E*JkjkD7}!g>!3%;GJ;An^T%DqeNXxgdOkO z1r2?TpJast6P$rgmBHV?SMC6`-Dg~|ZVdl5btK{Rn|dit@Wqf$ z_6_1CjA`-^n{H9~Ve2a;qcc#{i zxSW9ys}sFLu(_3T4*3B{LJ9XG+HXhbjdzf_Qf2_fH4WKKJLA8t2J(f2 zrKRX*V;Q|b#QNm-x?p-}SD}m~s${Z)X)^^Lib_PSOq_idNpbS3Ds-6`*;z>7P*b~g z)0MdWUb!mksK!eu?!ognk~-9a62mSJJX)JPrqh`$H6rBL@}#_mv9#EZz}z zd48toASJ4QGT|Lu&+eVr(OvgZVEGtfGb`s-W|I;^(E3H-1tG0MmNJ)LWMMVT?FT2w zFz_j$PT2W(dsLKn`L<_Zfmq;03kart@e6%-wZI*_!YyN0x9?H66ZM4L@cWJQBEhx$ zqB8S&c+WT0N4qEYwDqweH#5~Mu}*El?>Z!IN_ zd>QNC+pDktz=s3DVSl(4*?71^6GdY$^9RuCy0s}_$Rp~6qjM3F12+|+KvI?GI&;Qh zX95CNHNPPv!Jj@OviU8Lh=ZY=Z1l*$z(7w=|0*SlJc}e2(dU?YQ5H-n+{>FHlzzL{m1&k7un)o)O0f-aOyw_`UcNWxv1c^plBx5?by!Snw{QUeq`%AzTKkh3q zf#nJpASD2gmJ$uehc<)a+2ahZ%s8QsGD$QyC4 zab}CzJu-vp>`KEKqp5EK)&(#HVip5g%()MXyW$aJ$TefZB%VS^>?GM0pfwe626bnu z1h0}Hq%*f*2jARFDqa*9yuOSZjKY8gEYpA|F(0Tb`GR40IYJe=@q;roYwBUA|SV;{s(B)h+&m>5A z{!+@E;dNZb?7UHKN%Gc;*pD^BJ|FY%^eIcB&M)Vp^CmS-mWB;hTVeSATb=}FqLAN$ zZ$sw-VZTtXkU=MZQj(g~nz|o8<7sVvz&t$)9TGG#&HLgDa90Y)k*ayZMM-%(GEl2#+6IFD6H#NYZT;v}a5fUdy zLv~yN&7+Vk6SuTP@@%(o6;M-Yh^$pWXRm0n{?uU9e@%8-4J1~s9~iv2LmzhSrR9ol zmp$;ba`>x0`hv7bY=%2YvSIwWF){HC$=Q9AEj^OR)&?JN!U`gv!<}f2D*X51lpUqO&2Fd-X+W?}PJgzVwgl_nk}v z%Xg{!C!T!`NC-R+t+P+ohQmhm!1b_UE?zK7-lU*cW*LzBe4u$!{@x; z#mypSk=VW;sl#;OQw@O>B=ys4P8l|xBaxbJiDA%qOkf`gO<(O&_9pyH&uUJkvpI(ATgW=)V}x39lZk07=s??P6siwmZ~;u*}D(B=UL)8^NiAc=of-3+=(v zKR0zomx`uK$|suC2HekLlCq!Aey7THKY+*IJsSs4*Voqmi?P_WFSS<1P{Gph%Lrj?%}l~*G_+(gGN}zSarLQugk|Tc(uig& zcOPX0iDmn%qNs=z&&@8^mo3`8B%T!RA~I6omp4KNIMkp6VG)h`c_Xv6r~vj~^wJY(%kO=5a5%wV!a z76acQFS70Je1NO`%ko>=#rth_MI@DnCuxK}tIpCCh~h08Xo@&9#uDhme6Y%kY{3$En|Sty2$n03BS58*{o3phG=96w1v!xZJ4Xd|Vq~Z1iTr zZ%Ul@wowyG_7wUH{+fKfhBolFROZZBGKFvfk3tU~9j0OAYWd+($BYLHJ_AZp9g@&VIy$}Bu#;6U@()n;o;~~Z{)&z;VQ+gp?lM^S zSjRQ9qrrZEL#7W>hu5Pl=hIr1?-O=o>C7%AZ%;_=6lWg0{c8nz52GW2@2MXd*|Nui zyZBMc#sXF|lAIXdd%HT;<3wHH%!E0~vufjGumEMlnmNBN*;7jco$!^_Uo)Rtub z4F}$6$?2G_+%B#9@D5j*(%S$fu%|%$cEb|M7n1f?*kM`$b!Jg_QLuaCE7Zcbn~V!Q z4tei==qTwRce>>;KP-`k6ND3IATnm=(^O`7e8tyutKjW|$-lM&%&<1y{<(7E9$5p3 zqPv>p5O_%UIm!}U2!utahxiGo=6Dtor3lO6M0SS(c z)PR8<*6-95ZuX$1fr*gw0*J8iJ3eI-Li<`Rrq|Luwe|IX?v(!J1^zRtpRnU5E5$Mj z7q6Zt6N7ZU8nhai<2JmG=RPyEdpj^K05P6`=9%;M^XuM?rF=_!%E3s!J^SwU%AWPS za`uBt#J;5;N!#CmrR)H`wSTY=25KpnqlG}A=yT^?<)tp-7c1+hF(qcp868!;yt%m` zsMtS9B`ZW>wxby`I2(;6Qv%%nGp(AffPCutv|f>0QGs=R5bYB6%e^uDN;$GVw?JXi zSoSQ&7fy9D1GvmHDp&hB*3Z>$yf8il!@rydzxb+T`pvwwkthh?(iSH&^|VDatW9_c zi`z(PfF!oz5`Ou~Nl@hLWQLR5F8JF%Jxh98EE7iUIBni!I{$lWqn|I{+`y_VH_2|1 zKSQ3UF?HQvXh;v9f8ZwUpNC}ut@ie>cO7@xpyG+ORfdM2I=o|_Do-GIB0x%{Az6XF zI%<>i97UZ%kwnd_yOP_>+s&GR-9UjK^YD!l8f|8DEp*mJMcJL3p}2InA0kSUc6sn5 zwgU>gIvFMghD~Y%!esVOd2q*&a z_*s^QDNAxBnG#0*O93+0d!&n->s6b#=OLq~XTr|40R0LsGL|TR9cW2{vX{v!S@?^s z3|r+2pCGp~3t?b?yw?TXxnBEu@Tj}aYD#c$y>ipofYA3>Mhh?@ZoTaO=)EX(HKhi~ z>rI!c6i$~5Y57@j)UtLMi%dfAl20G(uu6fXt$l25Zzx_@f zkfP>DxD%=`5_Xp*Z1)#L<}Jo&-C*5}A-xzW<@v*0d?yq~Pb92}M)G6jmjN8&te^uv znhpPZdb-^xDqQGi{fUVjmFSVvQPSXzpI&5s;N`rB(%|FqwqANvt*(uUJc)UX6xxP1fh4nLm7C~ z1Nc+Z6}R19L(uTjg-3>&FfMP-M=m&DG3ulrh%#5T4cM4GpGD_gC#wtrHo!_$$<6y! z91x#3jz65m7{v}Rp@14?p;}sjn@bdb)uYe?7H1PY2Pn*F?DjZiK$h=t+`Jrp*Q7J za-ucNNw_saBoc3bPY>R|zdG3Vge@;G%Ubuqgzc%GsWBXSSe&Z7(_M|@m;~bca4}d4 z7Y`rj1r4%VvqBn#AANmoPZzKWlv?j$-8ATDAt*wx4I> z@m$=QZl<@|mj`k$rZj!t)+vCSJbXBPQ{F0eUAj7qh1u4Zkt!tVrOoT(H8W!Ff%amz zi0M7y9h&j1_`F)yVBeFA_1i{`qWc>vr3B)eqoa^JZG1w!1Ju>v+saR9S;gxN)F&cI zR#7SD^c^_5EK`|v8uYpE(?u*S7+Rc<%ynr>b6hI0`1 zyx15d{5ge29zgA*XyFu%`m8NWG7XO=m(eQ>qQ~b}3^a$L>o`s=d(Amac1&sQC4%=G zaS=$)#E-8)!&=H}Xw7|aSvuJ2^NLF3)R-zJNkv*%vBvtOA&~ED45+TC>vlGjq9Mf@ zg@?1|AV8>4o40RL%gb@j`_~?xR-JM?$}VN^ZO5Dk zYT`66HUx)`7zAZ&*rjU6e5(C1lsO5N8h_swPu{6X_v>Ok^DqX%(TjHS3*Ij{Rq529 zv~?qazVWIE392|E=_O}GCf!lBA{-I*;4?NeY7U|aK`0{`oZ+Ba*XEiD`85%~earn&&+&B?+D;*Sd zLO5F1@1|&#YO>*h`2TaJIyQ*a&QqoD%{U>apO zJ*p1&_Mk@hE6eUh_G({fZH|OHO?t>kJ?dt4u?bXDlVd&A@DF#W&jNXkGL*BIk%EST zO^CP4k>Yp8z4hZ`TR~dYI+kJ%QX@nc_oONnzNKS-Zp|=R5lGy4bXk~k-$A7%2k*g_GiTY&t zMg-B0$KH;|bj|$5H}yCJ?e=NI?9h=9=%&I=5w!)wG#vM%=H<=&rzPw1zDNJ7HHYiD zmmOnCRpTL`tJC!!qo2gS>LnTzi;Jo6S)kjpS7@xQ6ojEE&AaSypPVfT!kT+MelD#^ zXbG!k!_@9d{tnR_4kx^8&K6UI&D3j@lir)i5r(lm>OH7PoS46*5=maTg=gk>xHP0&-CoQmR zaZngTImjy7GU|uzy#$Y@7AZZw!1N9BY>>G(_`jYY=C%0HrzDC}^LUFaxFJKDgf6+$ z{%1Y(1zHpyQ}2MQ&VKWsAE`cGPABcZ!C~QulVE3P+plN~>6EWx*qg_N@X=r&i>dEF zT)%yG=5v3RVIB#5*i4G*Vt*IlgDG>DtPq!40Is5lhsL31We*NbU{=w`D}(hENfi3Y z9xpaG9)KuAsOoEogCR{#bN3ulDezU2$Ka-Of6(Swul7-aRUS$O7_I&BGnVKI_5eh1` zhVu&f*^`G~&#L%!a;mAtHiL^fg+kg-P*G8T4-W(QxTt~?29Ocbtl;#;)KpbV`SCw%TIU_Uwy6tY5(r{Vyx z_A6UF_=|5!Dx*Hy%*@RBfRcAiU!N2ZU-)}uB;Kz?h1Ww(RJBT{$T#KvQ*RxTD&f2R zoN`7kB)G%TfsFy0{Gh8Q?<4p68Qb{6Pl^q8TXXWT_It&Z1uiRIhiiG@C41g!Yl=oA%*Lg30vb<1Y_+WMHC5xISz*zBJjjThDoZp|-KBpOmch zb3}|{(T~kLFyf=8UEUK;MaLPALAy1#QpZ`CK>5T9W-;+`XF>)MLHh~GMWxLoLG_Ru|8+WrP4 zI}WS8qhDOZ?^@UuFW(eT*qZRIHuh|7Nf^M(e6It%VYtAlA5)kc@fiq=1R`nttE#H* zNcEwzO_ioHvD7r?!mR@7_wf-FLP`A0GzB zAt-h{5DFf)E#e|6vA!MJYVoQ1e)FvKjz;hUQ3`Nf*kU4?*cEF4FIJy;k9=DanM;~* z%eM0_)t>OMz+|PDaYO24{$6oTa?eRFZI4OPA&bcSb(7Ap|_NG>QXREi%cg zj%3(v+^I!jsQEt@fX|>-cl`@nK&)8M&UxS;;H4rAm`8!1UbFNo*u?Zcy`Yp2piTM7 z|0S#Vd(l;D+XWJoS)`oY2-~;)T^{#;{QoC>9=gNtNK7gRB9Pv?dTX+TU)CQ&u!s()|U{n zfq!%fxVn(2zEqQ)U4(XjY=VJ?p6{+FD1ZJ?$@XEOczVKLs0-ma0v* z;+gy7;v?C-5m)0Phn^C-CdsMcTF8Eqc1pO6x!oi8oX9h#Pt`=9^Vp!~Peh4WepVKk z|45JriKN?8EJ%n0sW-n#wcQ(eP}9*FELJb+E{HgLy1}hy^yfCH)jj8F<>m$_F*S%-MBf92WEnXEEU1<>%c`w=Lb3n=t^3H78yoj^t(JH+YE;6OC3QVMm{|Xj`*Rz zmU|-P4P+jX8zo){)~LwEUPuLsvg85!4RqfYte7(~L?Y^bV$v1koQ0DEbi#MC&&MavKY{g3aFr+9 zUail42SNOd($dllEQ-TVqzdl7iy>yzhrB7CLYYRL3j4V^IsOw96WY@8U5^3!%ux`% z*pWI$byn(G#@xOSWJ%qYBb}C20~Ah!Csc3H+1#Cy43%3ocwC+XlAhvN8O%oZxj3h| z?Jnw5&mNw(c6R33% zmqH7Yj|+OTyUTscE&O=zV>Y`(a{F?<5I`Ir zZ*@9lw$b}E^eOlTmtJ?!%*yI+_K7t(f|Z$369|v@8G1YOwLNs8J$!3wDP(nW?8~Yo zaGji&MhOW5w-KT|TXJ;2??c*-hvHU^{g<7P&>iHKt#L0|sqIlgpJz{r-?Fh(YR`%v zTy=6!X_EEN7nskkh#|kstA=%c{C8;*exV{q;>#uz8A1}rx7Z!?}^ozfre|+}< zaD0hii+@{UT@Uybe;Vxf-QB7ec&zvq74tYK*sMumnA-ajFoi*)cz%i=;%o|JGUe${sU zsn<*t@<=UOagf(XC?0>&nA^>N9p}JfCj9FlDA{={RZB1awgM`zJr?T zB3tS}sf_kr03F;NDgOJvuS?neAR>t)Qg(Hn6F=p>PpKx-E#JR;*)% z_;tWO<9TFd5Np&Gt0XwEh`gGx_+}6D^3F4epD$;Zlz3Hy=mhs z9tyRDp1b6dX1d#3_Qk49zmI^JUnMIYuVq*_oGW$QIn8-G)jeo6Nf{w&$@K>|eW7V% zJ~^N1YUqAoF8lJ5>6yCta?Ed({ZQU~)Tl%nCtTux-;#W2Yu36cE;8)1KkO{EC7fOv zVmNq$;&S>1r6uCF^pdn6>jvxmcju1)_UIfn_nwRV;&Y1bp}Sl7(SZT8r+atMOohSE z$>e+w^qW;5;fmJtL4Ofw8Knvi8{+F6DMmcNm5<*>boY8_SkH_LO%fj;@7qEBC(vJV z(zVVOWONU5cl8dpwEGc#;`$%bcwx=1OtIXVOmX27d(qH0#l{2{a#Mp=O`X#Z32e)p z@OjgBN)7cN9D4Rl-P|DxUwqH0%y!%a2n$FXJjK;6VQ!)TSXg?pl^cho9)5oTH-J znSZG>pQ&L~#PBOeHIz?#`siA#eRzG15gj$LXQ5w5$(H|$$6sZEhyNo?0Ls_{^}S9_ zwXprV6Hf5@k07qSt5m?)zT3bt*42mc2^L~4_0bY;C1u-`wbv2;Pzr*4zJ-i|3Cy#b zUe6hcr=4&0e6*?s*zv+pU%3+Oc#YSP5d9EHG9`5IvGC~Vh*ZEe>iXK*Q%wlCt8WWT zJM&a_gJV>i*j~TkZ->4mq1Jbl(_3?4=})xm*OStD`*YY>o|a=0Os-je$-&15*%f65 z$`;_T1#NF{JG!_`E>AKGkM-VOFVzJLx*SCps?oey* zN^_<(#7%pwW~Pm=_$ewZ4E5_M&ill2qr5u|(s&XXrH_T3>*K>d#Fr7VD$S&9uP;Mc zkaAUphh2`BXr*Zte##4RP#z!j8AkPq_$tOS*i0}uRZ%f7dz`eLKkx#f1JIko2?&e6 zm}FqMdWr6Pkt^4}TVVgr+Y4jEY_U6<*&@DKhR#HRlYt7eO+IxiZOQmUF>9BGF)Ml> z%JNCAFpW2ZGV}X%Rntm?HdC%3e2I*|n$5~b9CykA7HhME;bEh0?xe+MO9k%t3V$Ms z_axLWYx*N+%^Elo#@QO$Qi@F7}{nB%IMV0Oq=4G$={m-cE@|4MbE@UP0d5iDB6an6L8L!b+3T)Q9(?XJZn{P{4PGKXw8Stz;|(SQaF{5 z;csK~B)8;=azXp+PNiYP;$2$aK+4%WrAALaK8Dk3$c{7wlKv}?%|jJlU4UC!UJc!i zjuRg9FHe;1ki@Ivc4&4U1fFm7^aBKc83>B1xi7GIR0A{}nwg$GI|8Z~blC zJj(QEB3`v`?2;Er!#AF4ADs->9JkHh<={n&CV5KL`{4N#Yt|7bXo1I#r<(V3)}wdq z`aVvQQiY28Z)1zvEw(aA|6V2 zA=+vUT{G~L@fKJA|oV3o|pNi z*`43e&MX>-TK!}&4HaQJqcGLUEaRK`jz*YBxUjK_V>RsqS$8}Nq8q!SMCS5Ro_$4b#;H!X2IUj*! z1hOPPUUtyypo{a(hI8-_#;Cowd3oxe^bb7)E~rrz6n4w=ncB$UGJzqSvb*R%P_8mis2ZI$B!RPzfe% z52wQx>%Pe~>2W2I-R_FdxXWh6Q&g>22|D?fTN{O>ls6iVH%p4zjZK{UmOSLa4uEgZ z58r+aLu!-9GL-)+vhmbpNF&fM1lChRZts@=82vUx5kFUCy6PohK?n?6%n`cgLW^&~ zCdsXbsk&milcU8I|GM7wtVjR^^M!Gw4dg}g?x~LX;QpZjQ;d*GSbG;Z%c@C`PZ`5 zy^fKp4J<%D_3r&@ii$8HZW5@dZ$A7~Hw=M>bf?a`^Gk^DCvt6024n9qn~KL!4|FvI0&-?$uh-{q;- zb)_r8IOXUBNHeg-KbDR^3s~tj#L#wR6^8Hq175MRRBgnmqE_qi!x#MftTw63N$u*3 z;>Ii1gi~0f3db&6opA=Jd7tD*7&9^+^)A)bX)}qz8@->x~9`7rC)a1k&9_* zw{o(cP=WH%yfX1$G~~of5_#0QBT2mua4i_eeMQ-2Rd>0bS8v<#XQM7KoZB7t_5u2ZR;R?t$qC5& z4$=`NpnbKz9Sr1;4?~nsaCg2Rt2+3;UXtJBoI|j|tz%{fDk&`v*wWMLyE#U7yIEiw zLd@SZU&Qk-YFZyf4=!2NP96~!nEr{xl_#X$*2$JSmGI$c3_JHk^{bK)EQ1`YzKU~6 z5Pd5|U{zZdTi@8^*%i}?d+JBSFD|0opvBL}qN+ay2(;sO)zc1(Ieh%Rrd|nVsbWma zZwu1#F?68=2k?{N%a_&Jo^YRg>Wiy_w6v!Ad7_D|Rcleg(g_&VHf@>n*?Wt3*$*8e zWY<~fc!mT4!9E_*guhy`I;?>+px95#MdpvGqD zsP&}9XVUqZe0uKs)%&TDoQq!_fGSJ*J2eJO0n^h{kbS&WM@cmFm)^4J}BR5mV z*Y2d#M%1{O?wyG<)VPjiFD3y2hu8+Dx(R+r;F`|2fl7X>O&pn|^E6ab*S$^6rt4rAQjMJ;l9PE~ix#MlG~MX_S25t~>5- zLCO)xSXm>gtH1Q<6f3t+btazSEP!4yvq*Rb8CD$(n&dsEF1fOF#!6aM%ZPA@uc$B8 zCXE_INfrF23PuSYplAR6z(8?jB8G-y$N67@2JkA7w@h_~|;ZRUCSuHw-&73+< zRtb1}Tf@Y`{KNUfxRi>lH!1Xkvxy5QzkEh6A-A45*E;0@AEkk(O0CtoSTl%c)fD+; zu&wy*T**{CQJTCE!nohyIeq%di&8J;pF#q>5M+~uo4^Souqcb3vU_7scxGJ!1+}}B zaX6|35`HB=g*I43gl$FP7#CSW{pg&Ec0iSgzjmIA-7+ZYF#;bj z)Wu&Jbj;=?T91$H3rTQUzJk7=b%+3WA_D6?!B9?f-O%tXh)HjSKP381@_L$W{DdQK z+zAOGnx$CsVpShuB2V2xBgH*ufl6WpM_CaD{KRD;)S*y%TzPC7kZdrvUq80MeqD5o zA85b+a7=t`?;t#MuQ)Z?lbH}X4IUE%S~Py@CQ1Cu#<19n9BC)icqfM1eiKI$^`a@R zBQ3;OAdZffiD_@wnsW=%L_<%LUzHtQ?_doelGrXuX`!K^cf?;@?tc&-65h=kt>sn; zKI!@p!GJ_}|CSXOOCF?Wgh~z-fx4!am$gsYA8kHD8Q;qSTj>&P1!-@2=%4uY{-G^Y z|In6iZnPaEth+4g3a}*%-|F}Ixqv@xdUa?f+I<2Bks+3-#+%hEo{amP%J5$9(#dMc zm1)<7O$@%V(NgQF9!se@VDlizDkuAJ>uZ zJwxzfHqMv7@VC|L&Z+&iKwulcC~68I0UG$PTUw_f>8Q^-+Gq07>UAVtF$0TFa9Ubx z1;;%uchiSjy6&e=Pnq7pn2}6yFc5pvxz+H;dD9CbO(!)z)~Bf!Xlo@JRG8OBoNv6N z+-iX{_6u4puS%ic5YyLQ8@W|aY3N5mDQW!<0TV=rC7eK2AbP4S@DJvn1G2pK(0J~n zsM!Ur&6@;$I-FHa7`QU-m)-V=pC0BaH!cr&up*1h`f{O9BA#A%avb-|SZ81m_Dqse zXIM4k{ich)nJ-p(yfBCy) z?0FWef|Dt|?&!t*d(=Vk14y$3RnpjJ+vxIS3*uMe%0dn|ZC;WMM#)FA`lOv94=+Sf zv|rW*jU_ug(8G{b_2rLyBfI;DUgb_iOH8qh6sc5}JOm1&rz~Ewh!C3*ue!%1BJt0W zAZv&^$dy0Gf-Ccr#Qa2QpGFcFs?fy z9kNcI_S+_fOCVgfTgZYwr z5lX_9kMa&_tifSYz4iJMnv9??#omhNNlMbe$%#po952#lhRQ>s=Ut(vM!8xU9^HZY z!7mh1aIOU}#v z)*ViS!ixIKJo2`BOnYM)GAQX5gTJ>fCs@^C*~^ceQpPxhfGBHSCaX20@@fC|&oEnyC5K&W(GLNy z2jr`FR}My_+~~FG>o{~!shS1Xt!evA*E7PW1B|R~y_=2^pQl~45h|RIV?_KOTh6-X z&oD5hVy*Ad7ysselTEfVryq6xwU9E3YN~}I8+l$*mv(pkvD&|UZAwA>05V48lT@E) zy9Hg67n&h>!Z8BCq@Q*fAe}06%_f842>+E!CyH!qsgI8w;h5RG5T*qG&KsFry4E~s z7{0EnkWGu_9OJzgF~4UrKrm`XDMXzB3p}gVf)W!^U3s_OTvuDnysgka*qX1tHRa3H zI0Hj6rInlI6@WPp;F+1|GFm_BU1i!lpy7D+r<1KTALHF$`?+9Httha~9rPKccvg)M zrYYcwI{|kOEOiwfW^|W1v{S`5YX!n%3RU|(^>6+vT|4eQU-2$XV?hzOpM>JFjeb=q zI{qYxHcuXn=U$IZ2=S+q{Hb9R`O6#5D`n)ZAQY+4U}4z36>V00 z?ON?2y&v9jk`V3$zfr#Ak=ZYa`1vd@zYYUOq_1U-o9uW!*zE27Q zFLztKz`KTIsjd)Uy1CMMXO?5cW!``t92{Wr-W4~moWw7lhGRM@(Ut=OpT8~)IZG9% z!YrAyl{(|I59Jq*!v}bgL}|3UaaO;d{^N?BsjeUu;hzC{h)#fb0S+_Vkk|dqO0Die z4qxHaSpT-;#q4b?`_9<{eWeY>IPrfcX0m-Ec9l*t|r|*;_K;8^T?OBWW3&O3GDT!I;9`kvu32o z3n`Iza0#e<-J3ik^B)yYb#!&mJotvC(aQebXFI@OIMignOUD$s?U_)2 zr zB@2#;WqwC+XK-u@q7@55*DB0t_>KZ|su#_;B$fP>3Vwi5^)1>y@)=PO<$~sD8)Ox2 zGJYP4&S+6%g@E`_S>-5vH$8=?EmVkqbng^1PK)MWXF5p%@wf2P5xZ}s<)&Kk-U(C$ z(>;DD`Ae}9CnmmM{Yl!jW8z-1Zg&*%v)p%LcEyD5X9J{SoAL|DcWs0cxq)tjL(iax zZ_SHUZLgmMlj-W1@_Y%UA$O-3uQ{IQUhAE(Vovi)hJRdNg)est^q=&Ry^j7g`|xD1LP zQzw}xAtC)>zikWOW`{lbOpg;Tk$%T=5bjEhL&@0KSUe0=>#+@>%c2HYZIwc+{vGVy ziy3i!rN({dgoohP-mSr)k-hJGfbLP$r6F16PjU3U=;Rww6(~@r*h4c6-$Gr6BpM_f zxf?Iu(u|Gm^sH7?SyXVUm#yznufcZ)gnIDXQ#|tX_NV5uq{=t^@!TMCIc@ymBm=rz zhfqJmKmY5FPCM@4_&c%^jAb-+e+4{Kr@3CSc8tHiKFG)-!(Djwofmaa@Z!L-f~}B=!yEQLoq-J+TRT^!PrXk(e+%8Ns4kj$Aw{Z*vYGvrh2+3fV?81f?NVVZowk(-+~&9w0U$X8F{ zwJ#=caEU4D#jt7JfvHF@Y=%7I*WJo6H9_HQSBgP%!F;8AlqjZo!ecZ*Hz|g!=R!u& z+LrmHWC`bmo51XwWQcp7G3P0wo|IkrJj3YDHRVa z*xwky=F&a71TP1?$x2S0PESA8x=56dPex=}6v9X={_JqY(toay6>x>fue7TMJ2Iq` zx#v#6?6S`f{g9WtdiRA-FMn&sA&2p<=qeUyzrN@^MM^WP{$`3Z08!yI-OR7St;H*} zb7lUA!A78*cHrq3Ojlw_*I_yp{8J@tJfjDTcuN8iHN>kJqC_s(Uv+BS(E!Z;-`SgH z+cvmRUxT#{wzLv25|`XY>Zwr>7&g7}M#8+z;=fz}LB#E7HoMhG^0|qE4g}gZ+H-d* z0O6t)OS3?eHQ7q0Ks0$FdzKwcfViL_od6z|WXSmpqU2}b1%-vG!Ipd%*+mV1`>~B% zT3tOUhy1c8L8+4^0S1aabR8LawnOMr^=idx5*Ny3-4^JwBp_T>RQ;JJDb!q`Cy!#f zCDFclZd7&cbHy^;Y(mrB!Gs8S4|j@(TNqHCmC;w~yXlg5*zos%LtfjA(diiN`0K;< zF88JI`g2y>f!fP41C}q}ug8Xi4fq7*B4elCx-OaS1)&rD%&dtl>mCL7n{uUvBq#@P^Y>>(vhn(`?=jx4GY) z8Mw7D&Ph*BQ3wgLHLdK?(!Zbb{_JklBk2kqbAmelB#3DMuk0-aW2|SK^;-#in=5G+ z1VaH4uD?hc;oWa86(V~}OI8=QwxWeqHG$Bk<#ETj_AS|=aDrMoeG8ga0l><75Vgav z+APD~eTqmv~N*Gt3*p%>*&%4mmtuoSIIZk1!{5>z#mQ)Cu(}8TLwBd{AYnp}@RJ*sv-oA_A{oshglv zblzE#_|tLZu&L{h;#%jH&+}KbYqU;T*pk4C`OL6MkasQS$?w2u>|!-FH3+abbv&HM zDQ5~q|F0_JfvRjbsyowg(|qdZt}}W>zdxY}fl<{2LK)pCk`kGW_4R#S);u^1gm+aa zN$Ez=;xA?0?RRj`njXZR%d`{*&M-$sHaXfS&!i&jeR_B3;E4{tj+34?rYTft_e2a^ z+||5#1{oE}L*{1F>=P4N46uI>|IVjh>2mR*QFER1FZQD7slC)RqCW>^pn~NmbUKFX$Fec{AgirZm6Ff3@i%+=sCyW3qn|h^3x8-KYr(|B&jb=O&AEd*1bND9Fxc+94nu}!(?x4}`RKA;GuI(^7l|c6E?`13 z7gd?rx5YCeXrKY+Ls)-;8K zsKYNX`j)%Y!5h!+J7?V0k5hw$v|Src%DfsdLj|PIcI0hXh(xXn~P#=%Ok2kAr_`Y!rMR$3pK3T*5jS*Ni5i)q^ zJRdO%4d|mkIt%x z;<7DFm&)VBXmBW8pvr7)Vxn6q#I9G9gsuN+^lBy}%7;%m@QJ5kM9@X?;!|@iH zU04|O@jf1J+!J_#zYVqX-GMHlV}8-oN>tGbee4wiuJ`TbrpO_*pDvy>4O5FIY*I}Q zrlkuc16-P15J{2{PCjR=HQ3G@c;v>N^^q6XWs@!Yv@iFu31P^JIu*E$+H_9WGn13O z`^CwS&6mg1y@R5x$QF71d#a~~H3>U6o%tsKBm@*EkUAsGjROE2yfO(0_WA}adO$D# z`HvyP^L^=pMQ`;Wvw3vYQm;vLVn2fU!Y63CbWpW(oi^YGKpKaf63r_Abd96bs7;Ra zze2KQFz4}56v?$cis<(&EZtl**-0Kp`Zj~;ynxO&ubGQm6!EurVQ?t*g=3QvB93du z`Y2Y`fJ0{*DvsOw=#O(N%=}F`>^_!ojFL|+Y!R8}*DR*k70+7p%2;_ivM$RbOMW9p153Uo`B<#~vDN_8T6 z#GN1&Vz}Q;ih0)sGnMYTtfrBmf>B5~;i3 z5NK{ni6Ss<=N#f^Y1{OX*lolK=ER4^%7iY7dz=m(tahV6gmLFp6xGSsx(y0Xi+Ud; ztXt-IJvklOZ41Xa2Mf3=(~sTvs))U@Vo<(LI|4qm;NmsJs%W7J9D}D zntWrwH;KqpJ-ZpH?`@+w9!*}BN}ogwUOlSw`Gfy(ld=t&kqs7Kx-g$;%f`kS{jl^| z>ytSy1n15P|9dvT;RCKqO&mc%-BAnRRTpN~_CA0nRc}2CiHZaE^O##%#j6O87=uuZ zSKcKrJ-6?RW(3M2NY)@$f9tYA41Yt9=O?Hr7$RBJLBsdpxgTlYv^GuwznP^FM{(iL zof#G$wovVbj2^s?!Upw?*8*aewzs$KPVyYi2?wIFA{C+rjLf+G7FLNleq|@b01;S> z_07faOBZA>7p92#y&cuIl=cJwIl&$hQO>jJBc?#yAUL*+ z;@JGN7u9d|HC8JoELcp!f14vGo6a~IKkyvxuLAS@`YKj62g!W1I zF?bf96I_12_<0kw=F$~>q0xnq{`%mub-3zriq_I}@juBG!K}CfKN#Qv_r@E3!_-v( zCuH?aO^m_g>{Rep`&_R7r$kjS?4J`G&d>1zsWt40M^{B_j9WjF(y=P0EGO)t)2c;r zyJ&Tuiq*nM#bYH>P(G2bMN}!$3Z_!&Etg#+bRRL$jv#rdm?97G^@=DR#Bc}X_!hq- z2!8G&MeLHzXqiM#s#Pvc7YF~+>)tD`54Ry@pax+kwx}M9qNOQ(^+_$qQEkh_`<(V^ zx$EP`BG`-(l0!vNeoIaan*8Ncb$f>9<0k9{qg}FZ)c8xmITz0{u?hrs1f^l8XJRL6 zR}`96#cC_OX(Hz=8O^S--%5~+M_IL;1 z^}8LJ-tpVI2E9GIsg|D+QD4~E1I-;JBLgrYCX*>RWln<6yv4_%J;$av?9+2HY+6)lb{c7M$(g?fWrKn2*bguF=Dvs z=|F>kuFsvFtP#)XlsfvWRMwvYn_dbbUpiVgRtd;{?O$4u5~rayR99D5_WBSb5Azc- zQM_yC-WTEy3yqf-bVFV|%F2C&a9ZQ@=k5(JygUKR=EvnjmqEJ@6 zdzOO1<)r2~LnCx(W*huY*~=&fA0l5A7uId{O9u4aHMQZ~83rzHOZGn<80S9?CT-u`ZwgGDTw`hz6KNI(y_$;3url&gQxW?}LO%Oywr1uwg6)5!A zqXHoGZDJXB*6qc^aR(0kvvKcnip86Fr3x`;M11ZrqkQ&SF0L>#UrbZwN#Mx@^p|SEI-Jq2H!<#^jgC5k$rfyj9!#-u=573&9}_1N#E#!L_ES3IY@d_Fc%YnT`vA})Tr4|` zk2;5tev|5p`s|8M3aF+gKJUmM@9&dwa;gWF02@Do;8e?N-#Wln;geg$Vk5w|P=@rq z!$W1g??FI8AjdSB(Exvn)i#!ne)!#q38US z0m*~R5ZF@)68jg$KX@!#H=GY^SC>2Hi9xEVx1<3}7w=go{DlV~UFUs$x>QoIGYY(r zfl)07;zq>Y_h`|$g3NVBx$o~H5?a8OpYbhJRe3ya+ds@WJ=8>BUbzF|WRyDss(8`R z4}>|3IQRFm1w|@<@OgH`={ccz;pz2(%f)ZiEjrP=*v^*N)k2UJ>k>;<;6A^VMT6v~ zqPQeTGbL$I@4xvD7=BC$pw8MXn5svbO}x5|9<}@l$|BQd%*Xv7niThBss*!1qYYX4 zjqx(Nutg&pDr&V?#D{`Ge$zj@94C>dK9(}Kug80Ywxi^I7rr({mBcw#Km(_t8&}s2 z5#kgc+86O(1!J6_!DGPMy-Xr{KZWBr{_!R+lT%Z}V}@52A}owdwq}u4-IHOcL$Xgs ze1O9fr%(Br%qofhlux%ErB0>n z2yJamPit5iIXs+krEX3C>LiTMJ428)eQISaioPt-abBDrw*Dtagcq3V9SEGC?I-s4 z_gkAODiPgyGnrig(FKJ*y{uEqii57B1y(K@55~aQtOFoS1B<$t0Mt z++^VkrDrTO<+Ye+2+WWe_JI}v&Y;va0ZDoDg2I~jWDImkW!)@Io$o{JW>gz=oQo~I z)IJsre>C@o|K{BOS305)D8;mzfZZ(#Wze;VSkuipKAm2|)i>s}GjBi;2q67*3Z(p= zU*VjC8uYN(6}C?vxXB`g)yP^-$ZIfm#h5jQd|%eHwD{2J!J3a6)4#pc|o5z;#I(4dPOUH)ke( zdxQ@rW1-zME8D4_4WBdh$HWbxd5`!>w2h!PP-wd985c1(Rd(a~Gn~@QasFIQV6hgI zW9G|eZ4*0mo#Gl;KUfpxdEqC;7g09w!hl4?=(bB@^ub{FZe6U4+Ecq6-os|3T#3eU z?M03*hP&SH_2+_vr_&#SD7bJY4Jj9`XMmDZu-PoII36*7Os}~UXZ(q^hXSfyMh>i! z1u`Yy?*Aw`#C)Z%!Nl7XFt4Am#C`qp^X;j^4zndiMmT@gxZPaQ#N(LcA41zTF*@!U zfj{GoF1x$3_puP0C40gJ%>_@pO?bw7z221_`49ijtw`Mxy*6k`#fFdPt&gGxnfL2I zUl(9T*{j9;GoW<26WKb;M#_x)X$sW1a-!+8hleUNDy%lecEAA}C-rU*9}s)@zDM}d zK0i31I^?ec^9lxcVuYCz@dHJqCExJd=chQHl=2#Tv*oQ$>r-hG&LK4}ah79&&Y=XH6-wyw5xFVQz-`!b+38#{B;@HEI>w zQu1RXrpDt8CKjTeOvf$5=V^*dgwiELik?>`r z?w_8z?!zx?Gjml2KYK^1frpOyqn5mcj3QDziwAhS%TUErTE+}LUd8UaSvC9UU<%YH z-iql|isj}W00{ZckhIn?og+M0YJo&y1WtvD?3sLGga2OCTf2B`7zH;uHcWPhmSln1 znA)AZ$ZY&POvW5HWKv6gg=+CaV@U;27E8g>iBvY^>*aWG!@DqxXczkCDwCJ!18En_ zgKRbJU^9@~In6c8^@Z8-%7tTmft=?oRYe8j9c1{oga zWwSKmZMU90f$#iA5YujjeF^NJUZzD@0F#~ zHK}Ly^#HK+FFVB6LrD>QVAbFpOK0#ldmg|kL&m3AonkU zQ-H?Z@z#-$pQCL{M%2AuT}7uSZ_O2)sS8A53#5*3O3bBxjt1f8vJ9aeLz?F6ti`k_Kk!>fi?2jjxi@BV@|(40lky3Sb_5B zxjC4Bc55JNT!w#k0S>%Vony*-2 zf^x11s-@y~6h-}<+?j{GJx9CNA7|)~J&9f^@>UQ4UQKlkSjj{fsK-f>TeX#4VEwgyPgrrK#DevDE3Tt2ZQc0Z_n`3I zudD-u&Cq$oQNaKb2s${BP&Jj)ngULAY>@#Z1rH(E<&F5Yq9H$B>Ms{m8rw}&TzKYI z{1Ar!tJ1V-LLNLA$c^8m7|~juGZOsPP8w^day2va*rM*^B+9AYgAk<%uGhPGz|y}P zR5u5&2pg2)g(X&S1vl-=@-Q2N_521G?vzPxZ?7o*X?Q(>qRP0eKLS}P{{S+OjY%0V4h3;oOA5vaSNc%+IV4F zWl~^*o4$`zbL~(%`E9AAyb6{Q$IS^#RD+Fmfdi0f&EMZy$o0_!Pt#CP@ZkK#U=dZSdv;*`VPEdv~R_Ekz zW-AIv^S&P>6lQue*ATFxM!*!;d{p>!uRwWVzt<0!f-P8Xk86~9^;>ZI^uY8`+Qn>9 z)O`>_^~e}h&a>bW15^;iwd3OJO@tepL-}FM1SecPBLw(FZFg>=0JCjvTwujRy?SQ$ z4$1r-!aiF{cbGgSsvN;I~ zD1yRFll;Cw#_`KUa!(V zMRM@$lT=qbrKmfs?d)(k?3JIwRzWoJ@fURn%0C%5EK!8XOR+?t5578S^%YIuE5mZB zgFfT0W@RQa!mA|{YM6u1NihdZ!I|LXG~Nn3Yk%Fe(f%=o5uU2TZN)xO7R~t`vV$@j(+QSF0YWZY{M_Si~6>g zXYHH}8WX9I=Ubp;w-Dm5=Du+eyGeOr$>0kTYTC@*WOn&QP(jU|`TZh`0I@}Vt(8zc zlCtbWyq3_~R}>-H+1d~e;LN#M#^&`#wWeOh_(mo4-(APyoqF~6?gUI>gV6a-TWt@T zkd$TfX4tf>z-+BF=daa`HD1q-CF89!EsB8{!1n{vh;JbCqutV0G!1xNXngXBTIO7~`r6K6w_qYZskrKVSorJJ~F2 zayzxb4kME*rT<=y(vS&1@^LpQA@ z2_r5=qYmjQaC_l5_8D^M`?r;KR*X8u)$ueR;=`o9x*&lnT|b%eEq+x@xyEXjU`sOm zr8nT65*bK!_{qb2XC3z)nqH!{goAmR^I+W%12tPpkxOezR3yh-#?1HV?Z+bjQOVHZ zFLk~X-Tg@EayVqHQ&xN!>j%|MhN?PB$F6#oSg0R{aQ&DRw1U}5yBOTF1B5;r3~EhP zJK9ak5i~D(U>~0j15DhX<6EhRh%M7@+6C!F0CD!$!<@9k^&DSTUY-g-G;oRA4v8B7 z*|F+Zz8Za+Z*tf(ge^gw^n5SSJj;&HJX8GKj-s?DNF@W~p%#5*Ri)7vyZ~&~6YMOi zwWSArOz=5zNT06>25JQ&A^w~A<3?oWu&;)hNxSfFX=&-f;YnBu*t25l&1a}3JE^6; z(3jchVHv<0*Vq2p7euS3^r@~kJAK&6kyud8)dE{l!Z6cggZkGu`6!A;Co~0%){-N+!>bhA@auVzz#g}{EA0i1}@6>K$ z4hBC>#fcf1zA0TR>9f6@sNN-d&H)@=%szF^iRq|3B+4@}+;dBqAcPmAK9F`{fgrNJ zFkM0&V1CU8b%A|1V&-2FCc@+gy{J)CsO2~!llxvj=Y`1&Sp*ilI6D*I-IPz)k>qBE z0J#gajEsfQP~fp8ZUzW2s4VkTe5C!?Qs)s3lv=7?j!JY$$<-x0+yN6B zux-Ys+86xxx1`JVHMGgU1hah&AYad1d7HgYfm{Tl--%egnQ!n~P!vWJqgg+rbeUuN zhuchlFOcnjf&kKM1_pzTXZa$Pv54fdctyrU4(sJ!z&@DEn04d`7dj+~pM!O;(O|WZ zi^@oc3Tp;CotTK{$xnJTS78b`uu|-)P!wkr8B?B$#Jf+}BU*aGMEc-Lfb%DENb6&x z@V0$fK>q*Cem{TrKu2akJ4P9$(->L?PwxCRqV4Jczdzs56q%Yi{5~?G+TJz!8#)QX zdi9*1!dz^6z!s$G*iL5XXG2bx%KzGPesJ+>{7VVVbqV?pBL<3TpU;U>(&0B7NA8bFdAou ziod)2!FpYNPfTvsi@@5g_4;Q(F=o4*ejR!Uw5g)slVP7L2~%|_6slV<9gOP4e`ziL zt#IT3iaS&}qwuK&u6CC;t8L7Fxz5m?uz(I%ze;(;X;FPT6z02_U&$mylVBA&50XEY zgiXApcB$5G`b@eEL_s2CZuIIiR61uCR4`v~9@aJ3eiuvlfL0h#f|m7lbjaA|!a-uI zS;eSH+3)PNkL`=2Pp_3x?{}l_@901*7)7FN{|_pif1py_D^9`L%Ry(YXFI1l`JwV! z=X$}(0R2G)QPT^u!`pCWH7 zJ}vxh33@=v^m@<)%%W+SQ35YtG5GJY$+y16e}S~D{7Td0cE-~wiD4lqgbG1_bvm{F z@3b=UfbpP89@z{<2+3g*#)RX?5!MGl0T3{2!(;H0y;cE-KqjC@4LN&>P!C#gctT*_ z5|t5^roop1Q2xfm=3Kl4X+WTuy>|Xl#(e|AO9|HnY{;Oj0tW|D!ztGF$H~5^zr4+zd z_e@ke0j%dAC6zcZEbX9i>h7h|pSgk9G5NO-4>bEnd56nfiH^?wh{f4!5f<2FW*M}f zalv?rZ<~|?HOQa$wG-b3MAY*W3_HrEDFz(Tky)e(@EG!cMpkn0W1HzAaW5`9_PrWT zqZggwmTB$!#bX|lN^>>^&z@&afR$?zctQOOt<5^uT#=%+qqrvEeA&J~V~a&L(9ZNw zqcC`5`9p^>fuL$sMS`L?FkVMl3mBFhn6Kkya?zb}lJbrZc4;#U=_uXV&ICH+EATpC z!0a(KX(-K5>b-97Mf?JKsjNjTfoTD?30jmUW#ryV`oRQla~6s1e^`{J0S2?-*q(mG;v-e4uAFScusmSPskTAG?t0A8WY%)W5utzu$g z0(~;oK=x1NYqyuuLwG0e?(Jo=4-(AZC2i_G@##EK zGL37f1&myX#b?0`hAQx?QcA>bjc zbO+M39Y-m#6U0mnRR$b4-U@oXydE}R;NgFy&%aKEI00&H;C75r(ULkU73fuMARY%+ zbyj&5eCGT+E$P!+j~z36D@})gcq!n;Zz3?bjPiSMDCRO9w(Ne;2Qq%ZdT~Wwlae8& zON5YU+wJq{g^(2d+V44W$*Ag$6=bv8ngWcXQ)!vw|IwKv+bZlX8GSb|;gIA_PXPDS znw=@jgF-WomoSu7XGkV?fn14I&tK6p1D{}<|1Wci@>DtQt(*CJo%LkK7~HmgSW>+H z7fQfCl4XC%Q$)33SD+A-wLoDgR8HS#>qo+zTKvy5$jdeYxSo5h_J(09aj4RnGm%$$ zlYgVNId_7&H`f1@xh5O7MmCJVVfnJHKDaMIi$vb0W(#5(Kw&&NZsA~7{N6Pe_MJ9z zM*F#N|9~-U;U)W^r5>Fr_lX%T*`yF&nWvAUbHsC}CVHC%CAh5X&!y}Bf-$t`tv06o zx-rt2Jk9Jm_M45`PHX0V7NK*+hKa4Jgw;F*AjlhSn{c+_p{>uN$g1N(kpZ}%6N(hp zmPb+)zko1rr3M8NDSsqf;W`I!DdoYLseJ#@c+{)(3IDsp%*|0^<%QGHobQk1`7ZUf zdk{6Uf_QC)$QwO!rxjXe`;Yl-|LHe3IH zUbB{kn*;R9IS~8MDs)8jXX||3xy96Lm0Iew>A|y6vF`h{Q^aSAu@uUZ@r=BZ>}=oE zLxQ)cZ@HdU4T6GdqXJzYHIAOxXPts49vNed*8e{}D=?;7N?6>$hT?WTH|EWm&8sj>+33Hm|P*m%v zW)iO8Jn=U2q48|v3)idpyarQvr(<9JiuTthI+&)6$KI~0`k`?U-be&>InIu#f?(GN z-@_AUhr6~O7~W-p-xTny)PJIutaxpvZkLGAGHq__?ZaJmZ?l0d0puO=rj_$5aGBDJ zUPV8GU+e(4A_wvKb|7{52kW71MI$~+UPM-uO?X2zswwuFBgZJ|F%u{DgIFgEuW!5$mtKD>x-rUVLGg>}Igb&Pe(4 z-(hi5a@I6EMG4lW#J*RQ5MfeA#Z((cg$l`k(T8H??oMtza=}2lcm>eNs1X!sFW|Gu z_F}h>Sg<7hc#_`{2xi%mw4nQyeE-&k3FNDe9|RR|n`RuO?dQwq{;R}8XeD99dwxvDR$W}>3&%S}*mb49mTu^eTGHR=3=BYfp#jnHs9^KZFNVtS z%CJt%*A|^2-^W8X#q0&25uMs{3YU4^3SmGKvfYC0u}d9JmUGo(Q>gd}d%6~5JsdN( zn_|j?s+}c>Z59Q)bvSU-qVOdPwB7=fkuCs&=k-*$=mhWS~eLX?bPOD(DvS=X{&L&W&c_|IhYTekdb zKkFkoCXPiPT__QXspT^|OIQu4+Gnz`fdFhqIu5YW&l53qlf^CEV^g@8+-|s3J>u<9~j}vz7H(s$G8`U6Jth zE5bnI3mCW{?eU_$-B2*{=@y*q{OO$u)5%27WY}_W@~2H=g6)p5~oziZ36ywVm_AN~hZsoN4o z3yAh$tE!w^$K26O+d=$_P4L_iE+6v3>tFBXx?@HdS@@Du@7tC)zT7gDGmg;GQkjO1 zjHY~mv?Aj7`~Yk&P}(biMyN^(PM2Vh0@Xqlk?l$K$FGWk!tBi_GgN=+T)`hma#PHc zq3PfX0Bq6CWIa{yc)$h7k|K*0`8+J9l#g~o>nI0*7!XP(Od=s^(xWB=d*IWk*@_co z7*&*=Ms?pef~qY7!Zi5SFD1HF-wrjDbU9;LE@3{1vMLUK2 z_Yd$iSC7?xxo1({0_cPh`)ol1Q3dPfB|az^k*)Z!3Q^mP0|##5Rb))a)<$u5$TZ1O zZISsdnHh;AQ@<`C^OKXzEF-PKmTE2MMFRD?Rh{D|({&9=o1w2QC{cV?5(9+Ja%b=L zwTsn>-i0I|X%>^(6Ez4vHQK;O&{pyBlP&2F!T7QS)+jD$gX!YJ31s1DO0>Zz)?9)h z$8>2c>bU{INkR#~SgGB;e*0{QKWq`DE>h|)l87Mgh^%{54JeY?|q}^ z!H4saAJoxsq{czi$^Ky0j%j?DNx3*lPPtD5yph7gC@ivZk{oviobG~zFc{Vo#JT=8 z?^te=QcpTRtb|)Cal|Y8J5U8U=%|PY9O!3*zR=-xf}AvCp0Xq}E$d=n!P1!Q1il0j zzd4YkD>k2yc2AQ!!4mtN`1yxaV{2U$)=}#p_gEX5cKH7fRbLquW!QB+L#LEMBQ4!9LxU(KB_V?}NOzaCG`zRZ^S$d`-;Y^~AH-T**LBW5 zd+&1&?|=#V!Am>SkBeGuV_#m%nwA!ZjMHI`rMWMLZ^E-qNEiNi9D|UVFNj~S?7zVA z(%+00X7Q94C)5$Br?x)fd+s}p#6qPAY$?CAr+#1c%3>}3!bA(X{g4!`My%&Un&vlP zCtnruS;y@}TTPp`9b#bL6=;HA_(Exwy?K6cP!HI{vWkTP zo`k(Nv)YVw$Y3_D8hs?7SHAsF=p0a0IMA0R#`2D&x^&%BSn8k~kPO1Nljxb?vNokr zX>(JP%i7ORrE=_H>$jl9I~axVCnKZFwJzfVxv;y+%Jg8?$hn&%}BsO32D_=eqm z!kbS<=;5E#Imd#cOM@@Og$=!9yC*BF#c_I!Jjmm_zJnX~{5Ngma$#2ygg`4xny=rY z6|Py(-DWj|zv))l212bMz2T@AC%ToNF3v zV4bIY~%72gF&qMxsmWfJz~z0JhL&jyh-m9y zSJ>t7q^_RWC_;Tc2k+Esm*gule$<5Lr-p>7R89V=6cBvy>u;=A;f&SWXjq|#Sz&!g zMfMRMVB7oYyI+7*`Ics@YMO|~ zk3M?)yee9=A`z1tfzHzH#(;Ozsn`$5QU1~79VKYSpIa04g$;Cm^1g46B?~REf>c&+ zzRHbcwPgO%fJU+XVR=1iaMuXm^^(-^=|z6+cxGn z=f<4x0yvuBC0%{V7q&;MG%57GmQVjmJ-w`x`tXHm1!Fw;?piL-O_j!r`Cfuj^Ol!7 zmI2pmUJh}4?cIJoQ#IW?(WztMY@0{!Gn19^VbN`cAQGptr)X7QBa|CWgHfDkqU%ky z#M)RY)}HlVMI4!4u7epb-8VP%*#==>NgY4~!O8(57rM8L#bJ!rT4MEK`}Wwc;CL~R zt>%Yi4&tR7ZZ;;7rb#svR7iL(f1aWu++;e#t&TBg!62W51b%m$mZ zz`2*jPb8?_%Fs?~4xb;kS9ln##Q47bSWYanc#OehdRV$;ZKdtM!YLj*AV*B>w=;d; zS@c)!;)o{j1FhtE~RP9V9%t3grS&1e)_jpNm=BG3w>rVlw62ia(WZAOEb z)MISp=?+FIaC+Px0OM*uHh-NDUybQ?Z8?%aY!9(fzSAu-Bli35WqdFfS>f&c>VONh zGdJ>sM6TSy1fv+jqn`%BLgIgviXljUm%E{*KJak4NF?nLiQg{lb}N>Z9=l}2sv_&G z)*Y*T#K0-ZXZD4Ll9G~!>65^v{-~}PN2FKq=}(h%0tD)epla?8kE;XNy?FZ!{prCG zs5ye(!@`0zbx=$hs>7->;F8jwZH}gYGBf+YKZv_2oz5mMxx$8aPfgtFbWVP{N1Mu@ zsi{fIb$hQjKaLO#VVPHfRpDq4Y!*oC1H&_q+S^J0GWf^6v;Z;9A3J@iD$~Z+R2?gQ zwXObjr%`iUI?8I|IGLyBme3aX+*qH@sSzITwQ&}_E7oe*@1Lr%mYaF{qPsaxCw+-~ z#Kb+%ZCB1t5OhWfhJL@cxOv@*axL&1rHw~pjH|cHlBB8N&WRz|T=y}abDsxQ(j)L2 zEJ@2}lW@fc;=SW{Kw243g=*t+WNe{hl8^jB8H4H??Ail6g6evh`t+KGD;K?Df4z7u zJlBttLAm(34qC7AzRr|AYcm+Bb_em~GUkth{)iD!gy{$riMepkbWV$(3#|PCG08TU?`(HWyZ7E z*f?dAu(oWA9d)rR2=8N?{>eCTrrzXi9-XFO*tIh3szjBHUVae%>Fxl57%!gjNfxP#?RC@EN_ushk|+pOy*qqmih z4~_Ne$maR4ht)}=>gzQyur7afGe)%*bsM-Pv|_XHxe;MWQz~n3O1;ttEa4R zCWjzVeTQ=%``6C)k?8LFw7s{f;ibUR)Sre8nV(!zc!UFX21V4jm&TqH%JFsQTr@Z#aLO1@1mFsct&oHklZrh#}O| zd{v$w4@?N4&7%o9)l0Ivyq_<&90s*^fsvrYT_}|q!Ju{jeIqeswG~rxV4s2b=mT5ZF+KzcF^C6|Ct-9r-Xpa=)HTs++ z;P3%Luxl-44zngyS9_+dswm90$ju8zV&Je_q~D;J&K;?$5z+SWAthuP7L#Q5$qLal zSqVU^dZI8=d1C90MP zd$DGC5wNf24OZ#)wVy?$Wv$F}6q>zP>velFEk?;p1lJlY>!;0VIMsuYkRtxWj^eat zU9>EOL2a%g&s8Iff!e+qtdSbS+u-C7BcMVTa~caybD(x8hnXv}R!A|>FWu<%;hQCT&pw*d-dQsCp4up%>*c$Ti?Ytgs9FTmwpe173J#am5XC4Zn zixAD4(K3o&Ws_f9i{g7Eiy0mseo?rdSeot5k1=j%5@v#cp|``^g{csbH!PxwmnD9T zJoT;^Sg+Bd@fa5tNpm-MGm(SM$Rv^lcGVe!P#T1?&Md)xH+V7U2CaFV9 zK-F_Qy};4Goz}oz{82&7EbL8$b7M0rev~7=@DQvSk+J~Cx7bm;^bWRV>BK(YaMY8y zFrp;Mp0TGpv8T(r+r`AgjaTldGErkJbAX(xq3y1D8Fl2ELSafrgg`Low zAO>Peh)Bn8$N7aBKZu=Uby=j42ARZ)Oqx3vayk86z=;#@H5de?i?NCUA70bq!det` zxu^BDs>7EY_;Je@9%1MN)Bdyy!riP{eH@nOK&pPA$LFla9gpPT1X-9MtylnaF9B%w z`rB&DzRciH2+P^<*Jo3c+MSNN_3o;;iJ#L4 za>iUNk@^M>)>%< zPK{#YIevG+_(m>-8>~HHe|K{^Rc(nWB`qx)^6z+Af#V%krsJH!de)xX(#ZfIgZM~g zSf%ctR3}SIR?rffa^HOJ$@)c7f*Ea&k!jc*&$%`zS$Y{x@Ol$gbu;E8rEg?H)ID+5 zQtQV*^-x;>Yr?C9qARPoX;_LSfFU#v?!>HQeEGQ%kW3L^kJR_40_j8IWjLiqOZJEd zoofDMxuH`5TaU$<337hPuK(&@2so;pi=h{@vZxM5v!K$hPfemQiL3PT+PcYvf@qaG z9xVL`7YE^C!rfzVfmdt87;WOp>LAk$pLnN(=##s(+jgVM?Qz89W)t$Evs2f?1~?rA zD`ho1rV6G7;jP%Sr)|0`USptD-oRpREH(d1O+%EDkrjvt2QxM}lU$Do+QPk=@yph6 z2SR6FMcb8%EqF%Fns!BwTkO_R$mJmo!YPNX*Sn?4chg7$$Jvt6LGtb=`nrvst3d zDs^Qy=Id1bI??b@navVNARG|!tP$JY?&EqEfWLBg!q7Ll>pMMNXHn1X1ZV^*3RLho@+_D6tSe=;csK){{ zd>9IR5Af!h0CWg2oK-u4yx5v2zaHuv-u`^@A@Qi;Q1`K@peO1W-o3=Ffr)Egrto8T zlv;RCgxLSJm{eWbt;x*v`=NlYweP6DF|3uva1?eX`9Lv_c1^pEzOvv_QoGKvH2%t; z(fI2x_F=9m*$l$D_JT=TGdZAQKh*;o#B^?w-b1h7M3(2bm^X4}AOY;!Lo2*u3?f0w zcY5!>ejL(N<8DhiQq;pR*m?Qs_|6W5nh_$iCho)@wSI{p$hBX3Xyzk)jFDzUje zN2DFp=;|iu`L#hi8MnY`3Y!3Iap{}S!ZUpM^hesdbSGmqG zXeu$(6DstEIEt@zRx%+O&aqJ30{auNk#tttv}C@)7LjcM|{>f{=Z&;j*t7A?(R=o%sj6J zijbhvSQFeGhaD@N(%Q5{&+TWa%%`SyVd7EZmh#;7`tCx;j*vc zvZFD?jn%IH&u$RPqj0m`0)0E0i zJ>>e{+rsTYX4;yHl}5zL{LkxoLlMN9{lkIi4dn8 zW@1xa*8-NsA&jZ)g~HDlZ|$^mClSEU_L!<+)-(9D%t=I4z0X9I*dGyMaSFbjWfy#F zNk?=Z*Rn^M!m#%+mJHPv);PSiWz+iYSn4Ex^7DtU>#484ifJTVy5EGaE4>k)Ck9PT z9y8n(ZQp}Hqo&&}uFY*n!hioXKR?k)+>b7aQ;YRI28vYCvdSu!%V}O>&A5&8_<@#kC zzOKM~0S4E^RsP}6lnNwZiu)kS6&<6rIA_oh4Dvu8*3ItkHGZ7B`-GMP?KM6)&wT!7 zv8k!)u)ZpQ`1}pYeT?&TEw;e-Q|({Z8StA@K$`is804=$E8!EittKQS6yi>u=Fb28 z!O0!lL4VjIJu_fnxP<>-UKk8^I8h}W$O0rVrC!d=Qhbf5Fpy|=#kzvQ4t-hKQO}M8 zXn0)LK}?Jz9d%0v$TK|0o#ZZj8t)onhwM%?OZu}i(i0-_<7#Ig&scN3`O_8X)RkG} z_Chx*OVaW*&MetO(?;TRBGcwOdbt0|YpkjubdzSp&zkauW9mcitPvS4N-624N{{8A zBab3?fwzIBr$1oKxdFgWRWzYMML@oi?(dQCd4aI`;uw3R4@8cdLR1uV+W)NL<$jO5 zrgwY0q*k%L#o|3m$@W~qlfLg4j_~Ki&dW!bX>!7Npq~fZ^73y5eu**_?$LenDCo%` z6s4QwHmJ)Bc__(QX#bEj{6tqhPy3EDicAG3n^sgvBd3RaaMb6M;WKVNArMH;-1BP} zXs=05c$F4phWC1TGe%OyNGU=}HC%2@Co`jnPJ_EGsqXZ5sBeT&**YqEXuE+$U~6gSxUN$PtmYOvh2TyJ}}X_q>zNZbBM5I&#K>k~)Jb z2f2JZ^mTWB|6jT0oPiJxk@)mxae4Q|X6#y%xJ}nA}u)8!YfnUNRVc+UQ=P zs?YwCCN+NUDbQcNF7+(j72|FsXbP5cH23e8pm*O3aNq*V*tXi(f+z=f>B42ZBV!it zp4zqH>S_|+-;+zFcr`PId-05(z@WbKsCzjpE>>V!^v}v?wvuG!GoU65vSxL(uav6q zatdEJ&y>sR=UIK zDt42~48#`RYr=leR(mrCP$x6GE^!h@NNDPK#k3p#l*q~V%61#K5m|AqqkT)K?lWiG zk-UzRVj#U18EnKEb2EvhTgP!FRB&VZ~VHpELNX!)_Hnqtv(_kW-}e z8;Q48rYq1=I$$%KK7v(tFDhc|o8Vt|GM@+zR39bis|FLej6DWzJP9R_{sdXye9B)R z-Jp3QQK?I3`3*HEX7y=ie_tq=L{9i#FyQ`2ThDCP+vm~rn#{d_(_b3~{!RmyiLMc? zSI=_HG!|mM^_HSEEmg>(Blj*Mx0~^C;HJ~$dzG5F_^Qa1rZt6i2Zjwwoh{nABsL=< zvL^ZxHIa;F-2Ca;{%IF#{5%77n--x=`)YH+ zuTgv7t9dP;6_^PQ3?!uJdtLRr!nmZd4bNcH zXfW@4*|XD{kUa1y32}RhLnvQzV?(-25o&B}>oE|uI82fFTn-94#Q^tPZr+yty;gXP zxG;ajI5Ck|9UBq)ZG5#`={Ux4rJ}5v>6&7n(ntt__S__>>T&>=&Ix3G9+cB_FBcva zo|-kwG4NPn+|@e+*cUf7svq_#?|r&HIsB6x5@L$*OsJZS8_~wqSl<>}8Nc|`;LOT^ zK%U8sKF}4Ku&S8M>*Vv`k*$@FU+s0jID8)`NbL`2q@Drxb8Z#>1j!_G&3nLNvi+MF zMa#GVilsjWc`-KRHvHEWqW*&G*Nc)`($Pg>-j^~aZ6}eAAgxC<0~nn zDjpF{K`~i@;xtd*)sN{7&`Y4?@hEwE_5_D*wv`q{%yMQdFD6b&>Ro~n{VW+r=eUZ4 zMDKz|Yhrobu%}NI8zC3CZfcShtmj4#n~nC|V{*RRUgG}eFDQBcLbWo$ZkBcKsFU&W z79aG=r|E(vW@V$0X~qi=a34H8fv@Wh>mah!q-;*$^&;7$z~x~((XMaOj$@D{KQj@} z)-^GaS$|mwVDb2@EWX{Rl!<2UzKwxVN=By0N_^^|(;v(==M#G2345&lZ=j|(uG`|f1>eR_!T8#nI&~fE%9PdCOG3HZ;5lQE}MV`is9YAmxD7vwN zF>Cf_D{ykE5EMJu%M{_N{41>hIJ0%}_yEHf5ZwW#M$q)BXqi0ZbH4^OnLO|PQF!}_1UW7e)6r=Goy2I^#e1O&IQ@GsZQjgE!ie4`a8`RBf?wU3YC z`JRbnDzZDfw@ItpqBwo>J$;9TN(S|((3yR;ce77I#v@c%Sa7w%;d8quo%dXFuo<<( zq*d+(Lv9~PiocYV;3IB{VuI}SXeuo3wk>P^RKkkXE^8^ORKA|9-lxBbv;l3q=2{w4 z=A4^*K3HJwDMxLk39{i{F{vNhdcxsv>v_HT>H-vWV!vG#P)YCEWLoM6u$z&SH#*!t zJJT8Aecw-XoeKKwx>Q5K8p^Ag?~AcaE+zv)>fT&gl#V^&z4losY%qp30FQUg^?N!) zY!340P)7p?B^T~^GJ_+T>vy_l0Sj+D*l$TqD~$!!ZqJ-6+K2~fFTbJa(qJ~XuR+Cn zBGF}O2O#8)E&_~#(v+eG#MYbiQyI--*XiU@*`#OGDb!lF<(Mql!Dt=4V&Hu~#&Fre z*ABi3WiGHEj>U~D2Z3xf2Y@_DKS6+9Pd)GT^9#6lS_XE1kb(0tTh zi92d zS1_x7ez5QsLns`Y2<-33oN zSJ3tBdBJbfsGNIX*BpV7r=Gr zvP5!o93-ew(%M=oV%0(;gUvQyqUc~+n$#a|Va`mX#33kPxlj<2@*2x{FfXmx)trT; zv9hrz6tI^0>}EF?6X(9bmcd@3$nC+<-1LiRB~97EhJ_0z63X^j2XdcOyRrWzIx+m> zJTE08F8577ky}P zpBhFj2APCs-!QSi`qm`CDaB--Ta*{^|t?$IJO*Tba_JcAuqV@Ni7pvTo1^^0naQuDF|dg_V+ zgzumq*Db2QimxoiM)Mq&V>^?l+Bwj~r<&+~MVMpFfSDRLM3#h|J*5$P&$nMgxVpgxe{e z*ZDyYCg!p#2S}!I125aeJ?y{AZJ{J17z@6vcW_v3_(r8REU$fS4ewo&`H>=zznR$Y z-{sxR4{kzCIm3`91`uity!n#*ll`CPDdf;16Mm}f+Fjn4Xa(H^$F|q0JdIk3-o&dr z`(85Nf^iYZ&^W)8J;F0|&+OEV4#NIFl58LQeF+ zk=Q(hpI=#78RwsqXjTkAfWsoW!E6Gd&uTGQ8jm-K_GE?&x?qs=tNlsV0kQ73g zx_>4X4UaW#JF|Fj;n&yK%V+PiJ~@9gcJI}fEnvRtX{n|b=qY*>oW$_WXMeLAB{=sg zRsC=3!~$^ayt_CXJ%sVIfY3U}X#0u$wEBSF+DuZaS?Xw+ey9#~*03+(mGq~*vfcV( zA$%W%;F=8h$Ti8(Ve7Pj=i@h>6fLGhKyXv=7|$+aYF3+(tY4~GAg^pUVb3qBpJsBu zTaDVcKb*z$;Co}~rSUh^XkcX_`T}2~ND)R}G22SSvZuhI?N-24W)jPB{|%p*`0OXJ zBDNCbi83isJo*iV5oF`g>G(|7nUJ|i&E_GQszu(qef++k$)Ie0EHe-0=KiKcX{dWxYyv=UCVZ)%Ww3St+f%Jji5ratYAu8vCNTi57>o?iR*uqRfdZtMiU3y z)`EtZtgbHrfu4@D50E9am$@wBqJc7ul+?-eW%y^S%r`U@PD)eF2TTjcKtQ3{S1!c4 z@Ev-lzwy0-vJ~B@Z9E(4g3OZS`s`o;$@)Yr_2_0gw>vpqZXpzfhIly>b&;q~2ro{! z-Dw%?M0LJXV0bGN%Oh)`*t<1Bt+3mQ{FKd7Z{>=;BR+lt+DYLv_Oae@3*S6LZ4b)p z6)5_)d2s+ZLP&KAxJD@qZ{`}vFoEqTFUazE^mtTaxDa$|nF!KcH!$+iWJd-&DvQPK z+_v~c6TIIGE012>J+lHP$0;jn!fP z`82gV`vaiE3KrSq-Vdw&awo8&{pnxO(8P4makYX$#EZG@oN-*ku{4+g*;)H7$X|f8QP6UtM z{$}o!gxI|Z7X19rb=60q)$P@WYKdCOIBi-v9rxaKRar$@ z>UPez44cp#$;>GI?6`Oq-t1DeNiYFtn?B z1n&_jQXJ!U`jOyKHz{k%Ci*IbBM|Lx%m*k7<~Jmd}AL_jO8!K{%_uct@ALnfU_n;(z8 zjKzbovllc0Z;v3c=V2_5IK8*`z4MLIj&n=ey{*~yQ&50E3-kTq=p=w^#Ko2t-^zxN z70^OG01Yvr;i%Tw7HS~%=(c5H#97nf=$9P=e0 z3w5>7qL$3>Ralx49|YH1hJXi?#n~*Rw6vvDUL$y=>|8X;k%)tgn``nl|FXq=@_5of5^zg`tCQr-%8n z$fV8W95vhsp~D1~VwCyyfD{RV*MF$7;XcytT8eQqBuKDQbZ2$126$U4^0$+w{_aG3 z`V61SQspuMum0c5pFRt()UA1~UAxk*ThF3bo@D+wiUWVaH!*=FS%na;hp7WR>*~vt zg2(2=1IGMe$PuwD44_n?GT4b+gPI`54FyJ{2AY8dJ;19jqst{9(2H+68?2b}+tmNt z$^cz|O8sqzB5iha-d*d62;Ml;5cG&aa`^xa zgD$4eMe!}-o`&|1F!1CNCT9er*d^noCjOwR)1R#M}v184d-&IGe z!S}%*z=!Ud#GtL`U>Smz)YQ=POf>&E)SOx1K=%cVUzbftd`GkORPXQKP=U6O05Fuf zIL~V)7oT3^a?vrZ70_(~>2ml;(Vu99b6k#Kj2T*N>msyS*F;REiX1ZG#r-S0_9N#^ zx2$*8_X58CT^5ejyuzc;-k69);?xpwP!SKO3cpph23dt5K?qWK_cyj#jS;-mOP$PD zR_NVdKb!>SdyI>5iWBy0hzk`6$3ePm7}|Qx@b0b0nC2uo z`{V)vHv~ujd2%6_`UKBHlnReWEKaVQ=l87OAxeB6?|Rq}gRUrfllG>Su66mpmo4JR zFCI@m24KQZ85vQbxFnERN=K>s0+Aad4JBGH-gF3p&dHv9ItR%4A)f&X$F$T41kp0~ zr=Oz;uuU*aR9SX>6jlnQDRgsx(u(rpw7$+MJ>EK0|k^>)(+ zW)Tl^-6*f(1-7`M@|uM_|JdkK8%F|lPKutfUSJuUB8(UrCRwQs$k(fL>z%i;RD~FI zW67vVNrLuYfjT8n&oHh={dKSgHdDZ^cw@-$p1|AnnLYv zTm8qnAuuD4&=XR?+{FR`y}3Sq!H!EiiTkNN4N3P2ZOMSW4xPlkqeM<&nF%)yjDnC;o#23FS{E)iBD zEE6d^aBO&l3=_4Vp8%%CF0{n9E3lb8QO1WL?6O^FC@5mnV>)1~luac@S(~`1 z>-0R6@Tmgz&WArR;5^kNgpWiQq~0dIS#Q*`#mMe?_K(N$yHSL2o)7*QdQsdhD-l!7 zD@SJmTe55B$Qa<%BUHyH5;c{gY-Ri)C}I?N6lLC(%wu5nzSKd4GB=sfupp$2-CfkT zPeKj{ii5%!=>=^8*nTMkJX~gHLCHa&(|F#)0MA86TraLA;_tMXN zjv4@Jc3?9@Z=l5blNt5iWQ8d%=whPk?8(g3zE@Ie@{dou7DM<}VAL4CHgnLHr7rL5 z1;P&`%soJXPeut{2Ru<(jOl!@ZnR+{S>y&7`J9EYNj2afp(>iJoiLny1;|M)HBw>* zAI*phts*Ff>2uxAxl({!4M-1d(QR#Q=3hdR;LhLZ0fLxpPzSoWg^Qe2Cdwzr{imM~ zGRbvei~~@S<^(No>ZC{f6};iu_sbjv$~FB#RvFpJC+*t1#dwjCW3b#O%De)^bHMBJ z+*6g?_*l+LaJ4YpT-i{<1OE~k9c4X97#w~aD-41<_Hpdp8rl3H7JA7m)?i`=XnK09 zjXT?oVaB^}<-L9f137%T*uvx-naNX9UO<>Z!l>knySn#1GbQr;*ljq4Gb<6oRbOH@C%Rq7VuM~KLNrDyi0z-t*Bjj&-^<1?l0{%a zN63ra**<>!=PAgYFeMUMT}|q}7$}|{aNPHKfl^;#n2y(&meL{yr;_}egAGx;YI&bD zvY|DF1~hL00ZC!$ZtD>}rF>m--19zY({sbJdwKomE>ZJVBOn4~;%I}61fs;_wI6B! ze$g5lCW)+xB-EKmId*?l!_L~5(6zvfW(pfZF-8)<{J>^`GK?)VN|TzX1k6qdYOdt^&?3h$3>TCbI zD5bl%u+(%JU2eb!bv2S@?2^Y~e)9Eo6JUE|%0+#*8l3+Z_*Xl!)J#gvs;GhDKN6(( zARA*0=q2<}5A@!Q}lm<=4Sn`JX0>NlvtJY5nJM8yiuTS!Z ztbkALd9n!-U<#?!Uh4v&&%q$ZvcKX3T(=!zRx=uCIhdYy>Q)31O(I9771yxxWZ-fz z2V5$F+Bau|-#w!6{#bc_ols#|6(1u-ncjD!!zxqM0m|@sU!toO4k@uOZx^96lroqv zawsz3zV~?C;PUF11?AF@i5Lp%SH0w^kPy_HF$i6$J0w)EUI=8>h{XEo07jic2s}iw zVemhi&T67rMy!tyG?AJeOrubO_W!3mcJpd;e>(QdI}HPx`LL&6j^rVeasa9|=65ng zZ$%(r|DWa<-VY_azKv$Ph^t; zlD}`q54RLlZQc7|Z?R3T*r{s=HetO&<{0sS+KqtA#pIAPtPFNd;dp1?0v^8$@^vZ4 z(hNb`vv3pvN)ABeZ#g)S4nVOH*R8FDUmR(AT8>LWkY>3bs~0EN!C0hHLIP#Vrsn}I zr?b}}konDrUbv|?I+i(`=2-?e_795X%_muM@01!}s;H@ja`WNJQ@06)8^r^xzo3Xr ztnW)-vN&#JehYohVgM24`g{xFy2D(FcGLcVclEl>#akGU%EXQWhY?&WBAY%1y!5P( zWIkEgd7S$2di1&8K?YMgH$rN5i5py^Jv_cm`SqkET7INb*fo=9(4g^c@m}smuKUj?MN&Hv+(FU%ot)_S&;} zqKyYY6?c7fgal7fYt$(gQm%1Z1XcI^k(J|kzDMB9 zlih1vEXL16h0Kc6=dFYS&IEpw78U|{#A$k+v>T(#npFI!PpnejTr7HOjcwU1p6BNK zJ($f*76+O@3UK(ET{q@I+DAn|MPVT#$Q&Y1hld3=Z^t9hA=EagYNahRcrs$e^+F^p zs23PpCTsJ>fzu5>@mOnN=rLG}B4PZ^t>AARwN(CYbTW_Y)^J{0n_&SMc?8dY@KYLY zja>@(UNMfA2eH#8pL5^q63bv0Q|FSul2H5SE?9&Ax^o9ZBwIIXrHHcpfIXs~Hqt&8 zH@EN4h3sMS%Jv*Hn9+okAhWCez|!69xX?4)k?JEBPo4s&4qNA#q7o6WdBny_$yh)@t00#*d}1GYZGa2jt2pzoSy)nu5wFJBH&&(x#_vqEp zsq5+5xrIr=iB9RWS(+u6g9U%l5HmLCr;yk?GYXx>}KUjvGS%Q8cJh z3=idt=0LG#ZPmN&oH&&9^GyDDSfQw#=xa!m337BO)H8cYsKW) zZM3A}NPqRkAK7qBB(UCHL_{R_`*+6FEGIj6V2HOGelf7}BRsM@xd|Zfy!f|))Ih%H z$UU-`#u15Ah;q#%pd?h!0*E!X&lN>XKR>DA+1b2?ti}ibSM7KC1m$d3U@2;RPgj(?Sc{TG+%lytCo39ku>g}v}+(nD;;MG62! zrlZTPWc8sQE-%Z&+8kE(lWc5R0BiM^C`ozN2bNK?ak$$5)qO2$HaoUxm6~E)BeV^S zeTQXTR;hjmO10Use!UfA{>D`i+E|Bq?Y;K_z@b-9G9{kS;CQ^Rk(Y>}vYFOqJJxI@ z=h@{Ve>Z*`mD76{xvBR|7jV#Dfb<+65woF1A1s!PK1f%3HhC!C+lkn5GlJZeMBfLA zQd0krX`@jY0KNI;|C~>8y$MeER5D6HG$+=MN(pu~S<;FK{uxLsK0Wy8f7=bCWu_-| z#^#|gqHK&Bc?#L0Vs-OAry1uy+#%+etL&=tJa1P>b)3w zr@Nvsf3obBN%u>)K3JQ4qk#M}p@l}1c~dki5+@h3KdauL9iozk>Pb$wEuOmZ$=`O6 z($mx9m;ns!-F~gsYW0@#+Zcaa6L^w&IC4>*FZi%Z{r*{^>x%Nn?Q$(eaV>`2^QReNPMy~WANt3hKY#A}CsQglHK7owis%n}Z#oK|8+Zd88{!iVm1#K3#1Tv{s zo#ru>iejGoFM!(o*+}5`?Sw_xGd`vzq>&4%#|eV_f@1w*tfbKd&0LZ1ib4(OP-3D$ ztJ>HgwXO5YYuYr(raonV+rqU6zww_cCDAg+>TBs{cwG~Ypx|Z6Q24Q?J&5oMR#PoN z^u7@4aOERK;77Xn95$$!1V!$!J1V8@7&9Px;J-7qi!QpW%Lz5!t1g% zzSo6qG6D9Wsrxq#-aQ^`IjD&@+y~6*znDv zoVb-6!KB1@bAUr1Xa&V4orXrf5pcQ{i!OX!(;wl!l1(CRVf{mypRQ>R>oWF!+XkN}vxXr6B) zK1ghj@K_41r=h>6XSg+Fs77-S&qhIWzPkAc#a}JY8-JD-YJej(O$ zgZuT9Deq-T5Xh9#i;{nfryJve3ZrWC`^0sP{8{#DZAaR+q;Y^T<8DhkmOat>T}J~V zJr!~{MIStaTd=VtKz6z4G?{<&N^R<9A4S#05sLcZR z^#HBeln7t3X5i$Kg%ZT@02gr2cG0aIU$x|Ka%f*u4S|x&rd_h%3S(IcYv=)icb-qr-mguz%6+Uy!&_9zt-x3 zos?G5OqZo5+t}J?E`})VQirB@JD-9HwlLup`aFAH(&hR*Ev-U6fg_^YEU`lij~D5g2s_WR^lKSu)Vsn*)}2uO@QqGOKNEEIrq>t3h{noI<+GX!4V!|5%*cK`}VOLsZ%L{r~mZxdN(Dvq_u;B;Ro3 znjHu>e3j!+K?HtWfU~goeHd}!3eacUaTNKP1{|8SvzVX1aWGxSH@j?MuVNl~8N9c%bW{degY=2NFAv zQ^Pv+U)HdEgJ*AVZ)kEZ2@f63S`KHK*fDvBaE#y7Wpu$^dLrE0m+#?qogy-lhj%moL(^49Mb&=Yp`}DhLP|QMyFn@G z7?2K0hwct(q*FSiTRJ2}K%`rwySp2{hxfNW7X0Co8SdQsoPGA$r;3OL-@ixGz#(9y z(C=eSAd$h3@3rucEfBYFi}#8rlXuwA^YDj4iW)UvYcF6~IOhLGQwck>%ilp#wX}q( zfGPyg>+KFnl&N%QR^d9;F%n^n)s88l(YD&n&~g8-vUGd_+yKIJo%EGi(#3_^ge{FwlLX@iY8@_^b9#G!B$x1w;eBP88R&Sq zxt;vs4kz+74@|nhkQtO_$I^p;><|nFSN}U@b3f-GnSTCH)jE5=lg$i&#m$p<=ryL3 z_!TwRu>A5xo~4YOBC;2mQ-aG<>Zm^rDb2qzC@O@{*qyvUuF&wvBPJ;+_@vr_Fj9&z zURC_IixjTo1$~{s*Pp4r2o{To^oxjhof+BQxLdos?`)?`Go;mG4uIhQUY za=&L|K#n&1q#$D5i4LF@WN2DlUgyT6%@H(bKa0M~nde*GNrE1^dN#MxI` zdH^z+oD^J}D&VBfBJO$p7Rt-99+6Kv@ZL(=NMz~qmqkMW*()UGlO_{=b@X>zhwLL` z7$r3smsiOhe&=}jRhh{}WawqHzs1j!#m^-c`4hQfh|#&JsW9_6zO{&r{;y0sTIY@1 zxXIhB4nHsrVX3K5P}$S?>VCqF694h+9)8bz=5yx4A1PWj8W0h;4g27B^qoH|n?@F( z@`@eUCi;EznX~cJ(wjcL4>2#7c$;7iCadRXu$Ig=oWl5U`@w`Smb4G90mlxwaXzQ4 z-`nn3*|OYT{f_;ow1)dd4-8akbXZ3dxn7G;SxD4kUX>x2|EkpCbdC4McLrs3opwXm z2C`M=HR>$zhJWk(+7XMuGt!cwUL!ubkSd2fe8pk5F?cdUL%;qw_!0|Lc*{1Rh<{1? zIYDakZTx?YI3rwkcgATZ)9oFG&+fT?8d^ZUlV|-nC)9ZJ>hm~zSfaZ8=~(G~x<#4@ z0){s-VOm6Ek_)DjNaPy=-01lAzF)uEz+_Js%=q^MBy|Gjc%a6YjcmuH@}&l2m{o|? z*CGM)1aC!t0>;>$Eq~VD5JO_jQdZQ0Y_A%^)B+=pG{ag=L#{L{`>2 zU?Toof|jFo`q_+yTSS#X9!a0s0>Q^h(y33{ZDM!uuxo!CtG0D|phqh5nukS=Qg#y7 zh^~3Aq>ldjO>R1hLGPT(@G?~&Gu4jU;^S9@We(TNK*1gKN5t&5o10QXaspoR7iwYp zQP65qW;6WuMXZL|$TIl{%foYz>HQc-p_~?x%B}Pd^3lRKgf@?J`;cU0)y4Y*S92sW zATGuGy>Vc9>!ZYt@LiLhn&xv*krdTG3~2iz#PCM$a(!Za{PUMD_+M7b{z3-KoE^>C zGc5T-KEGb44XJq#*6mo;Wm1LkAEsAaPCGHcsZ_p;EmdAa|H2hBHm=V9N?liXz>x`T ztYpkQ0-NSBFt%0>dhLMWvaLLXz-!#VIp)!>`^^X* zEaUK}Q;bH01Vk9!%d9S}OiVXBVcGwzNrmSFm%hyUC2+a54xr9El#=hN5sg?4d`y+{ z{#d^p!0}s8b6z8Gr#}eD;mb}#pZHGG_XytXr-_ZV99i?{CzVSY=Dm7YR)nmWI{6Iq zafCA&<-^OoH!{?dbm#pmd}r{dmnss zS@o7?`X2rlW}ZcsfHEsh4JUaq?;At{`5O(yrA$We)rc<(Tbl&YMF^HIaQ8 zvE33&+cjpKH*e1<$(DiQ`titVy-q`YDS-)C8KKk-&Jx#>|3sAiQ5nKtNEv*>s8~n3?Aw09p(ppiV5oj(WYZZ9mRK`?ZX9fVGa+w@?m#s_V)c(a1@-J zxacq6h^fW9g^GUg*vxe}|GP#FN>+T_+sX9i^C2ZvQ=b9Xe&)wWH%9%5_Ef2fkyYo5 znzsBk-lUq#oOj3&9_;FB-q^idsgKuj_!Iuh;rBX}D3 z@3ka)tPp#ks;%e=-v?7cw4@y8n0QVBo>1Es?V)~J;s28Ur-Ch;oI%wJL6LcXjQ`%f zdO<>ND0e+fdX1pV5jDKd>q{irdnmP*S$&J&jHW1h^X$3TciNA>kn{Yzs*Nn1l#FW` z1}1YL500*ejN*#jcLeqYBg4u z(zH+Q`i*SBv9Gq5R zDrZ&o4lw|9BfTPrl?vBpesr4aQT3xVd9*{TKMkpTHdTbsmDdh%o zV^hnZeg-S79~OqoBXH6@r~XdBL!x-erdldF^%hu@qGh}GVVrzAw$apOZ+*w0wtI_yRTiSC9{|SiOm~ zTMP8W8gM}dDWIuX9EiF$$O^2(vE&Oua|&?szJRI$dljt#z4>*>4k!@D?q8=y0$bs; zcDAqHu#`>IM$K}D8nSuOc!2m_PfxEIGNBob|Ki><7g4#XM;pqi8|kDV^YT%OCiL7~> zUu$cGoX{3=;M1(De2q1hiq0-&-nn@6B-fKwnA836LJU9 z#GwL{5PU<5k`ASg7uhe8zxvzWoo#B4co1cOswLnXRaT2sk`5M&jOu9K@89$IMFM62 z^ob3LO`+gv*w~ftUWU6{ylLBm=yWQ}`%7rSMi-{? zX?kzl+*4Z=GB-~b77x9vHziEv^ep`ntSi;TFW%+`;|iUB;9Z(hiEeMs`QSE#%SVbD z+|135L+^Y_bEY~e?Q#y?S7;4Vo8HZWp{tc6pIb$`iJ1_>ip>ATHM3Z z6m}iWh+DCn!z(yE09!$MxW4UTsTQ)%cIw5mx_D-OmVp$DwHv~0VKsIi>gjcgo)r<| zd|*5~tmEv2>QK!)Ly8UCKa_-so3G2)Ar||nA{?J6mWI!MMQ2^znrN-nOSW8SyL0Jd z>O(`|HEv!-C}3$c>$@Qc*Gt4nfzG3)v0(uj7}>0rhAbi10I(Pt9( zVSg?TU_yMStk=(2&rd7t|~nHeWw99Qua%e?M41!3kmt-?)Rd>UHF&B_K{_JdJ-13SeYmNF22&QUr<(4$2pS=o82cP$!8>S zB^np{eD}m46!6=5K^i&Gi7S11ukCoE=7gD^8p;S5PEU?0Ne+=si61d}f@fBwKeA1CjW!`Y7ay3Bn5*=4e z*p)qAAx)I}^dqh12mC4*=SzN5B|m173iN`R*-B|Gzm{DjH3QEBZb%y+evd&vibjxO zsi7X;kW_cJc*)Y+x=H0`)kJ1lcqRl-j0~7ceT<;M6r&Y-MJ3bZ)=toCzTYL>17do` zfeEfO|6dCrJUE_9ncL{JJ;n_OmBY+ua;88IX%mAfSYtX!yH^_DGC-i>^<|LY1v{E} zqL|(Yv(S>M01ZJey&`{j_+O3t^%Xl!u^bN_{V(%=m4DiMwHS_d^s3Fz0l>0UPr9Z@7ELwNY>@n63>Dj0uWMp3rhu`Ii(n(-g)Bfec4 zcKI>zoPkat;~6GdP)QTEXz^zvMQx^#&QA(-0+oh$UY(yT)pA(-xI(1i!1;Ll?yU;F zJcS0NK!v7Yq!3KF(V1ucQ!fg0{1NQ0Ye`QZ_`b;v3Hz0M(BsWH4Vk81M7u2ttd#(K zD~_=wC%SfIFbmqOuJMl(c;tHK5+$RpV*C94J-M>GKc0)O?#Ykk9dOTe{vcbXOo5L6 zu1tAlZ{6DURqW837?K#}FM3YB4%R4QBryqb>`)1b30_JEmmF%LmPH7@Je=BVDXRPP zC_+Y)&;Ws0MUBfXDN-xHgw||&@p#->w`C>#GSAwmY_W04f>+b0PTyavyv-Vy?|H$I zZtQ^(;&Am45KC6r&=@FI9IIc{DTjbsSdCdw?Noqf1U1}AyE%T>;3y44gP2z)oX*mb z=QjU#ilsmO`1KUJmBMhRDiE;6DSuAlfQ@Vzjvz3(?z6q zD^1>-4{Waqc62^?ha*sDIK=MAI^x@M%bD%DH6b?f#^z^l(a$Z2b`x^3{+RhzLcRd> zLhpw#(nm}w?WX#vkz({!R!G6ack|u3BABbmH&=o+Ts`l1i1Z@Vt*YFxuDXJz9Mj4P z+E@(fTsS&;N5onE;-pLdJ_SXn9Nos*r}6Ert?b4;5Oi}=FE_m-5?J5bvKXq|V(QOr zcqrno8|V`=Fw*2?8{3_104!8ROQu=tIhL^Y4S9uucsy+ zor+{Pm_O&wiSyGFl(1!PfK78>YAh_t?`{R55a;jrn#^z|Ql-ld%ciBhIs5L)Y6iv) z>AfyLgsmM)oC|uR(n?WK^(z8-oZvR4ViPzy#^F1=yE6=f=n^+C$Mq9FElA}kzrZJ& zT>ZzaSA5a8jRfMN99Q%jhjeY&ehH=78!~jUgjq$%iF$aL!|eM2+SK4E3z55cbn7n` zT_21ptPj<7LiVa?MD46VMFvGlP92h-DNV5cP1S|;#~}EStx*VH^AD<6=McXn7HB{` zUVz%=cm8*B=#G~p6#Glqr{13TEz`TUa%x;WzVSF>686e4ru+`&aMKoaPd{lDi-`$=r-#9$Q?$1?U*1d zYOk2c)GewfmiY8GyNdAM*!_}?px$-^(U*AjpnO_rk{$AQTI`+qC@ZWbn6O&KqVk*bg7y}!55nuS+|&QcX9P5*4AdLtzV&cJ$xy^tsEmTvQTuT`Gx3z2a$1)o z8mIO3vj$9MB=j=YyQUSe(p_u;q%-${1=+h{Jty<=jnLQj1#d6)i^-5PiVaFeeNfxi zz1UvA{(SPqVaOzN+huMULp8^DwMKXI84J`imDiPQm)zhn9=XWhN(=sM5I2I5o$r+x zawvPo5%Rb%W#qFev#TG9p7GYtro_(GTytjPqZ_bRKmML~0ATXsT)HS0QrtF)D~7b| zQ{>O7a>YMqvMalfn)jSWOd&mi@6Aot+sm+jhOc2N_9FTD*Hef}Atj$5>VB@bK}xJy zbv+N$=EQBzA2fEm_CD=;RNm(ykLfjMm%bpIq)$q{&6;6(=`BUK$~c~ruoFw)63f_9 zZkRvki;-GFa;o$lOSL`y3}1axy;hq~M6bo)qLh{QQh1*shN{$_`$M(l+TNdnZ2HDm zfCSFEs*m^wY`+nzg{-OKYp@Sh%odZPptt`oC(<}$57gDQk4F= z9coCeywj5hW=+4!kej29*ZS3Xs3<-QL0ma`o1WF&4*lO7(^_HdXEXKP_ zr)#j10}2tdVd$#XG(S~9Kba}%b93=2ii=VJSJS{A=PBsQ}HH^gif8O%V!GIJD(hd|C;^SJ~Sq|SA^Sv5qko%nN+C`Tk@;-R>Z!-q{Ankd`d5r7gx z!&j$nkfSCH2c6AKx#ievV0~dS{Wzg2%unPwrmXPGiZm+#t_Ty8TX#Uf5sUf_JA)+I;;evL@;T-zga}t3zmkvy1m9tih&X9s1M(p?enWK8}0B{ z%JX!4$rOAjnDjYp)p_S6M&LH|V`<1DJk#;Iq>j%pNDy~K(# zAy0xTosT~A3+hpAYI5djpRkLEhJKCAe33IG z{PNQdqRsT>Qz;wsOwt;D&6-2iwcEXO{zXsZ&XpU2Vl;26?XIH0aYsR&2IPDQVbK{q zh8P1ZxwsW3=ee`C^NzmFjdi%k#tf2z&-d}Fesg{ZUt}lrh<0iH55ws(6VC*zK>GoY zD}jys4MoBcMD2S5jXbxU3FC3rR(UnL8WJj-I;7|VV0j;DhM0SO4_$%7B;N^*!tzFulqlR1smm7~w!p5(HwC(pi#==G+Q~+MtHo_+V z*;hMHwu<*8!QMw0%2;g*N z4O-rq1vm6B^xM?#t?=KRWUr>Crr3mpKv1eXd5?e^Keo*col3B~8DJL>tStZJBO~){ zbad3)_FqT^uUH+%V>K^-Jtj&2UW^0OdZ(8mP+C&JsdXv{N1EmR55KI&H&cv4vdT~s zyv)o@nM!!oPgsgdY)I1lZo%5Z`Y$xZEG?O;5{-{P+}3<|`uxdjp`dp4@%B`!C4qab z^yPSV*v8d%ue^c)su*Ab2t5SVtE8xj*8&3SA7Z2<_MI^xA5qM^o)2k=Yltj}tcBoz zcU~coNRn77KIxL%ACBv{gln`yaJi)l*|MP4FPLiK^+TihyE9;B0>3Erxvp+(ZLw$1YZw*ePzY& z;ig-l6jF@h>SK*hK@%w1%9^N+B#By0K!`-^cC(bbJT>Ueh$uN7EFu0u8TwYOZ9b;R zHUZT{Aoz?Jha2a``FQNo+g1?KD3JAr2CKfMn7nM)>rMT%3c>cB_fCGCsUB}psMG(b z`0lddneG|e&VY>=R&JD(t8YZbg4qa-u2(Haynn?D#(qdiU}J$#qF-r6a84uBJOcwN z3Wd;Iv(jdJ263t+y@Y9OE*LCvF)RO=ajHpNfVihBk7-v zQNHGtZy%^Ql7~c#|8NmRe2Ms_avmo&i5jGB-H5pW11Ngz3DM05RE5 zF`V(RW0{4YAoui}Fr*Gt3t6Tx69cPpJ3oXk)MZETU)Xzlk&xl zUP@7MgeYFS-L9-yrS4(@ZjMd26D@WDpBF{K&#|Xizf9q2dRO172r`w1J9}UfTcb-#eyx-f z{M@l41%c)WwbS{*t{==?WCp{3F7#a@y|0dTa?E1HL%X}bQ_;n=#*sY_a(GxEDNZuI z2mBSP{-KJ;71Q$cuT$jl5O3(>O`6RuT8>I))K~ZWZNwdxDazC5QfteBnnv1u)0PZ| zOgg+fjmer&=0QBOz0Q%DzPOe;Ge5NNR35m3QnuBuMK(B0crpm^&A+MQm$z(uNAnIR zC^dFtw&ih$p9dgEj@D+^?)U6`<(j=a{5>aM%Y32p3S%PiMo=(ZecOb)FY>QqCIX6? zBL&r@*KEDlV-^nTp`53pUK`QSIQG*#3Wk+*Tw%E~vbmZwwyq_@=8Pk(o8Nx?iu~@!HdpC0JnNWmGk|JrY?G{Rr)uKH zpn_dM(T(I76>ESu5FE*L>m?$m7rr~*TSOsYPAXAsp+d=`dilNQr*n;Nv7z3ItxLZC z{o=V@KC(;6vx$_AWn<~c4sq%lm}m}6C1(^?#ux`k+qI7lruly~7gZSxtSv`pZTXq= zE+p6lLsVnBnZvp%Kpggy{s-|J8ssy-=Uv3?ls3Yl0xNG@`N5Na&fCTfuVQOI&Ew6& z%nbJ0GxOR@bm}CT-d*^A^YZc{}W4J_(Do(DE5^`5@^KgnB{7jrT2=x z44xvJ>AIsTq&V--P$N&cY_u=YmTQkBNv}N)v`)Q$i{6E`2rhhQTpR`-aCev*LTktn zo#}_Y>tkr>UuW3f?YEy?7^Sqd^dZam`&JL&4W}(bRa72om7taL?Pxi9X}HpqzvSX4 z_`D2Iep~rVj`#fsqFh;9hoLP-rt+IAkFKt?+idNmr?A{ z`f*o91F<^M{0BqP&>d}~5>t0yH#c@8qwahE;&(Y6zhre{v{@_O>NAtQG=9Z69aKD3 z`~l_{ACX`?VwmOwx5S1cY6P=G{ug>ScdCDZyb%>zcz0{1F*d`JIX%yCaWMX@91hZ+VSS> z)6+^*aZ)M6@rAXUr+B&hp~zfy^8Q~aQsV4EqU!=#rCW6zC{fVuMn48zAJ2q zuzB(j6&H&wLM8_XBY_C_OZSa>ruk5EZ&^xBW3qQ_ zL;wQo_|~xH>h^YTNn+`d-R08iAi0|A7}D=CvqE+e8=>Rl2MTCS3uy|E8Q$m5pZNp@ z$F1;GCcbS9ByuReOcMJPH3_do8;^~TEjd%h9~ct+8Ylddjm?IGipV;tYHFqK_nUbS zgkqc^UQ^S2=vODwMcDDxTutc1*_(kOKhZl>;~lu4h)S+j&o@tyaOLs*@>}&w{XO7| zQPsxZKf}tdsfmw>FSK{OSUKBhXx=~k=46_)zDs_KkuWT1ebN_T&c3^82rwpYotm>T*1TZ^Da=)w@-BXp2R>~BH zi~Bx3Ikd8poDzFtYRd88E$uBjqY6!4T1Rn+ZlBz^6dc8rrTwl|=V*4Fzyj#i`^+Xb+>@xQ&AChx;gB)HS!uH>DbQ3 zXuq|`$>z75jmaURptyPtSa5yQC@n53TDm%3B@u86Eug(Uuo4Hsq|nt;K;w@eHK1Qc zFdGM-=@0{1$cEg2M}2_ATfNXOPXa3ts%vVd>nsVt?&Xc1gQiWgjp3}} zdh6ML_0~EK-qvtCGa-K+R@P8|3>%*v^(-xmS|p>LZ7bHHsO9*M4C3VZdw??3$*>3oH8hen-VCjn6d`J2@?nSgU{4-X!Q8FJ7I4i-cQcfOq%avKe) zVu-w+z%xnHD|Uzt&;#%M1I@Zr`O^RyXO>e$~yYOpkYW9PQg8 zp1a>ZH$U$VvU_$84l7NYnKc5eQ3GiqD+fQ`-)y|PIuKOl(gumdKC>ta}x%_Z@Kqn-W zE-G@_0~gut@bQC&ey}c!`LTaDXfLo^UI`MpI8X&1tfq!jj)2v4+PeSW4_nsrb3L2k ztK;K=WRU=H_Hl`czv!}T{tGh>4R3y^e*;${PfPWh}17-!-DW#}LMQmMZ_(1C~ z$cc?FLaaG$?vyWr-!p7?TW0f~LL)PRB4NW%O1~WY|C4~;&E-&<&d3+g4*#45TU4D< z%%e$itB(*B+4U6VoDb|Q*f3BXheqT?UYH~Z_6VNk{ zUfpg)bDq58vqa&#HaD6nHFA8hx)gfG%Em&^7V3GR-8(nY)Y#lS_V;hF%!Z%pcHf>PlT4ZV=~xO=t;KmLL`jd-(dHq()^>aFG%N0@!`&sCIZ^h# zygWG9WJY6o@4@fBei;r_a52hQ3Q!klV^dI87UBDFn&owWJ~f4i(t-HQd^mFuEH+_a zWo@{5NRrJ5ZuE7mjApe7s^{f_X=gAd-piL4ZY{I6?HTL+Usu=GBrGiG0q*3~ge-(} zq(r1}nxFhLj>aY+2!S$k`}X`gLAxc)$3l zpsI=^n~#$yD+#7uaim}{4^@6sx1z0A-%WxIO zL_U80(Yd*SC-ze_EYcr_OZy`A>(?Hz@@AmfdAF#dq8`?1h^nlVF4O^FbSzB*Y_%gU zjls)&C(78tA}?GSYp+kWtFdEykOCV?k-HDdESCDfDlvE-+V3!3+l?q^ZL~8pSuoq$ zF%j3tlmOLd@0^H;fO2rCmK%cqkSyzVN@qP;J-WOk$I&FxBnquoe=jN4?ROiS^#0VI zgHbtL-Z9{%DSA`i+-t`HWR27)#~Q<(-|1{T8-dON#gy1(tqsq7eSLYXqZ(;rh{*}C z>hg8@yay&OXNR-IGWsSc|M=m{IIA@Svah0M5Rf*8*%Uy+o1X><6PeSSENX*siESvW#fCh zQ#1-^zI1b-Un2KUO?~Yl_e}?$8H^?6r4Ma}O){3YWrD*)#B={Txb#NbYaoR)WV!}S zpxo6c?X3ZxGn{~xth%)H9Wwy|!AoXs32*P#Np}@(?JrP9nx)SuR|0G=T+9FN$$GD^ zefs6q;x^mhxqYB~E=pPgVR(%w<PS9mo9v{p~%~?sv zV<>B}qya3W2+FwgY6tbGA=ohqqWC7IZ;-V4} zM5{@@!c8qn-g#}jGf~{t)fJ=X5EQLwkXN6NA0{KwQYjeCoZj;-g+X^nq-PYD*3}Ry zL2aoq9~~dhi4sjl-9SOmy5QGdN$zMiWc2$=lQF!y$>|zL0NuQRSq7Y9nsy3uf=Y^& z)zn6&`v`8K)}^6!^aF`#TS|}nDZ&n?+YgVF0>(V;9TRCzmu12lKUEjCL*{(tD~(iv z!t0eAm(1&q!=59qOHcpXc#d%7(v|p@@3O;^~+CX#Vz6Sy$VCg8ubC z)=;e)Gj^9fO*Gcb<)7@kz5Xw#^Ofn7`HbMRh~NOR+wqlyK$yYd$m*7_%|H*R4&Fcs2;p3RT!XAT{Mh)R}~ z3nz#qqq{oScm2NArn~Qd+(Iv@f~Kc?Q;<%_njEh)5|X|iH&nXXiDL&Zu%>H9^Z3NS z7^r?`UQImn&sQYm>bDn8og!hRJyc!eyZ5aNgfZ_R-3g=cEzDnxu{@Kw4%KPSYU-20 z%~Al?6FmJ8XO!D^5-2JCG1rR|7TDytd2+k>n3cO4HYfH<< z7V~7K2?==mUdNILjjPXhcI16^(1QFIA1)f+=r+ax{`)TN6#D&SP%L~0 zj9`7e`-!{)PV08kOUJ;(v^tXW?%m1)X%V2~q0!Mj!^6=71M)TFZh*r=H8ixX(^67; z-(d*{PJFwp0{jPHJBz-)e#^tnuGi!JrN%7?A#%sJV`Q3D(|B#>{#@+OmS;DXTMe6v z6A=+v{rldr^NT83#Jsb!(|xb1Ct1Lmv9k4o7yw5>Q&Y;*?ey4X*7w}!eqzeNNf3ev za9HRRgMooT?DFLPLFU=Fv1r+!TSR`Noj0Ch78z>gUzg}c(~L?&R6;@)@FZvwZeHoN z4vItH7C+Ygg8tl-9c-K#o*7GIBylvhLI14&`RejS_^$zjPC{307Y3RJ8e~%S7kh9Y zI}^#KS(ECI4rnfF9*ex-Z-4%ttCQJds~H@2Ltb|;T_H#c0jGjpeG@46r(uiusfbU= zWpSp>^r3_;8d_JhHR6b z0=6mo-+Y*uc+*mEw10O;bWY7q?ChFl{)fZ6VCa_-z#y;V zZh~|H=RP$0GwJ$lD?aXjt?D$fGNF-?-5nipwzjq~%O4_V;9vn@ANYNj`apaqsAY9D{JWgJv=^h;%;eaNpHQqs0K?d0WhzJSGH}P^W6va z4-E|oo&9_#LygmRwS#_oNJ{Xk=dS5AEId57tR*7jhikP(2PIP|V1u4$V#a*4zve;YA}aI9TxQ*W!6oPWsXy^z-u!O;)X0ApxK5 zImbpUCP)?=(gw(*>{9QoP~8L8J;}_Lw{8t-gxD^K;IX`W+V5R2uUg0s$ReV+&fg0= zA8^qPXS|*GhV!}c6df^~~h+Ij+C9U24f%V&Bz4cqIrVpMX=dUtToeo-1%F7qJ zBL3Q)g}_({)-D@;4bZUAjr-P21R|yCbw90JW|;__AzN4#7BvOD$WNF4edE~Pju$dd zdzqpuf|fff1HuS8;`0KZLS)tvc&Cn6)1bx$3jshXh|nno1wF;WcmMs<1kI~ioHlcO z^)~Z;I<~En_V(0RIFYai7l4ty z*@ozb1&{ES7NNMfxF>aNdU|?oeI0<}02r?L!~xU_6}dY-TwPuN!_(be_vIi0K7iec ztLl`o%9@&?s>N&dvo^+k2@L6?zCbK!W1YaPySu-CFDIAV+??urziR+;+fV9;m6a85 z=*-NFtYXx;dA@3KUT!WzhN85VmR7s=9RSogaCZn?F7pctXirW~_Tc{l&I|^D^#j}_ z67>-ReNbl7XIP?lKfz{;{%?}uZac+=nhiD??(H2AsN8$B;STj=w0Y1!xZ4HY?J{#M zF)edMN>K=Dz)Xmx&n8Ds}sw-kI{u<~2l za8t>(ax_)xo9yQXlYb{2vJd>!-5&=9hNUQWFrk{7gxlNOp%RpBcPDbCy+==O>EU`4 zG>9m<0q1f(S?SZgH(g`znUK(>rX>6%4Pg0R1(`rEo0sj6!lIAY!$7j|e2URz^W%Wyc5rau zbKb#gznQGGuwX-q0>{_>cE6#&)b=7xGzBAKy|cDk{oniDZoCO4k4mEUScJ1<&=uZ|C4ZQ5#0=IKF`cBn&8J{`*M@ zuwgrefCI>GKMlF;4of^!xa@Jjs{@0Aj{CwZfp7Tz;c-UN`yB#E1)&8|snIG?v9LTR zwK?VCl_vY&2t!EoX$3CVairyP2)lhiDv9Pd6NJ>>b{aP>&f#3`=M z%gbw)Kk%{R4hg*Z>#zO50+!$YMT#O9Rdke_3LLfIayU8?A5$Gq2A6<>MV?piyUntq zy)shsjoGg&RQWW4$Z>PUn#Z3$z`fX4*>`pS9tC9b7`KPteS?}Yv1E3!)f51iWKdQ+ zIq-G5L+w^z4AWn zMgtRwnQlTTTiS>=^CVF<*a!7~g-IPM5J9Ol*_yzZLL`)NEjzZ1{}r0 zFY_q0X({g~uL+%{T!yQWfA~+pxV4(J@RINxnvOWM%m0$l=8tbTdfl=0g7p#GtKphf z4wg-b!OPiB($qN1MZ1OdW>UW&BM>qh4u$V zUBTW%#o8TT7;=&DAAO67-tnQ9`%J7v_1L>j4|4$lfsqSkj(Kt-f8(OewlAdLDB6C^ z4X8wNl78s_7!*TK-tt0nF{-i@oig?ra53TGSQ%1$EGNeCX?44XjXxAa-a0g;=jBm9 zDWk`$J=3+Ha6w*uzRi)F7!w>Qq02c(`Bbhje}DJ{+5Aa+TE+A~{z&M5fQjw_{3BR7l-0@A7J4VZjWgm;#7(LPA1zE-nT2^+{u6V>XMI0vS=@5_~Rd zvT}gmBCwF8#0G45gKXd3-F;pg89)mo6Vvr7`Qsmuegg`4#B|iK+zf3M`Ppbo83ydCy+6Cydk(; z@MPVcs^smwTDZx24*j*+yCionSawr@mj3{+To+h8vQE8^S-?|Q@`umyPssxNZ&`Nr^f4j ziBHkn?O}TsE}f!oLsb^=0%5pxE1R3rfRH_XJRtm)={Cj9%xHUgdmmq1YybyD0kRw5 zCUFsCUNR*9Ic$4%$h#PL;qrItFYeUDTjYXEn}KBZEvIIadB3dRHXFQ{n|eTpuo;2T2Cu;S(&EIMFb$ht>b(QOpunP*dY%EQ9oJ}Y-*R;l4hH%=F0UZ92(@ZfyP*QJ z+q?F`0y&qBlc}FS#mK-s#iYgh^xp+iz)}WHiYBy8H%ko<{! z`k^T+Yl>OFV@3|hnPvAD`Vlt}^xj(52@N^mbKe(Ppp4hN>vNBcaQgcEP6D|ia|}AHRd?0T~;bOX=w~81X5DiH_BYQIKh?GeYtnW!sqAn%O=KZRLtef zfyg0Cq%RcJ6%r>K!TP(S)26ON4FYW9{dXFjt$B!dVU7gz45EjMcUQDh(Y(wnRsp$) zVfbimIt~e~U(lZl7Y=fJ{s~(~6Y1|%zJredVYWFHHP%rm@6=m5gb&e z9P2gkR$t-y$-Md2nvWDPYIqQUMscu5VSP*qY;Do|oXDDaK4bNM9}E2jk-qF&Kt3VW zn_tWih;$2%%Q8E7slT1MT@Ep`FOZd#GF{k(KLnCA1*8M0B)e6-pnYeDk)ih0_!-%| zre_c876OlFQn^H#H?GMnZoMW2NbTC?1)3X@!Q&Pi9uZQuc%x-?TNzileue&bcX!D` z?i`e{p@9B7f{uFq_DUdY$S5iG7_w=8=ETCnQdO1D;(R*iYrXNUWQDD*8BZkW$tcdw zoWSe%nvp|PVRfm&!N{Nh7o>uAF5Da(I8;V8eH52eT9Q%>%i7}8*`3kcjypz=v)wAZu3x`bI6t*9_*+N`mfnd2(cD`xIXdX1jZOtgMqA2l<7TUh1!$n|o7AB2AJLf@N1>qtv;$Bi zN_VDpx)VLhA`7AEml zRu=7t>!BIQnS#vdLGvyP7~AlE|pF{unsx=!V)^}e|+&uwx8eKF_OYirMB_l@3Ay}sua5y_mJ(*?B@>IF(! zQL_0fXWQeo4Go;G2f9y@aAB6umr;wZ(a~7o0&s9}{&CrmSYnYQ=f+M%U{Ln;{qZ`2 z1B%L@wuJdZhs%zHJ$d=$KM~uUd|%z89z9nd8xtJEfCLW?xJ*jyFFn_}?r%up|Be=r zefS;_0E$v8%I1N}_ThRT0D^_1o;s&Xczs%$%%nx zn-%|}*DWTUVy0ow5Gf$uH9*EGu`F@lUjI7K10s=+4|CUZ?zb5vd~SYvj|-B!>U{QkdB`-A%Grf+^k?q+-y2_46&;Gz_m#+UI>q#w zIE zd9wGD_5SpqVNz9i5mFc)txcP$`QZM4su=^hPUr+wpR^LeM)m_^DU(Ibc=)&l*BD5p z>KFEOPU1H`5(?DB5*maPagCmqc8{WW5M zr~#Z6Wfm`?$f-2|>N;qI*kAAe(3xBD7McqeJ1Ul6aNAAMsu-eJD#_w1cJL3$6w$DF zYIjt&j*v8hq;;QuT$GKU)VibMh*+!n9|?^fdQ$xtrmls05`uiDLXL}^ahN>;q(pOI z>qz-`7hPP{s%7<1I`x~r8Eb(TU`6u?q8?1?(~ z&DJK+0L5uxVa;K;`2l1kO4Xs(y6ec6fahAFa&o%G~y*qc}f8 z>IhcZQ~7^Podr&doyHjcDmPU{eknZl-ASI0miZlXJ(k0#9 z^{svGy))m;Idk-kg6_Tl>s{-4e$RTd)BM`DtZw=m&PQ@}jOlzaiC$M}A%8?-Pb>CA zcCf`FSSLk z8o(m5q3MMN@2Ci6z9k3;PWAb zw;j^e2CtqVA3P9ZFtB)bZfrN~hv9X+di(%H7dt3H(7m-HXLf+oI2>0VVh6RXy)L^e zkerl+NW_~1A~Jw zme(ylTdTF32W|AVKF`BSixDOzC8gi{4RDc~4*Lgl#Jc7h^N%4olqEk|tl{LLWh(FX zDU48W%8Y7%Kx(4}|h;wZC>ABXcn6f=J%+xij-$!o>C2nI)YTqXR zqJy|<^m_g|-1K-lP5b`Xpnwh{&R)5Gj^@3{aF$T^rg<@t2LZ{+6A|&p$BR;-gv7s; z<#~)7c?Yf!+Pd{zz0J&4%B(~|T5>GWEY&ySNyEo^K|mwQu@t^^*v+6%9Xll41_{+(Yl zpw7Mg{nhjLfaXiD3zs~(R4Fwze9(Dc9izT{`~Xg2AJGu}x$SLv2?>dst2ZNbnM2Pw zI7ZDs59Z0fygmon&&9k<1&PFf#}@>WI5daZ{T*}JfwZMG`MJ>d{CtB)W!!ScYiH;D z6Rf4A@h5WWoIS@g-ZqWnsZcHIemfxjm$w(UdsBD~rFd%WZr?}4z%X9=oEQ@uADNym zFKsa*^sTr!ly_#EjGV#uUFYD**7^4Dhr?#Cl=SrE@~d&+q=hcGz@~tD{>>dy@4ej* z`pGK=W}p+~8t2mJ#(aJ{v3OC0*yemAPW9S{FI3I&PC=tyBm8xr;fDl$`t*#4E1)qC{Ii;uU>tZD;2zb~f9Cb6t+W)&$b`1Mka>7Qe^f>zN$?m6v_qFNAGllXKR19Yz6h zo)^oH6(8vm$oaJ6BCnzgX0C8$pi2&5QPY; zrm`FC>gu4ExgIQsv)c6XkZ2yG7cP)E&(Z$raWY5H+mklnn7%Y0qCwN*a^=j&`1q)W z+}5I~RTKM1A5~};<#-?r^5zy6_pz`{Pxlt#x!M_!X5O6(B%Q{l?1oE*v6&lB48p_T zJ3D`MSe8Rhnm=yi!xgS@yt3645Pl{iBHG#8%liI(sxaThW?=m=CN2(XU??ak%y2(Y z5~>{nF*@PJTa@;2((R*EB7A%?0|Rm(qu|bmBxa8^4m)31Hx8e6h#=m9?ef**+aTjL zocs&vFk%Iz`cqKQ9Qu5Jz}DfKQy?g!R`mo~G=TZ?3N{g)tRD4+6^p+GL;! zVOFkkn}lkitsSC-c+SD`I8lbJz`k!iHzVU2IXO8Tei5p*cM=2^8(jBGy7$pY(R`V7 z>u)CziTYMsjtPOmj84E*>HZlU-Heg-L>Qj{|5-e(d?n_2@TiX_w#=4nuS=?-=>$8b z*ZG*hkx@N%eQgasB9zdl!3Ry6Gv3U?Mi~BPXB~L>2c8cz>T(l7mMwSfHep)U7o&=u zTb+A{Qc4b1CVT@$8eFv(f776(eF_WClN|P|7Y;2dDjJ?IE-r@A2<(pCgM%E&;n*jo zgX{2JTKhW}oVnb$HZt^+6|==M2iFx|BkFIebQhib-gYssOMS>h`96Xox>Lq``;nsM z^_DvtYaa+Hk)1{-vI!kSXJ{HYRaW3zhLU!YPF>t}zWGyH`$J(7a}8IR#PclC;ZI!b zPxBLua`XfX9Kw}#^|}_n?EelYY`3}}Ubfdl>f$ghcjH30<#$@tCmp6Hw+H2f8%!Jt zaw?KJx@8ut2Y-g*aBv8JMh#m;NElnXt}{D+TI8UeD&^Drxh77Utz5LYj&&s#7>cg3 zvGKWO;%=e4?=Pycdik5vUf0%W!NR}iJ0)Z(DPG4`C9^%!)A>C`P;pItsvE!LBetfap~(O_U7WfA`ua6RCj1b1 zKbQWHY6C6{%;!e+V*je6$qx8$c5tE{R#(|79#LlgYt_@v_}TI6*DZa0{g+=r!v)ua z1vE4gw-qu#W6zH^=bQb})y{hWF@m%(4A#O&m=3}MFbXEUDV;Fs zzFc@%Rq9YzQBl$EbzY=a4E*VKb-g?TelqhB_+VvL6KvqTTzv${PAd^(dVB|8JdA{l zjPIs;EBJvh*m!E{yI6L20--RziQ(X6HpT1*v(L(vjY*lyu5#Mdr+x5!uG$w0C=LI z?9(fc8e#ec(9lu%S)m5Q7CuRTw2rQ>or6PmUEOJY?D|9(+_A;$76VOS;@q2e?+|14 zTZ@av$B%`~;8Q?OLj!g|2l%iN99-DEuB`O8ZoNHsHt{~o9$sF^AiTYtUw8M|!ju)S5rvI$0>fW~G8HoV z%}UZ_=LDd9uMt@VE>@bPp7-z0H=vhVxQ-<`8>rGw*a0$Pc^a`wiooc8|v zD=7X#K{8a?RmHK~)}Da}?~bAe{x#h2y514ElbgYJn5jk*D6fUPdA_mV5Ht5kL)FBs zNN&_Ph3l8?k(Vi&im`1@4jXDj=b~dZx}U53+*=hgMHforxnrl7Nxv#qKE>j&dXs;3 z936@bYwiAA+7>_AEYvWpeD6U0?JG2#iGfk2w7OHx{Fbef#O=%j^jo)4M~7AiHSLGF z7}U^huFq-BleBiwLa@VJ)$eL15}M&eof=Kh#}ME@_&hT4w5|s0>vZJ(`1F~h>eRE! z9G+lPy?V?tYR8+7PI!}iR@lirMwWDR)P`#8+Se*RPP;#@#H7=LJGf)}JiTje{%pn- zJP(uq9u;Vz%9Cz17u@ogYN2Z2&lLNYHI;lclcx9Bc!h6Jcw;XZDE+weWHT!Int5$J zdpjA!|0z1+-oV)bV0IV&#Tb_dBo#U&q~thh`wIg$MeKsj>rHL`qkI;AU+2&nS>d^o?eTc|VNv-ob9v)_W6h)Y1Atg0%iGxIOR+xF$*4OLKx4t1$ z7RYiAI9puxBlMg+nM9#)jl|5%%<+#dmV+It&L+k$tk4T?yvuatV0~?+^|a2_$8w5F z@ObP<|(A$c!bXe%|Lv6wcrBF|?P9KUmInHlhPPufdr6VBTg0-|%l0LIY zrNC^U^Cedqpn<2Z*>7#ve&^!7+xKkur%SbuE+Du^LV|)YeDx$yN3%w&I0}_0VtQk} z1c#~$Kg3uinga{VM};uhu~LH}L52#3LHjzQT%{l#rglpAT6r?=R=sj^-08_r|GKncQGcd^`9UOS?a(d$cFWy6s8QZr>1pb2 z39k+DA#4H}E>I;kiZr@|CUG`K>kM1$i;k+D;~2D>W!Wc1Oiih&_vMsI=<^}(bamy0 z&#Wb*w$wql2D?~6~3)if4?&B~JBs7%s@=j_5R}te*ch$g8MRBv%M8>Xm!&?Hi(~ z^p~X+nS^zl@Sd;8WrKIpJy#qaihWP^q`%3MWSn7g^w}(T$3ejThkf{3BG88OHI+bw0 z+Y3oPLB$#mU*iU$JwTvLC6>je25E2V%S(s$?01%Nv3+J&-yiy`POE9=ll@20kdj91 zj`TBIp&O##A%5@pA!-jhPbSH4*dX)nxjmg}i?xz5dFkXC8Z_LilF^BYk^YUv{^9!G ziT@gOdr7yO>YZJ;vq&0bIlij%DuYs za(+GYdG~~0`9hiU-m3}jNHo=ZT&gcv2}LY;YN;7xFtjihP389UXReY!_XkaStHa(vG;dAR_Ob*P&D~?>4Bs>z<)>|1f>!9PnW9{2&F!#Rc zoVe+HYWvP+O_Tm7bIls-sSICQap=Azo%SJc5Dh^2KF}<&@LvZg3lmk1+*$egfq-iP zAmsujQBp!;*86JNyLKtbqINYexud72ivA&QIuf=mEGlUp9E^s5f%C>Fi`mmeng4=2 z|5^bhQ`X|*y4!i$24k}ez~~!YUEr&aeKkf0Fx4+GkRraD(tR6@VoDUe9|qNbMn<@#p{ zPp;_s!j2TOS_3vK25QEt&|;gm$YfHElJa5pA?2by>bF8S8u7E0RSP9D#tk^!o9LzU zN!)hGSYNWV`nj~}DhVnjM83QgW8~_rE@tFY=y+rerEzE_Y5fB3=>!$^y<`t^ z^LeKCs(aBs|GA-(QdDY^BadaBUMV#Vjf9fxsL*rfVe=}ZIh;;X$YZbSXwTy-^H|5$~D;6#NJ*rXOQ$$kr_P zK!u*|Vm;Bj+;p3SyP21YDqyU_1dBUuXh;R7O_oGi@Mz#1?3hlMwVGOC4(8_Kdhz&y z#+O^@#Dn>=%g4#yeSQ`C)4wvazWQogfAc@7brJFvzA;zv8rO$z{Lm^>sUYFuD?zu* zy6;lWvG_8ZJsn1N5DfT6rT-B3PTVuX%e>a+Q^%uuhUm^eZ7ueFecNPgbO9+1I2)4{ z(InJT*-&f74>w&3d3T3T##@O#2>iKwlBh^W#IJdK&fDXjZ|^=?JvTSNC85JB-Yh;S^00TtvXUp&Bq_ZC!gk83ZSNHJ4QKwOsgDXW1CWtb1U4r zk`iAOoa^gW*>OC%ofh=?)T72lAvq;Ti#-t(5cyZK@;sqt!%do3%G_6 zcT|p9pQ+9N^o)+x!6TcWVCI{LbkiJY*K$qb(EdP@D7tguz;kPRJHM%EW~=7({C4?0 z^VNY|5a1p@ery&WS~#+Px@qHWas0U4e;OY~5m3J>ARCCZ+nSoLKSloovo5RO3{pc2 zARaTh@&Z&^tK#+Q3B0rLI0vc~Awd*pXLs$BlM~x1rxCkhkQ0z9`qWgY5~5{hh7_bL zaq+t_?D8BADLaQ(XfSvHfrp%YkU@H`gC@@|M+q2~xQRR~M(hQ@P_Mqp30nSH)E6j&w7!vV2GM+(S=J zT)fUFW{@_ll$2D?mzJJn_GlLFkNN4ITI7Ln--25EgUFB@)oR|4zsT{vQ}*M~W5wHW zP_FS#k+T$GxY>ARMq$twg<$y@T%^XpDbi3KtfX5h-7yq0HNCw?G~z(0-@rz4Z=vTn zJSy@k$kE-+oO{)~^U<_EL4lHV5t#>Wp^Ekc~De1(pQ% z{IJ;l69Id);LDfFZ~PP#w?f5)_4K9-hKqY=B{G6*f@o-HewbHbBCcXPjiBY--EAkm zbt~=~TwONECjcTODJx3}VGl@d@SShG1XI{mBllm1PVW-5I~oknhllqSbb04+d|kO- z8R?W#Q&HWqVYUINZi;sb>JfC#w6u(wIhB5s(RCMVTl$fFyu?-Gbzc=f<0SA|aYf=# zoRXiT@9phx+*1h^`^ct7Pg_BpsX+4_1<$X~42tm8)fHIfnBR?0QL`$%2#yUr4Du!WX9ICQoaNdJ}PPh(3fp@=sD5 zj)NDY)yRwv<3d^2ZG!>)!U!77YjxhtP_?XNquX@GF~!vnZKcE%{6DYW%_~2S>yu20 z`Jh$2Oq$@A&QY^%qR<$KBxfR*F(uVLwz>@Cc|s<8pIz4`2*O@k60a z)FM}y;679tQhiu7yes~6PsML^tpQP%B6|;KnS0$|DYG9NG53-nqISp+2Up@BYDkM6=+nk9twA4`=C(!)dfEJe z=MkiwDJVWdH^ln#WoK_M)vH%A7*E+AVq*&dpr+gXjpDOdcFcW@W}CjM5j|y0lExVHjRcTG)zL1cJ0K-!Ulb0Xi>(7$2{1K zZ@@Xx0Yc;AVwoTLYX<79i=u6GP=T!w5^ zD6PL)ua|{;P58e#b$vIZs07 zNHhs17H#rj#n`ob{nOiB1BlKPQsiCR#0<$dmuz3!n=;x2GGVv^u0s#^YaIHH5u@QgoOdofiF(mG3D&PjePGw z14X`ffY$sO9&UvILhd;h9qtz;nv-?E`xge|uU6Lnl{D~}S@Kbnt3GE~wC4l~Kt?i6 z=nCP{ihn7k(SEXMV%cO!3dT-E}GBN~|ID7osppejq{hE)D55!-|uEgpiHb*?Jfx!XEgcL}Kpaw7rlI1ASfKU8pYTOAR#NGbh z@RiNYShc=ew{F29k^wg-o9F*kU2(bcUlxCFnU@#E^&0PC*FWeiu5NyeT?oVXD#shf z$DrbT+jW!tSyO#j-I-kFT&7WL``%%Bb^^Uz=7zbc{Xg71D*4>+*{N&e=4a>U{U>I% zcE2#5Q$KgOSg>n6p>rQ4;uDVd`5MfMO(jdk!iW43w1HsE+n*ZGe07`)|3LHRshS1) zJ2s=qUiQij4`uWpIIgS6LRr!v*xt)tr4ib^EJ;Y>!%8kh{%m-z)31Z;KIVfg*%>)- zHQ~itd{I~MM*msWOU1I?nf)Gq2}?=pa>`UwXD@5h?QL3~2ha_Kp!P|wx}1tr3WK1%A!Nw(=mFd~h{k6hozD7FzZ7ta~^GlmAyG0-?cxFPGN)%aScy;KW+`v%E;I zic)O6w5KOAN#jiqZt8RzO>$*+8UL3Lcb7H(#$Tl@mwKY~h|HZFI8_g-(&M75;Swk* zGRU|P&tpJ)9+dW2R^A3{hKN^2S9q#yQSsTs0=~VQ_Fuj$%UkbC21+_UfAMiD{d{jy zns=p-$1jIj4<`2I728rC1Zbf#*q{{U}cZ*V>cd(>Ua*y ze$o9F2hAXIYIKl5!Mlw&1v@?D0ZEbP*}V-p<;YK3F#W)aCZNPXgV({P1vE4f5{GWz zy(a4hNN0bZea+a49id!xm`DJKwF9IB9X*z zaBwhL&>n~+d?&NFkc&M)E9-`NbO#DGpx&(^1P&J`cJ=l3$eETRW7zyP3kwUF8))$N zpiP!%iht>}rea;Uh!5=$0)fcP$oL@_S*SvXG_804wf--|@lC^j|2|Y)=x-!Iz=2Hw z#B5L2kTwa#Rp?7_la7P38`IyDr@p8 z#=!VESBIt@3$k9rs9SmRYZj$2vP0#KLZpiG5&6-!{)2lW<{zj&Y?7X1k-ur3AywDB z&@GnQJlMqDQ|E3kJ-A}}G?ei{fYrpv_WAOsN)0*^(_I^Fa;L#I`}hK-^`~nHn}YX= zbWR|zK?6$t{_=up_1YTcaG>SAD%WDK;N{yn4;X`yJtr(i(bCcaIg%XCG3YYCe*O9! zMOCG~Hp}xcTAptXj!9DhGcWeyn~*@cqm$F4$B#Q;P)&q`6Qs>$&?asGI1YCf{dzs3 z^9wSOG71V2IUU+H*2JJ^4A7C?6TN3(=51m^g?t|=DJemfd*Oa$Nlrl_ofDZ?= zVM*heInn{L@!Egtyg4okFR`GYAcKBm3V0g3tNH2Ux-l~@^P$Mk6qv#B{1o0_>wyZQW=K`>VAdS4%VQ$!U|JSv!|w#o*$96sz^#51bux|FRi zpq$%+6ar^gMEBx=$S!#P+3-D)%nrm2AZ&bR?A6W2w3mU}VC>yU#a!R^?$g!x?$MQH zys(HVRDt8^+mcMta4^h1Fl1BnFr@tWAfTn?A5^VXOvOU>h?JBR4Gn!|Z3}v#f#G3M zko%BOKstLmyk8J_eP?EtQTZiiA;(CqM5A*zWu7Kh3L6JIF_P~iyb8@iza*q&$T?{f zp?!97cQ<5B+!;QJ;^dA7jM;qM{GE*rH9IqMdSbCyVvwQ2S**7Qc?=#*9ky-Oi;K$w z8{8)!ThV!uHvF51nK(koZoEFv&5yzWOB)4mR;Hg2Oa*v@oY8T;p78sk_};_Bq@tnu zw3TKJbp}U>3U+HC17s!@iJhkR(NpExSG@{YY44w~1!^;QFXU+=ZvQ3d&yo9~o=s-q zjK4cB>EUqj0#($v+2M3x@pnQTQ;hTKM9_$wJ(sniKB;j%E2v|Xi@DER*CjqB%gh*i zE)b*`v_{=(Y1Kp3xjXcxsuANJj*_A$ok@D|=xJV@ekx?v-U6A4h(q4Lv2)^1lSjles_0nEftBX6In2W|OMI3#B85Y}{iBE|- zW=c|<^Rn#Kh&V(7GLz#&?oOPaFMnx$Wm8X|J^$zs|$l0I0-@F;o?QZ zT)b5J9=oV893g`z7pHyROAz@N&s4C5g=cWIC&C*I6FQK{dr;l%H%80fhVPn{zxj!R z1bP6{I2}yCdR0K_)c~&WA`r$z<+J(4#j#?~8fTv2X90p-g2~RN&+) zNx~!mH^01@Zg7Q;?>|?`-cE<+-t$Wa_$|4QGXu))+e*N01W94(X0SxtU(wMY3)PWF!B#4I2c>(O)Zo1|} z?r|DzaD52}y>sHlzw)OB2($tt;+_sJ zzm4PKiH%OSNFv<^7yb}}?f8zN8}MoM$j>e+ieObC4$1%FRH&l=k=Z}UpTdR*h0Bwh z_JFa$X!8;>OEEF=1LM@+2(YsyfPwQ13xh$xx*aO^3#_{ySfvxxZx+Ka<$km=hsaN}=Tanm z=gTq~|1E)nA`8wNxVifUlHG8by$KpU+$JhkI-;ztEe-Z4^e>i^wU3Z}m?s0@Q8#nb z0st9p2IWY6Um{l`>`%8*N=!FxboZF!QT4YZKlF{cPsl?DB&1DioNOXwPz0f@KIo_tPcxaWo#P3DJ^YRpO?0jVL&xSdyZNNWCJIsCS14DX%zL<^Xy<1c6;E#p^EA< zo4OgpUhUJ`+&CzD@}BJlKVxb#+vKNyGZAp|W@h>_DFRQ7`j`%g-Kg5p&6V^?^<(Jp zq?xo|8Bys-Ytu6~o?_=&M@Mk)AKqLt{%vd?71#Zh3PrllTGMa%48<1v#TcGAXBG$Z zhj#Y-{h~m5h5Sf|GqaWqtKR`8zjcd0JO~NxvZdkn*0*~U_jbHXba6GdO}68ThJwPG z_T>Wl3%7gaXe4QAI8jz{5R@e897^3~GgWO*ps%N`4@F zOo*_HO&){c{Tv%_7KQ?zqftXBBV}g&IC~f;0Kx78R%Q%xFCg#0n!~SYKXn=pX*K;9HD8>ihZ z4LOC}hT;lBN)IGSYoTVJ!mtDbROECSt#aN@P1B_;Ihz%-Df z9TrJC$4x*4!4_5-0K!QGJ^#+mPR6%y$zXuN%l4mw&A|&aL{Cr8@1)luaL_}m3vV?M zhwY7ArOxbdKJ)xE*eJ08MVOqLTAYs49DcIWpABgYz!iWBQQ|g-Gg_YaFeX*>k0qNl zS_Fh5V0ziz+4=G2g#sMhtSSa-*yVK|&pkqsa zwQY#muB{ku)7`^KK*EB^Q!XXtb5m1O&Lr}zM^Y@vwLi~fQiwa3VG}|ah@{Y(AtNFw zd^WIY02T`iWcTlo7R5eE9zc9c((2gQdK>L*OHq;Fz4pLr(~9U~?-`(ceu4h;^Yb5d znDW7)hM;IySGSqg7mr}+HKh!rfM98?U`mDo;1w7bGEMT7X)FcUX<@1ApW`Q8O$@u$Qg zaIM5;p4Zybby^0d=08@?yp(uu7~?I1(3?-`P`$FX+BU>2(=20xV~l4klb$52@ZrhN zGsbpvtJ`5HrZipq3qd_0;yi4vt~WQX44Ar?Jf-FmG2m7QQ>oxTViqh~er$G5wGp(N zwVM*R3qJw+a4NLVSF?T1OS{An6wQu^Y{X0vZh^I&>ObKfZ!_tVmh`$JXEv+Rb1aRJy| zsy8=gcKP)9niqs$vczfVGK`}!-bi!lU(C(t;E1=z3V(ZlD6AKg>w!&Fl;e|!60Yrg zG-b>YT9q`(t-=xc2H7?;DtOd;4!e5?l@-+!TBkRhnNzyA{2esyW*^dH68!_MY0G2l zQQ8-qf1MUr=pQPp4F)Fs;&uzw$eM*7#Y$+Kp_nl9GyG+G;wH1e<`g|K@G*CRV~v+N zlZIQcrj!|!BS8q0oE`k|w}giYx$sW)G%TUq>cwN1r9@K>ctAmW0n6s!+#J$21epLt zg@I8H4O)j14%fZs$PA=dc0c9rjb{-;=^lHXWl~b&9M<$ven`0m&{hgg&P0G(A@}zp zQ3hlRMd+2FhlWq0aM+YVxdKp_&@lEunU$21B4=QD&{wf615Od_gH3^$0GMd;4?AIA z1q_!zD%qfNWp#B96kMR@W0mv8su!K!zu$+QDN$)@OsP1K*@T5N@K{krOP=)X>_P%7v$j?vSPAXH186Y~;X)9fGvL_qO5bKG&Q7 zyp+Q2c0dD94$s+2w#VsWe70LSQUkHEVFrLruCyCwUvMOlu?AmXU$SEgu9&tgIedbb zt!BZh}IX|TDK|8^)Um7*ZyNZC$KZO551T^Ld#>D!2 zuq2^8M~XL+^o_a<4Yn)gqM~z?^s+C|U0oxy(pG*CpUwvF2JPNj{ke+mgO;s)wgsPa z_*J(~SJXxjN}zI421E%SUG*0z{d8R&g22P(#-+CYHCwG?%7 z>%)4-XT}KWSr<~zO?UuUgCF8WQQpiItA|aszBE z!TO9b#L5MgRUKoAXM~~7zuTzvxAGaP6Dl2J4`x13>pa1yJ-@j}d zUI0TRvYV#qRwE=bd^4CrKYv~zcz@xGWWsD__}1)M?e-{|?e^v$ggqavGw@m>@p2sg zz^j?!j%7Uc{!X3PM^=*7e>#gQg;WrPoAdnmw5SOBcJA;RT+Yp}RV-IO6Uh^+S1R;#TvZ(h z2d_t)v_V!^m^XT!8cREc3L9~w!>FO^pH{EY7y%xpI&LnPbc&aLh7zI{+MeCLJtUD> zRq^PX-8&?8y#xp1SxMkr06NTD$fNlL`1Rj_tG}`|ijl}8;dJw}3HNaK5qGn;70W}B zQAfZ1-O7aS^QK#KxgXjyZudveB8u^xVuh`j3*nZ}<`$v&h}aL^pHv=|DE&ss3CxK$ zlgqH&uA}!Lt{4bB+vF$U_*Oy`CV`qMp*n+juT`+NxZ2voKE?2;VC!O#^iE1oNc+ns zr-_p(+dJCisx4-{Fa4!*-DY{hx}$kA`cwY()a0F3l<%Q03Y zRsfHjjtRIcl7z8O7IiXJ=<0xWLS`TnP16Wfh8#+6n?pxiq+VK0p-=;#z=08@`TzqX zqOkB^2y^2PBUVM)`291@+$@P46K8ZkXL&U$AVcT9rlIGtEBb-lRwW@}d*3H1J)M8W zQ@Lo^veD)x+|R{xxiPq~h?Q>ln3%Zd3t>gTa|O|ZqoaRCyT)+rYcRwKcG-zncE;e+ zcorz%BPf6a3pbauBRPONLsu{ZqVHaZGo<#KYC(?497Cx#X0C^wMp{pK#V5mcvVT&L zJxUDRc_QW1&yeDI!`KXM81qqcw86ZDoWws7JK9uyESUh4FP^@`PCU2i1nkN(gyhX} zsFI`U|7qI2;iN3jtweqBaN%#GHIJ`BjyLzmu|G0>h+hR4h6<>ne>|niQi5*NJ-`)9 z)H2^m=D|1|J979RL--v}Q1R-3%MB^RO{}h9%D~#UQ`WvHsISE(U2$!^%6uuP?=U@R zK|x5`#e%Dl+8T0<^Y9tXN0>8qR-%<%j3=HydGg&BLgzuhyMZoOrtqf}1+^VhIs?t{ zbKY~d;Aft91viOv;_lH^q7~z((j{y*z8u|775Qe6F(joI_pyD#yVY>JyJMm){iZ7m z85{sGP(ZA+Z|+y1?i1r)3~=ySX>} z^W(-;MZCp`UiW|NZaNk^`Y8x(TMPpmiuF$9Hd)?aJo(i1?ghQs3-l5{+hnCKfg;H+ zS*!S>vNQitqrB?TO>TC61*L*Kc^oh0%5gOK2j$gOj=aV4jvaIUglt$*Tt~xhp^~tc zU#qP8Lquw0s^gin)HxBe2S($7S9^#m3;o#08E1gktyQwk$ujHXgifTx*fMgz_Wlql zHhj_x3JaTOX7rQVL#bYl5Ki7Md@7uY$PH?Xqw;9*%-PQ9PcgNoTtod(ELE17=>vNf z*epkX(3dte^Iz?TzqJy#9yJ69w56>L60DJAA&=UE@8eKKL`B)_ss4l!9X9B|lCV3A z?=g;B`E)X>=jY*j_R>CfeGZYW=$IH-Q_E{?Z2WO+W^#sk>|FH1vxg3i8nd^82t%aV zzQH!G-Hqw79ESV8EW1PB)bY;GBP^GT&i24d2DrB}n(MWb2$)aq$~u-rNEHkOLJ$Tq zI5W8k4ryxx1X79ATQ5HI4jA3LjpD?xrhLQL#ZT8KhSAGwVnXFu?=3s$y`y7_KYj6g z11R;{sK$XpIKJf^HVQs5bkC)fyum_>X)j zk~TrhT;UEn&WE(-Uw%D$&#eY+Rm%E9S_)-wL`?hb>do(d=_I*-{|i^+v^B#G`I!p_ zhAt9CPc&b&=dMaq1+n>IJIDLfRCED)hFE+Q5&6}9v~=?L#-PAG337!36zEYH7@-@QOkgz=HKwzb)VS=49w@&f`UZo@1LKXw zE`eg+PL6I~mMl|*{@$9?^M4&@ZzH-rR|L;DCRr`$ChCMMOj!i3l%rxAxN&6DB= z#ya1LC_0z3R*YpCA?`w@8tbRta)qB96mx?)5$dINNkt<%j8j`w3f{Gkw^QI4*(M&@ zZ~A_jYR5YrDt#-gaA?lY5$zx(cwP!h+C;ai#WB zwxW{5k~?5d3CjiE@|0;6!{Sq{uCph>0>y=e$eeXH%#vW$KzBrGd|8Lh%gd{xs*3SW znZH0`r%Vd3OBVTE^Dn%*KwCz2UMoQp<V63 zHhu9x#FwdV+{Wfj{SxvPFXOf_7oK1gj%qAC z(U&rmrbJOE5?|_kz-pRCwUR_U;F9KL_c8Sh_Ze+T*m~)uqfD2wI51WV_NN8CPpf|4 z3T>W{vr>A+;#-o&6t%W?lQ2X&?3S$p+4VG?JaIpmPsYZJuBT~Ne6!#MisveYp7lW< z<0`e@6)9CrdtYCopQSh~_fj%3Sr4_-Ff;ct^-W_e*Mf{vcX>2{l;&aC?C%6L^0xws zNr{oJk~GSTR)-xH{_C%_Rq5_^4MmI1CCRDe-O-X2(ePWhR*W@IeMaMy0vD;_=KpIF z{pYw|UAvzrb@=*3Dkr~41@X^I*T+FMH!m>9aD{yor=SzBLFIAxG9}A051+WIIS_ft z*0|Hu>IF(SxtD_rq*S|NI*j)O!*^BO?GKZR0E+c@oPe8lU0~&V`)ho5Cf!dCEQ(}i z^f81%5>v3`pq3~ozc(cdk-M5gy4{w0Yu6JK<36h2zU+cFQQylN>_Z+w%QNh`4x{$A zHrT!*3MsnoWbdiRPnDEzH_v&DpQgU$Kp8F(aRM*dorCgKUY51kOec|=5?VYOvlon|nOSu`!J zx{GAtLrw90P2*1vs-NzKiW!cixs_;?FFd4YCRJekv^Gf1hSkeVj0u({`M)YvSUAEh zOvh-6o&!Om8^VS1s$`0A-{2~3rF!_-Qn{Ec?vbJ{{RTxNc^bF=_g~iMnO`N1T?`5f zW71~S?$bx*?v-^ORI?2@o81Mr;WkySWVj7SJ*lb$?$Y!T8G4Qykw$OV$6JLe>**vp z3rhrdV#PVTC3r_BEBa~TQxVcc4!w?rZ%X*$eof76-16%VS2cfqH;`7^VLs3YoX602 z=Rga_GZloPf?{%mK*b;J;gcs^dE46n+OWUlM{8+qg$;6oPELmj!Nmd1xdk##aq&;` zDj(*(2&ZSp6I096lPVm_$$IX=tt*`8eCDi_z_HiNe($!q-+PX4bo{Z_+_pV8Z{T~? zKC}%rI5JSkMP6wOG{CKlqJr6`Y2M%L-t|+IhPLwqfiKDW70d-|LT5r9S|tiq00bv_ z5rGAA=#i$g-h0{<{6vQ*PR|FK3e(Cz3P7c2kIOG4K zBpK|?K3O|z2PuGksMdA+3R92qAtkh=-**uLVxazjQQ^xF?_?RtWF1ZuR;PZQBHf$^ zDc-DA|C9QWu6JCkUeF#>J*7RIIyAlZR`YkGii_`Usdw}U6QTQBu^oxtp<+6MQ|%w0 z%w{E2G>nolxH?+zL_aniv~esaRJBa0;;#SX`0-@z!JH+@CJmiEPJ#7jf-sRn#^Zn0 z``;cTK?Pw5J8`92%bcpu{{%fZ)x;^xUw}9L=yEqpiHX!`n}DIAck{A@CIUrpmvdT( z{=1&Mq-2ovJz&RF;EHNpsSFbJGpR+z8^MG6p&BHp&7$iror^A3cg4*ckuvLV>RbSg6wP z@51#A{xzib{G=-7THnrN&VjRtZ zrD|vv=kW)(HS(REtcnwk?~E8UzbJO3k|-ynRIV|Hf%lxJGB0}Xw?%=zzvvGqoH$F3!YESV81edeFt8F%3f(0iPm?=yrXCCja zIEotZvRxr2Rp771?5A*cagT<&YTd{AC%SWLIrVns6aeHRl=Hv7-=5xfqp{XmK&mcn zdK8I-i8->;hTyFceD8s{g)>9CedUS!Te3fN4~sVK=Njj_@&(EQ(mP}+1m?r#@p@Uu&o)XQ(~4baxw9$i6SOZzuoA&Zn|$7Ahl z^bKIYD+MRQ-+RET98_Cfb@HvyvFnfV4~Q(oZn7H;8bLv!Z+}(sN8KBOwGA+LV}7V^ z@^76IO_(1kCMIR0>2HNo{I&ND+qrS&Sm?N`G-nbDdV8LVw+ydL9BB7qXk+H zJj*Si>vxl8LiSKx7K4ls9EG|4(b`*_!iru$$}|hI{wXi9IA;E^r5P5DW|_ymS@;C) z=wN&*A1z2|YtuCTeIZ)VlPHBM$M+d&F@BTYJLTbNk3|u^u3>N9S<=F2c6;^Xy@9(d zb>wMycjF9M9@Aj<5?6k2p1_(p!Np}2WHL|wxQ2%vmRo$sFg?gCHNMEfkh*p8kui<ZhBle-9aYHAtV1YP-Sf?XK!&ITQHSTE9EoWQ2NwH1fkS*?k%#vVqsReSbYhc@CV0Rcq2IqVlM^nXM8j*DBpMMpQ1 z2)D0DIw;{iLn<1}V;HlK^at06t-Q8`n8o~5JX=&N?EKkrtD+Jr>bHm)dhu)R# zLK%hP&v3hO(?A4R;eFc3T*@S(=!TM5ZaUiTvwlxy;$kp-=FeUi&QYu4zoun|;^kz| z-gJ3F5*CU7N7Yw`MHzkHlG2JGA+3N&gQPS_4n52O(jh6`(jnb3bi)8Mlqj8|gn;w_ z(%lk6ND186-#_lX&x4=%gy%i`ti9ISYokB#h}LsP!8j8pCwA;a9%viet7aRtibt@3 zVXFWfu&nzt%bPE+9w+zUyNN^tZoMnZ!ArhEMRf;?HDbDGNNuo8J6oTu=_3GH8aGgc zRo&9#F0VLm9M`Y`pAyrk#ohJZdalHl5-=q} zTeCR4F>iub{qU(x2_}PoaIoi*jyAVtlf&rF!zz-V9XxH;=k#B`06L2iH%yjTA^+Rg z?ZIRT&z{GO&N58k?rM`darINp0Hyr^RAkg`K`ZH%N;1b zSUlXz@H7QoJhEB$mM>^cOkYWNjjx4JsRK-fEG9h;t{3U5<2$Q#7n5c=SnD0q(_zjh z)+J1>kE9@PHOpYNo$!d>=oj+9`I&A>F{``eftzy^$5gy5TnA_y)?a8X3I~eNt?G+y zzR>O`u#uku=t~|@P6KTiKVSy~I+_u2{@u9$^e}*nL}L{8kCXB}x8J>|`VtT%=u!p> z$2{3EV&ahMC(_%l6XQ_re^Z!W8Ne9PWS&Ury>us>C4k4nA{F>%2r$BGG;xnSqMn$R zp2I>Un;|Q|Lrj%aOW3-6FMF6aE5FS30v4rSmMC19!M zju{e>PNL@OzfR3q8Dv>vl(Eu$FJilvT&APnO@pyfyC5B}&#n#ab% z(w$t%jc4S@LZs6#>Q5k$!z~gm#z3s#(c-!bOy1xDo;?q-#SeZDZE*Hnwqq>0df*nz zj06et_SW8s5H11TS5q)taLs=nl~I_CV=DXA+;>xOK|*h*bS{Zsy~|H&+{^x>iAYFR zjEnWYH$}*tp3%n^Xmh5M<5}rT>0nOhvDtVPddc3A5neeKaI)d=6aBp8igEH1MHX$x zQ~lU5_t~sw*vDzXP`_^khXmV$79l+j`69=eTh7woMO*1@|$uGh3R(gPdEmJ{m=H=Pw~=O@q!%ZGicvmn5d+UV2)18!JLH=CWU z9aD$G4;58s73ONz_{DK-Tzw5w9SGSfe`;pMPKJ}aVm{W6_<8-FVO~l(U+3slB<8nX zXKU|Ab-JAQ%d^`qmEgr@>XpWmwpEb7=>V#T>u%%+q(fFy!I%{@8$)6$Ut<7b;{xND znpxpQ2=!y@RY*Cye)vWv79)nRN2Vxi8PeV>b3l}up9g*&Ut(N!+?Zw+Gy9E11^wN; zuXEca#7LkM|8`QTtEKmnv?u+gIc9S=XXb*8EEj(o#}o~<#=xE*<^mGMC<=JY09zS7 zRrIyvNHWoM@>(A}8j!|4pkhD+P~$?S93V|fMWy8JEuyYoGb-sC_kolj)j|d^xTAnQ zNOi7LnvCw?md|XJo;!IDgf#{GP}SH|0bDd=%RHSFJHSR;e-uj{8xZu8_K!YkZS`6W zW0z${Q0vr-dk;~M^Zpc3_0f$D#m-qO9(JjI?AW5zyBI>Q2Y#wP?@QRai#m)xtYaht z0KpAZjK$QnB4o+H)Xqkzjt^3gf~>GuxEV>5N7kWRL z*4)?}hD>m+OSLv|ulE~8&+>fPX{Vm{Rf3=w2wpM2pmyQ>{3R2BmGX+2T^%gtL0v|0 zXMasQPcm;x&A9WLob2$YXONjhBCBWN34QY*GGfC1qPyrLqxn(#^$NPi~Y<2R2h z5|CR*eq0{~pupXI)WAU@#DILp$OhDB><*LBI?H~e?EXFFLg7YY-BpAn3I`A8k!oQ= zekcG z*VkUVtyL`ka#F1^b2B>sWCgZ-y4(^sObIZEPoG^s20|$ib`p0P_ewq$pN?ma9Rx=HIjzgms(U0T{};z_Lee{(jhtO4;}t zaHIkAjxCT@Ub2b=>KF%a>*f1rJ#tY<6t1-ZP@uOn^KeOFPpj1m4{eNUt@jBabil@by5@t$n1u^9M~GI*c{3G+un+s z3OA;DbX0%Id9m1tn9Tn@>ohr>|7BjRVbZbHZhBYPD-{*}#gpuH0(XD1V{{`ArDqXK z49<}VDGp|6^ZJdYXxMx(4nAnjYRTP0-Yj?(gDzBHwEgI)8d)J%KE+;Bn|Uc!r4f=g z@ptm*ZYrU@z?rL3(Wdd$eyu!ThRcz$vs+6S=IHOiKVwVFK3_W2lA~7EvZ1&^oSJ$;W3n-@QQX+0VBzht@Fo!#YscvjP3I+* z#WL&t=e*MkV1DjnMGFWH-mc?e4I2*WP{A4HDUZF<*30G; zQj9w_^xNzg5s&oQ=>G2Z0i{*}bDLzfwpN`CWDu|<`g=0W6X<&O2B-Xhx|DqE>ZyjQ zKVw&6|M;&240%d_hnAvPnHbs&k4?L~(U1%kh@;h!40FR5xP;5+yulp_o^1^4__ro( z8;>;2&jV}I!A88#G zyCVOZ3HG+d5jj1Z@qONUc8LsdKfx0sEy>V?Q?a3#^&2KElm$^Kc)Q>Q*>Q#@wYXvi%=9IgfIJq4CJ*GF=7zi zS%v8s9p)n{xT7du_5nGS8L+X{PoKtp8_`NRR5!A1lsT$o(qxVzljgggUMk&<#CzC1jIs) z_|tCB6*+Iem~4fu(M`^-p2}19q!tDH;ixJ|CiHo2G0UzE`$dcVUV)_ge5<Bb;^^e$^|pb{J#r>dth=oetROO>z7bDy7iq}*n)VQ;dMh=ni1l{JO0b|QciQ%DKAEy z%pT|cmF7-h?Qwvf8@!KpPB~3?Z6+s!I}gBIt>bV(v05!$tkW0*K`1gkg-|;q*?_6R zwZUqL63DgC?Y%|yCxdVuKkFV*9p}Zt`Ndc}LQSas`no*^irm-Gz~9vS zWU76!9GH{;LpvYKku;bcgs19ieZk;_Q{<8F{(RqJ+OR{{2aUo&; zi^T8Y88m{$&S{^Uk!HJRh2FMG_`{a1hm+BRas&t$(U(n+nwfS#JTvV1J1O6H6Mc4J zS>a^T`pI59z15MLGVfJt3D24$xs|7ekp@*)`>D|LXnbxSS4D^I8@!%z0`Ic^$U*gt zOoE12uOQFA>x@>>=N0xAv&%BuD*qhii=-@Qp<6yvrjbzh<2`@ipTM0t@ARxnWke*; z?sxB(^XE4jN7(X_Rg;_Vv_yWuf5F>V*sGR~phe*ITOdC4u;aqy-_rX1j;BcBI^bNn zS=M+}@VQBeBR_-6OYb`ZdCUCB~i<6eV z?nDZIjNwj6fk0b+B^HN5pt#E66{;`Ey&U_1TASW$(QQ%3$H%9I@_m&zSV%k%zw9&s zHP!n9Ni>rNR7*Qz`Ql z45VvdTDF_`_mb}?64O3r2^D@HEBtT*timL0gmi$T)8Eex);|_JxS06ukeYF`c6#Qx zUo!hzzW3&)CsiEhqf&vY;VAHx-)){hI=$Wv`i}Z^X`-T_new2|sF|4nE8i9C&|D#y z#@Uv6shuj0m74ek@dNVdq=G*?66et`-L2f)T{G}qfR{MoEuQhV0+pk)vGepbxWS-H zulJ?iE-HtHB#iy5J`6bp27Hvv%*^&_rc>EtzM%-vrp~8!PN6yli4he~xSW`>r#}71 zZ?d7QS~O~so-gRjYWk`m`im3nIm<8Fq}+QiS*i9`XPjZi`Jj30)A@H8tu*s&)!v(} zu`!<$dCTmLSf~qSFNM(ot_g|hOmPH5HRkN>y*KVHV0tv}A)yhAw(gtd>U&-P&OMOv z1&7zey^XUc*kRbO0Met%V*8=%-%LUs=q5ApkZM`ajskmo3MrKx`2cIiV|<*9dX$p{)*$spIaf2aM}LjD>dz~kz5>Z=nHx}@E<#?U;Y zhd{A4j=v17!v(i&6$D=F{v|49v8&RpqBq_lw(i~Z%?tL{kSN;yb-as7bC&W@%GZYNrs%4#|Mu=vi-ey@>#pTTC!qIOLb({9AR zj9G}H5G%LSBcjH5;PI1FG=?h~9RM)Ix-Qk5_wm1#EQi6U zk9vHnX<0QJGOHV_Z5e!w721#+JU#*uO@M#SAJ?fJJk{i;Ai-H+W&v?V9dw8c4_K01 z%^KR52Rac845UtLiS`im698Lt94((8!|q0L!Fu}__6=#fpj%XNtga^> z1UrGR7sP8L4z0R!k+Xc&ld}IRBEIr4)7Wko^5shwoAjx8n)sj4v_#j4+hqFe5}(ox=(5#TI;v8vMKBcYI^C};jc;hCY&KCR4p_KY5y8QD)c7H zN;)S%cT-UpI<VfRDiu5iM`-kxQ?UcTF51s$y11^)WEQpb3V%q zwSW3*eOOAFvmqV4TJfW`>lc7^AIb!r2uK$`x4PRMTIQ^h0j2cW_m25uTkB-4xm7;^ z7J%EW(9DfA_Hq7R3M5uEn?a|t9j4e6~2pGoLc3*cYFrt_gq?NE%+ zNd=2}42*BdZORgN^q0J*y#nvcoed|#EeLVOaJR`DCzzm7E; z0sxuaK$TZ&tZ(I@CcDY%@}w)-QMIXME?b`KR{K= z(0U`qaCNz6D}b4w5Ev#M6|+9*G>)@*fB&ZZ(*1YfXmNAC93+Yp8gnsPzto2+V(Z22qf?W7D z2Sh;tAp@M(!9P7XI4P77=-a7eaJzH{r)NWq6A&r7`J7^gDCZ&&m7bbkhKQnf#1Bw})oa znd1a&fk#h|w!h7KXXdGlph2GbeK{9vB8J`ia&O-XF^!R)xwxZvl~{1!zm^@<2i|Dd z{MJ^ruej~WWA%OrRSwXC)D-l77_T-VgO_0VW(#Mv#-p_n&?q96{cu9->HY1L&k$X(2NU!)Qef>bx8XQ>PS~`29Ql%PT>3*oFiE1mHb#le#u@ub@aUTn?pR zHPQefDi!Voa)^i`DzY@Jv?30&WK80ZsMz2W2sOPu`;dHK&$6~LH$z(O1DS)F7wd=F zt0scqRY!BxU{m&1@7Hy!rZ-iy+;)LG>VA*6obF5|a1X&sH;88_se_>T5j+r;rIuHX zLMGj_KH=TT*4F(X{CHwAfFBQbwsll6Og{Jv^JwV`dE?!seu2n~84`*hvk)McH{vlc za9Wwjnv`E;rlxg<;2_B4&+)eSP_NmmpFBJJn(3opC>BE0_s0JaeXqLR>HbOrx7h>! zteOw$Y{;0=bgq5KUA|zb5nGw%7v#xHg9CuHFH*eayd9c+xsMA(GVz@{v?bp1#U%ex zW{K+FE*r8gX)lF%Np-as2_N^x|=A9>U~Eo`Of)%lj2VkR84dB!Zy}?yFVmgpZ-ca(KB&NIPZjNBl<)dkcUf1}Pp=x) z{~c6=vLrYa%7bOo93?K?G++8tl-1Z(_tBvaQ(L65p?XN9T&Wx+ZGDzEr>;>q7}3`opVph&QM;=aYAYk6>%D?Cc+uCr4j2rYzz8A1jv2br|tfanb?%$@wSfjfA0(qB5KJ)cB@8J z`RLLxk&~~#23@axi47+#CL=(<+X-h}EZB@W7nSfh`aqReXw~+7a52Co#YX@5B=!6y4sD?8HW>NsBdsH#W9vW>9Nc0p{y<5nZbjmO z62$|hhQGXP6hT40`@UBL!_t`YQLQ%Cj|vK|B^J}26p7z6K4*t%EIy9qe+k5_r6DO) z@*aW2Drjupejdj7|lSkdAN{365*WRz+5YwN<|nVxFzm zTf6J#@@TB(A{bw5z5nvvhE5!dTafOS8@y(#3UY9aTbJwbxEW}V#h9G{nAQWYeOGo~ z2%LOrjS2;k7N*HvujZ+5?j8sVOB9xrhjJu=*QaSsf$@wY1cLpj!1Dz)u2pb$i!?$e z@ErD5Y)V*oWILh(zATyQCiwsQ>XfB)G&p{nGBu$N$SI!Pe z_XR(pr)B2n%qNAU&!R_~(IYHDidjrT7;ywxu!E)vTlLO6bQZzW!X?j{$5MalGA26j zM@`#c&Vk$Hs`*Jzaj{F(i-*4d>zXYc@cb71L>DdznZ8Zx-#7wLi=SF84FN^LeMpj%|E;{hOyB&C*wuIFL zT7CP|*QW?9eT=TU>?GW%O-KVeMttWYCZPry!Wird2HE}(dANy+3&Q43GzTqBHFhDW zqPFEN;8E4c>AuR)^sKVILy&#?S+2$bjh2u55t{hpOjM6&=5vQt+yS>`vyma18$y8t zhJUCE2XSO`@R9>j!IqZt{rypRTVv^I76Q?1?+~OEDNLSnCFWc^Y|rt3*HouwXx=QK zpeVN)VUgJD zGxd|6Td~0I$ftKXdJnld+ zyc>{WxZlB!giusBJk&Ym&JSf#?$wvGi1itNo9RAuIJvoYyXunJ$;scUd6;I5_!?u5 zd~y^CH@CNrlZGZ9xo8`bt%*}LqML3TPJH#=2zSK?J7LC-$f;C)j7i!VF(S}%taaWV zWxNy^92&F=zV`TCOSDv`re_~Uy4j7r1kHmHsw5Grwt+DpAiW;X-v?j%1MuxdS{4>J z1fc*92Mxel-TO!Ct&qay!mRSpY`v_vgr)YDmB4hX4AWN>YJxF1>mQe9(+Zio-JN3> zSXzFnzjCVM)XL2oM}0OVCH?P1z^h<86K+xWV#NhlVrm`Tugni%Auj0sFLvpT#MWQ> z7=ymP(#uK%$4MtgJ&q5L{y9u~Ix=`MI`XTz<@CALrj$nBlSlFv-J6eA+$oedD-U(V zUwd54tC?il?8%+j*Eg1?MU41mN(6HOFiwl% z;^;mwqNC%(&}|lRj8){K%o7iSEt#mhtPw`*vv7Z|Ed@%&IO3_V-^9i2>*X)OG?578FK};5xu!uBvg| zs__li0sv_?c-U9(0OJpK1fz1mGCCybrW+hI1aZ`G6pPA!ZvsaS!;#3|M_sH;_SS-? z1PL5K-v*pB2;l*8%jez%8LJ2TD!gB7=Xr|esh1%vgtvqPgVLe-%qn(wyY^3%tvE7> zgoOHdyC?M}tUhVh2k!pM<5$$(1+CiuZTpI731zrOAP`YYYM zcfEk9;PX*wSnHWv` z`hu*slp%ihA&}zwP@hv14X-FRU%#8)4{?6ADEIe4+|Sw~-$vrY*|47VS@?QPzbdYy z-pW2u9``5Z6Gd*|2la?&ebFN9v1oj{jHOr^rWIj{mvT6HPIE*RJosArQKlM)3>4M` zBuR+^YigxT(VJXINVQNkG}AyC4S6dO6YZmmMlI~X>L=J!$K}<-^=W|n%2+^MUfZRe ztF$Z_mvR!003Pw2WyN2l8k~816~8fl#GtYL*Z*8#J}$iT=exCNo#2{)f$)j+!-R3- zlNuda>&Sj5gP&G#wCMah+r%RuV$$t`Esi9E=mgfE?Wuf|O!9W5#S6s*CycZF>S`cOY;vX z?04VCjno0VtgL18b*NaJB&xz`ZmW zR695>#7x-_-@HZ)3f+6a0U{>Y3P}WgKY@+aLvF`^r_ZG(Ncn)Q$9jQ#puY1Gnxy=B?zGw zTx5jsQ+4o+Uy=Sd#kMBphqU|1?9E{A93%;lYQPVDxj05h*Zix#+@J)|J+O>X2f*qs zYcX`=nw|xHZ%*A>AbYoAVPV81B3NeOSeM1HL-W6a>td81 zL=pivrs%KJHz9ukCt`8($NZp#*g{dDglEHb09Ky+?rdf)uGv*_Ay-%^rr)Z9>D&M$ zHp-*eujxf4h$qAdu(i+>VG{XaoC-i7*-D?>eP?FIwEtbmy^;Ohcdvor_Q!p)_4V~; zud=2$8#z@t@=`$WN`0iG_@ZgyHgm>1H zVxn`D$01tP+_JgCr%SOCUMlCWDdTQJ&M<%^DpecMC@i1U|v8f_v{aDn%6wgMr3`S0b5BTxgxsnr zl@VAwz-V%t_-&z9HY^9J_Ny~_?Iu1x9+>Er`0O`WzsF!d~Ck|H4ARgRRPlpe5vaOmY%x zqJq5NC*?)e9PG&`pEafw6A^K#sq-yS6?tB8iTtK4+0F1xVS5M)*X7jqaESY1cEW@N zep7JQK?H%|wU}RUQTfsJ6rZaRVNqF2%2O`?{D&Gt6D8Xu{Ldd%pV zjyv}Fx7M+YzZ-_&_$f9`3eQE%Z}mCqEFIOqsI>5xX2`bjJtnI`ytbeTpb@OLr&y2R z_V!PUkZdXuftl5MV(mVh`ss6T;12g1!Mn6y#weJypStWsQXqB5wyLo}U7uJ6Pa+wYn*2 z023(WG5+HQ{7YNGB2B`A^3WKgTD|^4N4xMHWXO=nGj1|74&YC7vKk;eX%fRVg9W>Zj zIKH6IRlAhz1Xi0J37Dib5YA4w3wqTt5=n$P5SXil?Eh|XJc>Z z#J$x15fhX4)!h(Qy*+=ULf+>LiJSZXmy_5opnA62a~4k*c&iJj^q>nB4JbjG^@zHo zm#~1q{xdPIJI4$rTk9+om_n_dS4ud`uoS)D#LH8sX(=}!XYZD9X!RnE*&^sD*QG6-mjQ~5!ybe~Z6 zB%g_(HvB)}+F((GG219!E>cgM{+SXYqK^UYKNAy3(Zg25lCZ)fk~SMe1>wozY)2)S z2}YnLeexriZWV95?uNH^>Q&kJ7;2*Lc!!UOh{*1^zKo-y`H)%ZaDz>W@!iN&WRVe0 zVT%k>nCzRuT=0wMcN)Xj?R4Vv>V<<@n^KO6BRW)?tuh*Tp6v~0W>P$@mh^QP^hM@s z(JwnZEuK_6s^wnkGA{(%w57*lkCNxo$=KAD2))H`iv+&NWQ*Iay%!_5CwRGHCprta zHfUmF3#SDI&v_}1#^{@|x}ZyE)IleO_x;=74H{~2tFyb4o47p52t++y^^%O>lhW&m zj@;W>cQw;pbClS?Z($O=2Xmx{cH0;E9rPElFYQ@Au+}`|pTvJA0(b69woN<3{8s4l zi(&;APcU>cmU%C2+S0_fu_gGV5PcWW>KFi0qdrt1A$7w4h?9pzclG~m94YOF{P2SN z-kLn{(_Hx!6Rz{3#BRXn{<23DQ0a@b>+l7pJPk~Q`vL6|?p(-E@(IM(u%MkV>o2`n zzJ!~CF=4!_!I^qJ67I<9%ez3~^r7R5gCV+5Xs0)J1uaSwAIyYri%Xv#m6y2i_py}c z4fDzRz58g;>JJoc%svPg8JJ`0$|b{3Mk>1}0yaXB$fYHU{Cs@lkhWgA0Rj*mu9Y5= zxl=|-S#ZW-3y@wU#+{lho96!w^Z~eO2kp{}1qo(Wf?Z5jas#;Rs{YwC`?5+c0DQxc zK=^eF1cY$lqG;r8@|Q%`)$tE&=OE+p!I)1glxtAw=4hFjO^+>{3Md71r(T8B{l8kR z-5KJG;seg#UlIS+ZczXNe11^2=6c75Tzv00mNR~`Y@8$+B3n`smd6j7xeNr?AEQ@Z zPkGW1@f?hGpw^QtZ)tKI2m0pypLBX8|57_CykJfwK2Fwrh~a{c3%fr*dl)#S6XA`H z|NUzblkP2LK9WH9wSphd#5*wx=kMqfPzv}~i}X7^Uj;i#Lk4XF+? zl|#Rgs2uuLj|?>qWlvAmU#DIqiGSBh0EO$79rZV(j=UtlOn_PgE|b~I^>1y?#p8RV z^#)|ImQ?mm5;D;xDZw^mfUl_yC}1RhQeStnn(*=DBclt)i$x4=f4Sr7WM~Q;QOchG zJ)6m1IpqtC43AzSM=kjTqlwm3-f@wYHFl&TItAR?Kk0jp z;MvkX-5$k>r&-p6*8k_5vwF|n4SBXR8gn_?A6~VF0GKaw0di8p4XBvV`r|}S0IR29 z14VFp#-td&dyl1JgXDME05~~=-0w_Z5q3(lKqahZSz;u4V3m}u%ra)*b8#?o+vIXF z+=NNM({^*Ubi?~fj3?B<5~ZeJ?yt7}<%+tJR>!CjY^5Ou1q>}fG73rQ7T|4Fr23?o zT5A|{(RK#QY4iZ{zBC?`V*n8|50Fe)({jL8SLF`5^XqZuN)r}n1w?OeYdj*X0yL(I zTY&^ap{#+Q0(Rao4rV)Z9B_jDr9H2F6OU9u0qUSvH1TTcj_r@GMH&nMnQe9*jj`g< z(!3upf*=0oY?{^F0@090sN~xMwhl?NZl)SugYEmj1M;ipnt?z)fT5QL_!hcWKhLcK zxj+nxuZ2yd4@W~}WlW!U267j|F!sJ-MJsqC`plRlwpsb4vMFarl}yyhjg2z^Wqr#n zD9mE=z%AyV&w^*|?p^8ci%zc?!=uNVpLz0KkJ(IThh`CEAO7s-8#4snOe$UV^p6Z2 zdzgJ4_+9lT0j+u=d3#1hUBFKc`ZyVkAX5g!Tr#t-o*{wNEoK+&EX?mfd)51!Y$EqK z#<#joVkWWAFq(|p<16^P$3}4Fbi#u5UkHgFd|z@C*fjJmoZ3aqdvZcWJhY}-Bd-_n zcK!BEcWyT?>Sn~)ogJ*4{FAtc+n!3^JVa++ei77n(C4t1zi<`&w$Lo$B7tzta zb%)uXGqV1)^<{=e!2L>&+IffOaKh~?dEA%p+e2norPjuk1Ep73S$Z$vZ+`&%9;YV* zk^|b(kZxxGtXC)LA(-5-aqZmi@mATS4DyQ?tw}+KndqVxQ}0c+ZY8n2z+!m-cD( zttopfpIM^f`0dLC^%MB*6=`S6F{knuB^A0N)Yzw#=rvv8UUs1#cA@^Alj{ECFpjFv zoKv+TlQ!h{4Db4GbX3cqUq~fv4GyRS7eGh|_5jQZ7lXj(hcKs5XU8CqhS*ZVaX{@= zxpdkqdi=y&|rL-JMGwgp|Fk0u+A za*4HgJC9b{G>-rs57t6S4D8C~k;9h6K0nyo>8EmJcN=oFUK3 zgV7^~R4f}T7FuFwzfxxBy-CX$);`QExj~I=7UUK;FDqS6u#%ahZ$P+Uu-(+7eD9Ox zf=(dtu&nRT0sJ{cdTM=Tr%rbd`CT**`=m9It|c|YS+x1+LByUN#EQgF(v4?yP2orjt^x&!3 z)dSy>X5L6_sllejA2-rhl$#@7eIuQ3T%00WT&WVStsCnX1Aq$hW3~BEy1W(_~wg+ z8X^T*h)`$kp8f9sr%+^18-yW}j3sb~+Q2qKVn*0h6Gs2MwK9i3(i>iIz!2aFxMFr` zFPD9+CC`j1)C`weL|%UZLa}Q#wMBFzN4E@NFa4j@pyVYqB*@AdTH+HIPccTW6`8t6 zc{}yQIdlO82myDmY<3Q1ZST2$8SM1mJj#b2yw88iAgYKYfvf|C{OR7fH+QzRm?%5 zTz!!RL)Ih!1?|JxxDr9QoIGV@W%)NRxHhTu&FrXfPiH+OPFiOI+8ck|`fR@F?%aFH z9H^-Y7ftc;?y2){J|VN;Dv@dAkIhm~z6i2M!4pTA{4dG*w$f$_# zER@W*G+`k>is!vs4*2Vrn3nUixZ&crzIoNEDHOoAOKOea;U3tR9D}8~!M&1p+9Mn5gt0aW99r$AZZsLKTwIbw zJl9le6f1kh=SCNrV_WJl2b&sJ8AO%BPZhBQ$bXJTu|;god%5iXi2c_}MEe+d<)%+N zus)6@dwXp8vW|b9Z2RY)8f%)!Qt-TILSn|fU+3}kcZn~XPw&bO4IxbjmTTYq*6urw zFq!aa?7bJiU0$sZG}d6TwrKwAhNpD@Kc6=TbYJd0ZW-ko2sQ262E+DwXpHFu6GFqW)B? zOP~k(*}sS+LfXbF@4#^;r$yZ-*kMi&AS;=hjhKs=f+ zqb)#6r}v5SW_Hl^BTlZQlwi0SpM@|C7}XuOKN|{#1VrP8Df}&|#T8t|ulp*Iyn>Z% zmgK|r;=9h3-&5k9s%chPB)ACnWHrM&c9VSHv_@tx7I=7pNE3HT#oJ-;JCZjg!+-mV zyj$+y4B)44Naf{ulB)OUE0=a@W@$hG$7xx^w{|=L^fAOIG;M9^f6_DO%Z!o_{m`a4 z6uDeJ{QSw2_c7d;bxzAeb_b)E19$iR-#V*3I(5Sa*v7{EG3Imgoz}&FU;kLY?8A$W zpyY$4>#VjXquu+XmA(u9ZV9V%?;p>pE`ERZ*A?hV5KFEClX|{mJ7Q7#h;^U zpVq?)%r<@+vaIoEJKw9n80k_q^NInseJ;Ba6aDo%FF`eWKR#Al%b_cCc+a^ST#yu$ zK9OCW>F{vjmec*Aga}{H)fMi)dWfv(=%6ncEmypPA~>|(6O?_MsDTK$+Eek`mbHQ< z6KL9{c(+z0UX-XLT!aDdqx4a~86O|xujl2q2H6phaY9j3teL?x+C(MWLcQDRrmqdwE(ch9@>AN&g{zrDGjI`1$A^!ixe zy9O;Dy}k57jxDM!sNSB~RBJ># ztK3t}Qf%(PeZvnG-(?7V>a59_7osu32y!{P!luS@Vfp(i{^qc>)sYuIW$5a8ANu2) zM93^Va^9)TfBxYhO|~n2P`JxiO+h;OlBu=d?HPnN;^b6Iy&|vWB`BX!#%l#l$~M+} z@rek3J%cgi@83%U8Ma@SZ>QgLEkIQIbFL!aF13ZAdc`AAb>ejv+ zxxz3#pj{cokp&2tR{OoZJ@7LC1S;5ae?`d|A+jFd@f;l9f0H8guR#A0|Nst z`5i7^#x1V}j1d5k1AM#v22KCbg55PW^4J%rqPF_S3byo^d1Wjs1 z-bV}@WRS_wkLi)#^)QkzcT(B(3@hE1yC^O+=W3X_Y9N_DHFYKSn~KNrZEyYj_D*)W z3EpDW`yV&9UYpFI1Ba?14+-}(qEvbx)xcX^1%r?!~>A`Ok zf8l?f%O1P*FZU^U!>He>$pp{53Kq{sQ~~m>hA-4dcxx33)~U z7T7KTow{#tcK|jI_b}3O-;lj}tR^XE^O*JK1|Wn|ZZx8!BDx#~-g zezx^zwf>cw46xBZj$y+Caw*?ko&l{up84L%&1JcwkK2g~LvBD)SA*2|WuJQifcNMZ zpVNH)tn-ijYiHKc|M3Dy^!+sB1%7E`{i(?;7*JU6JH{&jR>T;(2t-}(NkE`TU0L9D zw3k?C`6xNdp!Pekn}(qB6~q|?PKa^bVtMNLO2dM!7{GTy6wj0XF6wL56! zhi8vA7f*S>0k7@=1~k~4tp5_&Tck+F+)PjY3+v%n6kd^P2upz--4oB0H>v zoTzhj5)A;@~%#6sZ~=~M+4!-{6azvtLrx@F;AySR?dC1a&ipyNQJ0m zNF>oDWL6EL%uWpFo#D*+5*Yq=N0JifKNvAxhQd>ml*jlv7(DW8)FKl>pAD+(mw$B@ zVdn*i?!`#WqDgvuV7CSz|OC%xsBs{dm-oReMbh;0o`n)q?^Llw>bi2`2! z+qU0|!*S>Rw^DL8qgz}_zK2&YUc4Aq{Wb~61`_w)&N@02^7^GyK+_EUXYO`;W0^Xh z&|=Z%1I)fFb25F=r>nQebr?@-_kWIDRg%(4zkzuFnQ>SIH?GaLAog~5&D~xR+_rHq zN*JDVG0CA&_pCoS>;O*9Zdh23@XPWmt6I-NcQ9stu7Ap?Wm z>=YKO`FG;~638(t0Lv%BK*88KlLP10R*@Gw{2xa5HM0Eo4!slPek%sG|MHKEr6!yZ z8O!|QLzo``CnAqi=)&%{gk_);c}0`|5!l1UOG_f*>|35)6&w$iftL!VhBM~ zP9azb;J|O~7G+U@ZAcWbP?Xe{@xlR%XZ4N#`MK6!C)RW2oZQ?};0?lK^mlpFf5A%O z4jB(R)XbLCH)`Mze=E*b;uK${=->8A75mDH(SsRQ@Ni!K99o9=8?dc zoTH$7%-5Z~c2W$$Ta>IysZMZhn+A9Tvp@U#(#LcC0+?k{+e(L(2SIB%s+}_=f&+QJ>_R%9s+y? z$ms+@nQY`lwj*`*!!n+N^rQXUqYYlgd#vE{y#kP-Y29A#qhml+{D)Ms5k*C^z(5_? z6XwxjZeJ56UG)=2xXa`@S|jQ4d+B?kDP_qr`2Udg)pj=FKHie{ENlQ5JE*Iu}7NjN5Kj)_(YUFt(v zMA2T{9`3fk5|nJJ2)wqx|D*-cL>v4?uhob0PV=$~(`W&K;r(+)zNw~7?#pwzIE(_G0QbW^Jm(C|;1sPxE|G&mE8C3LZB|@j zU+HIgWCj#CM$i)UoC=R;X5&v|3A&7SMpPO#=Bq8~Q>+_J?A1`jyI)N2o&neYy1xfN z4hF#$jyW?Ow^@(WY*!AC zZuQ=(y0&$c)TloI!UDVI@1HbMleVIdTaL^S5V7j0raDx^K zsIJiHE`&N6MBnHwFphI0)4|TD$mqu92+_J`+_J@60!)GvjxJv@TX!I=m)XdN#X)uVpC)uWTKOl$IGko+ zC_Q89L)jWJhJxx7{-3y(0!hSpT(^H0Kn z-PkfePFvG~(fQ^0Q~qO=cRC=(BGFfbep!}oS+<_ZS`60(RNuhSbPI6_5dF7#ji5Omu-N0cCwCt4p_O zqVxr5(Yh^Ge@;pw#_l=~gD;LuGSirUGt_BJ(0~Y>T}BPKTNzF|T+94cg*$m&rH;qd z)ibd5=$iaY@r~$ukkXpQd{P3PUc;{H{l^mO@sL6zD&eyEEZ5DCnIwQX@0XGyt-;? zNZUFn+Vq8RwJ-`cb(tCr=xNLY>GSD#+ZX-0tajK4sG0i-=XzV}BwC|`8|==TQ*4e* z2R6iS3Z0>&)M!lgI1OCfJTBwdMO*X2@12w9gec043I-`#NrI9g61)4_ETsWnzvEFJ z1w2wN%wlD9$2b(ZgG;8}oF48rfwa#%V*eKQpC8x0_@k;MqX3C5WXomE=fAm~nBjb; zJhEk-7X^vZme-2L8Goch-+p5~8k6b+T5=1j;l?G&_Tl8zC)n7P?g^2Q_PZ0+?Ba#V zOrn8tUV8Pk&lramQ~9j(QGZ<&Pgaj)?_cfKlFrVo$w|mRns`<#^~Kpm*XhmIhR@LI zmzt&ZSUI_s{&U)#9h$Y#^kAL>HmUMB#Xv!GXI+qL{fIIeX$?Ll66%v`a%3Ve{LH3} zeYrjlI&$zzr^VG6-qNYqv6Q(gw^a2wZ;oUObW$#r8a!<5IEWwuXtFV_D*DjWf44id zveMw_ny=@-p8st04Cwi%*)%VIot2yZ`7@<%bqv^F>*$mQzz8=2_EL@1LFlQ-?ZBOu zo9%FazZn^MJol@;bH{cAr7?>;#}5#4v@G%S4AaLs{Y~MT9@J-@jMVi&rj9e~vN{`% zu9~)r`PBDv1#fe4j@3}DX|(5+b<+dc6we#938bG*HXd5+vT446VjhUf*_L5{m?H;a$sCHf*n;d(z`&tg_jmnd!U;tpBim5<{{2j!Us#yF?_TOl z>vN{GLNs^ErIfm6MwTm{EdE&>3OXT~Tth&Q$8SipasBrkD`8$nJB~EG1UWu0kC~bn$`5`@5 zR1P9s$Hqu9<@woPQv!N}!SMdmCL)>9th`Opf{)eFZf7ZSCqyebA9 z6+5~z_+>fuo&yPUnH~)>fa|}RthTROR{oQ5$HZY&EXFfoFULE_GvT+aGMgq#-%E0@ zs44U8a`4jmwvnM_WhQ23!7VwQ&qNz6<{xr)FLcwQ~)7mkQok z2j)56 z)|1z6s)Ff(GIrWUUE=c}vVV2?tmZ615wbC?@8jq~q7@tKfS{oK2tAb@u$Yh?8c0mL zK69i|XI{QL-Sh23(LEsP8dITB5A6x2AzF4O$u*8J6zeu@;6^OmCC=Sl69sg&qEDe4 zylt}CDgAbt{HfCU6I<@qfWwhigDOFRV(7814s}oG>jNUv1N1PKOnjmBL4-Yu1#mb9 ziJ@&JF75E}?8?cRa!#;?4HdlT_vriTFhnF{gKgnm^$SfvYvVs(cz2*s`tpJZ7l|cD zi;Y)AM2QAh%MIIrxxcF5T}&Ele^=IUo}=vJoZzg>hhJ)Sz~+Iowg*oMc~kWRJ4HpS zY-h!%Ek=(h722If?LUo)hc%=}znc4aM{*6>TOT@pRRbD6u%F$>QR805@Gtf$&2Ge* zgAq9jQmJdJFK90aok%`8N}a1F0@f$@UWP;ZZcK29Ek>XNRY;vBS^$1s(SDeJb2Ktv zV)XmUL>QlXUZ7aZ^pjzNj&}Y=%?SZ8hQLCCt*k+O0 zKcuWXhr|Yq9jg9eWX*@rt8c)J>xN~j3tw0xt!WwqA(&?aJ0*5wnn-_|^ zw%@_bu^1GsWFji6nZtYJioqHeD?~C3S#5BclJ_O1&8ybpclexs4`z*Hkp%bVo|S@_ z8kA5bz;L(bvRI29;E_o)G-&Eg80=f8^=xJRr4LJB^78E2LzP6m66i~^(RT`w9Kw9t z?Msh7sI(+JR=#^b|L&4N3CY+WHUQs7r!F4S`Caz4+7WoSz>L0!U9h%5z_zg~^p*h^ zgp76W?5DnT6ij^UQsyu7dBf4;j_gx{zTkNwwjL`+Z#KMF*HNrF;J`{-DoIRT7`32;^iL9NRvWF4*pDxTF zb(?BWSL(NwlrN>B$tORAZeMtG7=Uc@${jS^LU-RHR$douD=w~E*zt34-C0%0uqQ$a zt!%*fqAS&(g3ij@ogTIE*N^L-jA(4Gi)(!AV#C|`9LXE;X{(usBxW5k`SPEh`VrO1 zmy6Gj1{Yq^hQ4^X5(~g=V*TpcMZzjXjz|N(|^XRfyb8VEhUj(tRqR}q0GcPfh z?M1(PTSj?bkPIKuo=vtFq+3 zU=HP0P^G_mU{*#d#%W6F{uJ%A5I0dA8sx*#^QO1$!%5QHW4Ah;Hb9PIW7B8b1oS^d zl*RZmqt01H!ao1OQ1dqzR-)O?u>N0wgIf`t?54`sXU;WKOlk~eTtop0!wG5ODx5wj3MN1cd zSMGM}*;J562m7JlK*F|jJ!r7WCN^(!)t@8PL2 z-0&{^AjkJi@U8EGb>WE9nK&>1o4(k5X$`y2d^xU-4a16RvMlbMjjj8NFug+2bcK7x z6_{RFMbasnBK%IeGM)fr?N(M+OCuWE9R1lG{>slgn{nKed@lvmm_!kGbDu5_n|E%; z?p!vDCL;DP+DvtkKMwX^()oAS5YX`8V)1MT*B3C5e|YHmO#K*>_xuWH zhiMCHK--7)TXCJ|1(lDLzj7Iw`g6VP9IP#fbs=ApnvB>Kz8RPx9gP@^FyrBF^)VdJ z9}osPwO4Xf^3n$H@O=s7{KwzDGUk0A$YwwS@IS_wSXJk4#Dy$Y#s=)$9Cm_`eE4j*$0uF z7@(TI+PT@hfS#&xJn!dRy9wBcdY*{?NP{YO33)rHC(W}jqVLZR1%H#HnMUcF+!EEA+!?$0 zwi?jIRd8Hg+Z84%GJ7))9^Qsjux`4Y6^b`QlCu~IR6t1)MZsTN(8a^SIHtlPa`&YvbEM0&7e{^OJtgfwWI@H*|$GerJ$bQ&C z8Y#83xhQ7uK0Aoh*c$=e(oZC9FzDt`a(s0+h1VL+w-d6OZ&>nSK4MP zHDUxl5rn|OYv;`Dw6&#B9;u1E%Z4J_#<_cq`I|_zi*P#v;qGb18MA-sNYZsz;nck+ z0v~gs@HVNm5Hj>g2vD319_3Z9zM*tSIUWt(31jJ(lAiEraKb1ULU8b1nQ;mcUO<;P z4UOeZQ2vZjNK8>vb%inJjM1T)=df(3fcNzmmfG%y(x1IO#(Yys0u(1sI;SBk2k3~J z{Hw4S&%T%x`2*$Tpu8{4*iW(OIytpwfL1jW!t8GpRHtQJ`a5F{^ONnb?5JA-u+fj) z3QH3erxRz9kCGJ!{}x`gZl=~w+9LZuNF)N*5gxDz9xVSzD26dRj6u=y)%isEytTaQeFnd z6lRja3FpWwC6eiL#Hn<}k33rV$OpVF>>IbNh?K-SM6Ez*++T8MI%F>sll8EtM6qBf z9zWeCAvaf8uX3BP(&|VB)j7xn1$)`z8lT2cZPD&ih|t~Nt*6>Fg`W-zf1$|Jbi zjoxn>)B6GZcLbHvF1J7P{y^K^tEF+9{`2}t{(6Kd87VKRNtP3Blv2Y>sNX_l$2ykl zFq%-j2`0Xhm}~Ej^)B)0qB1drhDgan%|0`ZxUQdP%S8fB&Chzqa8z{suRsDabHiol zu{>VMz=fD1J{a{KyScj2cNJ=+1)utUwwJ>*>rV4WKOff2eLU9N#hXioOjh$gFW5|& z2LB+Mg}r8cqWd`-MV_v7ECheWcXSW$$h*5%IzjF+YFW5*ICNAny=BrZ=$6|?jEhz6 z9h!FF@FeP*W1+ZLp=uo(i8kzX+@iREiZ{C2(te&g=plgY#L$wKl$95D z85+nJ&wOt#$bQvXCFo%qbpsM#lY@hU(HI{SicKHXPEAcoNDusNA$spTWpkm@2~Fi1 zMk}YJUQMgz;`%`e=cZ?kjwo;cz*rD=*=bZ*V>!jd^z2!mkea_yVk`$&gNHeHRo9WH zy>6;1DNBJtT8mHUrreXIXNv9fNYlzw ziwBPv{Gbkd3tBeztZ?u1}dA`!9ErE-gh9&+=MT^my9Qw9`nnQE*oVA|5Vs? z>+w=?4o6PshgPx}G&RPVJY41+v-ZQ@U%$?sYn<9L!LbOwnMCsWL_{3=bCA>DHm}`4zP<4Mz*IN!bU|H+ zdIF{zOd%6rQ`X8$4 zLq7|%tNMI-nJF@o=&7AfN_>F+oHc=fJ+>0Yd3WC7b%lBC;$W@In%!~2cYS>m5Z%-` zIO~@yzLS4bA=4|rE2m%WN7kzJL1V}G+a-NdHrMG<;H&IsUTCOBn@NHeu|aA}jStd} zA1pI`gSpEU!`2X4x?RCVC%su|+;9G;1z=>V=)(86zyUInSX40=t0-O8r#_dHYX zSvXx@aARrJ88UOwl`-5}MJVX-B22u*-Ks{*eFs{M@4B8gY6gm1}7?w{dB7Zkyo*<#!Tk+LL$O$#3TP+JyOq4&r;Q#dn+-NO@hVR~b6CY#{@ zLrK#1K>MA3iIL@x^v9@P%}WIC?bt%znmrWRn2fO=Z(J~@i z1Yrx{^`GMZVN1?G7quHynl8oBdI^L{EP+x!P}P+Ow08xT3hMZ;Rjt- z<0-0Cg~TgWm6b&xfX>v?&Mq1Z6?-pH2}B_Xy2#Nd);(@2@I{ zfA^G43>rz_OCa2^q7bwv1$b!&x< znYyOc3ASLOCufDt=3BQyCV_RH9Uo?{3GQj+o!)sBSBngxUr?-tgY2s|;vWg<0hKV* zKv+G2%fI zFK@SAzLfMbtfs>&gdlg%8|NBZohV)jAQ15f146z$njk<$t$@`2`yrmO3%gDm*t6_3AwDsFk(3Sngx;yJKqYh~r7a^O)ZE@kNR(4(*p*A#t| zL%H#O>8XkZ0;ce%;@{jx>BiVXa3 zq3wJ{va+-MV=U&#L0I@+N^YHvlL_h)D7VpXG~bos9AnR1^ed3bw;g@p6a?75-%04I-WiWW}%SWw+l2@QWX|P z+;V+Rov5kxy^qgH&#yFLb_#bQ@R2b31WU z9pTyniGL|zx$jvksF@6pnL=?^wJnmu1&H;(e1qpwffQ4lr5O%#l{w|fDUAW$=^?Cn0<^NTns7GPYi$!mo zJNTr?Gv|G+I!GN4QZ0}F3(Xx60)4g9DHt#=;`|4HPp#=Fi3NGkn|?HcXYL zq&?qY&TSA?qV;HgbalYv?mWG_aM564ILLVF%LDg=n3PJm7RvcOds3;U)jA0U>OPNA zrIVvF!#nFR4f;?Lu!ii+B=>7bn-e?*g9ZL`&MCJ%BHScVR^2u*7^5o%{T}wvVq9I( zj+Jw4kK4KNH?@F~MulxBHqXXM7jN`>=@X|?<% z-)KGMYNF-;=;1BkSWC|pXGQ?A-!4sNaW-TeFI{CTZF7&4q z?-!KJw&P6Wc02pl5}Hhl`zQ&|%6P|a1+j2yupQavCl{$z2@@2q3mNw{!+8L>2Kcr} zN55_y#h|8St*M^L1l{dqbs!I$LthbkJX?Vk8(B3YM^O=PfA%j2t1Ux|2oXFa^=_QY z2TzO^iNC`AI2kL|Y!3Ln(rq#JRh+x4akI49|-Ff`doD&f_b+uf*h66J6SE z#&!KWah&uEi^ea4#3yt=e%(@k1#lhM!pkJ>KTw-tR%@L5KVuHzQ|>CPnO4H=cYfi{ zg++Oy7+-(<@N2Ao0dGC!&4%h^k{Ey4|sAg!rS8>wpg%H(KcMSzH#oj z+bx(O#k^m14e%5L3ga7uQ-TJUO@ffCp|LRuM30_)ouy7$f2aQlAiH90I7ic7jI?^k z)n7;xDzch0?)ds|sD7m(*Bsy`46Nj`Q{5A&`Aj0qTmc%WMi~36 zYT5e)xV~W4N@Klw;4pBRpULXSRuJ%4jIW9voxHC9@xjC||QmZdQ#B^On7<_nu5<6BF*k`~B&4H*~1 z_UasDDAe*<(tB3nE|NA*(f9K5lW36G6Dp_KS?vW-C5*zc8{b@avg_hhy;Iy2)Jf`10)JEk3C2oeWcUo3fRt`77Z2L$#9_A+ji_o+h zB-`gaKzH#cy&g8}hZ@~g)jH@jq5gM z3pkf`^*g!|DE-J$BzBL%4R3IXH~9^~lcG3js#?dxqt5yf5rx3-lgy0E2YUxw;*FNK z1d=aa^YwrI^8&TKnNeh)jobST@w+*GQ#Sh<^WQ=<-;trzx9;@R4O=J^!}(F2DvH{c z+9Lqg%Oo@VEggu4yN-Fml!YC4+|6}do05K;u0H+q{xs4MXoAJEboF&~1P(ln-`CAq z*x4z0ev~h#g90S6)*BzW`5n4rh) z)t0)+?Wo{}!Dq=n*kc>@L_mTXcHRy&8S!Fh@UU&>iox6XlPn<7!(r=u=-dk_yOO zX)}cJYlpa8vG@%uanB8PBS+mzH(IXghACR+8Qn59H72pjTmJ+a1LLI*o$?7BAPlQ- z~`6zgpJBz8p})cHe?+ zu)4?2{zk%$ALqoClyE@Ps@r=o3>qyAe=c%aM~&Jfa?vt=baH?&H`4gEGea^_!HMBi zn8Ytl`aPj4cDP7-@K|xUvW8(D!P&`Xs5-VKhvq`-lFI?RqR2RTL#+Bc0TvzJ5M_?# zEqV-0mu?c>yQn-gtoBia^{A~5&jwiM#u%3;p#tMF$~j5}&MX>XJXB*Df)dG$SNM8j z*Y<6uUqp1aVL!ef%bjqb6EpnxW_$xJ$B}>gvi7Dmu;g*c12=_C3<71PjajF5Q+fMO zH5dg{9^Z#vVUJ*xWL7X4T-x#{D>3a~zvGQPx-F9$uzX5s&M@`8#L|ak`zMTnDqEFU z*{L=*0aN~QQL%o4I&}P5lvIh|JZM>neA?`&2JZ&qjESc4hA_uR;td)a8cP+fVz6ln zeS#;7uydSkRCQ@iv(lc=6}1`}xv1Ob)ASQ=HOg%{{{#pBO1&US%z~a6hOn7eHMhaz zv4-A6sx!h~wpZ4#xPGwvVx3ptUa$0|sEQg)Ka{JQi;^lc8S+GHG6_>?y5;yl?gmk7 z`ZCgPoDpwwn&CyM>hqY~?&{@6B>SJp)Cj|ERGO|<|0l0}vU*x0U-t($+kPAB?nJWX zGClc2LiMY6*LAg4Y3*sUZ|Y04t=g-`yRWU3pJEuE#7l^K;g{=4LK8%3QlfA6+oC~u zvcXwRQ0V>UTi93bfHI1(l_#R-ls*h!Q#U7}LU+zu?bMrYh5Pdjtk3{; zE_9cTTn&MS$|8=-6j7%4cxPZV=m~3#00?#O@wFr@*V$x^(fPQlA6g##epdh zAuy`uxqB9i}G5l=O(#!UlNfM?hk>-!P!5cN6hMe&iM@Lmz z9}0E}W)7}}$SSb27v6eIon_pdjn|yHINn7qT;3kNYN7D!f=~L~9+4jmDZ(tnoq-9rs16uswT1GIo-=Tj7>dZc?FOa|%9 zDf?zI!^v7uDc5(;T+~^U1s9ZCeK&j9f>GN+E&Z^t;=D1rrN5eQ2IBfI>7(MsUm0hx zW`cJX+1_aL;Ne#uf`e>>o=IlQk2G4I4*^52BR!f(*6Le9&=jhpuRjVR4nDiug7KWy z-jFG(UgB~gV*qqDyhIY#){IBY?weKN=V{2Kyhsf*+#`TybrYgTgZ&Sw8Lj}RfW}FP zWN>5nw!K;g4T32)nut*oq~>iyxvr`j$W)6!(iY`4+xSMbbpe=@@r_ zg0-=pHE1eD*$r&{-g3*rNXv~|)$F>REy&{3@+_y<2$m{OQ7{`}a(b~`CDfSorOZlm zM1<&@e0iJ3ns;4eC{qrL3VzT%n}^H{c-PSpG|~S-KTZ!&YP)xohmNrk;26Yl?i@7# z>;pXBrMd)VS8FMUdj=CLrbMs$Q~%r}uEnUwb6;2nH>H|LO4sajuZx)+4BMYBViPGV zHEcQDcZ^HkWZxWgj35j%#@<_ge6UxD6Dz)7LPA0k z^5z*4a_Oj9uW^l09i!n+LaJ`4wIf^eUK#~GciV&6-{myymb?}`I%L8wuO2#K+YT@+ zRdn^gv5`*m;8w!=?o?bKj0HYeMIVL6=E%{;zNjot#hY#t)g8&<;9O`~GzvDmd4?&; zv3zIdDBk_NGE&(q>`y!OE|{Nu>-XQSZ3hK(Lsc5BFQM8c$o@2BLudYUVN5+BcDA>% z3$bU1o(Tmal8h5~p3^D>7Q$Mj*J*e*;DmMMrT!CKSN0B<^3SSQXJDhvcTlqxsF-Ji<=**PIQPCooZ}d52s57vZ`f5Lghq}+2fL6kIWKrQSdOZ zA-OPbZT`pf1`@d7X@~y5lmfJw;D(mhrfI;$b46^XX?vCltdYwrEw|8-G?u!C9XTyhm4!MhD38Dw2(hSN5Ee2cU3k=ugrF^6jKQLi>KVApaATY8l52z zBv7xWv$V8a{X19pPEnEL41$W>{Zg_*nMH-}-|j~U81fQ>a?jRVMfnuNr4ZTKbl7%? z?V$cInS7ozMqV4_&S?DOH^W+s0Am&|v%=Cnr4JDz`%a^O-L(XV{24=!tW#X_f`vEJ zufC(!ny(?w8P*WEzT1Q&{WosO={?sh_-{wV^fOEPZo!jDyYh;Wk+IZfG2j&U+B;v~@VjnN+1&bT>T?v2ug{ypSu8xq zV~={GCp#NKjq&iH1jRXv=jaq=aG)g_1GhjM31$GS0zCJ@#mU{CbIUN@GvroG&} zrSAAS5jFhEUjrwOxS#3SpM$3A7H54ee;74YMr0rBiPDx+w)izF4B%VMz10D!{tF3a zW{&PXN5D@ds0}}75V=!(QZ?*9mh#0;jw;pY`-rhuEBD{0UE{+R7k??{SI1mgUL9ay z6y*MiWRhYh(Q-rBsocM7v;AsgCzA}R?Yam8}j!M(Y zv|VJn5;ns}0N%ua*@>_ivK_fI6#sN$VOHLmlQ`y27z@~6u}68(ogJ^AEg@U|5q>Kg zDP(YUh};Vl8Rve{Vd!31a5Z_~xPO$0o*}%d+Z#Lx9Z{HnUG#F~4WFZ`iK&fc+y!!P zi9Eh%_rsW(=i8X>mhuHuBy^|mixc7rRM`4JwA1hJv5eX2x-Yp;R31UMpFu?5B(#MC zc|aebvdck7;OeybR3{%Vk_!SGJ=3P>gF0Q}bGdDpK-*`prV!)>)Y0M%YSUyZlYukz zhivZ@btlNh^3f`=8J=89OFwPEQZ^ckV#$$8l78E>YStrmCzgD)fheok?L6j!rjl zv67mVS;i9iBuCH*OTkwfwgsDk)xPh2n89HVGg+ghL}u~pPWa40PcTrT2UA;iesT-2f5NlD+KH0=h$`7ofBZ*~>Qg5SdqF0Lg=gTb zz5HCN@YnO^k*~O)65mJTU+qGME=%W1T=uK<6zlXbeK!Kc)`suNe8nqc>V}syvu~Fg zmrk?zAB$S{n(^pRN+i$Byp1<fl#qATsFa6N1&4c*o02ndVMJZ4Gg@)FJwj z)@4Z8e^}68;}w05+%HNhq-gSvg7u3|0U&_1p1HaVS!s##r==J1z1AO+%Xohi-N~i< z9fW!J6-B16vBV$){AB&^gsM0}x{qK5rw~X>#=Wk&v9Ph381stcMbYddaB3b{Memt%$x~l5&(QV_t#1+Y-EE2`^CPo6*11HQgju znQ(rSgtOAa`=M7@Kn9`U<`~TvzXDz8IUIQQ(~Nv`@(*shuoI4UP@x*{{x{3)oQo0J z3<481zWto?_uPHEd~v!uqtEQ%+y=8eq?;6Em0dybFaZ|wCZ`?E@sKa=$lY=|wY6~> z85H-Oh(~I&Zxci^E&dPAHm6{mBr7tKAA~%|yVJQEzi8XA<{x}XfBE*y1*dF;@8)<& zL;l|>#o&RhodHpTrY}~iICZumpRG9tTok#sBO?xW6{#MxMnfc+W9I8V;ZSGZhB_>`kF4iUEH7upAw#uf;sOgM z0QD76r-HmUo!<;J$3k3iGlr6@1{419eN8=qep!)9BYbeXxkq<<&aMr60z>^JWthUsn+P}+_x3FT z&}v&veR`)c8+^D9n1-nkv4m(8?h z?{7h?3k0E0^X?+3nI&zmduu?1g(FM@j!>Sw$0fszoz$}W`jnvlSlic13nf%;I}KWV zLnNI15+XY4z8dmJm_KXAWpB}T>({zB=sYV?m!}debuF41F9?$_oX=^fwW#qVxQmP& z$c?@*eIa0mmQ8;5^AQp?s#i6lNKE)sdS+UwHqzNGr=dpVK?p=cC&_-@yOGa&*(9&; zVjZX)cC2<^`>uM4TcZHyM9^jXfCf3idvw_=IsB{hkkTp2Nn!3ev@6MPCE6N797at^ zwu$bIqSm^!SUG#ru0i~c+_pVZWw`KH%T|WS=B=o54$&hGIxvO!K(EE|!xv3DK;4tK zxg9+GwH_^Eu$K5Or169>Z4BozVFKRwWCAfzy5~MGRF&w}pqRqELp)DoRsV9?l*LEi zFy0Cwp$GhA`}ouA2kt%TrU+x73kshS6>PZtf#!H$OYgCE_pbv# zL&!1^M>5?zAGxgOj18L0fZhoijd9tIFO@5Oq)d3Z3NfVFd7MHQ@b#Fu7gb)q#Hgqm zUv3~RJ>AlV=yRp2f<>+t0O~ZV9K@5SS@i2c)U*n0?Ppw6_f%Q;z)ipcSbDLpcTedy5*<1uN z-?gE;AMv`MP`A8mUA2|La zFCV2(XC$YGOjwxO+rQX9J3Br7F@bl}kVHR=eSU)2VX9;=|3#uh*>zBlqO7H_G`*QA zBXimqeh?DSFx($W&j0D0Ej~V8zJt(Tw0flZp!3EZ5Xs4&q?mNI&Q^NXYxMbEnN&M+ zXepB)9-12!4e`#*+WqQFK6&7xxpPxI`a)HJ5&G?hzDbpI-S-|=g98X9Yv_`q1P`52 z0G+6ZvN$&y+M=*dq_@QFYlf`ub{Xq8fz}KO#|*dZtmI$a3UaKkM_ZaZWx_;bMGxui zuC{sFG~BVH51seEIe+tzRRW8E?Mdth6O3VAa1@!CV zCiCD{-&6$(>uYeHVg?wO;va;-njz}p#b$cY5#T7zC09I2x^9PQ+J9m>B5W8YGKm8X zKax&QFMR~eE`6)!iF53AAExp|PSg z4OfsIaB{G83)>j-4jSzN;)}WtR5ik0?sMVq1Nx+y$uV7Ax`!OuF!6XBKs7oPMEV_h zXCe$hul(6ahCKTE`%BaARo=;2l*0z-^lvt35C4VOESf8p0Y!Z!`*&4_egNyH|* zvzHgy?p2{pKvcxVt5Y0@fj*APd7-hhmF!IR(nlqCw;aw-dcPLL`U>a-EkWa})|`L2 zxHEGyn@{yCJjHt0kQ^=-Z2GliP}!SJ!^>B=w5$ve_{!ep;2^SnW(D#%zyQw)Rny|@ ze~s@i{72rj85pRm|0jhNeG!uQbR$}-fVDx_@Ea)5{O!410ZuX5Px>p)n4 z*(jpDwk7$RHDh#T8|9+4CO*V&G z7XQ7LODi?%18rVWlnheC823x_naQI#_HLV{Pn@~F2Zi-j@(Q9IUXJf$;lnmeGkf;c zJ|Xn)@y^|R;RO4)-_d z6;mGVC+}4*iPCZ8j^%#VI>^^2f01KD;(ZAy3h7ajm5@UquQ_(ym_X%AXW!uh6hKr| zRLTIGblM)aLEBH+!hv3~jw}??9YaHZ(FXt!|Ni~k{`~LcG7O-h;pjw)4NZCj%~G9h zwbh0;2dq;Dbpf;qeJE%pRYvT#9M^b_(gDd;p(nOg57#Y&f$FFjM$J~vn44F<%7Y={ zXGZCBh6Euo^X_LwIlHe(clM6;j>PgmmK>C6SR&sIKM``It!{~+X&+fa|@mMnp< z!$5FB{-xXmtkJtMFc22Nt_xie($pKND*1id)m38}dn+S#-lK5yQO0g?VbZ_|=RFXx zT<^XdGvo?3>_*b=XTul`N+4u#MHfu+yDoi0KjQtbc=Iq_z7!te%n4x2LskJUx}rlH zj-xl8!;cv|f#XL6R@N+gJB28X7UswKdf9(vF@JgRb6=h{AcS(?R!eddD6FgjBBc*m zAuF9T#Lk5eqpV}CkS#V_ek+<{voMgZN1wYfxB6im4IHa@U?r~SQ4(Bvf-W8qA1dHn z#`xtv;^Lj-FG1-Kc(LV}Du1hr2SMR~d&#$i`bZNzhlS2^S6Q`Wa>ezY9k(@w27yK% zxf(Ps@JokfkF88borxa610^IRJi_CZ6-QH}8S%z&`X9M`icPixTG8Nw``M!3NwX_t zxmJwRPdtVHzWo2;>aC-yj^p zl8-6KRUj(__Vpa4qk+ixu=gAunEUBjSaQ!>bg6a}m=o=qg!q5(6_73wp(1_*0w}^0 zDwsG0syUDJ<aGtEz3pyje`AkIx2Y=3W>lZSF?(UcZ!|jJS&H zOh6yV202=D_ENuf;{ZN3tSanNrjCVPiqFO|d9q8%DT6(?Z1!iI?-(%3fOAqiJK*_q zPyi`Q(5=30aR>P5cNR8~8bT$d2oR$o6pgr`6nXAWqrI@hmGW18?e^hggyQTGTUpkk zJF#&fva+*Zu+2Vz$F1dU(5gQVCTRfA^1jcYvSfu_yw>XLXW#Yaj*`A4;N^DQIDK)) zT57M9YX2D1{nz2$>~l{p@{kic#7<;O)qbZ*F3X-@DCHAqqV)Z&6q@<+Z&{`rHk z?WFM3QlcMRK;Os5*{!wRxdCX_TD@UH*6U*EgzQu4yD-Y>`oZ$scPtq74v zxB!N}gV{@Mr&7F`Uq_x?y#>=99(rx*cD5LjZz>Q>J@MtB>KYnhUzR`F8Toqir)Sw5 zphdu&!}rBDvnT4o^&{BzVu&eRshkD~{~OUjYJM=5&*U>J4B0b$wxyDU;bF}LU2W8X z1+C<(!S@+rhV}gS?Bgz`uWR=*OvH|`ua-pghOh4jl#WR*sl0ak`Oi&ShA)rY%G_e0 zmAbO(UK~?MQ(75)2WRng1%O2(IJXr(y#4vp5c~?+N#k8>i>p4wb$3euZpLLvfk3V6 zRoZ=U^xseWl+S7H|HD$g;*q_a8u!YRoVcV64dX<(tcPEwE_O&q%}pbfXEZVoyhT1; zfp&aBbol;E$Bv5QE;q}zvpi$wokN^h-i%fa^d*uSD$z^x=z`-B<=n9zQsu9?d6)ir zz9D6mPZ>NM-d&UZUa zSifQ9rX+yQiig%@{4U)xWH3fSrglNn$%~bQKIPUAnN>GfEH)|-cK{MT${?7!DoY8(k(QkkkV`Yuvn zHUSnKWWb2GpGvP?K6mf+VgRk$^I3?EW}={G{6$oY20S;VButXo_4tj%owxAz*jliU zq6Xorj*zMvTv~E|IH~Guu_O*S3fb$9z9!QPdtztke|F9p5d<7{H2=(C32HM<2m)0oV#gxc$|>^bbmm)=}Y0 z_r}34P7XjjpR-yKN`N5d!l75sa*c+NP&Rh9|1((%N+na0Y@k*s1egFP0zjUwxm
r&zemmK=Fi%+B8^57yU&I2vJ^ImG(ZgR{ea#_fgHS?>^o1M)^oj zjPKdcjvjxng}Zpyq<5&%lSVos0i%oQ#g(OO(yA0 zi%$UvJJ1`yw;98WBZkcIr{EC{QyF}qgZ_FFdUeiH8GElz9hR)AyFPQ(`n0EhhK6ZS zK=hW?;}3#2-z!{QVZp{6M|dZ)99Q<$FYS$&7KR+1yD)~?%4B3N(vB*C{gqMxo?tDr zqFhW=830Ju4Eyd)JqK)0y|Dd>N66t1-%wsnPfuP&1>1To&uFI-xcWEO7A}d4{<~*6}=RZ;cEP0AFlE7TgUDnT*2`6+@m>Sco6!Tv%JT5*u*>F zf0b&6_e$a%5J>@A?n~9Xwg>tDhnv)!3j5UlCQsd2B#mz%OscrD(q38}J(Rh~h6rzLCi1?;|}R#PHLo6uAcl~by7v>_s! z-_8DFQ7oScqAVUbmG}PFg{b&nkqDy;4$LNwE}JCW*lTR+D*Ycs1iW+l(vEzMM7fZI%5LY`Af@gAw44dHp_e!xkKk0`#16C(xQ3J{rRa~L%8mHoSgUpqG<6AE}6x9-+ogWF0B z?1sOWx`I{o#_jNd%~QR4dfgGl1pDEG9q^hwKRpDD8R+kktyfB7bLaPNuF|jp=MVyR zZ)Pm9sP5X2MrklN2IjLk__sdMr=XQzM%W41pRfT!5ub+v@yO6CX6Li(H+tru3o;3s zffFA%#i^XmZJnH0v9PezV@FmV_DU8NQH=)FbD|%mUWihxTq8)JLt)9qkpNbpBBD1o zHo{3th253Rr7u@W9u-vaiAjl1*)<|c4n0|+FouUn%=?o8Ln(rQ zG>2k2h4A9RyhqASz_J3tu<7&noZMzugenY&LF@0=!@wtd@~vnt>M{AoaAq1MJB>Fboo1N1vv+O!Pf^~@!~Xh~o2+NA3ok3W3n*Yj0c zFv0~EYsB?l#8ypiZEtsPdzkTNZ}03V>=zW+W z^$9>cPh5bi3Ot48h^~}$-YRHNmpK0o1oovHMI~EM(vEEmlv;B z`*Q}jQ5{4(ceTxzS;W!$f)Fv<`=1b?Chq^kjjsI90Ne=yJ9!AGc1T}=K$xFF*L$z7 zf%zGXu6CQfXZ{BJ4xYSK7{MFO?o%)?I%ZP6zyFM#(B-2K#-mK65ax$rEb5ZzlU~;U z@l8YW;*g79>xNFE?88@??W>9`C3z_{ck>eqKLg8Il*9p+JDe4IitCjxv)c1n_-1Nm z{5xClSjE9U?MqHmy=GCL;mWhPy36wD-t)@8jr6?R6(oIj z5O!BfGjDK|w#YY@^_<}y?Bms7S6AMfeagV38)Z=3Q#rMg;Sr~-vV3~UVMWTo#PG_` zFYEBo6*IE6i~MU=IO$`%Qcd7flY1DMBUKlqeHX6(v8$y5@%lsHfM&0xl+mMyh;$mP!BJ_o0`c{wD_30QL50 z>u#3(C-6-*I9MlmHD&(j9P7P$jx9K^q{vxL@TtQ+%i4Im0QS9@bV-%AhV72yVDYFO z&M^4yCEQM1`|S0!LCDvM9v!Z&G`7PMfMKlPQpRI_4ZO3!D1md}efs?Q^X~KoPtV=- zMmz|Z9trDN25GD7jWfmuJC+Z{=W{xX!B^o)e%&`rjgtl4?c2T5U>RKrXD@j|2q{Z? zEo!+*^4W1I3CAhkoCUmA7E?MM>8g(Cj-Qu?&wF?V3UV!D6Y-?xJj_i&2PeKJC_`CU zZc7K5Fd4aD3W*7vu$&DKE&&0-iBW5qcBM3z`)cQ(vWedp8?ta7!7YEXFAvjI(pqKS z?i`h>FJ1Spbb1ky#U@piL#y!8$l*lQw2r>d1hns0-lmPL2^Ude z54Ag15xACLsO0GW=i7n84b01uQt{ytKpIAm-R`eZ$V^0cH-ZKqd*K{-XZtLZAFVe| zOXc5Zf(aVAL%d1zOKY1|a^GY+TcP~)Go*;gn@%^wSxwh5iTE?WnUmm{xZ_eSZhTEG zBk>@0oVITLXSuUK99CO$SQ9^NogmY6k%v=0LSwhEctQ~}ZTiWodG*kze_+JY&J1CU zXCW>?g)pRcfo?2&PeD=+>GV5P!kkiXar>7n*fmyZNedzMS$8N!yV^~ikh05 zKRT!MDN1ErT@UNM3RsY0LfU3rB~A~43%LhZE#Ds&+kTLm8=m_@`Qx93BTJS7MtY9B zQ=w;TIzEIWJVKZbfj+PAeN6e4#EooxwU}=pI;&SJ!C2TaU0%Pb4Eol5g1n8MFGNx` z8H=KbD;`+Z++RFLt}-&@_{v7l$HN2i;<6?M{r&v5w%!Tx7L@pGME&N(RVO%y{{7%D zEiGvU1O&iK;RVfjkXO*ag4gnQQCSqA4+JA$M>iAhZ^w>Q8hWafZGqhaB#q50eLQg^ zJ1|f-Md*_5Opl=}VWk1Xu-LF8U1pT+?2mDXH*Y`WE6K7>8$T_5{`7FWJc$M^zxz2) zFZtf79ozmIEY`ojl4sc+W&ADvuOnNR58H>WB4CvQCl}`cJ8?hf&Hy)Y{~)*7VE?Cz zw0@54{_*WUem~#UHw>_65|a{}j{8R6R3SK6n#+CioJaV16OvH#mFE5Uy{gwG^&sX3=YFR!ud1LTb8|#K& z-ZtCx5<($AFyB;SE&P7bRCx5Mp zlKpJhevq%!agA?%`?X+06q_SWm=2;x5HXXa+sXqqz)r1_3OrR1*DQEL?2naAdsQ2&`?P~C%cNeR)#sh;d zN7Am6)bDcL0Rn&nNLdaWO*w)22r0&ba?0J1RS1g!Bq*;Y@P6U`E&&V3Da8u$$274_ zX(Gv;OZ~jA2#aLfg6s zhAYS6&m$hMg%&1Ccu30U*k?RmPR++ZH5atBec)QfcQTeBY^@4NSyjw&*|pNy*^lSq zQqiFb-?Z+AH_7R#Cs@-q4kRaf9z*FzlO+l3lJss1`TaW0E1A(>1&Qt1&iL z;y*V;7LxYc59fisf~%;mCQ!elQ3tCfcVqjHg}}_R!nW4I;(dRrC|9W&V+c1hCDuz* zD^9HnCZ1X1`v7;f(l?tjWWnjYK?5mk?}iQgj3Z@b4}CheK4z|A&uEy=if>4XCXYo4 z`71!)-A=9@)VZ&zlwm|d>8q&tibLWYL`a&1-JX}eQ_fu5+%O&FE}D{SSz!IiN~D>R z!k?=$tW%@LE*!UcWO?N&2zL9B#zz{D=^^;ySy)@+x$L-LU2_=L&<&-2Nh^Y}!;*_D8&3nxGJm-Tqy9$|E{-_v%tbfz?mHRE2Z@`2JIt)-*m4g#AZTigC2 zpXi*mWb825PsBx16)=9hlftPL(@UM6nVhM5 zsbd&fGDSrahxn5WK@-ZPjRAxl1* zi)3J&N#>vWtvI(r3_>RXQ14!${tGk*AAlyXd2e(?KKV-bJx#ENXJl8QI=?NMP=}GC zU1JPHd`m1OWyKH&TOf*^aPa7C`_9o14w*MN^EqXcKXwvs`F3$?!GF}Bhoi+4^nA|t z`65Zw4%v0E>DXGvHct-ilHnWwLD^3%-Kk`^a@ff<5rG#0qH!|RnVFdumX@!0vpGCG zm-lzgZR}#AbDnW>aglI&aOH};={6Nl{&bMk|9!n+YIeDF6)d)T3I(S$)d%6-GFwhSpHLoZd;1d55$f;*MV6NjK zQw6D+=%x5ndfKa>9*!;s=HtZ!gUZlEQhn|;1xg4*;#F|x47tZ1<6)p>OAsUQ@;L8` zNu+yEtGm#96B+qk7RdlAE%N>zMS>6E6GwG=xZkCH;f8`TBvi}5z(5yVw1<~izgiIt z)ThgaKGY#aX;An<$8PE7=Ju}+!2_9pBTdIxZ^yEVbkY#Y9{jQEeBxd`CCNJO4z-`*Bh7X&hSXUO#vAk$|ri7edd$`LHpOMIAs90n9NQgWC zRqbXh=9XahuP?twzM8-5%@YWFUydlBJZ{5n!%do_V*R7>J-22Kg*Yr3XCo-ZYprf(?5OZp^XyI;{_3l@;HDw{58^HzuJ#Fl zxd7a18{fKgX|1KJ>X!R2!RFqX46y$UO$)or08|0UYTmtFzcotxAIxLr>NmEBUjWIugeqpG3b z)xPBYoF{I2yy}YBkAc5>qQYfM+&iiHcDnL$n`(!#vzj>Mj3F4MWyOQDU}Bkt?FAcK zLQV%SW<*fE0;Z3M@yCfEOg|A)5z{{fGsNHINuHqoYEPD4_&UEX6lr+*l4H^&zOzc>ltWtXGy!|) z<&0*C26vjt@~dmn`LKvdV3s=WIXKmXY@_YB-*@X92M9E-t5XokwSvgUU(!kzp;{T8 zi4PCr{FTXlT%5^`>Ebcjgq=XyH?^mz5C6D%dODjP!}FUYUEIw79g-5<5MzJc+baXu zi(6gnaEQqLMSl#(*ChmsF7vy72_d?0 zp~mNZ>)&D}gRF#U-C{NlM~G~JMj4$BJMTCf)aN{isv6dB(_hf=_H3NIk5con*4AD( z!7$QO?L4@C#7UDgbJM_bADWXyou;~?iGY7hH>(7HuEnG<4WU(YRJTx^7(Aer|9o&> zOpm_pL3-{eKkV56{9uyZ6pjn8xFOWMnNnjrptLGAhD1j*wkEQJwRZS)3nd-snuYQo zKjnJsNnWiIpyuvOm&-#%aX_n@;a8|>;KwJF!16+}Xz|m@`FR6~4}}Fv7NqN8H9XPD zy6H$r_P-Dcpu9c&h|tIhBv8bi<1y?%X~o(+>!sd-Hz$XSv=AHC^f}%;zkXIMhVdAj zY(3s2I}~O34^I6i?u~m(qTUg=k9+HC!|!g5$d@ji%;(PI^PX=#4jjr<)M8Rw`m->o z*xfPObT-G9bEy-%9K$R`@Xiae^A<;u-8fdR!)<-gbHvM7KALe3G^bO2z(xYrv;nx^ zG^>b%idY!}c<^JeCE$&31=gA$Ok>8D^Zmj(53|Q$jRK1Wja%tiP_<;)=ar3uY3(eH z&3A(b_7V2$ojGEWOhljJ^zx$xe}p7ZxR(7`at%3=%37YK6r68UQzp?wQqlt z$JXWg+%4FUQR4#Ap&|03{1PVeC3yy6auJs=%iFjn5Yb5xB8EQ}YVORYC<-?J+9)!H z*sb5Ki*L_@=nuv`!wb1?SW#D3z8sB4WSEPUSgt$E|udAw9KBvmoW9*`Ho`4ERNa4D%d#K5oms4U%6b-@zs*2Pd^y$xG0orytCRqSCcK!Mpl8RM~SjQ zi^|N)qf1i&zlJ1BG&D55(CJh7=~|PqlP%0lCDIhCNSJvRa&lqOuHcvO@ONlzwiz*# zgvAG}DPnAm=lMpF;|%^Eh=08%H(~Km_;8M4ms#7A}aXLWw_-%~+}d1~(GyRQL3R&Gqc!>l3XwroDoS>(Sv z5PQFo&l@%f#}I-NsVea0=c^iVPqAaHO|uI>D3PG&)<;^$T}WxK83!wvs9l(%%FWHa zxD7%^My_%0j$MlgtGE1+MWSQF{S2|rV4ZIk!!$v&k6y)S;^#=*7JnK+B1qkPQ}mLJX<) z9G=PZsN-i^Fu$bA{F>OHl*_~^yhb^fS3K`r*M%?Gh@ZsRQ%*Rw*!99IltZ=M=74Be zkuHDv1Z8?Gf4xQlBG@j}wRxzQrY~7i<3yE&dV72O`pbGulMVM^!&mBr7V9^wmvo^#m6}@#M$Dtb#5x-9}*z`(WvLu1Z;tRw=Kb2l|dqsa@$fwCBURj;L2-EA)6^ zV$e}@g2Pa7F_U%QVPQziBc>ZF;nd~%!cKzP-ii{#O{E66B27Z0(Zrrf4Wq-Hc-N|O zlpGTg6%ipWAt6ZxXh;a9OX08AIJcaZ#Jvq3%aE-MkenzHnp8@Dn^fl^5y|+ndc=Mm zn(<19?4S)HSi|n%-aLHnx{z6OxAB|^Tl5X54>s7xKGqgCrK-{#Hn#&Q_44va8Z4=4 zH`m+#y?;X%(zhw0YR!O;K2&GX?KUwp)0ado3p+2kq?E*>*NXp%;chiCQs&exyJA^J876v z;9MJ}39VY!*;hJaKi|toC2%KEc^-2X;4u|ucZ(6He54Dn!G?6sS)fNmeN;N(bHA&T zWS#Cj92);z@N`C6(PMt^7Os}yXyzFOB!MNnIZ=g&&QRsy)#5`2(_IgeIt^~L6`M50 z6K)b5#wo*^a>l8x*>B@8EnD0_60a1>o}{UNrn7?@+lt~SjGRfjYZ4{baZU$J2IhTv zhW;~lnRjb18czBMKe2()YTBj5=DjXW%KMsyP5b5Al5ruK_uc`cb9)DmLgBWxVk{V? z>7RT+to#;j*XHUA(MNFfiF?voH0t1h`{KX@C1rL|p3tRD?;sXhkHMr0I9M6gMsbbk z)zuZh$Cla@2>n%c1E`6vdaL)BReD8FwST|JjbmK3zc0-hq5nxYtWQ?N@niimh5U$} ztJ+c!+DxUG^F^B-(vEw=xv_i2_tRf(#n0->5GDI1c5{;FJ&mZQhSxJZMeQudC#P?1 zSvxi>VWMd?ig}&Kc?rQ6#;XV=Zs%efKfiUjZ{UfFsXJLe9iQ{1{MlD!hGu;E-Bx%k zzr*AIHt z&8f*fk8|f`8ETpx)r@A^TyEw@%6zAdNN}sPoxWtJ8ADGI@|EoLX-<0?qbG;s&9VH9 zej)l~Zu=Ga>5EJymBL+to2&#~IvI(J5DDo^a1*FUP5e6ums6YLv2;|Ld z*cHnC@r-+}m~mr!#^uM`29zBH-Ql|_VH=4!8BN$w0WbtVYqh%IHU@pHUs#CLk`u~9I$={0IER(sMhzfSeN{*g%Li|i5HA?1R` z^-sAk1dkYqWbfoU-_d3dyAO?`GKfTuZI-qNQnMzY>tnObcK_*u1_%l%`nV_Eud}8s zcxQgR8yn=g&(+eHU(BEUh!LqWyLU@r0V^1Gd#wVI*Q%3Zd~;b*8QMsr2Jf{uw?6D| z1e0?-Vg72B)OD`z_Ba^D)Hu{`EH*TapaSJguX-nA@$_(_&p+3+RED!WzN`Atz+Sb0 zoQ%d)WsH_V-Ue$<->}7oh!cYrvNF6oDDI5ngM<~lr-*izA*m107d(ILFesO4>>dsuT$eyMYTdMBw$qO?h>W}FVl3cH|8t_ zv19OH%t(?;mn{Dc)6)IHGt(L*WZT-hYDQ(9$obge#zR1pDrIZ4R1Z#PnY)CGy;?!Nq5 z&S~QmQNR{A{{rv#q#Bo_AqgL`>}L8Rd+_lTDlw;@A2qy5NC3ydYcm$Y_73tIGQp{8 z)fA0DDh~yAHatzdoXd-ZPp6R5(WD9r@J1nDU0=^O+Urbpf+4x34}05Q1dMge0H3C_ z@EOsL&j;{AoXAH=w09$jmEJUc?-P5-`W@(*17Og&u}$9|nS-v+ZvgLUB8pD|GQ z2hvyXo#q?LmSnXu_e68lA9N|+O~hiQl&5_Juhae`+s!cyQgVv4u6qva>(FIQ2gUR+ z5bap;>JnoJqhY?>LaY0WM~@!Oh;TpKXgZjmDlZB&p=jaY_xVFnu99na2J9^oDL921 zl^LMoyPTfgeck97Cfje8e4Q@9-puL2NR*aDA3Iq&B9U9mNU(#U<9{zQaNkdN$@MiA z?WR?`tn^ikD;^KzDo(R)<3p`A5tEwzX2G0E=^*;#cbx>B&z4sM@~)gmn1$(ZK>g0S zzc3fQ+IndrU#82PJhZ)b@(c#63(`b!Vh9;3PR^PdC_A=^!AQ_~={bO?F;5cIo}JL= z=J11X4a2+o#j~yT6jj`~xVOxAY$cJGk`FD2N^Ee)ID`2r_GCl+tpjt*dvIsk8sGn-9@U_Rk8{-t5gc>+E4feVN8g-&NY! z-`Szcby6x&;?k8X=&ZjhnD|cdIPc5p&RF8pL<_xv&_IT~;IsOMg)KOSM(?Kz*{9(n zO1wQA)iK&%Z$c)oSa;^b!H|6<>f%oV5GP3OMt&!EO$v~ypymJ~P@r8@W zN*oM6lR(c89G?v`y-0P>Ap8~KlJDM3{^@p@Pi^Vi@#VBz^<<>VLhk6FbG+%UOZy~f zHlMSVnb}Gkt(~P0zAnO4O*$wce8`dyGf+>!`8{9%e%+s;V&3Fw-c-|Nx208(=o*6% zc@{Y97xZZEdJi_~AS0PDSn&#vML5`IQqu9}^zAOAOv~y7iX6T*s-Gl9ro{+%O(AbN z!m0lJMJ-sGBU6Cj6aR#a>osf7z`(j$TJ)i7S$SE%1*Zk)bfX7r#*17PoM@?j8jp|0 zY^=&(*0uYsF)T0`04GivEaXQQ#mvAy+wH(CXPPpcH@{fmeN5416nPe8`RAEc#TOEt zCN=*qlAR}ew_yT53N^jPC(Y)rH`6L8!pgL>(3DrcZ(+8c0XEg+>m{h@rDOLHoSPEcb zm(};Kt1>`d@uE~mLI_1oYlBa;mdSm36XY-$55*ClNj=s||rQt3Y-n zxzu(c<%1zNPA?1^{Mq?vzHy2sA7LtR$7zh$bj1gE3RHL^!qU%|Q}l@wWRn8dKPPK3 z_VmOOF%ZUrX6bX`lUBpGVEMd(JrjHv`2@FoxrR@Nu@*QF^#K|;{J3W_-6f?9s+)v- zc_B}+*zS+!2o`fl)>Oqz)(*%UUjMmPM9ocJ(e!*-UZ7vHA8lkhJi$75jdYx>QeF$~ z2$qOu1P2n?*(nOr;XxC>Hjt9T?^-0!q)$SX^oCk^ciF4GR`K;BGcJ$+Z`-))X=$ly z@#m)>4tE#*^*pO z{kP7?E7Idr;iH4Ki?jcO%ATugwH?8ou*v=3-2PUqrjdfA`XIUtL9|~*ZzjAmS+3e~ zHs5(Ez#LAL?{>4K!B#L}mwl2d6zWL~Y#8V~8AGp#dy5e53UnwtSOvYY?QHj<9goGi z77({6SX2vqVn^*u%mp{c?vu>k>(Ux`7_)&$&8F$;BQ)g{55f4cRS5|G#~{8;AF`LD zNdt89bSWN=m}Y)>i0w*d`E9=5H1eA)NMt|k5nTMxs0cQk52EUos%I8W_%8~0u&KWN zSfTEYf7x+%H~N-UBU1~aJ_?~_d{Y2TGp$CFgJ=kyHxefFy`;x)vm)^;R-9a!7Fi>^ zJA)wYFg*n(3?>2!h-yL5)&6P39W!C6P}nniMSX#1GH6jr3-H5|gpJi5PEUiYg>#QD zd{*xrU!Rp z`BhpbSdp}!KxPlFDp4mQN;-7}EB`LvvoCioe%@6ES$lx{Od(v2_>EZ~1 z4&`D{meQ^2(6u$mGvdXlix#9=9)Q-#apm#|Is z<%*E~2)xe73L>!LT<>5A1QZTcFKAWOQcqyF8O8a@Dy2E@av?>!W;&XXau_6;hGyb} zlpS4o^GU1G6b(Ab8`?4w5)z4Y8bLupK+%2hzC^QVKAO(Poi&T=x-p6U+1O`cp=IXb zQG;*H?6sBptpRMksntnCw@gCkk9bkU2r)H}Qt|ZiSU$fzyuMMX>|)U)N_}|ONC)%@ zE7D$R=zMWH?MhEV=Bt-taasru`rY@gdUrM_e>b zbC9RY*0H8FH{GYoHwUKbp-EOCH z69@l$Gg>=GpHv&5Cpck0JY=}hh+sMhgPi#Zs*^si;~b4-sgqhwBV(fw*GNRXf6jaD z_zDH2e)}i){ojl3vd-=RRH*(*B;5MkBqP=-m<@V}>Bz9lrCKUwn?j>w>4tx%=`RrU82X z1mC&bPYeLN!74Q*-e^hiJo*M-5afSfMDuVpWYkm($i#wjxU30H1U!qMME{iJ|0yFZ zsyX*oE5e%PHH!felST%0T06A85%vCu4 zEdBxZkErBB5fRbuf1L=c~(0o zCMr6r#vNmu)t~%Y&sS6dxAARa4>yN0-UNGp$wUixJZK+VXvOV#6>Ab{GZ@$fc;k!c z!JQT+R#}K>+lU@wA`~$9IU4zuLm$(iUt| zOU7)aM6zJ!D}ixKyb1C<7o6#t<-?Z4-su$b(}Dq9){G&XwAgA%mXo)yA~hihe50u9 z+vg|s33~zX3fICisM6`**7?(5ZUF%~h20YN*o^DELDvE9O?xl0=&ZJxXp^#Po^m7V?ponwQhHS1W1lJO;9Jz zFtoB~g1>j~j(KpOfOOuEm&)?oQ`?xhvKBa8|CtV3;LSM;kJ;_ktt4#70+IAR7A2 zyf}qEM)DK+*L5ybZ}}2j%Ef2QrWFjG0d-nwSL)_3%Ml`!7XI7duxR7{u2NKwt_fOTg*=`7jbPBD8{PU9oDc6RjDN*3k* z0=1ayF2rFrHQA2z*Xbx@%Rz^-a)-TTs6n^UXr1?ybqyWK2n2*St0=op*77;Ca?iZR?_PXpVDt_fz5{~H)g?m@%XUu1uvJdTOc0>p=9uuy!8`5Z>ua685JCQUGHBg zAH0mw_btU6SP|D0%Uy4eQ227i8+|p^eKgZ&EwX@;vZSiCe17fQx0%gF)N1^nx}$EYd+LLH01PEj|M)TUAI;Y5`GVPe% zI!-*|B#uim4yTF4q(HF^OFmgnZPc;FZ5-B412I6E|vd z>8Mw6i}4gOay5|0UPTHLJ{Po%6qNGsGQ|dTLY&Ev(xd`-1{=*WCKaY7L$qk>u@d@r z9h#e?)F4P*Vjf0RJf!h%z)+rD_FuT2eGfRbAH^Au5@bXiZ`#hulCw@X%R6szfr_*E zhbIsm=-u)AdLO_2L*tS) zpoRcWP34r~%~@dRFRRU_c_(ul8#%zNnPP$W0WIoFz{PSDI9k(8b=HoAfNgFo13s%= zKP!SI$jkCi$<``EUXP?;+-L&~(cdOws5OB`H0YGl)aWByGRzIK!T%&<^Z<<*W3BZ(`8zX26gNBn*Jbt+4~u({>&Y{(k}O_(uIy5N9%)y=wZ zqY)FGMwgF6GFy#W2!N)KZVR0SywwhJE?u%~XX?^;X zf}{UEIJy@eI|nbyT7)cbh5zz(bK(zNXr2GL6Aq&%9`#t9;PD+1`a|I^bOmel{xa0P zQh=({f+`G<5~KfA)-h}SGg5ukxCg@RN_t*2|zOfVi zjqeeF97c@`Q&ZZF)i6@B1aIRcyP=8h?rtO|ReQY=+{PBq$5-#kA5CXp^I03$l1API z?E)QW&#OsCp+NNhH=GH>$nnRMnuL7O#i8GS2DP`L9rKBX>rH_G6k;RhI2z=U9{Qy5 zBe5rQpzE-zwYU{BAT%byYcz>BwgQo1lj_L^vYc)0?dMFQ#_2jxmfPEB4cfNd*mH3n zm{iiWhj}#bu4|))hY9Uf8C(Lf4d1UX5lYQ(U-BZP54F&b7E@mKGfe#X ziU?~yIc4&}7j9*ZBV7nVrQvMRn4znkCP~(MK%;d<79BAi9o>KwZu5{bJ24IMNpX41 zR;$vbUYR^6!3%?&o>hn|gQ%8sl3I55>?EO;b-6$bb&q+l@dud37>}q2`XCj7iwrax zrq!KH3q#Gy%GVDi{SW-x`l-jl_Z0L?rjWvEj1&!s;&%}HLB%SaH&>+{o%J6AyKZru zJQ|`y-L=#<()twnSI}XU%C1B)|36^9@kw-d3{cce@!y|I*zUsStfPQLl1C_uqEi)r z@0{QMxs$EdFhuL_t}n-tQjKUpL@$0l z0xf()29*u_L!WvID1*4PVX~$AW)27xXr6{jW<@{_2JW3un912rT_>^OYx%bp%aSd;6Ij)kq*aF@xQO5 z728GA^3S&wTpF`ot>y1Rd^c)7Eee6yI@(H4aED2V^_V3o37W^F&_g)H_qHeuh#8siDd7c+S1ZJqD3@{38SjzuJ-vNJ}Gdcp# zUVtKVb8#r$T)fmj87Utj8T5Ji)5pGfF3r9^*$ie?N9|&%k)><;%WE>EDmZ8@O=Wn{ z4w{y4=0VJ~o2g06W`4(SM5>Ov6zrheg;Ok%&45Xa6i&~DOz$?*wQYbO$o%YHS6^2L z>%?RKr9wB0uzvyadh{n*2+`+26)J|12e8eeY@Z7V+T+SY*UsYInmgA(qBdRzH+0U_`%s z&k+WTNgg^Jl_du*iaW7PY0gR}75hqYrsi;&7x^+`ls`1~Po9#KTiduKn!T6%{ETjZ z{rPunUiZhzh_=w2Qi`d(;(ErWx8gilkMxq+F~9hx+e)@945b@TwZwaAeeBPYV1H8b zE=ArNH{FFt(VCkQN3~#+%O;sT!=MKbjJ)%@1dWgU9>#zCe9(OcJ0)1O_2hvO&C#^X zn*3;pc?O5kd>)<%wNIl}e86{UQdBsAcax;iAbk2lHE-=}G@i2I)L^~Z(_q@RJnFQ; zCkfV>?})9<%zP1Cw6mqE2`bJ@#&ksP2Cu?LA3FduM_#^IG`{oi;j~&Yj_!v}wdp}_ zs1=*|Hts$u>-Y{o1iI_Kkt^xG#-NLEdbn9Lu8%tk=z=i2&<8o-+FU+x{^3dFEG=~d-{YABT4S{w{PmQ4|!3I z(*HlsGwH!{wvp}3>rWC!r(Vl=T0bojn^ZGcQh}LEYSdgTeD9VC)9~JJ$;}n=8l80} zrhD$_sJ&kHs>p_swHf1OI%+~Zhlogg)h<4EtLp-(tR{pr6Ei{*zIlkp+St}I0#-Zz z7P`h>l5>3V;|KBKtRCjXhp-yP&oB+$e9!5Igws;O`&4d?8vbfwop^DiM8yU*mR7sl za$ClE(TP|cmTMf%!NPY=0d`FN$YlAF{<5fF*yT$#Ov8%kJ!*H6HL3F15;Iw-C=1&x z!X(&OcAYlkxg@MssD%USxL=%pK59PKiBv&CCuu5GNE;%6KznSjl_9N4I#hqQ_W&Ra=h_<9s?_qHEcBOP$t4|K1EneK=ghwx1}c$3&I`p-uRx|X1&NU;b$p~AOI%FE{!*-y zfXJq4USX%le%dbtvR^saB`UchL)=!~TE~Uyl30u|O9PdZ-X0S9W0-#0j#VUr&dsyE zI{EzxQx8c7BSIy!5c}I=SFf%YI2315yZ?e{ZxFUJ3Ks2^5b#8So~3JPRjZJdM%Dbi zEvwIzf|^CUr^kv-3U=2&6)O8_6HU<$H`_Bw>ebOfqy>FX{8FqgDaoI z_T9@9Ba<&;rh6)+cgYq9kAcxnF-;}ty=6d^?eaZLDgq)Yph!u#baywKy(#H#q@@J~ z0g>*O-kTDT77+xIMpC-Fq#OPhdYZZ#2TEIf-% zrC_3^55SybYy&*O>Ka|GFw9Y3sE!bIb$NM|)LR_bwvhiNKaf-vm~C-DRKLw5Rp`XN z6y_-xelN?8``*y}#qWj6PkWQxnmH3FL?wL7PJN#ZN7(lN#mtawa$xxM()S+gP@~wj z@Tl`rSO)({`<<|Z>|bQI?Ts=*9{M0ryn43?YvX`EV4pt6Pwn;>a;W3_{ZGkZOXGDw z0gkk}Y<+JEAk+2KIQEPlfu_`=^tFih*@4e3C)%C_Noa8G*tTDv{ygWLq8wsM6*aqv zE<>B3s5x9EU)#fxLH2YGGlzHx?KLu?j6|Y2=(`Iqyzfh=Gy%?X3VDWxGso9?E2Xyo)77k`VWf6cDuGWUp;?Urh=TpC zs($<^zQXM~-Qk+O=km&G9Y2pQ$-Hc}GYso~*DhS?B)V3D6%@_k}#?b z(IEi*IlX7|ShrBRFQZJ>89=&QB^6`%ma!{uZv66LRUbRS;j&mJQ_>Y!*vLslm#3D| zsMO1oz-m&L^TYMO4v%}cDrgHBGn1i37~|~sFl_iVqj$mJ9;07JCN9dWncRW6d87_Y zNJ$~x_fC{#Q)5ZVyTS>RKGiI^6PstMD;$ip?sg~O-Q%PJ6FE_I6y#VqA#k1H%-;EI ziD3|~4f|loACT!gb8fFW()GYK-`eI5qDjmEoPwg?e)`qhl5yDwdPgDU6%AE4=VQL( zfiG;KLB;xkdad|H;I~Gw>XSjbPqU}=xHOuHM{0n=(v3rwDNa0AnfV36?Ta~6%i$p! zCntIBU4_^+>s{lnwUw>`LZdB(g%KK6Bi+nn|2pqA!gv`b^=nUR1eh#&M6EHu@*s6% zch_pHtP(9;HWw_p{v5_^OJ418`8A03;yrF*0=HDo3Q!X+{i0B`UJV1{T46l_1x7CX zc5@_)ihbzg{@HEo0&KUIW(pX*T;d4)d?>K!2sy~=Kt;3!#Sxj})w9vah8QOTTxm#C zw~Xf+f&LQ^>Y(cPKnVym2Kys?f4AIiGp+cOnm|+NM9c>5f;KjZ<)6#j&bUk-!$dm_ z9B?*#UkZ~$;DlV7acdb>XijmV584@)u!_RNS-MGd)T?tydr>(4&&=mxem6D~i`mXUJcY!M7{m>H|6F*O4;KJ=QN92{*B-7xJ z_GkkxG~^pHhSMtFYSorQ$~^o6GyMxSS8CCDh5^?>u&TRN$yY{DG-|AqrGwM>tP!^^ z^E?(_)lA{eFarA2x||h_$?rx{3Gs!z%&Z!A=o=#I2e7E-%4n*oj;_x5hGUI^`_zc_5pg}S8KU)SrhL7R!`x!y!RS?wR zh#^MH+LOs(+#~aifV$oOGCL8rB)|`yNiAS=Q4lc@4!yj>glI^NnA_plemD1EP~az% zJyPsb)~v-Vn4VPOO|zi!YPpvo=($4{V!{tA3^CE+(oh;H;;m#6npaPtf*gNAQ7FcQ z1-Wm5u6+jCv`z`Y)!dmrN{odi4u&szwdIW zyoPdGh|DsG{EU~Ujs2lWUOtLRQa8oP7GbkaC98!a|gwbzUoATon(jHjw4l$7vPt+NW`9IvRy#x*yL?~eJW!Mm^HrsU|g+0F3q@YA)m(pS~1h=OPDa%#K)tlh`-Yb-GUx)piT`Mlry=nMozA8tTpUZUv5r1amG{7Z7Y0u&{ao6kuuH= z?uO~|l%^C__6!u}etPq*?kb%2nF=41qcHh{212VB*3siBq=Rs10!#JtGY5fi8^J1# z?d`5b+sPZvh-lN~kM$Y%r(UC(FF*74@ws=Z2b9mGK7A^6#sDKPd7CV%^`)>y>NnIj zb+HPg7UugcxG8y&COWQarDL)3bezBdZSsiDvG(!3l;awY??mi3i@nI#Zm-kW)B=Zc zl?dPvUt5jst7&hzi|&!u6K3g+UI{5$rYT_wP0#{dUtc5q>~ynH+}s_Co(DgAZ#dVJ z;+dRGV(9E;Tjjc{dW*6KTnTG;s7`*@KC97ls)=fwF^v*k6BY#@CE@;E1>4aFYQV1f zqUrn~r0m`X*09>_5zpmkK5BrOcElQ*OpqafDz3a)Z#D@j5t{Ps^KD(F7j+{K_~ywB z{LKGaF}clI`Gjs=OLmX{q%0LDC-(Ul$q&RXU(CNoM|o%je6Sgr1cDaY`8&tV?=oNO zMR8GNnNWI@+CU_mOLFUZ2s_{BFr9vOYxLyvibC1M}U_25TN!EGy4Cy0cwDirq7^QcK@;p)pxlF zrs1`2KykC(?`YzoV|VK1ByEeDH{;dcF_!sj>f-^ah|mDVd195{Y7c!MI!P!Jd|CFk z!*Fn&^*h;XoV_X=@5aSIQ=ulqsRHM^!N(ZuInv7asP^0w@Z4$W_gPuwx-~e$E(WV? zT&{&}2VNt5teqZYlaPnEqcF$-9mVV$0U^Nv{+hUZcQPa%Pb^_9&N^5Usz0*a!D#?3XBg{u2UDJbZ{$MxrqyA(8P7&;sn>bt!sLZ zIxTS39`3PQ$&qq4)H!7+eoUS_Jluby3L=n>k`gRg*rWc|dbjzW4ju@;lne`J`$E`C14Ji>SXyaOBFJ8xEefg`g|m|xzn#|nG&Ibzhx~m@|y5H3Ub!n z_F)EjU41ZNJ`@)brTi1${@dyarzlrXN7iMGFPjrOgyBtRz0O{Wg44V z6^oC@gd$z%_(vJZ$-mv)GE|9xY*8qtom&!+3 z*)ws;J`-L+xasX{KQ%0CXZOnVgS=pd^HRA@Q09mLn6^p2gLWxeKt~_*-UCwE+VPC< z#1VThz@B9BFrugE%clXxqbMy48w=P*a$$xz)lZ0=P2Ovx08c-u zey^uhgUFDxe$lm0r%1vazFnls4}MG5MTx!al5pR#`Vx3PaJp@HpC!dPMfdekgtFw*erJC_gl|tZ=ag?usIE+U zpD&p%RgS8(gY?lO>MRZg3j$?&SzvfD=m!IF8nA@OW3WAesB5Gsx!|d)9fc=CUFm~r zB@5Uh@u9dF3n+(aPbn4Lx-K|=#PQG<2jwHsY?t3@%fnv#>gFgCMJ4&83t{s*jY}I# z7HnTJ6V`YxxYRRju(^zr71+GG2NoJBtMyC%q~wK1hgzudtwr>8SQ83){tk7* z*EU>rbMczIh)ebS`9ZU5P9RU(47CuwyE`0|-)Aei$A88j*{m-95rmobp1hHCSo8K6 z>C#M-l^<3NJP$tX@TJwwh&Nh%;|DI3RnyRYV!ndChRir$&L zw0?tpfO%c^u%|A~^g}2@Tr^AWplGcgn=4G=kd&ZP{YR(5VTr0>hUG=ga|Ak^hAPDp zW>WN2DL-{X`FVD#*5qfF&Z5+=V~0sZWN-3Q<%hFRDIH9!JccK%B8Gd6@~^R>;=D`< z_1;t?9T+_1LmWfi-l25#XMbptGmp`%^K)}wx7m}!ATMl~LSp1J z{m?F-L@c?`@Xd6JP~E@j!6+Q+9-4We{U9T#QXZWF_zXACa+r=nOk_YgC6Uks<66?x z%UvI<$thuBWma0%!qvKtVS3E!y9!z5-j}yibd4(ea{^QB*BFd5r$UM#XVf83U>L*a z!&uSh|2PMmTu+M-GD2m{T}OYqgA7~lU6#De=!W; zBUt#VVeqPOC*U5fhB)DDND|UxV*7K1I>k|x&Q-0Xq~58|3o{`}UJ5I;(l94VTA|jI zADEbs{JNVZghfPVV|!OsW3TS$F>e<=pF}Jzp$yd^L5q>MiZTMBI#h6!QlL3*9E6PUx^X`>{EssHZ7B%Gb_kdcDda^#pJornjc5 z;Sp6$8YUeH%?kLqWqJeKAN&UtoR3wv6S((PUJ`RhE=T`&aBB4N(jN=K1Hq^$?}?Wd z-y~vFiFHzt;EFh;cbdNTgnn-d;Oopk@$JE}!xD93tpJG_K)u7aUzR`X&Ilab%gSQ7 z`{@5CEQ4em@juDkd- z8XUQUn=0qgwwivg*drJoL!%`eMTh%DjzIL9Ni?5v3s-rdJ)Cy1*@UD=Q1Qw1Lx_xxgJk))=4tO~Zdv1X%pgo4~9MG6i=;J~ZDy znaSm>$EUjz#|A=u>>QDKUxd;tv~b~*9N`q}M~fl4pfVi%3bZ?3E;g?t%Xq;gzGH2g zJ?|#8P%#!dvg0)2aGl=;#U{{=2|JXwcG{L~+1MzyUo0R1e zg%;&#J|*%ZQ@vMyz9VB@;0*7sl99@{2_tSd;WDJhV}5sF8Zkt1HHp0Dx&_fg8s?~3 z{qKXi4u@GNHG0-bEXkY2Fbb4~vleptJ63t!e&-2<>HlEYE$ADYd61|KR6ctp-4^qN zKTQ6QJq5r=V%i|24etL9x1igP+i(NU{qJ7khd#;M}VbK&58J|Gr}5!0m~*bs{hp+wuTz10|vw=034U-APk*ofi) zFa(&D0jc;SMBfg!aZx(?GGJ&my&tEG6CF=2LX`uq9H*tMJoIg}*Wpvm+r76_XhEWo zdK+a_eOZiN=J|sQuzOMRRwGf?%}Hd^v_KmAG;yjF)fwA!ygj+uCsEDdq{K6?!8pdU z*rH~m;gtWan&KX_o2{WPFiz}V2wo`fFYP<~?(oL$aj(0jACK~KfOJ8nK*z@S=90># zA#ifBg*$xB8xy9<`0#`Jj{}9DOK}5tc77`BaaCC0!N(r`aT~1-Gv&kaiBcbP!CDkGN%M`$ z%b7(-kL%-l=B=IsG!Zt+3q;=*zp(&tBlSmk%_JOEY?7 zG)#1E%0SLY5A73&&5_$Ja4~~*v}55_aSG7dg*PgsGN@JNjI;`-n!9w&$_S_xQ_9ig zsU5oQ@<~Nd0{h_l#9K98HQ|6S=gHm+pJp}_5D;2%PDB(V;ouw8Z9(JPm#D|iB zxcK-=oJGFts{%5(~;Hf%4a$d1v^A_ZI4_01#;zYA}J zT?lxB?x;WA!Z3U9{f7fI=&QkqZm6##57T2*Z;rlBE~lCO4@L+a02o2P{MudyeZ#7Z zTHQg^ufM~)8DKwgrmzNuidg6RDj+1V|8>~0Gbh4Gl6YA`Zya99A!q= zU+bTD2VeGO~Vn zu%7HFk2K!x-)iz8Tu9F6?MOoat(qRrT z(Jk7EU2D}GX!ppt_t}U!idPg790DI0FNX+^3bm*TNWjU_$}}xKi!P*Suc_$htr!UR z2{8qP$y3ZZ?=5vctW0Ms*gN}tnUL~5xSjJ zN9E|`gdi-Q`P&=urn5R=5)nD(Zoe`@VF~nBJNF#{IZNzEQSJSYXo!n;3aWPPmAk)8 zfv*h=qZqnUyXT|kftixyjFx|;RYc;ghY{oCS+UMY%k4OJ<{2HpWKv@^3{Pn`Zu(~$ z(QDmjy)v_0QE_%CF$`&9hTCJ;l=KqqlM)iPq~S*v3n^{m4pH>5i)@e2lQVwStG(-a zCsY?p3g?|(znD&-Ld$&G3uSt+f-y56j~vEYsMauN0z)OEQX*~a0?}tAG@Mtc=?AlK zrO09k86o&cv8^|n`LQ=`$bCki+{AtRc26!8X-eP47vYCVD?&SEHHsD8$@$k-?O4hc zOFJu5<%#y(rYA3^1(Lj2`=fa}*H(EA;Hvr#kuNwR@k$}i;cE?DBb(YJ=PoGP)z4l_ zuyp5C6~BA+h%P2VgMm;T_I~DxNV3LATme?;D1YS-wJ8WTRmzS*)8%V1D5@s5W(<*XdxLhaR+d83QDyzrA3tJ_N>-Puuso6p zMQSM1sBplR%GZO(c3XsXypE9NiC0Xy(cKGo-vFsS^Z0saAKOUA=W@04_`0{HAf{;G zG#frMV`%ttKA0Be2&{E%TqX4ETv=45v0VqdDNbH`VkKb>J9D+eBT>JIkBEs#%;kD+ zG|$8MHyRG7+Ydx93|f=It9frO5-jh^*Na@m`yZZ!)}4GC$gN89vfT)}Iqm%IuiA!l zX1BO#L~yyCc7HNzNekGo!en!AFJEoHrp52{dkdniUC(wvj@(<`M9 z>c+M%vEr2CoH3Myn7Com>pL5CB-pX`O85nF;hb-ap&HK~2Fo$dV7yx9f@ouexyV?A z`BpQT^}O}KRkWwqmCuGFyCh(z&d)H(5;^)^C5(0>pwqS~^86C~!|nM>N$SqOzBmXm zs8_gitAHDJxUKn658Se^Wxu3b1x<#&mhlr_1f_3lon}d=G(RJoo3YsNmMk>)xmhvO zQ~;B3Do4l1``;+8qorGmdmfXMue^RBYW(tL-Og&Pz3^sCQD5fkU+g!-#6=xdg#tR{ zdlVFWn!a^cAH}LDPbLN*Ms4E&=1suri+Frk<$MY7Pb|*^$03+eM|VMFlEPx z??ClNuOOE>unb{{l!l8z#XyKTRrgG>-hS~R>YE&7>UoY-L~h+33BLCs;p)OMFE#a; z7#0dP4|VATU?x-h$#%uiHeqVQ98P|zhNt2A{nHbD&2=d5!CgbNRT|SW&5e{(n5j&^ zD*PU3nPm11V;C4r;Q1CTW@+m3NJe9A3*&<=rr)$dUASa>&6y^*_z$;J zN4P&V>@lfy+mL@upWX+}>SO;q z_t183xtA!qE5hOpn0ngeizdJR7^)Ca(7wP?OjN0`_qxmeW4Qhdd)b9l>OKL6HAZz1 zHFr-igd%A_$95=f0~+`oAziFfi#a^87&7)gz1Jf24r@&{1ufaE6eu7IOWFwq%wV_**G@ z)667;oSJuPf6J#v{mB4NX%W(c6Y^n9;}Inf1*?lWRR)g+#~;tkI5E1xghK73I5L>` z+Y^-X8e#aI3>gO7)(BaT9ZU2gTw~pbnkmj*`J9#m()a72@nktUW(Wri1P0l|u`DKL z-*orse1}UVy&dEai37dV9-rFcF9bp!nfY9jU>c8`*=c>4*-vFwfH{iNlRHUi5V9GZ z5v}%k&EF zswzjy6c@=9Q5j@Ck1D589}#S_DQ(ZVBVU?yp^&%Z-?|WRp(gdo;UvVH@2R*gZJ?eH z0jgTIA=ku}`|s_sD~ec}$FKiS{7S5~`*RJSi03t2MgGvE`o2AJu}LbJZzs4NNC=6Oy(~~NF5#r|-NqP##j;pl)ovlsci&{r5K?mRAk(X=RFrRfjfq zMo>QW(cG5gW=%zj`vtkoM&@+mJ+M^Afb{7>hqGmk+Kc%v5>*MSiyEXD_4H%&LhXdq zUSvMhTtb*S%R{8#S0>qy*kCJok&*CE8X7Ck3?IV3b|GuNyYa~nAGGMuJ0`)954liy zbD@Ez(_V1|%R6r-)FFJC56?y@iD4DnhALZzjE`&B3#rxXw{YivqP@>VggVA*mP(~O zl(#YACXL_o(B&75n5&2@gDFO#MYD`j-(DZK@n&50(*}%n4Csp?syt~btQxz#)*Eld zE~#cuzw=!lf#g}cljqSnYDF8S=e^CEPX7h#CCX9q(Q@pnZ{0S>;s?UHd&6@V&Gr-i zQ4MTGNk5T++pcBl|qL8J+}kmy09C zsL4(@btV@vQ>2g_0J7fy^JvYPKkE62O~u2j_e{E_3U@4qrw)6#f67PrQuXV5;4I&% zdzRL{I5c(Iy4-S&CNV_$@IAg-O8hp;a?aw>@!}P)m{@5fr zn-nQ4N8saZ(h%6ND5KJyhWqqt8gJ0lifv8x}cso|ckWfW{56>YLbEIZ;sX(8mlGu5lpXKv|QJ2qp`+Ge#&dQNLCCS*&=Z_T_hDcd5~H1z$F@ zLZ&-f;{=6IIy=^_eWnOX+AE$T)MU23x|bY&R&qonh+W`B#aC>Tr6O{eymDeFQ37*F zFetOiIr+3DG?>7E8HC|s7+R3EUU*m!f4fVl{EyA-zL$D|ixy61M;IA;YCZv;ULir` z$5H@R1uXtL#3vdh<{p`x?0yh%Dh2Qk(zkElF29LgqSos>j;zY>sM+ElG4m*_I|VE@ zQ$6X=Tru`)6LXwW-kU%E=Kt=^_4>UVlo9Je$=@Zo+&+TqQ$;N!t|sI+{)si)L;&ID zbPDN+F@r^4)BUxs$NG6Dt0le%GEDtV8|4%kOT|aISy#_9w527D5t6ZyUeN{RctiNH7>x2Y`nPA58PS&PK<7=39lI%gFQ#u9S zG`gV~{AA+f5_!GT#)0~5K&i<3O@bp7?`!_&L+M((Rio0TfDf(1Oz&e-u6p9&@DAc7 z>pS{m#D!f<2}L1g<@-%9Qo1djGccDc-y`DTTE)L=f)Nc2h%j|=4MIg)32Hp51Vzrw zl!d?yACiV^0eGY;H_wCC?(H9WbML@e)ivlRJ^g2Hn0fN0e9t9wg2pDACwzwiMEKo` z#eTXuKW{Pv(uJjiN@XWl2;z3x9*6C}Yjr&qX{C1IdGHl0T5!bcs}bMxY;uRW%c1Hb zSeEGZ6-#5*N8WsS19D3DWBugj^G$<@Nc7Q{E7MiN;)@ObBR%*eP7cL&U1l*mO69v+E$ZaMB$X-#)1 z?CCT)E$#pu`b3%M$7v7$_Bva77k6m>^iWDXJtV6Z%`6gRA*bi~W=+FZrC?)cVjczFai~bm&x` zMgNll$TyVm@bl{7%5Xt zcm$ROLF%jX1A>pQQn_Kzv~Z&EjfuV|rwBw*x3-yGd{n|A5_%U@HJmcDQgx!Q72VsX zS*lmpnh(hY8*Ct@S{j7GFR3LsW02-yLytlfSRT@n48I_I+rsXo&S0TH$K&=?rkc~E zTY!^sKnU%oL*H-W0(sV8s;tQfl(b0JryBF4U`GSm#`;hppSe?Puf%eSHiqvBtfBRe zsdvQU_z=x>&dsT5AR-bQ|8$K)WAo6m>LG~h935^E&lgc*%M*gcSvDhr;>QYAz>3$! z-ZXzRhny*1+Jp>X0?4v$Jl}i{G|F*sPkYm@GfX>I08Q|3qV?FBx#0Zx6F+f<+mn&O8r&xWmHc_>we?**&mtf7U=wpSg!5LPK?u>xB8Cbc!438Cw zf~DU@Zpq}<}C+?7vGY{p};ENba9od zdmR%|hjcY-%6VOWA8dYbi@plS;ZI+q&E8l{PmqHP%J+sJWnHng?9j7_)!96iu?1oL zN>EhImkIDzfPinT^+?>#ScJ!n3Ym%O!58|C5#*lQfCxdMnE?@nohSb^S${+7B9?6+ z66NiV6ti*6C2E`DTx+-6oHPJWQ0K%HVC`tXv{)%i&ckP1U<{OfCGA7_A@KzhCfMJi zKLhqIlePHzXU1$Unk%8?KcXWUtWbhAK!o584`F<}u+&kV{Ds3r#gX=#rjKRuoOQ?i zHKqG=M#7sg#7f5t10PtJU=q=i%K?-L{mo_$<&QoUFyhis1_mziFy8$350;|pQI9oN zZ-*yx^x}@#hFX_|=E$a`o<42xxZpT!2i~F7I;#{tyWO{w+WD<2F%5Yxx?1@&M9)=o zP%hJ~Ztg!2In8eN2WX(~<=(=b9r?{X@H4v!s9k_eW*yQHYVw^oRYT3UKhfvwxgdz+cZwOxIJ^We|gUk+j6&n-f6_Jn`=6hhCalY)KFGW2UT z(>;36DJ0Zgm$Hy`9vQlg;(Egx34~WtU;S9#R!!oo$1um33 zIq_$T^tS9{1d6``n+u3#f*;gU97m0biOeT8@}+*lB_j%YpT*fAx+2@u=;rg#GS3k7 zV9lcpV7nb+f2#QU{O5T0b;k2(lp}wM|4E(zrA|dnDXc+NGQ(arP;Fne85h~b_TLCg zLDedoxN!L2d^0iaq)f2IYg|JY_L79Qz`AtWy8AIsDa#VHr~> z9-j;x5?8R(I%Zi7(U3q3D|&Zi&U?51?DN?7C~ZqYo;})zGP6{=d3EcbSl<0G zLUgWSi3Sk~>YevV>8S&uZJ3lOORMY}jB3++C!C8sT`r&Xvj!Mx`I^cG;5+-094X{_ zE+vHUO*19=VYzdPmClaL!!hE!>@FU2EDaybLXTpnJspFAIq@3Yu#}p7|;%JJ9UIG zF@t?u2;f*0?}MK*=*d83WMDAt>90h*4W{@53q_JA<{SHS@Pvs|;@WzRF@=A;04MBa zvP7osy#B$#yw~GQ%Y*3@BnjQU3xbApvNVs5@)_Uxj~z0!7!wxiQD&$@YE;6P$vR(# z={sgh?ra$Zuyesz-m1zJ%N##^7}N=<&?i;vv>Q*a9vu959d)|-?lp1!%XLfmCqj6s z9IH6y=SD{WeJ)Ul<~9!v3mVCd`FE##F~8irYp8x!(r$S_T93UK_qNrn*3T9d^Zu^( z3GIK`5Otd8QQ&BMO#dn=MG}=Uz5+A#KeST)tS%d5_0#VL$-=43VDn?aVCG^e%#qM< zM6#q5>DgSQR4D*B0v}u$Z4eZZAB=!HsWPFgtge#Q^S(B4x%U<|8_Kw}iZ_DPBL0H_ z{w^q23jpz%uKq_^-{|SkmIsB)%uu5<9@A$%meU{vyTBU?ruXr~bBt4MJa#5z`XkXi zc)kwE6E#993Deu$!{e1sW}Y?=Yz)o>6n@aGYzpwRw+-{&T6^Ykvb{gnEao0- z_ifBcKs9`L)TI7jnkdU@vU@r5uEJYvN9^mEuW~n`dWAxcb`>M&w(raPgU7Gl$V?t% zf}XMa=ETFVpn>f{G>Td_FPMhQz8rk)k7DBK9FnUUus_RRM!Nku!8=5tH?9LzVw7et zP0V4|z8Z&_&1OUPb0}+V!|C&+7?SX@3(O+B5_e!EK(;39pM225 zu%^O~Aq=lnPuRc|N7l}^34+*=7v|*5adHZ`wf(}TRT>znK%E!F7}LcqGL=9uWiq&% zD8ya6q%@$6ll54*LYdLOoZANZN*E{654a})DxZTy|C(M(gD65gU7RwgRe0|uVehZV z0`ztH_XHT*AEGH*+0=%YeRQ!hycL`uKf0}B2<(goE?%%BiJX!rC1v3Os#Qu?iKvw% zpBqwFJ4ExC!A3NHY^K#~p%G;Nqt};^pGWgG-+YNSsY>kJ9&#yP7v5AkdXA4S6m1TU z#dGnz?e|amJ-O`(D5ddT{F6g(&<~27H2K|s5M7z&GZH|s#@6@y@)v0iOs&BPut@-e ziy1ZvzB)UO(y+>ZIk^Ey&6rQT|Ii+>TBg+laDxP!=3hmlfn#gO{`5=xUdMuC?AURU zZ8mmM+3-gNq}2G4>J`PmmMhss4CIWL-}Uq@;kJHg5|O3Jfqb%876~>X;aBxqPV{dU ztfte{t}PlTQ?_9GwXC}zj1QBe!W}5ma)4GVa^vr1HmT$0GZ+@dBW#l`Q_IQ-CmZ5= zh_N|`*iww!6@n%SG%X|Kozj>;J zw$Z6cU%_Jc-YSUnIOI|>#`{JC@I+H0GmpR3mMW1|eL19f%%_>Y!T@F7l$G-))r>%D~U<8HQjJU^%<_f;aJy; z|CiBlQ;S^zz2IMZI7S|ajQ?ve7V)U4I(7YnfwD|F5Nmn&ix1tKHoH#pYfwTuZLD%pyYEZtHKzFtX@npAxq^#nT&N^*K8A_;kldVu>wVz;xJ-_`nRp=$+w&F z&TEn|{n$Mege|0Wg0S@aRLOYJf5bMYJ8@?T-IYuuRzUrUbh|q%;2jZUfp<^t5(zFO z5k7nYj>AYO23$P8={2SeJO_-#(tUPa)tf`KX`^c_FowRKk`l7>2bt8dqceS-Dst|p zcF#r0`@=sZ-IdS4-d$~edvR60w^x3pMbdc{_z$ZFVnu_04|F7qw1~WXb*qjm^{Hw= zKvclsig(gIl9=N(dkoyyZPWnpae2rPwu z+Wx$uoxE`B2hwEJp;%8`l*qj~tl@TKh-VNX{Nygca`8qN3C*H^;79Mq;DLjWz%9+N znU(qV^bl>EahJm9DXpy@MkJ<0or%>ivSG>mW0oHI;Iw&7y9x~ycjs5}ghi!c{}Uqc z!?dx`0w}#&s&Iqodx;L_Ms!dpMo2?Jov2F~&IsjnrYsDK(jdX|(9FX!@zR(4J>@nW z2Z~2)+yLETQmqark?r5OJWm6CnQ`+aSAd_e&qVXuEfM7^d`lX%Hm~vN zDOU`+XvJ!c6!AS0>6Mtt+io5bsIil6{ty&*$7b@27JIa7^^^Igw)a{SQ&oU z-(r5{858ggA0+47SswMVF3$jOOhlc4w)*uv)&saMPnovQSZ?ZunWp;S?@cmKvvsNN1#jUmZ?Q|G0H{cuo;NQAV~&HUn=s zR*i!haW~C^Go+J$CMKTDa(bOKJQ<)k~k~Z z&#M0DFc?P!f1q*tP8nK-HB#fFb__=|Tieh`Xo@0?ifeCnW520h6Lc!9@ERJU1K zE}z6~Uwyr!G;AgpRnh1~JO{|mgN_@p@*l*E%N|mr2rV9I_)?bljOC9meFc?x1^Uus zrQVSki5|}x@lICOT&H+x2N+OZs%B{&!InRenM8Q-f?c_4C#YvjAvF6$&k9b=Dl8%w_bFKW~G z(;Kye!3jE+D~x zb6a5}PL#~5WTXAf>%9^oc}1`OdiTbqeaz;KvcE$s1&h=|-qk5!R3ZP{n`f;`K2zf;yphI*V30J#9?wc%Lv zWAEA%Pa$6i?PQ9K_TGmWcTAyOf(@3q7!2{@w1DAj584icwo6E~u=yOQYi=`oY^~+0 zGpI8VhRWtLgtz>DkDszGoS;ZP23Lpw`gP2Gc1CIx56+JSh#5X^uBCUvu@wpwkM{Fv z#A}rpkfqaXD^>nr7Z+cG?K)%yUSXX!C*#^Q-Ra|R^AN43RX{$8xFNJk^+7fsEmL%8 z_=7ukGp}l;TQkR-`CrCVp;|rmH)MqHvH#oFdrI8YxQCgICS5NsT83*rx$7H<2=EU2 zDz{s5?tPS41W<>YfuYSN7oY8mBmG~*@LN#4LtjFBpq7UBkCyVMBNgUxubL3QBVYY5 zOv4XbS})8>1O%$?cc7j$G7b5ktSW*_9yiDS+QiC-@f>b((&Hw!)N0Rj9tR_Z6i`hu z#mL9IbhfY+lY|83@W(4ztgP%~%ttHc|4?2%TNtE?)8t*=@5LOpt$t&WNo|zeQRBc3 zqb0!x+>#{5L%w7t%r)5vV-8s>IgFuUXPXWT57))-+HQqa*52Xc>-{e>&OKCTv9x}G z4NRUs&AgmzScjkS8uFV0@)1za4$0+xU)Re1^G+nOc=eHclg{O)HCiG7YExyff)VEZKF6s7$*KjdvD75y5)K_Ht>OE#g>P8O% zX7Dc}RZVv$5`={CjOq_;(a1Sj8B`Ap{KK7F}Z3SsgCEF5(7k%+;8<7?~c zwHw>^0eHb*E+ghH#oj*+=wrVLB5;9$%Um(00o?h!Z6-(AegQF9Z=7HJ_mxq0fWNIl zxnDVcHL!!&1&NO|_&lSyzT+)N-&$rb5aSKho`7?f)^S(7>)n7g`{T9*GL0I zZw2PmpF8ERffMBB1*HvZ&QFHP8i%-B)j|VgvDwQNJ^@!t*B;h5d79o^QPbSvKX7gI zV%(SYmS@|4GplpK(tu~yI2!h%SSOfTmQs@CQ9jT_m=ckQ0wWFBsNcLU6JQ`r$;imx zfXcVUwk_Oas*w@R>fpc*k{~b`duW->maeTa@QL!n3wn4Bzd?rKsvUf=ug4x)rPG+f ztfx2O<4Qm4w5!4O(tC+rTz98kK2edt$)Tt}^qJUNBiOX}h)shSYq+zAFo1-=8)}J& zDbyzbxhk<8#a-JXmH1#)o2Y2x2W4Q?HQo`q&n>22bmyJ?i_$U#0A8o4vZcC0@` zp0hmNuP;cyFeHT%-hn3ktPuaU{MWE>jPx7Lc00$f*ZMZ;gQYgbsA&EN1vgTGc}IVf zK42;Yd`~~#qFbz6Hyv*pZCY;`;CTmIOZeOnjdcSJ4lhe5-`nms|KwGm;clI=PDT(E z>XjO6>mvycGP-@EG$w%-8&ATZD!F>Bc-R=2!A$FsY~pew+|)6Y%P!;PlIZ1OMj9~g z-Zt!f8z;4@s`4jPWP}bv1O({Z?unrS?<{FZ9$yo?O_z0NRp<^&7G}Dj-}uQEciWBT zodFlhb6PjV2mGU7Kh3swCegvSUxLT!jINNhG0SXxSO3RzK)ifQli}L^K^eRDz}x}k z1zN?Oz7T@hQfY?}aTtNKbiJ~%li2sx=KDx8Lj#&N>2QTN299gwI|&jp^Ra{J7fz09 zV#gq75zqZAJX{F5g6IJ)-Ew7B@!0jOLLwC-=isAT0l_oMQ{x(xM2aOREzHO?Mpbt*W8rv|&men6&D0kk zOud(O&_YLiabnlAqHi&{aP(6C$vq6E-%++43Ln-CZ+$_4erqVCT$sri_@gLHUyA#3 ze$FDOkh-2YJsm>}xUkebrW>ES&1CZbwZ;h*J`{v8d#4VyZenJ*_&kgq-~D)M!($7B z8_7B1-ovS)C(PMsE7Bsfv~tDJ0IDgY-opYoK)S#Uw6l}ZX3A7%rVbaxs#3ep&Dy%P z#o|#f&N3Q?ryOgGRbgjE9H~iX6k$qqAM@<-)~^E13Rj&o=aqu76W2CNB2bbC;J`yt z0**StK6Qxg_}lK5H~zs78Mz&yZ<=D)0nI2N^r9xSu!!067h0aY1I=Fy;T9$?V(GUo zChAyl`r^W5KZNhCc@r|EICo%j=-ZF?G1U*yBZ1fDyL*nO!@pYi7OB z@c5p4^$9yphF)xs;pza~ZW7_Emq~*g5z7+%iaG(&J3LHdF==^{iNn&p@KcUL1|~6t z@<#Ge%c~#@0fz9P9E7x)Ly_Ja+iJz#NE~mU!Mauns+1+g1?=B=Br4O?s#(Za=Q4YgdZgSX(MBt6)6#U5fU;x#OP^_7cKX?~421u^&E~@~70U zwb3OSWG}jVPj4Jy6#V|Nb_UBh5kRFF#O>2&S##ddLxeZw z($uuP8sDjEkL8Ht)Zh8^m~z_>Qe2eMVLRI|x+_V0%B2E#{wcraup0XxBNY_nBN3b+ zX6OH~;7!`4U{bX`4(9a2gM)|E-?L+o?xjH5f7KqKbiCcutnvlSGGmM9z7&7TZC~7% zb~W~V8lB#8C3FQAVlOR27$&~?FS*p!wb}`NEB1J%bG_dgj@M`Xto8q>@7y^>o1Ac}zi}!p zE2i0~Sg>4}!L16tv5^~X%=Xf+NTlBtZV=ZF;YM!IGygP7BrKzif_@&f6)|IKpql=f z0+-QV?cHAEeR}byyqdx%20Ma}J8Cb&nf`;xWK zoMO^k))#G)d|38uPxOs!JBB~UTtv+xTU*oewB9~YJI8R<=Uu;9$(6TmCW0~h$aE*B zib{{E;5Bc=7E1@~?mKnfElTB&xyj65aq(7I^mRMLe!)^a8 zZhFTO-iLEuU%J?|e8b|tEKSl)K~de{0y`S*%%QWPl*H|nN0Fc=@MvgvSDWaN&yjo8Dch9{fV z%&Ny@Z_AAODr}^y@i4W_VmzXpJ;O_r(VdJfH-zb|r;g~CPKNVSePI@SeupSU;BETU z?a6KusdPCSpD4u}F1{roI95a~eQ&fl5UF2qAk1n9Da{05@@JlVon_xMRM&km=a=#} zV|LvG4>3AN-P}O0cJcYO$Je4ub<+(C?C15Kvx7uG+qv$pn=QSQj`gpcF5Wtz%yEcs zc~fL6c0~UO`@S;&VZWCzoIM+Rz(uP+N`)<`VHHn6tMO^7F$zVI%ab|TG#n3Lpm{2+ ztz$i4US-W&9#7sqJ()9~QMV*gI@oaN3D?>0!v)nA&*lKQ`}?S+s_@zTPiuZA0q-eu z@SQRO`YeF7s?nEnHC}#$X*!@-dcLt4w8wgHX?Cpn`oHC;FLO*f8Tggf!a_JIx#r{B z7QQmQgV*9d#0eU&thQmhsk9sSeN);~<|3^3Yw3|{n9#@G7GCk_+k^h!r14(5S%np~ zT+c0Zi6$hiScB86gO#xDCfe36Jx{|hY8}^}L4jfnT;+bv`+4wo9rY6zng2siEVI)EHa6g&^ znHnw1&TY(hA`5B%)xVHwg%aCpHKV_W`Ch)@7Q@2m@XO*$#~#CBql}@%yGKrI>dua_ z?Y$X`=}67@KA=z>Xa4O(Q;<$&p-J4v)2iX@q_JO<)As75nV#jZmC`h(;Pjqk^?QVK z9$^Sa8Hu2Y>XE!|zEa+_+J4jeo5hn3MsZUA=PW<)%#=*K;(7^5V-cUXRfUY{l!*!K zpX(yOpDv`-#eBCgJN-wsh<1=ky7PCLG3trj@Cb3A;T)!*%hB+nfkY8)&tJO!wdc^p z8@K9)ImsakG`R3c>GPYHzH0}$xZ?g2l|Q$V{-r8JJXa@ks{A%&dTre^DtMy?JOByf zOb9N9Uk;#5^S5_jgjK%~EZ1PQ$_vZx{eh!3DWjq|az!ub)$))rAD@$Y?_)xS`ED)SPNIU zt8RVd4*u3*dW~qwi&OS9`Ywkat-OnnFcz75NNA=c&S)f$_WfQ^_+_J$##YUg+k8bC zD05_SDOz{RHPATJk7s#t$amB-yCk%sJVjFgXSa?MyN^py?OS$`(_%GT%dgDh?VdcI z6i@S7_`5|}rA{>7xhidq188BwG0kSkr474*@%>r&F@&jLi%diS8riP%;c1K3}%OsDv5-$#{ zCDl|4x`~#?=WE-f>2Q=SSkLI2$b0T#%2{B*NWgc|L)gI6Vzpk z?BzGF46@JYsD0@hzj(hZ@gxfY1hW^9W$Q4heh?lvYj|-$1nBShS%)sW@kYZg^33$< zX|)(aX#euYsoa}(>u^$s;4hzWoCQsu?tpD9G3JESnCNO!~ z1KFhEN#u*YDemH*xNq>R`c z_eByX?GiA$8BPx_6cP1ih}Cv%vW20=&3JP%Tec?Vr1(QW{Wo^~8pQ(B7c)zZHCv_P z{Z;Gf&T4tf@8<)5r*qqJuB}@;d+5}96Gu0XvdjtAXCeENqHmp3*U%vCpb2&P`iczB zelBkBk5n?eUt>4p;k^nkX4Yu@u(;{f-Y+D@#FSK<);+eMw=X%5d1SD#)?f6ldcm=O zv7c{yzqZPr2cFdH-T&zEHAbuRQN*9p_>EZ&r=?r0uc5&%%WYcZFZ@kUo%1AYtE~W0 zLn#Ht4AQe@;_fOJe0gUUox@N4b6@(ExA9NjwT@{raYVK8{(MKhO)+EDc%8}@I z;YCp-S0}V)SjLAFx{T|V@avIh3f-HJ>LxOH-v9n}ybK#$_;uW6|DeDva`8?~V6_yQ zh$NWU_>=+#tLwT(%pOYS^fmXTbHksO*|{!@^thBrkGXpd8laoj9at5 z!NAagQo#k&AJZ)JuGF{R>?3idMm176TNmfy$@BQ~0neCbwogMds-#F1A|rAwZ*zj7 zXJNMTzdWMg4(`)~<3G+)pz4?WwR#R6tvEvBNiUkd2Wmb>AG_?A?G&gN`X;lhj~&bN zBCk`M%9vFkv7yz%*VB-LE8BUD_g4#6r*BF0)$wxAH)cpocUX@6mf!pXSt<5&fnKdv zOFi`!W=k{bDtrqT!!LbFyG;=yK-z5@LXiq@TeX!?l}H>!fQ(R>%-NR~-u}-FUu4w| zYgojk=_H0@u*GX4#;GK4x@Lwcy_?sYn!5f5Th~yLo2$pV4}YLcOgye>_j8%0d?gcM z&A-|)D>c^bM&x!Vhq~Wz9{kslMb;XtrnNoY$3m)KgmI}+=Ik3g^SabAJIBewf^O`L zz56}lC+56M`gCem{Y9q<$7sY1ptWBGbQ-R{(O75W`XANr?&f!YbaIUD?T7E^!W4R+ z+a)53U+5Xw1p^13H^+-wN_d@M2)VKAKT1~O-5TVDi6PiZgBWn7YC8#we)JkgMyzKQ ztOlnyaKd-a3|C&1K}`>Djn!?f{HLWK*PMx5Q_GAs^==j^AJ&Z@Z&>%-y1n~1*jRq? zwK8XvpwE3Sc@qYPBIKER~af1?E?gn{<(+D^7XLc~`!6x&PX0YFXH_ z@#LHvLv!h2_tLdPe=W|ip(c~>|GJ$=&^Gg!KH$T-lW93dd23E%7gufPvyB4%)Qi{o zi4P?Hk&BNPBRU_>f+~@H^ zkz4L0Ddwv3e5of0gLS-7w@VC;SdOq;gKW{Vyb-jLi{CMM?jVz-Af8TdVA+0YxfAqi zn2M)LZj0=h>wQJ*XXS>U3;(&Z-f9p7ZWzQek2>59fU_^i*xgK4e|=rH%1gHLJ}WAz z@cF_rttM$AJu+71lZZJ-DV24MM)LIk0-9il&F$#|4&Z0A8|-e0J&L^6Vx;Q_T*09H zKkAtHXl#1J#qgHN^oG5LzscMcND(a%Z)4`NM+QB_(qY3fbP!Q5&mUd-?TPg_z!>U~ zsXpuH_orjR&9`08;>7(fxMwBMt#d!_+N_Qz2gwA`sV{4r-Ca!g+G0Azi$DAA(*hEc z>*M2bxGP;MHv-7yd7u#++T@@B0o@C@!$f!(2B$2{ez_iT`qZi7cB3dIKDM{;+RP7Q z&Mj?i4gh-?8h1yvTC5B$y?if_;!{fcPx3XvYJ_9Dkl`Zgnnypqp|X4PX+B--^v2Rf zhl;E3C5?r{Kj)AVQ9+5k;)X)P)-z^4w&&&Zj?(yk!`oUvAP)Q=CBLKMJi`=Yygeh$_IPOZUjygJN zxQVY<2v$d^J753Wl-$LjBWoP@@&xCiVaI&mhg8|MXP<`-*aWLjnsvRuZp|^sAzRdZ zLOJ#-DWR(1@clUiRFSQy%To(`vE|_*w<fs#d$&esJ!+{|zbFZ0)n#{3h4$KqFiVz-A2?57}QI$*ZA z;b!6(%H@9CdzmXwbPn`7=bdn8Eb+Bd30hZiHtp3Sy#RUaDB}!|#*h2gGKX z61cW8WEA995Dd8~PfTe4Xq0RDxbsEzwFM$-ykAx!nZu!JlkZ{7HV**z>A$4T0U8ir zv@#qwzujIrKvA-JzNDDnz@Mh0`mlHE%TN)mpfUbLY3-J3LJxJtm=zsEj)Bx=cQ_BhF zIP3nqfz`}*y9yADcu1H(%JwweYcmZHRW&lncdl7lwio>Rpv8_+$J@ceu=9KpK__n z1|4P`Fh9B+b;rE4dD5B|H@86M4YfYf)~T?C4P3ci%<~oF{{3isQox%<;k%!oz-vk3 z{jzwhvLwwlB>T=6$#hs9J<-|_^{{H+#C-S9*2TmpOC!lKAEPRNaA#UuiznB99r=0r zqHu@#IX2aq53ZJ?Y6ryju(Ky!y-Y*|DTHu@x~3%vez>Jm16-_45tL+K3k@Gi&QyLTTQ}pSYPa$kIUJ9s<5;KtbaP*Q zyNz7w=`%`d8$SeYEqHL{_pAv;&L$J}iWX=!*Z8SE^PY2;4kFN_E@-`tRo>OrS29K9 zvc*`mx3|~R#Sm`W+1r~tI?};W1V1w9qU!tl`|068FXQ`!yVLeF{#rMM2(_})i-ef_ zhF5io^^c?pLC5sGWh1GSmTYD`j+%)a%`eo4>wWzixsEfuN`tj%Tpdc+fSVFk?qP4e zy4!`0A1xH?Or>Q>Nk*ns=P^F|L9P552kPFF)ozUi)YbG{jlsyhAIS1%_Z*IjKZW7v zE$V5ei@|>y91Od9>H}Qk+vAXpN{my7U(gnl*wcM$k{#rny<;hzt?<(3xQ+4D@eDZh z$0(p!_eCC-n=w=37hm`b*ZVwqALnVb4=|?QZ!RNLEgiz_-*bxV?Gfc$6?ig1O-`P? zC)An9(;GUM6mo1;zfN!1ibbg4@v{ZXw?6ux3_)0q{4skM5aHtKd;Nt@_XNwAFLiF|3HSTd`XEu zitbkRmkD!Eev;p?Au-Zk{*Xq?_jZ7Q%x*$sl$MhF3Wq9{Ci8)($#DPkdSY{(y8Qlx zAlFTs*t$Eh^`7J7?hZ`MeI7x2GG~4eCiIat+Jc|@<{PI@7SCPoBv4{G`KUVHKmUfO(B-`7XhOYNzTx{;XaO}!sV%-_Z!fqoY9R*qa)lbj{ zwCLF_CcDb2KPN5vq5Jc?RIF!YKeKm{TMZ5!V0!K<2&WH!$TOz(ZKms{31`d9_M2yX zv04++J+;B2w4&~o-{ZB1up!eTJE)NxMDTk4dxBb1AYrx3^9)M!thp~9MWNu|nxA&{@Nf|p)Qazica}Gfpk2IFr#l7*hs+*i>7;E%=8F!yC!AF}Pb;)t z>%02&vdF9Ci24FDUoT_kDwaes;=wpoaZ`JCzZGSoqO2V5w*Ya$k1Ve=kOqaD8PMJ{ z#geG_@OPmcRK5%kjslIQqia8oRtq1%$|{ouq~-W69H2+jYO)H=vISMrp<5j;Xl-%x z3i897?A3D^=jP^C9FC@!Lh0a{)YQ}<%g8X1&Y&AGC`SwxoO-F66EMInKD~$@z*{|c z#Yvy6sE)g?n-}Y%NuB1VOZ>Iyhgy5SloC-}Xj~Y3BJNOn0;W9cu-k%L@V@^xsIUtL zjqi^rOIcnG*oP8d(Cg|lqL0AM?Y=^@-M?wcaDCJD`OQ6Dl6x(A?{9V&bxY#qRZkqX ztCc3h4Sv~=pL#ly(J|&+1v5pr7#bA~E$!=>rHQ(De3RixmhZ+edz>G`Q>E46ugN&3 znxm3cTc_EOa3>*R6vY=zahhP}EsIL>U8#1iDvaUDi)TOj|8%FSr>4Vhp506)#!uv@ zlQqQG#Q3>HDF~=fUwG@5TMwsy+(%BHej#NbbC8oyQGus-OjZo~>pi`7T<&Um7Bi!o z?=3BUjl%NFVHt~|8m`i8S|wr<5>P0-w`xtHNl~DmgdV2Z4f9c#PUmE@7pwwW-Q0#J zcM{^trKUG@o6919(ki(J_YEBwg=JtnA(`wWM_iJXiqQ98^5@yuwX*-~W!(NZe-14q z${P2O4>#K1oiZAI?=2OQ;9apGeJ)_r_3(7{`TqJA_H<$`TF`AJ!E3PWLU3q)yn*K5 z4rI(NKXw}_610&Kn}mc!aaEP|ycQHn$rT!K%#%V@u-EcfEVzX!xXYz@k|URn{?v~l zUdD8riwP(9rErp-ymwu3Np|>4A06F1(L*=!IE8K&>28gq&t3dB*0_=sXDzp$`gNu# z7kqnPB1?D^^$%3ku1m=XN0N`Cy3_j0#wCT`QQYp3J;)pqps9jh=5h$R&sOsu! zcwZnqYkFico^m?>R9JPW)|KcpOBK+Q*jom<@DXg5aIpL`hTfr{Uu;rRZ~l{e4vSZt zT&rSHmQEYdu)Q)G{ayVwPo6=y!4&Go?XIo}zuRylOI8=S?0rM)!YpGqT9TxwhjZ;0 z4BJrMJjw?j@m+EAeE!DTsV>aQN_s0y<_{J5lgDD{0*;!(&9sYHTI7OWL8Y9LVvWHs z8p&jNdvC>}P9OU!YZ{}jo2Lc$M(bymj+1JwVOk4a_uEI@;zL_z)TY~*A@}BohVe+g z`NXT6lYTg2ft9VDxIF$a866!3#&w@&^byJKz%Qs%^IZ{TeHpr{(2s|SA@%-Y-%AtUqxfFfbfB0|X~0!{Wt6v_JeVptJo*vC zw2^N%VH=xhMSPPkzll+UVLL9FatfVQ+70i*Krjrps?F#=blh?hCBcQ1bR1$Fiy=Zk6|Aptap;hzjAMZY<-XU|6T zg=Alc3VQy&4IPct9j=*tRJ=iv(;0H>T=*@Yt((3W>?Yix0ei_ySYC4OHu>|ut76D+ zBMoF05Ja+SqtY`jH@#t9v1dd9Q%0kJe_U2OY>PZWXw53#vX`*YDt?ju;pf>s@pYGP zyna<9Eb@9m2sMf-U;LO;om{{~j(xREr`txU4gZhrQ9pPQM*TKQ$^Fl$KclUvxMv3- zzk|D1+F*VfL_NAAV`H8SbTF+amEyQRNV&B=6kp~$s>&Ja=Rs)GL@ zYE`aTzAn^qzAKeHtN)ymXRv7Z-F_{a^UZg!eXC~iaZA6nUvt42mf6On7<=`3qsb0Y z^!cCU$D6wB4XFe6747f2c^M514bQCZ#oV~q)YjOfo*+`d z>0`Yx`al=!_gU|qprCB1O-%D%da_OblCQ&U%F7xP9-qwOK94#bI8k}zk!?W2^javx zTLW}b_tBK&1qlOZ;_TZvuqw~LECe@5JVabY(B zlU@J&5gw0sPki#^-K$ptq-!Z1;0kt|XLuXbVj2V&at^pf&qU9}>3Ol}?w`g76-Fj1 zqMBBF*DK!|kZoPi*+2aJbje`d+vc3{GrsEDmRX#v{VQt7-9Ilf?sy@V>WzhZQqT;x z!mGeLKv21uIBVPI?C#2YZfjy)630!>&Ak`DUD)A7*-iDhGWvLBct((NoEuic+{`a1 z*w4ns_GMr|Z1ouC201iE%*rv@vzA~37_eKZJETb`Lv!H;`R3SA$MHt87j`{GwRKDr zB*4DwePWE^g?48u9TuhIi`1Gi+D<4!tqXO!!tkS&V`PFHC&^#sbdn!ODZ!8)P9?kg zBiD?>eLo5Y$dzXw97abjq5vkk&2iJiKU)0MyYHX^78l(YQbO?V{ewewR@M#XI%aUH z)U*DK$)SYcrTjm^F1ppvmf~h%SJE*#qE`P}^9e&?xtd*FX_lKwsD;Ajd_U19>dbj+ z&GR&x)aEw=prN~vV{Zmx-2)6I-S3bIBA?YR49hXy=h31cWK2&E`Au)gnl1|^QLRkO zK3g+Ze!djf%--eGF~R5Ke|mqT)AEbZ>Gj=Bw3^BNTJuG|1^1A(xNftyhBqRT9U~*= z&`ErDl?HU;SV%+OWnMAY1_M-vk^tq>FT26dS931@b3ESMsv+WCGDX1UfYo#r&KIc^ z1We3H&WP_FS*m*}$VuP?NaeMPe)@eu4=(JZkH^4vDOFi|=F7(~!}%Th?L%& zE7zAEm{%<#s3-hi{&9Ca;(Y#h^4w?rcSe;yw+t*u8ymN-2h9YQGe$o*UFbU_9^NN% zp?wVKX3ziI5S0P;?UXmZ!CZkW7_Wl<%R~e+8HG{KkN4fUjmePe0F@x6o zBe8FIZ=dD;nZqY$jqTJ8hepIxJM_fVDzb@A*K$(gfa!iy9oeWKo~MIDZQ@V0e4x}u zeM(W!FsZOS@see!AFtRWc0g-^MpK9NUR1S@TJ6UQbkiB}!jJYmyssu*c{wAFa7M8C zGVz|l584O!Pg~$sFw&3W2{3L6nj>DfhO>0g_L0@zlaI79IdEwGxC>cC%Kd%5Q)xjO z%@Eq6jEr3nz~m9sqU;|Sc>DD$_qtzQyCM%SV@QMf!Gi~{!c*ihgw6PCx>@9hpD#I3 zT``T!SB&Tz;u@g;-7oYjY0o}*1KbNklRL-A@_5Yx4812}3(0W)hjtSTLjltsIZB1# zZ)b9Z{KF>>y@EF(`cm+o34H!sA|nEgISP3_r`37uj0icPE1$A-E@_Bzjr=k`_}OQ& ztF8_Ey-xP2oa4lAgNC}dhf*z?D_rl#5M-deMjdX!y&qyu9dh&hliXTh+A~x|sg+8AgSy}?f^+k13eEig9OncpGdEf40=p~s2k^<-gwi+_07wd=kQT$y^S(0+dQ47Jgf z<4bp8C)}AfV5Ock?z!!6=g+mRC>7Ms3%bE1sS|$#^el%FuC1sL0D<;f-?FKutk^uOL5~GTatdnu5vb?6@{Og~S$ zk4+V>c}@ap;ZveuW7xh)Z*;*jWC_N+IUp8`jM4hm%V!s-P`amGMt(j)=@xBQyZ+?> zFZK(`ySna>&v^u2M-sDi{>tWjJ~r8DGqnUS5X*$}4c)!8hT@Hl=Xy3ojXe zU~>KmpK0ld%mXquGatSCJ_ zJ-UeZVaT^9Y!6gpVR?*nLPCP$WC#EAdB&*hw+qFqb8FlBAnHSqM@^hMb4Kmffo9#k zpZ6|D;O-IL*VE}9IX-hr`;Ni%mz~-EfFuCwnLKIr*|#4A$!rY0(QZn@C5;W7vMdTD zqTD+KGSI*J$nifM|EEp%{1u7t&d{OZ^R?RHjv%D}i$5Y*0G1DEm6t}x2o_YUUwV)# z9$AZqb)EWos4B}SfauAQ+ELGo@=5m_rfrN$^d`rSsWEO>`}lETii4>P^z_yNNFhhU z521hnCOFhBZl>kLJ4LE^`wN~pD<$lt7a*0d@$HJVIY06AG_7Xv zlNG1Mo7oA!p_*rGXU#q%BH6$iO}at~->8l`40h+~Vt=JvL2t%NPL{2Qi4!e-4a zEo!8aKAb9SX!s{TmJ3ueW66`k6q=ImyGCRzWf(YuTP^OiT738US1s+FK>6S$L7Yab zAq2uUfZyLbNpaYN!MkrQw8T|~O4}gDOR8IeEA`PdYpUS2E0u+mX30O$pnCiAg$j?3kBbiZ)9b`TIlY;be} z^Z0Q&+^X?S)?tp_C$u7tt<I~AJ9I~`0JC;RayNa=YZSFchE>L^u zTITMuz7jR2R4+cNnKNkLj0CR}KxUUyrnClGl*rJ|e4?{t+ah=*%5%I?-_0Sv2Zr-~ z0nUhwiVD^p23rr(!`B5b(3$az4Y7W_XH=kd?BTB1QOT%b9VYc_2`8U<>=&X<)emaM z-}z6J-c9f?yhn{v98me=^b#(6bky=g;k`@PV#hU1h>9kOQube_V>q zt4-cT9-`!rROIEG@79j5)bFy%S+xO@(Oz~T$8-irhVy84_5_`!=rzHc#SG#RK4e6b zIM(6bQK6!d*^{_mzS+Im&wLK1vW#yrQrOBEmarQNuev}dwcVPJi~KpOC;`lw>w;(M z#}?folo_@$+NL20MSN$^v|)_l+e7%~c<|4y0TO+ekd!Z#*Dnik zLHa}KxNF&|0K~F+bxY57Y27vi8R)4}>$`Zuo-Z7!wC9_#jO5M%hYKCZxc3msJuY-l z+XCTRmigEwus4!|EP2J@{Bsg!wXi4@rEmD8GQLMlIFgr__e=yJqPrK<)+HIV8i4n` z-sWBD`*KDpbL&%3krSDI)(c;QjfO`y3S_^pub%r@)HdO&ctQ@OKJ5krvPl;P%dFcm z1cyiK+@ftARUGnLeLXn16r1|G=XDX4S)8y~%Vw#_d2hq36$9r6&o9rd8*lng;-{7oM+Pqd~|cI zm!tv5;MwT+ve_gg-O7~!XrYS5G_JLy~NbpgRCG=ZU%n9hI=CFX`ZmNaD$g>5!Y+uojh)s=Z8X7M3 zO!V;`eyTaKCuxyck)&MUG>MJE`keKDiEv$*p7C`zMA70Y7s;_UzUQAVEL;gyIPgLw zWt-0-A9v|Qe0GWMNKA-X@`R)>uykt(IE_)TqPXV>6twW8D(Q+?_|*O(2_t!4k1kPv|a{-*6}YUG1WJmMo%U?+beb(`a7cuiHYst zs47Nqj)58Qfm@eal#Z1=(l9Af{X-3R>`CX>uA1IkAA_!8h1xEDxzahxJ~l99rp1G+ zZoM-aY%q7SBIBS}to8dR(oQTdbq0y$v5C#IPD%``{8WH23tZ(<%WvOkq$%++NDU9( zk!@=mtCLoJiE;ybH(8n-RerrkYvcVe$Ept|^T3XyCuK_#)PX(0=}aKCk1+!c9cyAf zDI`>KI0k=N&GaSI=yl*3>89A<$oL4$g8yu#IglW z6p2swU$7BJ19jU`YgfKA0m`c`VWaCY=vBb(`w!9dhPwFj<;yGBN{%#@=+FjpIErRp zc1{k$9<=1ZkLWrjUL(l-VR-0(736UrDSG?&1`~i6xW52iKuJMJR}guG%w~oBeO(oU z_D|(A_S{31rpBnJQ3psa4Y6eaag@NXTNBdxPS_ZUzMc|>pKt&2Wp7+_1IV(d529L> za$lW~^ERD;I1eni#Zl2j4via^vnuHdcpO?=|y<8qGAYQPH9Z^H^E)wm7%%GiSs_&d<{>S z#|pK)lJTO7&AlA^C#(C;p3mwFs{k3iK8sRUb^dZu3V*;G6BEZCCv_r~xI}&zZ*d?u zvGgfM%`ehm@902yy8ral0BS*~$S~b_!;t~}=P765V7@f7hfUU}4YV*Q3Nczuvefb{ z=7NHPE3`rr>#Ntc^BvF6@(P}>t*yOcU?6vnQ}UlS8;tZ!K{p57%%0IaY!}@Q z%}TZ1{zzGN-6C((mTx1517zB}f?0KEJ&H({OIZ37s2#?L_w8^h^UBJ~x+J4kZ(09zrQEaAIoUT!hZo9o!L83GN&f}U3A*FdF0$07jH@QyU*%}0lHLHCakEo z{i4(c;eJ8wF1|_e9OrvD(FfjXHamP7!;G9Zo2H3}>tQ~5kfs!dK$Ci!YR;4Ha+ca! zu2W`@4NG}&vv(3<@1byB&!x6?skJkih#O7+59|oe()L*TY`i)gZx4E77 z9*+FsZ9NEU0N|yhwDffqSk3`1S|LAvTnSUbjAi4l?FMqB9m?22#Trnno4Z!NltTj2 zt)-HpdRehI@CobOWpp19aBpbw+v28!jA zeSVPl7@KP$(Dqe~PKwOTE)*zD`EO!E2Y%1?i=tfoZnoC;Y)SQShGc0y+s)hJ1t55 zMnX=I9WeLwj7OxJV*qCnDH^Gvtc_UpX*j-+$zk$QG5=#oWHsI;Yzy8NEabJcn#`gC zA76Xq8Pyj0Nl`VwQ8xKF9>te*Js?3JfIL%4*7blqpE*PamIdni?AbGJI#$pFTd6ds z-r1v#EmJRIkHgSIfFu?M9#Xu)ETIiZ9_-4=cgXEgZR*IK*@~NUu$?J-l%>N@pPv2V zjS>j|e|t#u%fDrtK$f?HNI>a?=D!p){?&QT=v2(11<@S47iIsNQm?v>3HH_PAs_v)}kFlT{?3u;QS z-)kN_vw9E+1a>#PycCsMTRZqQnvR}14&=#`I#sHbpyLC`rTXgDvwWWmA!9ur!Zb&u zopm~0@MZC*bTzUIF|Dlsmmu$YmTNa*<@lUN%8yEjJ4ol7dv3GL-Ll2*Bf~hE-ziC9 zx1PlYfM^WFf9*UIy)KGm5`P5hyLyvFr)e*PD_ z18P07S_K7Ys(ib?`4t>Fy^@38L=fl!v+mjg)0&)32V2>7|B~|Zto}nGAAD>j*x={& zHQ`4`c;g4{6@kY>jG{fN82XN&+FwFF!4{{U9M()31){62P#Z3GY*IG{mq#Z~(yVN7 z0mOmukvEYq==Orh3EEmWMa}9rzJHLtj;}tixhzKb{6q>l+WCfl!>mr->i&Hn$cPXb zP+(>yC#PemN(;!-9f5Q8TSgpks1LI&(oz^$)3 zKvGA%xxG|S7mq4_xoJlK*rEhWLhBjQz^%$!E~Y{iI3e1+$%dnL1*Nu1fXbdu|G=)o z`(rur_s3v>Znit|lU$9o*hEHpG7_i*193+opWoft*$HKT3R#lX{qQ6jZ$iC+7WC(P z(C{wVACu}wM$EO^R50TcKmSQJ4j!1AO{0K`Z8A?6nLM!yVyel<#uqa~3 z%(h&yXd(k%5Vt+%a+PaSF`c+sfLG60gNKCY(HMw{BzULDbsY=)m?N94P$S%itw!W{ zywI*)U2{|MJ;7ykV{!{6-AQ&4P+ocI> zuY*0S)~xjG{pYSKG8SJfm0$*5?NL~;^h@$Rp3??~_OiPBk^g~b19D$FfU5crQ~!Lp zTbe;Z@MdyCQse$gH4IdEX=OfyOxWwjvzu726pTb#x}6Df~jP zt3EmQyc8eRhV5{hD#TAvk?d8uFHKQMj=;C}BaeYG;mi1LPn_J~mOLw1I%LhHkw{1{zwtbE&ciHiM8cQxOY<`Rw+ zd@w|YbLKnYsDX?rssWN)*GzNt`8IB(U0_E_gh&(wKk;_wle~*5CFEhakz(QGAr==T!q+1BeX$^mjEtWSO5oC8@uv;s^rWxEXh1 zB-U$Xh_`%c*Ph^9dFp?V*d@OQ!tZij#e7TLf0->a8Qm!5+On4)yitUn#rta@N_f+U zXa)5UK;}k`Wa{R26GB;55;2frgXXZhUjgH43`)FkTr){eynB(Sa_|@E;`Gcv=GtW6 zLv{A`8+2U4JWB*<@-!pvYJ8I`I|7da%XMlm)Ln=`92%MF3&Eowj%gdjcl=Y}er_a; zlk_(Wi983z_PW?!0%xI3;LHsV&@;U!bc9ki!$>Gvrlq6cekQaIdN4ato>ka$oD+XnB$ft3&9+klyk2)C;SsG0B{Mv~3vqF476d+j z*=!UMW$Px%TBJ)r1UKUP?HwIFH0NV8Y!!%`)0j(Orl5e};ZDkayF@Lv`6r;Ubd~Vh z7?kb_BO{|*;1d2`{&T&RGa9d={}0YIm6Vi_!KMb#Xgg@)F4NPG>6f3{<-~)^ZJ?UG zJ0Na#FH0xkFNDtP0q5)Sj>zT)p86F|berOoLGjEKKKVLpetpw&&NsvuD+SUo z2=@r1P=|jgW8|<04I3$bk>aa2$FE+=ey6q8AdryqJ=tUE8VnZ{YDaZjUXJ;N!CrvW zA8b=c?X-Jxr$#1vEx!@3D}zDNB%v}@x;CcFRnU7vyCfDQ`^jYtuHT-2-5xZj)C2sx@!HXgQi8yLLqGIr_aM;Y>c|d2h z5<<8FVjJvlyb76lyvn_?&E+TD3tSxfT|uKesOWV(K5q%4c%M%yo!36=|Nlo;yFDp( zjIwQwNri!Z#i77zJL0Vl&G$yn)L1T;<#(9XKp0nVvu>kAT$TH2aWSz}Kn(f$`SSk4 zyk}(pq4Y=BU0fJVOiYlZWNS%53jW7$=)=1{0CrBbP~XO`fRN9wx^N+o-BE|513+kA zDgB9m5or``)qp^Egxjl&z@IlBQrNVoZ zp#`TGzjlv3?NQ~ue<0-?U|`wOqLy> ztd0qUctDN7aZ5l7#3!e^do712har)c4Ke!s(sovO{H1Js&t4s zmHg{TEDUbocdn6RV>c0p`=%`fVo;S<_whgW!efC*#C0gYpB(456Q&;5eq4jPxe@{r z)b;m?>uBsVU~eW4#w&&WV%K#j7%A%=rm`Oxlj`BM+<0-j5Wu7>FYZ)&yKl4 z`#-$WcL!7jtZfA6d2=IK`u5X5Nqfy&4P?42qrX%jJI)|4H99ys|Bh~<7+IA@gw5!g z;<~yclNvegh0UTdg?j@6xVg9MRm1liIePkw8+PlDM|ILP_x}J2IZBG8u%!DQ7uxWv zlZ6d97)6jA?!qd3zQ9P&(XIvE&0SGWHD_`E|2@9XjacNraa3aP;-?Bvm({TjMg0!p zeZCVxXJrFFVd1;&ISRBXw>SuE%{e=2%Iai5yXi}x5RW0xVCZmrQJ>n|$>iuD*oLU| z@tWKF2@pJU|0oRis;Wad8Yv2=4vMWxVKDqt|4;^jBz*DO=f=&nmbv0I5Xi01y@*KY zV`zwr?QCp7p`e)%?T1^8e&tb; zPOKX0Kzv7L70Jltcn7djJz3@^(p~Wc3<+`2({pq}3okUS#gUrslWn}Q2s=ZrPGgJO zirO+PeT656Rl^?uBh_{5@SJ7cR--PKHiyls1oTx#qap!b?!fNxx{?jYK zfVbmaBHW59LERl?61ji%KcF$Yrc#NJJ*3m}!t9CHIIZ-N+?1xkf4)mzDj+ zR4(y*-otMD*#ROE@D8j!b4{V)awfw{80v+FoB|vl4YEpknfBo9 z(7kcfXj@iJO4Q6-C7@rBmW`_Lu{W{iiF#ni6-Cn`%JN{-5ZtIaj*4L$)kaC!itMyp zB^s|9)ga0VgRT_*#iJSuMdBItf7{!-K%ZM@1@FD>E=u{i>xXeeoRbOF#KHfv!fDQ7) zhhMLnhNO(zMl%db;J28Q9T!5|!TUTtIyB0i&{e9e!s!3vy*y14Pag$x1=Xq)+ho4= zU6Z!y0bQ8Bsx5+hG1m?SlLPj2)J6lSj&FaBS8AV`!)QbSV2E;+F8RLyK&S=C!BL)i zdes)tZ&}<145FVjew;4K7LqH^!PEXBkXUMz#(V0~k)P#)P9>qUSD z?0c$89L-S=D6y^KlADRZF)~nz*n3@tZ7c_zf}o~MRTKj@1LhQ11*#y_GOncOM@tbZzt&K~~TbvKqa+yBis#EYNtt;^?zLIE;A$DPo)VmqKQ0TOXD# z1{$|4sj3nX9$_owc_nZN$$@lhO3`xYtT_=-6(T5o3pKUBV9-G<8)D3H>>&_!|A?f| zBHVV#j5YS}y$b=Hq4+()Pd$#4G!(<7Vi>xZFapNd$0$xGG<_L$Sh3!$_4t$!50;pz z!WKHRi6moN0!NXC0;ItT`|AS&R$w zCNNw%+$M;bPbDBEu0(sc#C_z(6Gr#^DDxy^Rx3Wd?_0Gu&>H1yQ4|5f0RTX`^$Hxn zuO7te>|MVEsXata4f6C~j+D(PC}uINPNkgTg1Mt=)jD#+N}&*89{7tkkdd!DXfW#N zCJAgOm;<2600TdSgu)Vb0X%9!WQ`}N6!@bRUqfPj#dsb*R-31`nboNp(Xr2e+!3Pm8Uf+;K$n=ZD1G!zJW4+7@3t7id@NuaOV#3oluUl$NfyAA7 z>0=nONM2?-3bQID|B_5zyNC)h8pP6Wt zvWsTKy``?m!3}JH$qe!gIuHSg%|M$kQ$~!Q2R#Ub*l+gJ*49RCsp`GDWCnwmNWj|7lfHC^2i4gOzzz6Juqg5;F#1))8RuOpYLDT1MBu$K^v z0224>*Z1+x04V`hqLJKXVq8%m5xze38XnZziPH!)grXqcgVj|g;TRs-3KEe>?76g4T0^ETYO3ev$e0)Y)*B#y0ulPfODtAX*h(3PA}Fzniihgm-j-!Dq$7|SL|*gR^_}n*lHS}~ z;R||sRJXPF7>NP5rOaMd1C?p_NxmwA z)YUa8$kB@~?QB4C9)y-$;({Cp=6q^k!DGm90*0Gfpd5HGu{>cOGeQ_;E-X~psp+XQ zWMI31e25CZCr`HbuLOPXGz6e+s4rtMVbxe+2q{k-V`&a5v*U6IzF;)vCeeprwqQ=}CL$W#iKfQH-Yn6gpIw8??p$h(5G*<&A6*-e45_ z)le`FqTtAA?K{Bq2neJ!tCdy3TRn4e+hT4IfG(%1e08O3}1LWwEkfGlEDAGR&>)?$2J{IIM|zG{1-m3vj8$x&~*&+|59zjZsG6()_ra&h0S zqjXt{RA*=o%CfI_rBxCJt^JUBBdhz+WfjY=wsRcT+1@_81AGlm7tExhOI*WAP(Kv# zwJ8W{gJItgW1VI^HI%YF9u3vs#MB$&JZ`!#y#vO{uPIbb2=3tihr2Q9f#> zz}@kSo7;y2uxviC8P8>Cb9cAjm_LIN@MO`3XSr(qitOu1*458(g99Z5)g6}$$uR^# z ztXd63)-8|DaAkmXqD0~OV(Ayq9pcvfb$^ z$4)_Iq+LcB1cEZCN|tRmaAJDO2uNNZXwsjaMv)R1gKR`Uv~}B1`q*pCdH;=RP_{nf z84B}c(R4${LX>B=kw|R7^UT8I6iJ3zULc814>Gl7y>SGRIT6}+0how@>xLkQs?bHv zfrAPVz`~B?7XV=a^7vgpK)37wpxCFtX&gk>2Tvf5<%MZPPF?Y=^Cw_cXw~vr)3nS$ z40=mi5YqpHmrTHNbc|K2^gbJQ=;=d3Ow5!XpD{i7+H>g>(mXRY-tJWr1%VIwD~cQv z)ZExH6RuZ8Z0N&N zJw44}H?*}RJdX%|<7AxL(%9J88775gwUyiifuW~O9&?$O#`g&hcDcNLHJ89nR`xR3 zxKX1u&_RoN>+vezOAB}reUp1txLFIWm{F@&1xi~jP;xZ5Gii`?pkF6$8{veU;{?G) zUi%vc?j%9zPq|-&`xi&O%&OgEw}1cs`>f3&r08-#=OCFEgltmP)M`UDg)o7gd)0~D zh0~$x1KjY5$sTUT&%%Kjhi!z5eOtjylufg~=b6d?DeqBFkh%GX18tpZVJ5uIC6(-BauB+Rluf?3{-ZxxbRw99C@~wnrs@sHqg~5ZsimIeHlXHu0LLJSfgm4zmt|tGajwf zZ5{ujZlaMx5iE)JC^ zW(1oy#gOP!IH0a?^yJC3uL>9N-ae36K*Q)S2F5zWM6kU323pwF-tt?Uo9uOxy|fgnGxZ-=yc`?w z4_O~Q@w#AaoA}UVV!-WS_nF|&7SuQ20?kXOtf{2fuI9poD`qAxJDYnxzN8kc*mcu! zTVY{g#aW4-VhA;2LXRsAQ+kZ9{*b0cf0nd;b#YPA*yB>0rlaX+%XD_ME#QS^k(fLq zwGHl_j#Kf;i5Z`spAJ>|M(MjY|ECw#ADdKucrB@}6f|#yBV=e(yvu=@K;68|sd(2p zV`;i6ymbQ;leL{C5w$doyjSa$a=MES#BD^WJ)y^SvDcp1X0WnH#P09cO literal 0 HcmV?d00001 diff --git a/planning/behavior_velocity_crosswalk_module/docs/explicit_stop_line.svg b/planning/behavior_velocity_crosswalk_module/docs/explicit_stop_line.svg new file mode 100644 index 0000000000000..13ba18bbb7588 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/explicit_stop_line.svg @@ -0,0 +1,71 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ stop line defined in the lanelet map +
+
+
+
+ stop line defined in the lanele... +
+
+ +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/far_object_threshold.drawio.svg b/planning/behavior_velocity_crosswalk_module/docs/far_object_threshold.drawio.svg new file mode 100644 index 0000000000000..6e4c152cd79f0 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/far_object_threshold.drawio.svg @@ -0,0 +1,114 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ stop line defined in the lanelet map +
+
+
+
+ stop line defined in the lanele... +
+
+ + + + + + + + + + + +
+
+
+ stop_distance_from_object +
+
+
+
+ stop_distance_from_... +
+
+ + + + + + + + + + + +
+
+
far_object_threshold <
+
+
+
+ far_object_threshold < +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/limitation.svg b/planning/behavior_velocity_crosswalk_module/docs/limitation.svg deleted file mode 100644 index 3e507c0669a2b..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/limitation.svg +++ /dev/null @@ -1,164 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - -
-
-
- stop objects -
-
-
-
- stop objects -
-
- - - - - - - - - -
-
-
- waiting for the traffic light to turn green. -
-
-
-
- waiting for the traffic l... -
-
- - - -
-
-
- The pedestrian has no intention to cross via this route. -
-
-
-
- The pedestrian has no intent... -
-
- - - - -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/no-intension.svg b/planning/behavior_velocity_crosswalk_module/docs/no-intension.svg deleted file mode 100644 index 803ce223d591a..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/no-intension.svg +++ /dev/null @@ -1,193 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - - - - - - - -
-
-
- min_object_velocity * ego_pass_later_margin - [m] -
-
-
-
- min_object_velocity * ego_pass_later_margin [... -
-
- - - - -
-
-
- yield... -
-
-
-
- yield... -
-
- - - -
-
-
- stop objects -
-
-
-
- stop objects -
-
- - - - - -
-
-
- don't have intention -
- to cross -
-
-
-
- don't have intentio... -
-
-
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stop_line.svg b/planning/behavior_velocity_crosswalk_module/docs/stop_line.svg deleted file mode 100644 index c2d486a7d3541..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/stop_line.svg +++ /dev/null @@ -1,149 +0,0 @@ - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - - - - - - - - -
-
-
- stop line -
- (defined by HDMap) -
-
-
-
- stop line... -
-
- - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - -
-
-
- stop_distance_from_object - [m] -
-
-
-
- stop_distance_from_object [m] -
-
- -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stop_line_distance.svg b/planning/behavior_velocity_crosswalk_module/docs/stop_line_distance.svg deleted file mode 100644 index 3842601ae246c..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/stop_line_distance.svg +++ /dev/null @@ -1,170 +0,0 @@ - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - - - - - - - - - -
-
-
- stop_distance_from_crosswalk - [m] -
-
-
-
- stop_distance_from_crosswalk [m] -
-
- - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - -
-
-
- stop_distance_from_object - [m] -
-
-
-
- stop_distance_from_object [m] -
-
- - - - -
-
-
- stop point -
- (planned in module) -
-
-
-
- stop point... -
-
-
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stop_line_margin.svg b/planning/behavior_velocity_crosswalk_module/docs/stop_line_margin.svg deleted file mode 100644 index ea7fd9be3ff41..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/stop_line_margin.svg +++ /dev/null @@ -1,204 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - -
-
-
- far_object_threshold - [m] -
-
-
-
- far_object_threshold [m] -
-
- - - - - - - - -
-
-
- stop line -
- (defined by HDMap) -
-
-
-
- stop line... -
-
- - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - - - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - -
-
-
- stop_distance_from_object - [m] -
-
-
-
- stop_distance_from_object [m] -
-
- - - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stop_margin.svg b/planning/behavior_velocity_crosswalk_module/docs/stop_margin.svg deleted file mode 100644 index 924f642ad08bb..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/stop_margin.svg +++ /dev/null @@ -1,144 +0,0 @@ - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - - - - -
-
-
- stop_distance_from_object - [m] -
-
-
-
- stop_distance_from_object [m] -
-
- - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - -
-
-
- The module determines a stop position at least - stop_distance_from_object - away from the object's predicted path. -
-
-
-
- The module determines a stop positio... -
-
-
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_attention_range.svg b/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_attention_range.svg deleted file mode 100644 index 3ac1a94fcec78..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_attention_range.svg +++ /dev/null @@ -1,174 +0,0 @@ - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22%22%20style%3D%22endArrow%3Dclassic%3Bhtml%3D1%3Brounded%3D0%3BexitX%3D0.25%3BexitY%3D0%3BexitDx%3D0%3BexitDy%3D0%3BentryX%3D0.5%3BentryY%3D0.442%3BentryDx%3D0%3BentryDy%3D0%3BentryPerimeter%3D0%3B%22%20edge%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20width%3D%2250%22%20height%3D%2250%22%20relative%3D%221%22%20as%3D%22geometry%22%3E%3CmxPoint%20x%3D%22851%22%20y%3D%221780%22%20as%3D%22sourcePoint%22%2F%3E%3CmxPoint%20x%3D%22890.04%22%20y%3D%221780%22%20as%3D%22targetPoint%22%2F%3E%3C%2FmxGeometry%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20i... -
-
- - - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - - - -
-
-
- stuck_vehicle_attention_range - [m] -
-
-
-
- stuck_vehicle_attention_range [... -
-
- - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - - - -
-
-
- max_stuck_vehicle_lateral_offset - [m] -
-
-
-
- max_stuck_vehicle_lateral_offset [m] -
-
- -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_detection.svg b/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_detection.svg new file mode 100644 index 0000000000000..c517be5bb9967 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_detection.svg @@ -0,0 +1,93 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ stuck_vehicle_attention_range +
+
+
+
+ stuck_vehicle_atten... +
+
+ + + + + + + + + + + + +
+
+
+ max_stuck_vehicle_lateral_offset +
+
+
+
+ max_stuck_vehicle_l... +
+
+ + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg b/planning/behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg new file mode 100644 index 0000000000000..6eb1b25cf5642 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg @@ -0,0 +1,210 @@ + + + + + + + + + + + + +
+
+
+ (5, 1) +
+
+
+
+ (5, 1) +
+
+ + + + +
+
+
+ (1, 4) +
+
+
+
+ (1, 4) +
+
+ + + + +
+
+
+ (2, 6) +
+
+
+
+ (2, 6) +
+
+ + + + + + + + +
+
+
+ (0, 1) +
+
+
+
+ (0, 1) +
+
+ + + + +
+
+
+ (3, 0) +
+
+
+
+ (3, 0) +
+
+ + + + +
+
+
+ Time-To-Vehicle [s] +
+
+
+
+ Time-To-Vehicle [s] +
+
+ + + + + + + + + + + + + + + + + +
+
+
+ Time-To-Collision [s] +
+
+
+
+ Time-To-Collision [s] +
+
+ + + + +
+
+
+ B +
+
+
+
+ B +
+
+ + + + +
+
+
+ A +
+
+
+
+ A +
+
+ + + + +
+
+
+ C +
+
+
+
+ C +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/virtual_collision_point.svg b/planning/behavior_velocity_crosswalk_module/docs/virtual_collision_point.svg index 8084dc2fbd8b0..c409493483845 100644 --- a/planning/behavior_velocity_crosswalk_module/docs/virtual_collision_point.svg +++ b/planning/behavior_velocity_crosswalk_module/docs/virtual_collision_point.svg @@ -1,134 +1,65 @@ + - + - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - - - - -
-
-
- virtual collision point -
-
-
-
- virtual collision poi... -
-
- - - -
-
-
- path -
-
-
-
- path -
-
- - - -
+
-
- object's prediction path +
+ virtual collision point
- object's prediction p... + virtual collision point - + diff --git a/planning/behavior_velocity_crosswalk_module/docs/virtual_stop_line.svg b/planning/behavior_velocity_crosswalk_module/docs/virtual_stop_line.svg new file mode 100644 index 0000000000000..7d4b4017c2f1a --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/virtual_stop_line.svg @@ -0,0 +1,73 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ stop_distance_from_crosswalk +
+
+
+
+ stop_distance_from_... +
+
+ + + + + + + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/with_traffic_light.svg b/planning/behavior_velocity_crosswalk_module/docs/with_traffic_light.svg new file mode 100644 index 0000000000000..a09f430e990b3 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/with_traffic_light.svg @@ -0,0 +1,97 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ NOT + yield +
+
+
+
+ NOT yield +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/without_traffic_light.svg b/planning/behavior_velocity_crosswalk_module/docs/without_traffic_light.svg new file mode 100644 index 0000000000000..d4dea5fb78d2e --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/without_traffic_light.svg @@ -0,0 +1,67 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ yield +
+
+
+
+ yield +
+
+ +
+ + + + Text is not SVG - cannot display + + +
From 7c3ec3a86b7f33a58928fb8f3e1041b66287d859 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 18 Jan 2024 17:58:25 +0900 Subject: [PATCH 266/276] feat(intersection): more precise pass judge handling considering occlusion detection and 1st/2nd attention lane (#6047) Signed-off-by: Mamoru Sobue Signed-off-by: karishma --- .../README.md | 86 +++- .../config/intersection.param.yaml | 2 +- .../docs/pass-judge-line.drawio.svg | 473 ++++++++++++++++++ .../src/debug.cpp | 20 +- .../src/manager.cpp | 4 +- .../src/scene_intersection.cpp | 106 ++-- .../src/scene_intersection.hpp | 16 +- 7 files changed, 634 insertions(+), 73 deletions(-) create mode 100644 planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index 58c2ce59edd48..afb2381e628a4 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -88,7 +88,7 @@ To precisely calculate stop positions, the path is interpolated at the certain i - closest_idx denotes the path point index which is closest to ego position. - first_attention_stopline denotes the first path point where ego footprint intersects with the attention_area. -- If a stopline is associated with the intersection lane on the map, that line is used as the default_stopline for collision detection. Otherwise the point which is `common.default_stopline_margin` meters behind first_attention_stopline is defined as the default_stopline instead. +- If a stopline is associated with the intersection lane on the map, that line is used as default_stopline for collision detection. Otherwise the point which is `common.default_stopline_margin` meters behind first_attention_stopline is defined as default_stopline instead. - occlusion_peeking_stopline is a bit ahead of first_attention_stopline as described later. - occlusion_wo_tl_pass_judge_line is the first position where ego footprint intersects with the centerline of the first attention_area lane. @@ -113,8 +113,8 @@ There are several behaviors depending on the scene. | Safe | Ego detected no occlusion and collision | Ego passes the intersection | | StuckStop | The exit of the intersection is blocked by traffic jam | Ego stops before the intersection or the boundary of attention area | | YieldStuck | Another vehicle stops to yield ego | Ego stops before the intersection or the boundary of attention area | -| NonOccludedCollisionStop | Ego detects no occlusion but detects collision | Ego stops at the default_stop_line | -| FirstWaitBeforeOcclusion | Ego detected occlusion when entering the intersection | Ego stops at the default_stop_line at first | +| NonOccludedCollisionStop | Ego detects no occlusion but detects collision | Ego stops at default_stopline | +| FirstWaitBeforeOcclusion | Ego detected occlusion when entering the intersection | Ego stops at default_stopline at first | | PeekingTowardOcclusion | Ego detected occlusion and but no collision within the FOV (after FirstWaitBeforeOcclusion) | Ego approaches the boundary of the attention area slowly | | OccludedCollisionStop | Ego detected both occlusion and collision (after FirstWaitBeforeOcclusion) | Ego stops immediately | | FullyPrioritized | Ego is fully prioritized by the RED/Arrow signal | Ego only cares vehicles still running inside the intersection. Occlusion is ignored | @@ -219,7 +219,7 @@ ros2 run behavior_velocity_intersection_module ttc.py --lane_id ## Occlusion detection -If the flag `occlusion.enable` is true this module checks if there is sufficient field of view (FOV) on the attention area up to `occlusion.occlusion_attention_area_length`. If FOV is not clear enough ego first makes a brief stop at the default stop line for `occlusion.temporal_stop_time_before_peeking`, and then slowly creeps toward occlusion_peeking_stop_line. If `occlusion.creep_during_peeking.enable` is true `occlusion.creep_during_peeking.creep_velocity` is inserted up to occlusion_peeking_stop_line. Otherwise only stop line is inserted. +If the flag `occlusion.enable` is true this module checks if there is sufficient field of view (FOV) on the attention area up to `occlusion.occlusion_attention_area_length`. If FOV is not clear enough ego first makes a brief stop at default_stopline for `occlusion.temporal_stop_time_before_peeking`, and then slowly creeps toward occlusion_peeking_stopline. If `occlusion.creep_during_peeking.enable` is true `occlusion.creep_during_peeking.creep_velocity` is inserted up to occlusion_peeking_stopline. Otherwise only stop line is inserted. During the creeping if collision is detected this module inserts a stop line in front of ego immediately, and if the FOV gets sufficiently clear the intersection_occlusion wall will disappear. If occlusion is cleared and no collision is detected ego will pass the intersection. @@ -241,7 +241,7 @@ The remaining time is visualized on the intersection_occlusion virtual wall. ### Occlusion handling at intersection without traffic light -At intersection without traffic light, if occlusion is detected, ego makes a brief stop at the default_stopline and first_attention_stopline respectively. After stopping at the first_attention_area_stopline this module inserts `occlusion.absence_traffic_light.creep_velocity` velocity between ego and occlusion_wo_tl_pass_judge_line while occlusion is not cleared. If collision is detected, ego immediately stops. Once the occlusion is cleared or ego has passed occlusion_wo_tl_pass_judge_line this module does not detect collision and occlusion because ego footprint is already inside the intersection. +At intersection without traffic light, if occlusion is detected, ego makes a brief stop at default_stopline and first_attention_stopline respectively. After stopping at the first_attention_area_stopline this module inserts `occlusion.absence_traffic_light.creep_velocity` velocity between ego and occlusion_wo_tl_pass_judge_line while occlusion is not cleared. If collision is detected, ego immediately stops. Once the occlusion is cleared or ego has passed occlusion_wo_tl_pass_judge_line this module does not detect collision and occlusion because ego footprint is already inside the intersection. ![occlusion_detection](./docs/occlusion-without-tl.drawio.svg) @@ -263,7 +263,7 @@ TTC parameter varies depending on the traffic light color/shape as follows. ### yield on GREEN -If the traffic light color changed to GREEN and ego approached the entry of the intersection lane within the distance `collision_detection.yield_on_green_traffic_light.distance_to_assigned_lanelet_start` and there is any object whose distance to its stopline is less than `collision_detection.yield_on_green_traffic_light.object_dist_to_stopline`, this module commands to stop for the duration of `collision_detection.yield_on_green_traffic_light.duration` at the default_stopline. +If the traffic light color changed to GREEN and ego approached the entry of the intersection lane within the distance `collision_detection.yield_on_green_traffic_light.distance_to_assigned_lanelet_start` and there is any object whose distance to its stopline is less than `collision_detection.yield_on_green_traffic_light.object_dist_to_stopline`, this module commands to stop for the duration of `collision_detection.yield_on_green_traffic_light.duration` at default_stopline. ### skip on AMBER @@ -281,18 +281,49 @@ When the traffic light color/shape is RED/Arrow, occlusion detection is skipped. ## Pass Judge Line -To avoid sudden braking, if deceleration and jerk more than the threshold (`common.max_accel` and `common.max_jerk`) is required to stop at first_attention_stopline, this module does not command to stop once it passed the default_stopline position. +Generally it is not tolerable for vehicles that have lower traffic priority to stop in the middle of the unprotected area in intersections, and they need to stop at the stop line beforehand if there will be any risk of collision, which introduces two requirements: -If ego passed pass_judge_line, then ego does not stop anymore. If ego passed pass_judge_line while ego is stopping for dangerous decision, then ego stops while the situation is judged as dangerous. Once the judgement turned safe, ego restarts and does not stop anymore. +1. The vehicle must start braking before the boundary of the unprotected area at least by the braking distance if it is supposed to stop +2. The vehicle must recognize upcoming vehicles and check safety beforehand with enough braking distance margin if it is supposed to go + 1. And the SAFE decision must be absolutely certain and remain to be valid for the future horizon so that the safety condition will be always satisfied while ego is driving inside the unprotected area. +3. (TODO): Since it is almost impossible to make perfectly safe decision beforehand given the limited detection range/velocity tracking performance, intersection module should plan risk-evasive acceleration velocity profile AND/OR relax lateral acceleration limit while ego is driving inside the unprotected area, if the safety decision is "betrayed" later due to the following reasons: + 1. The situation _turned out to be dangerous_ later, mainly because velocity tracking was underestimated or the object accelerated beyond TTC margin + 2. The situation _turned dangerous_ later, mainly because the object is suddenly detected out of nowhere -The position of the pass judge line depends on the occlusion detection configuration and the existence of the associated traffic light of the intersection lane. +The position which is before the boundary of unprotected area by the braking distance which is obtained by -- If `occlusion.enable` is false, the pass judge line before the `first_attention_stopline` by the braking distance $v_{ego}^{2} / 2a_{max}$. -- If `occlusion.enable` is true and: - - if there are associated traffic lights, the pass judge line is at the `occlusion_peeking_stopline` in order to continue peeking/collision detection while occlusion is detected. - - if there are no associated traffic lights and: - - if occlusion is detected, pass judge line is at the `occlusion_wo_tl_pass_judge_line` to continue peeking. - - if occlusion is not detected, pass judge line is at the same place at the case where `occlusion.enable` is false. +$$ +\dfrac{v_{\mathrm{ego}}^{2}}{2a_{\mathrm{max}}} + v_{\mathrm{ego}} * t_{\mathrm{delay}} +$$ + +is called pass_judge_line, and safety decision must be made before ego passes this position because ego does not stop anymore. + +1st_pass_judge_line is before the first upcoming lane, and at intersections with multiple upcoming lanes, 2nd_pass_judge_line is defined as the position which is before the centerline of the first attention lane by the braking distance. 1st/2nd_pass_judge_line are illustrated in the following figure. + +![pass-judge-line](./docs/pass-judge-line.drawio.svg) + +Intersection module will command to GO if + +- ego is over default_stopline(or `common.enable_pass_judge_before_default_stopline` is true) AND +- ego is over 1st_pass judge line AND +- ego judged SAFE previously AND +- (ego is over 2nd_pass_judge_line OR ego is between 1st and 2nd pass_judge_line but most probable collision is expected to happen in the 1st attention lane) + +because it is expected to stop or continue stop decision if + +1. ego is before default_stopline && `common.enable_pass_judge_before_default_stopline` is false OR + 1. reason: default_stopline is defined on the map and should be respected +2. ego is before 1st_pass_judge_line OR + 1. reason: it has enough braking distance margin +3. ego judged UNSAFE previously + 1. reason: ego is now trying to stop and should continue stop decision if collision is detected in later calculation +4. (ego is between 1st and 2nd pass_judge_line and the most probable collision is expected to happen in the 2nd attention lane) + +For the 3rd condition, it is possible that ego stops with some overshoot to the unprotected area while it is trying to stop for collision detection, because ego should keep stop decision while UNSAFE decision is made even if it passed 1st_pass_judge_line during deceleration. + +For the 4th condition, at intersections with 2nd attention lane, even if ego is over the 1st pass_judge_line, still intersection module commands to stop if the most probable collision is expected to happen in the 2nd attention lane. + +Also if `occlusion.enable` is true, the position of 1st_pass_judge line changes to occlusion_peeking_stopline if ego passed the original 1st_pass_judge_line position while ego is peeking. Otherwise ego could inadvertently judge that it passed 1st_pass_judge during peeking and then abort peeking. ## Data Structure @@ -375,17 +406,18 @@ entity TargetObject { ### common -| Parameter | Type | Description | -| --------------------------------- | ------ | ------------------------------------------------------------------------ | -| `.attention_area_length` | double | [m] range for object detection | -| `.attention_area_margin` | double | [m] margin for expanding attention area width | -| `.attention_area_angle_threshold` | double | [rad] threshold of angle difference between the detected object and lane | -| `.use_intersection_area` | bool | [-] flag to use intersection_area for collision detection | -| `.default_stopline_margin` | double | [m] margin before_stop_line | -| `.stopline_overshoot_margin` | double | [m] margin for the overshoot from stopline | -| `.max_accel` | double | [m/ss] max acceleration for stop | -| `.max_jerk` | double | [m/sss] max jerk for stop | -| `.delay_response_time` | double | [s] action delay before stop | +| Parameter | Type | Description | +| -------------------------------------------- | ------ | -------------------------------------------------------------------------------- | +| `.attention_area_length` | double | [m] range for object detection | +| `.attention_area_margin` | double | [m] margin for expanding attention area width | +| `.attention_area_angle_threshold` | double | [rad] threshold of angle difference between the detected object and lane | +| `.use_intersection_area` | bool | [-] flag to use intersection_area for collision detection | +| `.default_stopline_margin` | double | [m] margin before_stop_line | +| `.stopline_overshoot_margin` | double | [m] margin for the overshoot from stopline | +| `.max_accel` | double | [m/ss] max acceleration for stop | +| `.max_jerk` | double | [m/sss] max jerk for stop | +| `.delay_response_time` | double | [s] action delay before stop | +| `.enable_pass_judge_before_default_stopline` | bool | [-] flag not to stop before default_stopline even if ego is over pass_judge_line | ### stuck_vehicle/yield_stuck @@ -430,7 +462,7 @@ entity TargetObject { | `.possible_object_bbox` | [double] | [m] minimum bounding box size for checking if occlusion polygon is small enough | | `.ignore_parked_vehicle_speed_threshold` | double | [m/s] velocity threshold for checking parked vehicle | | `.occlusion_detection_hold_time` | double | [s] hold time of occlusion detection | -| `.temporal_stop_time_before_peeking` | double | [s] temporal stop duration at the default_stop_line before starting peeking | +| `.temporal_stop_time_before_peeking` | double | [s] temporal stop duration at default_stopline before starting peeking | | `.temporal_stop_before_attention_area` | bool | [-] flag to temporarily stop at first_attention_stopline before peeking into attention_area | | `.creep_velocity_without_traffic_light` | double | [m/s] creep velocity to occlusion_wo_tl_pass_judge_line | | `.static_occlusion_with_traffic_light_timeout` | double | [s] the timeout duration for ignoring static occlusion at intersection with traffic light | diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 4e9eb50f2a462..108e021240851 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -12,6 +12,7 @@ max_accel: -2.8 max_jerk: -5.0 delay_response_time: 0.5 + enable_pass_judge_before_default_stopline: false stuck_vehicle: turn_direction: @@ -36,7 +37,6 @@ consider_wrong_direction_vehicle: false collision_detection_hold_time: 0.5 min_predicted_path_confidence: 0.05 - keep_detection_velocity_threshold: 0.833 velocity_profile: use_upstream: true minimum_upstream_velocity: 0.01 diff --git a/planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg b/planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg new file mode 100644 index 0000000000000..d1f488af7c2ac --- /dev/null +++ b/planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg @@ -0,0 +1,473 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + 1st_pass_judge_line + +
+
+
+
+ 1st_pass_judge_line +
+
+ + + + + + + + +
+
+
+ + 2nd_pass_judge_line_magin + +
+
+
+
+ 2nd_pass_judge_line_magin +
+
+ + + + + + + + +
+
+
+ + 2nd_pass_judge_line + +
+
+
+
+ 2nd_pass_judge_line +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + 1st_pass_judge_line + +
+
+
+
+ 1st_pass_judge_line +
+
+ + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_intersection_module/src/debug.cpp index 5f103e0ecd3b0..350f6d774f7cf 100644 --- a/planning/behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_intersection_module/src/debug.cpp @@ -90,7 +90,7 @@ visualization_msgs::msg::MarkerArray createPoseMarkerArray( marker_line.type = visualization_msgs::msg::Marker::LINE_STRIP; marker_line.action = visualization_msgs::msg::Marker::ADD; marker_line.pose.orientation = createMarkerOrientation(0, 0, 0, 1.0); - marker_line.scale = createMarkerScale(0.1, 0.0, 0.0); + marker_line.scale = createMarkerScale(0.2, 0.0, 0.0); marker_line.color = createMarkerColor(r, g, b, 0.999); const double yaw = tf2::getYaw(pose.orientation); @@ -283,11 +283,23 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray( &debug_marker_array, now); */ - if (debug_data_.pass_judge_wall_pose) { + if (debug_data_.first_pass_judge_wall_pose) { + const double r = debug_data_.passed_first_pass_judge ? 1.0 : 0.0; + const double g = debug_data_.passed_first_pass_judge ? 0.0 : 1.0; appendMarkerArray( createPoseMarkerArray( - debug_data_.pass_judge_wall_pose.value(), "pass_judge_wall_pose", module_id_, 0.7, 0.85, - 0.9), + debug_data_.first_pass_judge_wall_pose.value(), "first_pass_judge_wall_pose", module_id_, r, + g, 0.0), + &debug_marker_array, now); + } + + if (debug_data_.second_pass_judge_wall_pose) { + const double r = debug_data_.passed_second_pass_judge ? 1.0 : 0.0; + const double g = debug_data_.passed_second_pass_judge ? 0.0 : 1.0; + appendMarkerArray( + createPoseMarkerArray( + debug_data_.second_pass_judge_wall_pose.value(), "second_pass_judge_wall_pose", module_id_, + r, g, 0.0), &debug_marker_array, now); } diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index c92f16dd7b474..0f9faaaa901c1 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -61,6 +61,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) ip.common.max_jerk = getOrDeclareParameter(node, ns + ".common.max_jerk"); ip.common.delay_response_time = getOrDeclareParameter(node, ns + ".common.delay_response_time"); + ip.common.enable_pass_judge_before_default_stopline = + getOrDeclareParameter(node, ns + ".common.enable_pass_judge_before_default_stopline"); ip.stuck_vehicle.turn_direction.left = getOrDeclareParameter(node, ns + ".stuck_vehicle.turn_direction.left"); @@ -92,8 +94,6 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".collision_detection.collision_detection_hold_time"); ip.collision_detection.min_predicted_path_confidence = getOrDeclareParameter(node, ns + ".collision_detection.min_predicted_path_confidence"); - ip.collision_detection.keep_detection_velocity_threshold = getOrDeclareParameter( - node, ns + ".collision_detection.keep_detection_velocity_threshold"); ip.collision_detection.velocity_profile.use_upstream = getOrDeclareParameter(node, ns + ".collision_detection.velocity_profile.use_upstream"); ip.collision_detection.velocity_profile.minimum_upstream_velocity = getOrDeclareParameter( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index dad0c194b5c9f..358dca2414bb0 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1041,7 +1041,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto default_stopline_idx_opt = intersection_stoplines.default_stopline; const auto first_attention_stopline_idx_opt = intersection_stoplines.first_attention_stopline; const auto occlusion_peeking_stopline_idx_opt = intersection_stoplines.occlusion_peeking_stopline; - const auto default_pass_judge_line_idx = intersection_stoplines.first_pass_judge_line; + const auto first_pass_judge_line_idx = intersection_stoplines.first_pass_judge_line; + const auto second_pass_judge_line_idx = intersection_stoplines.second_pass_judge_line; const auto occlusion_wo_tl_pass_judge_line_idx = intersection_stoplines.occlusion_wo_tl_pass_judge_line; @@ -1221,13 +1222,22 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( prev_occlusion_status_ = occlusion_status; } - // TODO(Mamoru Sobue): this part needs more formal handling - const size_t pass_judge_line_idx = [=]() { + const size_t pass_judge_line_idx = [&]() { if (enable_occlusion_detection_) { - // if occlusion detection is enabled, pass_judge position is beyond the boundary of first - // attention area if (has_traffic_light_) { - return occlusion_stopline_idx; + // if ego passed the first_pass_judge_line while it is peeking to occlusion, then its + // position is occlusion_stopline_idx. Otherwise it is first_pass_judge_line + if (passed_1st_judge_line_while_peeking_) { + return occlusion_stopline_idx; + } + const bool is_over_first_pass_judge_line = + util::isOverTargetIndex(*path, closest_idx, current_pose, first_pass_judge_line_idx); + if (is_occlusion_state && is_over_first_pass_judge_line) { + passed_1st_judge_line_while_peeking_ = true; + return occlusion_stopline_idx; + } else { + return first_pass_judge_line_idx; + } } else if (is_occlusion_state) { // if there is no traffic light and occlusion is detected, pass_judge position is beyond // the boundary of first attention area @@ -1235,30 +1245,53 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } else { // if there is no traffic light and occlusion is not detected, pass_judge position is // default - return default_pass_judge_line_idx; + return first_pass_judge_line_idx; } } - return default_pass_judge_line_idx; + return first_pass_judge_line_idx; }(); - debug_data_.pass_judge_wall_pose = - planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path); - const bool is_over_pass_judge_line = - util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx); - const double vel_norm = std::hypot( - planner_data_->current_velocity->twist.linear.x, - planner_data_->current_velocity->twist.linear.y); - const bool keep_detection = - (vel_norm < planner_param_.collision_detection.keep_detection_velocity_threshold); + const bool was_safe = std::holds_alternative(prev_decision_result_); - // if ego is over the pass judge line and not stopped - if (is_over_default_stopline && !is_over_pass_judge_line && keep_detection) { - RCLCPP_DEBUG(logger_, "is_over_default_stopline && !is_over_pass_judge_line && keep_detection"); - // do nothing - } else if ( - (was_safe && is_over_default_stopline && is_over_pass_judge_line && is_go_out_) || + + const bool is_over_1st_pass_judge_line = + util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx); + if (is_over_1st_pass_judge_line && was_safe && !safely_passed_1st_judge_line_time_) { + safely_passed_1st_judge_line_time_ = clock_->now(); + } + debug_data_.first_pass_judge_wall_pose = + planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path); + debug_data_.passed_first_pass_judge = safely_passed_1st_judge_line_time_.has_value(); + const bool is_over_2nd_pass_judge_line = + util::isOverTargetIndex(*path, closest_idx, current_pose, second_pass_judge_line_idx); + if (is_over_2nd_pass_judge_line && was_safe && !safely_passed_2nd_judge_line_time_) { + safely_passed_2nd_judge_line_time_ = clock_->now(); + } + debug_data_.second_pass_judge_wall_pose = + planning_utils::getAheadPose(second_pass_judge_line_idx, baselink2front, *path); + debug_data_.passed_second_pass_judge = safely_passed_2nd_judge_line_time_.has_value(); + + if ( + ((is_over_default_stopline || + planner_param_.common.enable_pass_judge_before_default_stopline) && + is_over_2nd_pass_judge_line && was_safe) || is_permanent_go_) { - // is_go_out_: previous RTC approval - // activated_: current RTC approval + /* + * This body is active if ego is + * - over the default stopline AND + * - over the 1st && 2nd pass judge line AND + * - previously safe + * , + * which means ego can stop even if it is over the 1st pass judge line but + * - before default stopline OR + * - before the 2nd pass judge line OR + * - or previously unsafe + * . + * In order for ego to continue peeking or collision detection when occlusion is detected after + * ego passed the 1st pass judge line, it needs to be + * - before the default stopline OR + * - before the 2nd pass judge line OR + * - previously unsafe + */ is_permanent_go_ = true; return IntersectionModule::Indecisive{"over the pass judge line. no plan needed"}; } @@ -1309,10 +1342,14 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( : (planner_param_.collision_detection.collision_detection_hold_time - collision_state_machine_.getDuration()); + // TODO(Mamoru Sobue): if ego is over 1st/2nd pass judge line and collision is expected at 1st/2nd + // pass judge line respectively, ego should go + const auto second_attention_stopline_idx = intersection_stoplines.second_attention_stopline; + const auto last_intersection_stopline_candidate_idx = + second_attention_stopline_idx ? second_attention_stopline_idx.value() : occlusion_stopline_idx; const bool has_collision = checkCollision( - *path, &target_objects, path_lanelets, closest_idx, - std::min(occlusion_stopline_idx, path->points.size() - 1), time_to_restart, - traffic_prioritized_level); + *path, &target_objects, path_lanelets, closest_idx, last_intersection_stopline_candidate_idx, + time_to_restart, traffic_prioritized_level); collision_state_machine_.setStateWithMarginTime( has_collision ? StateMachine::State::STOP : StateMachine::State::GO, logger_.get_child("collision state_machine"), *clock_); @@ -1808,16 +1845,19 @@ std::optional IntersectionModule::generateIntersectionSto second_attention_area, interpolated_path_info, local_footprint, baselink2front); if (first_footprint_inside_2nd_attention_ip_opt) { second_attention_stopline_ip_int = first_footprint_inside_2nd_attention_ip_opt.value(); + second_attention_stopline_valid = true; } } const auto second_attention_stopline_ip = second_attention_stopline_ip_int >= 0 ? static_cast(second_attention_stopline_ip_int) : 0; - // (8) second pass judge lie position on interpolated path - int second_pass_judge_ip_int = second_attention_stopline_ip_int - std::ceil(braking_dist / ds); + // (8) second pass judge line position on interpolated path. It is the same as first pass judge + // line if second_attention_lane is null + int second_pass_judge_ip_int = occlusion_wo_tl_pass_judge_line_ip; const auto second_pass_judge_line_ip = - static_cast(std::max(second_pass_judge_ip_int, 0)); + second_attention_area_opt ? static_cast(std::max(second_pass_judge_ip_int, 0)) + : first_pass_judge_line_ip; struct IntersectionStopLinesTemp { @@ -2803,8 +2843,6 @@ TimeDistanceArray IntersectionModule::calcIntersectionPassingTime( return std::nullopt; } }(); - const bool has_upstream_stopline = upstream_stopline_idx_opt.has_value(); - const size_t upstream_stopline_ind = upstream_stopline_idx_opt.value_or(0); for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size() - 1; ++i) { const auto & p1 = smoothed_reference_path.points.at(i); @@ -2818,7 +2856,7 @@ TimeDistanceArray IntersectionModule::calcIntersectionPassingTime( (p1.point.longitudinal_velocity_mps + p2.point.longitudinal_velocity_mps) / 2.0; const double passing_velocity = [=]() { if (use_upstream_velocity) { - if (has_upstream_stopline && i > upstream_stopline_ind) { + if (upstream_stopline_idx_opt && i > upstream_stopline_idx_opt.value()) { return minimum_upstream_velocity; } return std::max(average_velocity, minimum_ego_velocity); diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 38feada725872..1a9cf74624fc0 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -48,7 +48,10 @@ struct DebugData std::optional collision_stop_wall_pose{std::nullopt}; std::optional occlusion_stop_wall_pose{std::nullopt}; std::optional occlusion_first_stop_wall_pose{std::nullopt}; - std::optional pass_judge_wall_pose{std::nullopt}; + std::optional first_pass_judge_wall_pose{std::nullopt}; + bool passed_first_pass_judge{false}; + bool passed_second_pass_judge{false}; + std::optional second_pass_judge_wall_pose{std::nullopt}; std::optional> attention_area{std::nullopt}; std::optional> occlusion_attention_area{std::nullopt}; std::optional ego_lane{std::nullopt}; @@ -256,8 +259,8 @@ struct IntersectionStopLines size_t first_pass_judge_line{0}; /** - * second_pass_judge_line is before second_attention_stopline by the braking distance. if its - * value is calculated negative, it is 0 + * second_pass_judge_line is before second_attention_stopline by the braking distance. if + * second_attention_lane is null, it is same as first_pass_judge_line */ size_t second_pass_judge_line{0}; @@ -344,6 +347,7 @@ class IntersectionModule : public SceneModuleInterface double max_accel; double max_jerk; double delay_response_time; + bool enable_pass_judge_before_default_stopline; } common; struct TurnDirection @@ -373,7 +377,6 @@ class IntersectionModule : public SceneModuleInterface bool consider_wrong_direction_vehicle; double collision_detection_hold_time; double min_predicted_path_confidence; - double keep_detection_velocity_threshold; struct VelocityProfile { bool use_upstream; @@ -606,7 +609,7 @@ class IntersectionModule : public SceneModuleInterface private: rclcpp::Node & node_; - const int64_t lane_id_; + const lanelet::Id lane_id_; const std::set associative_ids_; const std::string turn_direction_; const bool has_traffic_light_; @@ -621,6 +624,9 @@ class IntersectionModule : public SceneModuleInterface bool is_permanent_go_{false}; DecisionResult prev_decision_result_{Indecisive{""}}; OcclusionType prev_occlusion_status_; + bool passed_1st_judge_line_while_peeking_{false}; + std::optional safely_passed_1st_judge_line_time_{std::nullopt}; + std::optional safely_passed_2nd_judge_line_time_{std::nullopt}; // for occlusion detection const bool enable_occlusion_detection_; From ed5b8e69b8d439032f03550a9b355fd231b73c6b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 18 Jan 2024 18:22:55 +0900 Subject: [PATCH 267/276] feat(blind_spot): consider opposite adjacent lane for wrong vehicles (#5635) Signed-off-by: Mamoru Sobue Signed-off-by: karishma --- .../config/blind_spot.param.yaml | 1 + .../src/debug.cpp | 6 +- .../src/manager.cpp | 2 + .../src/scene.cpp | 220 ++++++++++++------ .../src/scene.hpp | 16 +- 5 files changed, 162 insertions(+), 83 deletions(-) diff --git a/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml b/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml index f9ddd3ce61099..3c22d1fe65db5 100644 --- a/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml +++ b/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml @@ -8,4 +8,5 @@ max_future_movement_time: 10.0 # [second] threshold_yaw_diff: 0.523 # [rad] adjacent_extend_width: 1.5 # [m] + opposite_adjacent_extend_width: 1.5 # [m] enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval diff --git a/planning/behavior_velocity_blind_spot_module/src/debug.cpp b/planning/behavior_velocity_blind_spot_module/src/debug.cpp index 7da494bfd5231..5cc90afb0043d 100644 --- a/planning/behavior_velocity_blind_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/debug.cpp @@ -145,14 +145,12 @@ visualization_msgs::msg::MarkerArray BlindSpotModule::createDebugMarkerArray() appendMarkerArray( createLaneletPolygonsMarkerArray( - debug_data_.conflict_areas_for_blind_spot, "conflict_area_for_blind_spot", module_id_, 0.0, - 0.5, 0.5), + debug_data_.conflict_areas, "conflict_area", module_id_, 0.0, 0.5, 0.5), &debug_marker_array, now); appendMarkerArray( createLaneletPolygonsMarkerArray( - debug_data_.detection_areas_for_blind_spot, "detection_area_for_blind_spot", module_id_, 0.5, - 0.0, 0.0), + debug_data_.detection_areas, "detection_area", module_id_, 0.5, 0.0, 0.0), &debug_marker_array, now); appendMarkerArray( diff --git a/planning/behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_blind_spot_module/src/manager.cpp index d64f1ebc39a51..09d1c5a7c3270 100644 --- a/planning/behavior_velocity_blind_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/manager.cpp @@ -48,6 +48,8 @@ BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".threshold_yaw_diff"); planner_param_.adjacent_extend_width = getOrDeclareParameter(node, ns + ".adjacent_extend_width"); + planner_param_.opposite_adjacent_extend_width = + getOrDeclareParameter(node, ns + ".opposite_adjacent_extend_width"); } void BlindSpotModuleManager::launchNewModules( diff --git a/planning/behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_blind_spot_module/src/scene.cpp index 62a5e06674d4e..efbff7e2af51d 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.cpp @@ -105,16 +105,18 @@ bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr(); /* set stop-line and stop-judgement-line for base_link */ - int stop_line_idx = -1; const auto straight_lanelets = getStraightLanelets(lanelet_map_ptr, routing_graph_ptr, lane_id_); - if (!generateStopLine(straight_lanelets, path, &stop_line_idx)) { + const auto stoplines_idx_opt = generateStopLine(straight_lanelets, path); + if (!stoplines_idx_opt) { RCLCPP_WARN_SKIPFIRST_THROTTLE( logger_, *clock_, 1000 /* ms */, "[BlindSpotModule::run] setStopLineIdx fail"); *path = input_path; // reset path return false; } - if (stop_line_idx <= 0) { + const auto [default_stopline_idx, critical_stopline_idx] = stoplines_idx_opt.value(); + + if (default_stopline_idx <= 0) { RCLCPP_DEBUG( logger_, "[Blind Spot] stop line or pass judge line is at path[0], ignore planning."); *path = input_path; // reset path @@ -133,6 +135,8 @@ bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto return false; } const size_t closest_idx = closest_idx_opt.value(); + const auto stop_line_idx = + closest_idx > default_stopline_idx ? critical_stopline_idx : default_stopline_idx; /* set judge line dist */ const double current_vel = planner_data_->current_velocity->twist.linear.x; @@ -156,9 +160,6 @@ bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto debug_data_.virtual_wall_pose = stop_line_pose; const auto stop_pose = path->points.at(stop_line_idx).point.pose; debug_data_.stop_point_pose = stop_pose; - auto offset_pose = motion_utils::calcLongitudinalOffsetPose( - path->points, stop_pose.position, -pass_judge_line_dist); - if (offset_pose) debug_data_.judge_point_pose = *offset_pose; /* if current_state = GO, and current_pose is over judge_line, ignore planning. */ if (planner_param_.use_pass_judge_line) { @@ -235,69 +236,41 @@ std::optional BlindSpotModule::getFirstPointConflictingLanelets( } } -bool BlindSpotModule::generateStopLine( +std::optional> BlindSpotModule::generateStopLine( const lanelet::ConstLanelets straight_lanelets, - autoware_auto_planning_msgs::msg::PathWithLaneId * path, int * stop_line_idx) const + autoware_auto_planning_msgs::msg::PathWithLaneId * path) const { /* set parameters */ constexpr double interval = 0.2; const int margin_idx_dist = std::ceil(planner_param_.stop_line_margin / interval); - const int base2front_idx_dist = - std::ceil(planner_data_->vehicle_info_.max_longitudinal_offset_m / interval); + // const int base2front_idx_dist = + // std::ceil(planner_data_->vehicle_info_.max_longitudinal_offset_m / interval); /* spline interpolation */ autoware_auto_planning_msgs::msg::PathWithLaneId path_ip; if (!splineInterpolate(*path, interval, path_ip, logger_)) { - return false; + return std::nullopt; } /* generate stop point */ - int stop_idx_ip = 0; // stop point index for interpolated path. + size_t stop_idx_default_ip = 0; // stop point index for interpolated path. + size_t stop_idx_critical_ip = 0; if (straight_lanelets.size() > 0) { std::optional first_idx_conflicting_lane_opt = getFirstPointConflictingLanelets(path_ip, straight_lanelets); if (!first_idx_conflicting_lane_opt) { RCLCPP_DEBUG(logger_, "No conflicting line found."); - return false; - } - stop_idx_ip = std::max( - first_idx_conflicting_lane_opt.value() - 1 - margin_idx_dist - base2front_idx_dist, 0); - } else { - std::optional intersection_enter_point_opt = - getStartPointFromLaneLet(lane_id_); - if (!intersection_enter_point_opt) { - RCLCPP_DEBUG(logger_, "No intersection enter point found."); - return false; - } - - geometry_msgs::msg::Pose intersection_enter_pose; - intersection_enter_pose = intersection_enter_point_opt.value(); - const auto stop_idx_ip_opt = - motion_utils::findNearestIndex(path_ip.points, intersection_enter_pose, 10.0, M_PI_4); - if (stop_idx_ip_opt) { - stop_idx_ip = stop_idx_ip_opt.value(); + return std::nullopt; } - - stop_idx_ip = std::max(stop_idx_ip - base2front_idx_dist, 0); + stop_idx_default_ip = std::max(first_idx_conflicting_lane_opt.value() - 1 - margin_idx_dist, 0); + stop_idx_critical_ip = std::max(first_idx_conflicting_lane_opt.value() - 1, 0); } /* insert stop_point to use interpolated path*/ - *stop_line_idx = insertPoint(stop_idx_ip, path_ip, path); + const size_t stopline_idx_default = insertPoint(stop_idx_default_ip, path_ip, path); + const size_t stopline_idx_critical = insertPoint(stop_idx_critical_ip, path_ip, path); - /* if another stop point exist before intersection stop_line, disable judge_line. */ - bool has_prior_stopline = false; - for (int i = 0; i < *stop_line_idx; ++i) { - if (std::fabs(path->points.at(i).point.longitudinal_velocity_mps) < 0.1) { - has_prior_stopline = true; - break; - } - } - - RCLCPP_DEBUG( - logger_, "generateStopLine() : stop_idx = %d, stop_idx_ip = %d, has_prior_stopline = %d", - *stop_line_idx, stop_idx_ip, has_prior_stopline); - - return true; + return std::make_pair(stopline_idx_default, stopline_idx_critical); } void BlindSpotModule::cutPredictPathWithDuration( @@ -385,36 +358,61 @@ bool BlindSpotModule::checkObstacleInBlindSpot( const auto areas_opt = generateBlindSpotPolygons( lanelet_map_ptr, routing_graph_ptr, path, closest_idx, stop_line_pose); - if (!!areas_opt) { - debug_data_.detection_areas_for_blind_spot = areas_opt.value().detection_areas; - debug_data_.conflict_areas_for_blind_spot = areas_opt.value().conflict_areas; + if (areas_opt) { + const auto & detection_areas = areas_opt.value().detection_areas; + const auto & conflict_areas = areas_opt.value().conflict_areas; + const auto & opposite_detection_areas = areas_opt.value().opposite_detection_areas; + const auto & opposite_conflict_areas = areas_opt.value().opposite_conflict_areas; + debug_data_.detection_areas = detection_areas; + debug_data_.conflict_areas = conflict_areas; + debug_data_.detection_areas.insert( + debug_data_.detection_areas.end(), opposite_detection_areas.begin(), + opposite_detection_areas.end()); + debug_data_.conflict_areas.insert( + debug_data_.conflict_areas.end(), opposite_conflict_areas.begin(), + opposite_conflict_areas.end()); autoware_auto_perception_msgs::msg::PredictedObjects objects = *objects_ptr; cutPredictPathWithDuration(&objects, planner_param_.max_future_movement_time); // check objects in blind spot areas - bool obstacle_detected = false; for (const auto & object : objects.objects) { if (!isTargetObjectType(object)) { continue; } - const auto & detection_areas = areas_opt.value().detection_areas; - const auto & conflict_areas = areas_opt.value().conflict_areas; - const bool exist_in_detection_area = + // right direction + const bool exist_in_right_detection_area = std::any_of(detection_areas.begin(), detection_areas.end(), [&object](const auto & area) { return bg::within( to_bg2d(object.kinematics.initial_pose_with_covariance.pose.position), lanelet::utils::to2D(area)); }); - const bool exist_in_conflict_area = + // opposite direction + const bool exist_in_opposite_detection_area = std::any_of( + opposite_detection_areas.begin(), opposite_detection_areas.end(), + [&object](const auto & area) { + return bg::within( + to_bg2d(object.kinematics.initial_pose_with_covariance.pose.position), + lanelet::utils::to2D(area)); + }); + const bool exist_in_detection_area = + exist_in_right_detection_area || exist_in_opposite_detection_area; + if (!exist_in_detection_area) { + continue; + } + const bool exist_in_right_conflict_area = isPredictedPathInArea(object, conflict_areas, planner_data_->current_odometry->pose); + const bool exist_in_opposite_conflict_area = isPredictedPathInArea( + object, opposite_conflict_areas, planner_data_->current_odometry->pose); + const bool exist_in_conflict_area = + exist_in_right_conflict_area || exist_in_opposite_conflict_area; if (exist_in_detection_area && exist_in_conflict_area) { - obstacle_detected = true; debug_data_.conflicting_targets.objects.push_back(object); + return true; } } - return obstacle_detected; + return false; } else { return false; } @@ -504,6 +502,37 @@ lanelet::ConstLanelet BlindSpotModule::generateExtendedAdjacentLanelet( return new_lanelet; } +lanelet::ConstLanelet BlindSpotModule::generateExtendedOppositeAdjacentLanelet( + const lanelet::ConstLanelet lanelet, const TurnDirection direction) const +{ + const auto centerline = lanelet.centerline2d(); + const auto width = + boost::geometry::area(lanelet.polygon2d().basicPolygon()) / boost::geometry::length(centerline); + const double extend_width = + std::min(planner_param_.opposite_adjacent_extend_width, width); + const auto left_bound_ = + direction == TurnDirection::RIGHT + ? lanelet.rightBound().invert() + : lanelet::utils::getCenterlineWithOffset(lanelet.invert(), -width / 2 + extend_width); + const auto right_bound_ = + direction == TurnDirection::RIGHT + ? lanelet::utils::getCenterlineWithOffset(lanelet.invert(), width / 2 - extend_width) + : lanelet.leftBound().invert(); + lanelet::Points3d lefts, rights; + for (const auto & pt : left_bound_) { + lefts.push_back(lanelet::Point3d(pt)); + } + for (const auto & pt : right_bound_) { + rights.push_back(lanelet::Point3d(pt)); + } + const auto left_bound = lanelet::LineString3d(lanelet::InvalId, std::move(lefts)); + const auto right_bound = lanelet::LineString3d(lanelet::InvalId, std::move(rights)); + auto new_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); + const auto new_centerline = lanelet::utils::generateFineCenterline(new_lanelet, 5.0); + new_lanelet.setCenterline(new_centerline); + return new_lanelet; +} + std::optional BlindSpotModule::generateBlindSpotPolygons( lanelet::LaneletMapConstPtr lanelet_map_ptr, [[maybe_unused]] lanelet::routing::RoutingGraphPtr routing_graph_ptr, @@ -512,19 +541,20 @@ std::optional BlindSpotModule::generateBlindSpotPolygons( { std::vector lane_ids; lanelet::ConstLanelets blind_spot_lanelets; + lanelet::ConstLanelets blind_spot_opposite_lanelets; /* get lane ids until intersection */ for (const auto & point : path.points) { bool found_intersection_lane = false; for (const auto lane_id : point.lane_ids) { - // make lane_ids unique - if (std::find(lane_ids.begin(), lane_ids.end(), lane_id) == lane_ids.end()) { - lane_ids.push_back(lane_id); - } - if (lane_id == lane_id_) { found_intersection_lane = true; + lane_ids.push_back(lane_id); break; } + // make lane_ids unique + if (std::find(lane_ids.begin(), lane_ids.end(), lane_id) == lane_ids.end()) { + lane_ids.push_back(lane_id); + } } if (found_intersection_lane) break; } @@ -537,27 +567,49 @@ std::optional BlindSpotModule::generateBlindSpotPolygons( // additional detection area on left/right side lanelet::ConstLanelets adjacent_lanelets; + lanelet::ConstLanelets opposite_adjacent_lanelets; for (const auto i : lane_ids) { const auto lane = lanelet_map_ptr->laneletLayer.get(i); - const auto adj = std::invoke([&]() -> std::optional { - if (turn_direction_ == TurnDirection::INVALID) { + const auto adj = + turn_direction_ == TurnDirection::LEFT + ? (routing_graph_ptr->adjacentLeft(lane)) + : (turn_direction_ == TurnDirection::RIGHT ? (routing_graph_ptr->adjacentRight(lane)) + : boost::none); + const std::optional opposite_adj = + [&]() -> std::optional { + if (!!adj) { return std::nullopt; } - const auto adj_lane = (turn_direction_ == TurnDirection::LEFT) - ? routing_graph_ptr->adjacentLeft(lane) - : routing_graph_ptr->adjacentRight(lane); - - if (adj_lane) { - return *adj_lane; + if (turn_direction_ == TurnDirection::LEFT) { + // this should exist in right-hand traffic + const auto adjacent_lanes = + lanelet_map_ptr->laneletLayer.findUsages(lane.leftBound().invert()); + if (adjacent_lanes.empty()) { + return std::nullopt; + } + return adjacent_lanes.front(); } - - return std::nullopt; - }); - + if (turn_direction_ == TurnDirection::RIGHT) { + // this should exist in left-hand traffic + const auto adjacent_lanes = + lanelet_map_ptr->laneletLayer.findUsages(lane.rightBound().invert()); + if (adjacent_lanes.empty()) { + return std::nullopt; + } + return adjacent_lanes.front(); + } else { + return std::nullopt; + } + }(); if (adj) { const auto half_lanelet = generateExtendedAdjacentLanelet(adj.value(), turn_direction_); adjacent_lanelets.push_back(half_lanelet); } + if (opposite_adj) { + const auto half_lanelet = + generateExtendedOppositeAdjacentLanelet(opposite_adj.value(), turn_direction_); + opposite_adjacent_lanelets.push_back(half_lanelet); + } } const auto current_arc_ego = @@ -587,6 +639,24 @@ std::optional BlindSpotModule::generateBlindSpotPolygons( blind_spot_polygons.conflict_areas.emplace_back(std::move(conflicting_area_adj)); blind_spot_polygons.detection_areas.emplace_back(std::move(detection_area_adj)); } + // additional detection area on left/right opposite lane side + if (!opposite_adjacent_lanelets.empty()) { + const auto stop_line_arc_opposite_adj = + lanelet::utils::getLaneletLength3d(opposite_adjacent_lanelets); + const auto current_arc_opposite_adj = + stop_line_arc_opposite_adj - (stop_line_arc_ego - current_arc_ego); + const auto detection_area_start_length_opposite_adj = + stop_line_arc_opposite_adj - planner_param_.backward_length; + auto conflicting_area_opposite_adj = lanelet::utils::getPolygonFromArcLength( + opposite_adjacent_lanelets, current_arc_opposite_adj, stop_line_arc_opposite_adj); + auto detection_area_opposite_adj = lanelet::utils::getPolygonFromArcLength( + opposite_adjacent_lanelets, detection_area_start_length_opposite_adj, + stop_line_arc_opposite_adj); + blind_spot_polygons.opposite_conflict_areas.emplace_back( + std::move(conflicting_area_opposite_adj)); + blind_spot_polygons.opposite_detection_areas.emplace_back( + std::move(detection_area_opposite_adj)); + } return blind_spot_polygons; } else { return std::nullopt; @@ -677,7 +747,7 @@ lanelet::ConstLanelets BlindSpotModule::getStraightLanelets( const auto next_lanelets = routing_graph_ptr->following(prev_intersection_lanelets.front()); for (const auto & ll : next_lanelets) { const std::string turn_direction = ll.attributeOr("turn_direction", "else"); - if (!turn_direction.compare("straight")) { + if (turn_direction.compare("straight") == 0) { straight_lanelets.push_back(ll); } } diff --git a/planning/behavior_velocity_blind_spot_module/src/scene.hpp b/planning/behavior_velocity_blind_spot_module/src/scene.hpp index 3915acd3532b5..6f8450568939c 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.hpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.hpp @@ -30,6 +30,7 @@ #include #include +#include #include namespace behavior_velocity_planner @@ -38,6 +39,8 @@ struct BlindSpotPolygons { std::vector conflict_areas; std::vector detection_areas; + std::vector opposite_conflict_areas; + std::vector opposite_detection_areas; }; class BlindSpotModule : public SceneModuleInterface @@ -50,8 +53,10 @@ class BlindSpotModule : public SceneModuleInterface geometry_msgs::msg::Pose virtual_wall_pose; geometry_msgs::msg::Pose stop_point_pose; geometry_msgs::msg::Pose judge_point_pose; - std::vector conflict_areas_for_blind_spot; - std::vector detection_areas_for_blind_spot; + std::vector conflict_areas; + std::vector detection_areas; + std::vector opposite_conflict_areas; + std::vector opposite_detection_areas; autoware_auto_perception_msgs::msg::PredictedObjects conflicting_targets; }; @@ -67,6 +72,7 @@ class BlindSpotModule : public SceneModuleInterface double threshold_yaw_diff; //! threshold of yaw difference between ego and target object double adjacent_extend_width; //! the width of extended detection/conflict area on adjacent lane + double opposite_adjacent_extend_width; }; BlindSpotModule( @@ -118,6 +124,8 @@ class BlindSpotModule : public SceneModuleInterface lanelet::ConstLanelet generateExtendedAdjacentLanelet( const lanelet::ConstLanelet lanelet, const TurnDirection direction) const; + lanelet::ConstLanelet generateExtendedOppositeAdjacentLanelet( + const lanelet::ConstLanelet lanelet, const TurnDirection direction) const; /** * @brief Make blind spot areas. Narrow area is made from closest path point to stop line index. @@ -169,9 +177,9 @@ class BlindSpotModule : public SceneModuleInterface * @param pass_judge_line_idx generated pass judge line index * @return false when generation failed */ - bool generateStopLine( + std::optional> generateStopLine( const lanelet::ConstLanelets straight_lanelets, - autoware_auto_planning_msgs::msg::PathWithLaneId * path, int * stop_line_idx) const; + autoware_auto_planning_msgs::msg::PathWithLaneId * path) const; /** * @brief Insert a point to target path From 69769ea205dcf77f86754c3b50592af70fac8550 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 18 Jan 2024 18:51:11 +0900 Subject: [PATCH 268/276] docs(vehicle_info): add docs for versioning (#6069) Signed-off-by: kosuke55 remove non-support Signed-off-by: kosuke55 fix link Signed-off-by: kosuke55 add yaml Signed-off-by: kosuke55 please check readme Signed-off-by: karishma --- vehicle/vehicle_info_util/Readme.md | 29 +++++++++++++++++++ .../config/vehicle_info.param.yaml | 1 + 2 files changed, 30 insertions(+) diff --git a/vehicle/vehicle_info_util/Readme.md b/vehicle/vehicle_info_util/Readme.md index c3d06a3b43260..600fd62270d81 100644 --- a/vehicle/vehicle_info_util/Readme.md +++ b/vehicle/vehicle_info_util/Readme.md @@ -7,6 +7,35 @@ This package is to get vehicle info parameters. ### Description In [here](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/components/vehicle-dimensions/), you can check the vehicle dimensions with more detail. +The current format supports only the Ackermann model. This file defines the model assumed in autoware path planning, control, etc. and does not represent the exact physical model. If a model other than the Ackermann model is used, it is assumed that a vehicle interface will be designed to change the control output for the model. + +### Versioning Policy + +We have implemented a versioning system for the `vehicle_info.param.yaml` file to ensure clarity and consistency in file format across different versions of Autoware and its external applications. Please see [discussion](https://github.com/orgs/autowarefoundation/discussions/4050) for the details. + +#### How to Operate + +- The current file format is set as an unversioned base version (`version:` field is commented out). +- For the next update involving changes (such as additions, deletions, or modifications): + - Uncomment and update the version line at the beginning of the file. + - Initiate versioning by assigning a version number, starting from `0.1.0`. Follow the semantic versioning format (MAJOR.MINOR.PATCH). + - Update this Readme.md too. +- For subsequent updates, continue incrementing the version number in accordance with the changes made. + - Discuss how to increment version depending on the amount of changes made to the file. + +```yaml +/**: + ros__parameters: + # version: 0.1.0 # Uncomment and update this line for future format changes. + wheel_radius: 0.383 + ... +``` + +#### Why Versioning? + +- Consistency Across Updates: Implementing version control will allow accurate tracking of changes over time and changes in vehicle information parameters. +- Clarity for External Applications: External applications that depend on `vehicle_info.param.yaml` need to reference the correct file version for optimal compatibility and functionality. +- Simplified Management for Customized Branches: Assigning versions directly to the `vehicle_info.param.yaml` file simplifies management compared to maintaining separate versions for multiple customized Autoware branches. This approach streamlines version tracking and reduces complexity. ### Scripts diff --git a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml b/vehicle/vehicle_info_util/config/vehicle_info.param.yaml index 8941b92b4e78e..72c070c17b52c 100644 --- a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml +++ b/vehicle/vehicle_info_util/config/vehicle_info.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + # version: 0.1.0 # uncomment this line in the next update of this file format. please check Readme.md wheel_radius: 0.39 wheel_width: 0.42 wheel_base: 2.74 # between front wheel center and rear wheel center From 4d5b47cc405cd6873adc10023a89821295ff5e56 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 18 Jan 2024 12:49:52 +0000 Subject: [PATCH 269/276] chore: update CODEOWNERS (#6038) Signed-off-by: GitHub Co-authored-by: github-actions Signed-off-by: karishma --- .github/CODEOWNERS | 80 ++++++++++++++++++++++++---------------------- 1 file changed, 41 insertions(+), 39 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 12ad752b3ef29..89bcbce9e5656 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -1,7 +1,7 @@ ### Copied from .github/CODEOWNERS-manual ### ### Automatically generated from package.xml ### -common/autoware_ad_api_specs/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp +common/autoware_ad_api_specs/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp common/autoware_auto_common/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_auto_geometry/** satoshi.ota@tier4.jp common/autoware_auto_perception_rviz_plugin/** opensource@apex.ai satoshi.tanaka@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp @@ -9,9 +9,9 @@ common/autoware_auto_tf2/** jit.ray.c@gmail.com satoshi.ota@tier4.jp shumpei.wak common/autoware_point_types/** taichi.higashide@tier4.jp common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp -common/component_interface_specs/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp -common/component_interface_tools/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp -common/component_interface_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp +common/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/geography_utils/** koji.minoda@tier4.jp @@ -24,7 +24,7 @@ common/kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.sa common/motion_utils/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp common/object_recognition_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yusuke.muramatsu@tier4.jp common/osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp -common/path_distance_calculator/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp +common/path_distance_calculator/** isamu.takagi@tier4.jp common/perception_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yusuke.muramatsu@tier4.jp common/polar_grid/** yukihiro.saito@tier4.jp common/qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp @@ -32,16 +32,16 @@ common/rtc_manager_rviz_plugin/** taiki.tanaka@tier4.jp tomoya.kimura@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 common/tensorrt_common/** daisuke.nishimatsu@tier4.jp dan.umeda@tier4.jp manato.hirabayashi@tier4.jp common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp -common/tier4_api_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp +common/tier4_api_utils/** isamu.takagi@tier4.jp common/tier4_automatic_goal_rviz_plugin/** dawid.moszynski@robotec.ai shumpei.wakabayashi@tier4.jp common/tier4_autoware_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/tier4_calibration_rviz_plugin/** tomoya.kimura@tier4.jp common/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp common/tier4_control_rviz_plugin/** taiki.tanaka@tier4.jp -common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp +common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp common/tier4_debug_rviz_plugin/** takayuki.murooka@tier4.jp common/tier4_debug_tools/** ryohsuke.mitsudome@tier4.jp -common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp takamasa.horibe@tier4.jp +common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp takamasa.horibe@tier4.jp common/tier4_logging_level_configure_rviz_plugin/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp common/tier4_perception_rviz_plugin/** yukihiro.saito@tier4.jp common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp @@ -54,7 +54,7 @@ common/tier4_traffic_light_rviz_plugin/** satoshi.ota@tier4.jp common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp common/time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp -common/traffic_light_utils/** mingyu.li@tier4.jp shunsuke.miura@tier4.jp +common/traffic_light_utils/** mingyu.li@tier4.jp satoshi.ota@tier4.jp shunsuke.miura@tier4.jp common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp control/autonomous_emergency_braking/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @@ -76,9 +76,9 @@ evaluator/diagnostic_converter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4 evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp evaluator/localization_evaluator/** dominik.jargot@robotec.ai koji.minoda@tier4.jp evaluator/planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp -launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp +launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -launch/tier4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp +launch/tier4_localization_launch/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp launch/tier4_map_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp launch/tier4_perception_launch/** shunsuke.miura@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp launch/tier4_planning_launch/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp zulfaqar.azmi@tier4.jp @@ -86,29 +86,29 @@ 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/ekf_localizer/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp -localization/geo_pose_projector/** koji.minoda@tier4.jp yamato.ando@tier4.jp -localization/gyro_odometer/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/landmark_based_localizer/ar_tag_based_localizer/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp -localization/landmark_based_localizer/landmark_manager/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp -localization/localization_error_monitor/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/localization_util/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp -localization/ndt_scan_matcher/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/pose2twist/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/pose_initializer/** isamu.takagi@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/pose_instability_detector/** 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/stop_filter/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/tree_structured_parzen_estimator/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp -localization/twist2accel/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/yabloc/yabloc_common/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp -localization/yabloc/yabloc_image_processing/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp -localization/yabloc/yabloc_monitor/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp -localization/yabloc/yabloc_particle_filter/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp -localization/yabloc/yabloc_pose_initializer/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp -map/map_height_fitter/** isamu.takagi@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -map/map_loader/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp -map/map_projection_loader/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -map/map_tf_generator/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/ekf_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@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/geo_pose_projector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/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/landmark_based_localizer/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/landmark_based_localizer/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/localization_error_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@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 koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/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/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/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/stop_filter/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/tree_structured_parzen_estimator/** 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/twist2accel/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@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 koji.minoda@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/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 koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp +map/map_projection_loader/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +map/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/** ryohsuke.mitsudome@tier4.jp perception/bytetrack/** manato.hirabayashi@tier4.jp perception/cluster_merger/** dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp @@ -156,6 +156,7 @@ perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp perception/traffic_light_visualization/** yukihiro.saito@tier4.jp planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_path_dynamic_avoidance_module/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp planning/behavior_path_external_request_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_goal_planner_module/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp @@ -166,6 +167,7 @@ planning/behavior_path_start_planner_module/** kosuke.takeuchi@tier4.jp kyoichi. planning/behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/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_detection_area_module/** kyoichi.sugahara@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_dynamic_obstacle_stop_module/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp planning/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_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @@ -223,11 +225,11 @@ simulator/fault_injection/** keisuke.shima@tier4.jp simulator/simple_planning_simulator/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp system/autoware_auto_msgs_adapter/** isamu.takagi@tier4.jp mfc@leodrive.ai system/bluetooth_monitor/** fumihito.ito@tier4.jp -system/component_state_monitor/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp -system/default_ad_api/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp -system/default_ad_api_helpers/ad_api_adaptors/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp -system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp -system/default_ad_api_helpers/automatic_pose_initializer/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@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/default_ad_api_helpers/ad_api_adaptors/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/default_ad_api_helpers/automatic_pose_initializer/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/diagnostic_graph_aggregator/** isamu.takagi@tier4.jp system/dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp From 5bfe1fd1681dfa7681b6be3536d36f7d74514b39 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 18 Jan 2024 22:22:05 +0900 Subject: [PATCH 270/276] refactor(start_planner): visualize shifting section (#6103) * Visualize the footprint from start_pose to end_pose along the path Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara Signed-off-by: karishma --- .../src/start_planner_module.cpp | 33 +++++++++++++++++++ 1 file changed, 33 insertions(+) diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 9ad7f72d6af4e..0e0a6b123be12 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -1415,6 +1415,39 @@ void StartPlannerModule::setDebugData() add(start_pose_text_marker_array); } + // visualize the footprint from pull_out_start pose to pull_out_end pose along the path + { + MarkerArray pull_out_path_footprint_marker_array{}; + const auto pink = createMarkerColor(1.0, 0.0, 1.0, 0.99); + Marker pull_out_path_footprint_marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "shift_path_footprint", 0, Marker::LINE_STRIP, + createMarkerScale(0.2, 0.2, 0.2), pink); + pull_out_path_footprint_marker.lifetime = rclcpp::Duration::from_seconds(1.5); + PathWithLaneId path_shift_start_to_end{}; + const auto shift_path = status_.pull_out_path.partial_paths.front(); + { + const size_t pull_out_start_idx = motion_utils::findNearestIndex( + shift_path.points, status_.pull_out_path.start_pose.position); + const size_t pull_out_end_idx = + motion_utils::findNearestIndex(shift_path.points, status_.pull_out_path.end_pose.position); + + path_shift_start_to_end.points.insert( + path_shift_start_to_end.points.begin(), shift_path.points.begin() + pull_out_start_idx, + shift_path.points.begin() + pull_out_end_idx + 1); + } + + for (size_t i = 0; i < path_shift_start_to_end.points.size(); ++i) { + pull_out_path_footprint_marker.id = i; + pull_out_path_footprint_marker.points.clear(); + addFootprintMarker( + pull_out_path_footprint_marker, path_shift_start_to_end.points.at(i).point.pose, + vehicle_info_); + pull_out_path_footprint_marker_array.markers.push_back(pull_out_path_footprint_marker); + } + + add(pull_out_path_footprint_marker_array); + } + // safety check if (parameters_->safety_check_params.enable_safety_check) { if (start_planner_data_.ego_predicted_path.size() > 0) { From 298b5a33b33128aab5f2981231e811e95be7d2c9 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 18 Jan 2024 22:23:23 +0900 Subject: [PATCH 271/276] refactor(start_planner): separate start planner parameters and debug data structure (#6101) * Add data_structs.hpp and update include paths * Refactor start planner debug data structure * Update debug_data variable name in StartPlannerModule Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Signed-off-by: karishma --- .../parking_departure/common_module_data.hpp | 5 -- ...lanner_parameters.hpp => data_structs.hpp} | 26 ++++++++-- .../debug.hpp | 39 +++++++++++++++ .../pull_out_planner_base.hpp | 2 +- .../start_planner_module.hpp | 4 +- .../src/debug.cpp | 30 ++++++++++++ .../src/start_planner_module.cpp | 47 +++++++++---------- 7 files changed, 118 insertions(+), 35 deletions(-) rename planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/{start_planner_parameters.hpp => data_structs.hpp} (80%) create mode 100644 planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/debug.hpp create mode 100644 planning/behavior_path_start_planner_module/src/debug.cpp diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp index 3dc230f0e92ed..74f6b843803df 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp @@ -38,11 +38,6 @@ struct StartGoalPlannerData std::vector ego_predicted_path; // collision check debug map CollisionCheckDebugMap collision_check; - - Pose refined_start_pose; - std::vector start_pose_candidates; - size_t selected_start_pose_candidate_index; - double margin_for_start_pose_candidate; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp similarity index 80% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp index 66dbddebf99bb..8f8d2baf9c85e 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp @@ -13,8 +13,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_ #include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -29,10 +29,30 @@ namespace behavior_path_planner { +using autoware_auto_perception_msgs::msg::PredictedObjects; +using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebugMap; +using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; +using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; + using freespace_planning_algorithms::AstarParam; using freespace_planning_algorithms::PlannerCommonParam; using freespace_planning_algorithms::RRTStarParam; +struct StartPlannerDebugData +{ + // filtered objects + PredictedObjects filtered_objects; + TargetObjectsOnLane target_objects_on_lane; + std::vector ego_predicted_path; + // collision check debug map + CollisionCheckDebugMap collision_check; + + Pose refined_start_pose; + std::vector start_pose_candidates; + size_t selected_start_pose_candidate_index; + double margin_for_start_pose_candidate; +}; + struct StartPlannerParameters { double th_arrived_distance{0.0}; @@ -105,4 +125,4 @@ struct StartPlannerParameters } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/debug.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/debug.hpp new file mode 100644 index 0000000000000..6aa5584807d90 --- /dev/null +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/debug.hpp @@ -0,0 +1,39 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ + +#include "behavior_path_start_planner_module/data_structs.hpp" + +#include +#include + +namespace behavior_path_planner +{ +using 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 behavior_path_planner + +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp index e345e3dc91337..0144fdd45ae50 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -16,8 +16,8 @@ #define BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ #include "behavior_path_planner_common/data_manager.hpp" +#include "behavior_path_start_planner_module/data_structs.hpp" #include "behavior_path_start_planner_module/pull_out_path.hpp" -#include "behavior_path_start_planner_module/start_planner_parameters.hpp" #include #include diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index 7b463f4fadf80..47cfa408162ca 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -21,11 +21,11 @@ #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_start_planner_module/data_structs.hpp" #include "behavior_path_start_planner_module/freespace_pull_out.hpp" #include "behavior_path_start_planner_module/geometric_pull_out.hpp" #include "behavior_path_start_planner_module/pull_out_path.hpp" #include "behavior_path_start_planner_module/shift_pull_out.hpp" -#include "behavior_path_start_planner_module/start_planner_parameters.hpp" #include #include @@ -191,7 +191,7 @@ class StartPlannerModule : public SceneModuleInterface std::vector> start_planners_; PullOutStatus status_; - mutable StartGoalPlannerData start_planner_data_; + mutable StartPlannerDebugData debug_data_; std::deque odometry_buffer_; diff --git a/planning/behavior_path_start_planner_module/src/debug.cpp b/planning/behavior_path_start_planner_module/src/debug.cpp new file mode 100644 index 0000000000000..0f95470d86d40 --- /dev/null +++ b/planning/behavior_path_start_planner_module/src/debug.cpp @@ -0,0 +1,30 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "behavior_path_start_planner_module/debug.hpp" + +namespace 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 behavior_path_planner diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 0e0a6b123be12..1b54b655fc424 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -17,6 +17,7 @@ #include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" +#include "behavior_path_start_planner_module/debug.hpp" #include "behavior_path_start_planner_module/util.hpp" #include "motion_utils/trajectory/trajectory.hpp" @@ -126,7 +127,7 @@ void StartPlannerModule::initVariables() resetPathReference(); debug_marker_.markers.clear(); initializeSafetyCheckParameters(); - initializeCollisionCheckDebugMap(start_planner_data_.collision_check); + initializeCollisionCheckDebugMap(debug_data_.collision_check); } void StartPlannerModule::updateEgoPredictedPathParams( @@ -589,8 +590,8 @@ void StartPlannerModule::planWithPriority( if (findPullOutPath( start_pose_candidates[index], planner, refined_start_pose, goal_pose, collision_check_margin)) { - start_planner_data_.selected_start_pose_candidate_index = index; - start_planner_data_.margin_for_start_pose_candidate = collision_check_margin; + debug_data_.selected_start_pose_candidate_index = index; + debug_data_.margin_for_start_pose_candidate = collision_check_margin; return; } } @@ -848,8 +849,8 @@ void StartPlannerModule::updatePullOutStatus() start_pose_candidates, *refined_start_pose, goal_pose, parameters_->search_priority); } - start_planner_data_.refined_start_pose = *refined_start_pose; - start_planner_data_.start_pose_candidates = start_pose_candidates; + debug_data_.refined_start_pose = *refined_start_pose; + debug_data_.start_pose_candidates = start_pose_candidates; const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); @@ -1196,14 +1197,13 @@ bool StartPlannerModule::isSafePath() const const double hysteresis_factor = status_.is_safe_dynamic_objects ? 1.0 : safety_check_params_->hysteresis_factor_expand_rate; - utils::parking_departure::updateSafetyCheckTargetObjectsData( - start_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); + behavior_path_planner::updateSafetyCheckDebugData( + debug_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS( pull_out_path, ego_predicted_path, target_objects_on_lane.on_current_lane, - start_planner_data_.collision_check, planner_data_->parameters, - safety_check_params_->rss_params, objects_filtering_params_->use_all_predicted_path, - hysteresis_factor); + debug_data_.collision_check, planner_data_->parameters, safety_check_params_->rss_params, + objects_filtering_params_->use_all_predicted_path, hysteresis_factor); } bool StartPlannerModule::isGoalBehindOfEgoInSameRouteSegment() const @@ -1354,7 +1354,7 @@ void StartPlannerModule::setDebugData() add(createPoseMarkerArray(status_.pull_out_path.start_pose, "start_pose", 0, 0.3, 0.9, 0.3)); add(createPoseMarkerArray(status_.pull_out_path.end_pose, "end_pose", 0, 0.9, 0.9, 0.3)); add(createFootprintMarkerArray( - start_planner_data_.refined_start_pose, vehicle_info_, "refined_start_pose", 0, 0.9, 0.9, 0.3)); + debug_data_.refined_start_pose, vehicle_info_, "refined_start_pose", 0, 0.9, 0.9, 0.3)); add(createPathMarkerArray(getFullPath(), "full_path", 0, 0.0, 0.5, 0.9)); add(createPathMarkerArray(status_.backward_path, "backward_driving_path", 0, 0.0, 0.9, 0.0)); @@ -1399,14 +1399,13 @@ void StartPlannerModule::setDebugData() visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.3, 0.3, 0.3), purple); footprint_marker.lifetime = rclcpp::Duration::from_seconds(1.5); text_marker.lifetime = rclcpp::Duration::from_seconds(1.5); - for (size_t i = 0; i < start_planner_data_.start_pose_candidates.size(); ++i) { + for (size_t i = 0; i < debug_data_.start_pose_candidates.size(); ++i) { footprint_marker.id = i; text_marker.id = i; footprint_marker.points.clear(); text_marker.text = "idx[" + std::to_string(i) + "]"; - text_marker.pose = start_planner_data_.start_pose_candidates.at(i); - addFootprintMarker( - footprint_marker, start_planner_data_.start_pose_candidates.at(i), vehicle_info_); + text_marker.pose = debug_data_.start_pose_candidates.at(i); + addFootprintMarker(footprint_marker, debug_data_.start_pose_candidates.at(i), vehicle_info_); start_pose_footprint_marker_array.markers.push_back(footprint_marker); start_pose_text_marker_array.markers.push_back(text_marker); } @@ -1450,29 +1449,29 @@ void StartPlannerModule::setDebugData() // safety check if (parameters_->safety_check_params.enable_safety_check) { - if (start_planner_data_.ego_predicted_path.size() > 0) { + if (debug_data_.ego_predicted_path.size() > 0) { const auto & ego_predicted_path = utils::path_safety_checker::convertToPredictedPath( - start_planner_data_.ego_predicted_path, ego_predicted_path_params_->time_resolution); + debug_data_.ego_predicted_path, ego_predicted_path_params_->time_resolution); add(createPredictedPathMarkerArray( ego_predicted_path, vehicle_info_, "ego_predicted_path_start_planner", 0, 0.0, 0.5, 0.9)); } - if (start_planner_data_.filtered_objects.objects.size() > 0) { + if (debug_data_.filtered_objects.objects.size() > 0) { add(createObjectsMarkerArray( - start_planner_data_.filtered_objects, "filtered_objects", 0, 0.0, 0.5, 0.9)); + debug_data_.filtered_objects, "filtered_objects", 0, 0.0, 0.5, 0.9)); } - add(showSafetyCheckInfo(start_planner_data_.collision_check, "object_debug_info")); - add(showPredictedPath(start_planner_data_.collision_check, "ego_predicted_path")); - add(showPolygon(start_planner_data_.collision_check, "ego_and_target_polygon_relation")); + add(showSafetyCheckInfo(debug_data_.collision_check, "object_debug_info")); + add(showPredictedPath(debug_data_.collision_check, "ego_predicted_path")); + add(showPolygon(debug_data_.collision_check, "ego_and_target_polygon_relation")); // set objects of interest - for (const auto & [uuid, data] : start_planner_data_.collision_check) { + for (const auto & [uuid, data] : debug_data_.collision_check) { const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color); } - initializeCollisionCheckDebugMap(start_planner_data_.collision_check); + initializeCollisionCheckDebugMap(debug_data_.collision_check); } // Visualize planner type text From 6017657e2b074d2721497b3d47dd0f7f815ddac2 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 18 Jan 2024 23:25:16 +0900 Subject: [PATCH 272/276] fix(start_planner): expand lane departure check for shift path (#6055) Refactor lane departure check in ShiftPullOut::plan() Signed-off-by: kyoichi-sugahara Signed-off-by: karishma --- .../src/shift_pull_out.cpp | 24 ++++++------------- 1 file changed, 7 insertions(+), 17 deletions(-) diff --git a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp index 51673410199b8..36b8b1dc347a1 100644 --- a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -69,25 +69,15 @@ std::optional ShiftPullOut::plan(const Pose & start_pose, const Pos pull_out_path.partial_paths.front(); // shift path is not separate but only one. // check lane_departure with path between pull_out_start to pull_out_end - PathWithLaneId path_start_to_end{}; + PathWithLaneId path_shift_start_to_end{}; { const size_t pull_out_start_idx = findNearestIndex(shift_path.points, start_pose.position); + const size_t pull_out_end_idx = + findNearestIndex(shift_path.points, pull_out_path.end_pose.position); - // calculate collision check end idx - const size_t collision_check_end_idx = std::invoke([&]() { - const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose( - shift_path.points, pull_out_path.end_pose.position, - parameters_.collision_check_distance_from_end); - - if (collision_check_end_pose) { - return findNearestIndex(shift_path.points, collision_check_end_pose->position); - } else { - return shift_path.points.size() - 1; - } - }); - path_start_to_end.points.insert( - path_start_to_end.points.begin(), shift_path.points.begin() + pull_out_start_idx, - shift_path.points.begin() + collision_check_end_idx + 1); + path_shift_start_to_end.points.insert( + path_shift_start_to_end.points.begin(), shift_path.points.begin() + pull_out_start_idx, + shift_path.points.begin() + pull_out_end_idx + 1); } // extract shoulder lanes from pull out lanes @@ -131,7 +121,7 @@ std::optional ShiftPullOut::plan(const Pose & start_pose, const Pos // check lane departure if ( parameters_.check_shift_path_lane_departure && - lane_departure_checker_->checkPathWillLeaveLane(expanded_lanes, path_start_to_end)) { + lane_departure_checker_->checkPathWillLeaveLane(expanded_lanes, path_shift_start_to_end)) { continue; } From 7d6ccfbfeb10eec03787d1a68e2e4cacff308ccc Mon Sep 17 00:00:00 2001 From: beyzanurkaya <32412808+beyzanurkaya@users.noreply.github.com> Date: Fri, 19 Jan 2024 01:55:06 +0300 Subject: [PATCH 273/276] fix(behavior_velocity_crosswalk_module): check if p_safety_slow is empty (#6104) * check if p_safety_slow is empty Signed-off-by: beyza * style(pre-commit): autofix --------- Signed-off-by: beyza Co-authored-by: beyza Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Signed-off-by: karishma --- .../src/scene_crosswalk.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index acb88a214b0c0..48ae5ff03b8bd 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -813,7 +813,9 @@ void CrosswalkModule::applySafetySlowDownSpeed( const auto & p_safety_slow = calcLongitudinalOffsetPoint(ego_path.points, ego_pos, safety_slow_point_range); - insertDecelPointWithDebugInfo(p_safety_slow.value(), safety_slow_down_speed, output); + if (p_safety_slow.has_value()) { + insertDecelPointWithDebugInfo(p_safety_slow.value(), safety_slow_down_speed, output); + } if (safety_slow_point_range < 0.0) { passed_safety_slow_point_ = true; From fd309d401b7504cdeacb5be72a946c3aab15b7a9 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 19 Jan 2024 10:00:02 +0900 Subject: [PATCH 274/276] feat: always separate lidar preprocessing from pointcloud_container (#6091) * feat!: replace use_pointcloud_container Signed-off-by: kminoda * feat: remove from planning Signed-off-by: kminoda * fix: fix to remove all use_pointcloud_container Signed-off-by: kminoda * revert: revert change in planning.launch Signed-off-by: kminoda * revert: revert rename of use_pointcloud_container Signed-off-by: kminoda * fix: fix tier4_perception_launch to enable use_pointcloud_contaienr Signed-off-by: kminoda * fix: fix unnecessary change Signed-off-by: kminoda * fix: fix unnecessary change Signed-off-by: kminoda * refactor: remove trailing whitespace Signed-off-by: kminoda * revert other changes in perception Signed-off-by: kminoda * revert change in readme Signed-off-by: kminoda * feat: move glog to pointcloud_container.launch.py * revert: revert glog porting Signed-off-by: kminoda * style(pre-commit): autofix * fix: fix pre-commit Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Signed-off-by: karishma --- .../launch/localization.launch.xml | 7 ++++--- .../pose_twist_estimator.launch.xml | 8 ++++++-- .../launch/util/util.launch.py | 18 ++++-------------- ...era_lidar_fusion_based_detection.launch.xml | 4 ++-- ...dar_radar_fusion_based_detection.launch.xml | 4 ++-- .../detection/detection.launch.xml | 10 +++++----- .../detection/lidar_based_detection.launch.xml | 4 ++-- .../lidar_radar_based_detection.launch.xml | 4 ++-- .../detection/pointcloud_map_filter.launch.py | 7 ++++--- .../ground_segmentation.launch.py | 7 ++++--- ...probabilistic_occupancy_grid_map.launch.xml | 8 ++++---- .../launch/perception.launch.xml | 6 +++--- ...aserscan_based_occupancy_grid_map.launch.py | 7 ++++--- ...intcloud_based_occupancy_grid_map.launch.py | 7 ++++--- .../synchronized_grid_map_fusion.md | 4 ++-- 15 files changed, 52 insertions(+), 53 deletions(-) diff --git a/launch/tier4_localization_launch/launch/localization.launch.xml b/launch/tier4_localization_launch/launch/localization.launch.xml index 3fba4bd773e68..f4d6679291849 100644 --- a/launch/tier4_localization_launch/launch/localization.launch.xml +++ b/launch/tier4_localization_launch/launch/localization.launch.xml @@ -15,14 +15,15 @@ - - + - + + + 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 7733b4e3117a1..02c6da20e17da 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 @@ -23,7 +23,9 @@ - + + + @@ -142,7 +144,9 @@ - + + + diff --git a/launch/tier4_localization_launch/launch/util/util.launch.py b/launch/tier4_localization_launch/launch/util/util.launch.py index 1a34429f438ed..22a45fe7b8530 100644 --- a/launch/tier4_localization_launch/launch/util/util.launch.py +++ b/launch/tier4_localization_launch/launch/util/util.launch.py @@ -15,8 +15,6 @@ import launch from launch.actions import DeclareLaunchArgument from launch.actions import OpaqueFunction -from launch.conditions import LaunchConfigurationNotEquals -from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode @@ -71,16 +69,9 @@ def load_composable_node_param(param_path): random_downsample_component, ] - target_container = ( - "/sensing/lidar/top/pointcloud_preprocessor/pointcloud_container" - if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) - else LaunchConfiguration("pointcloud_container_name") - ) - load_composable_nodes = LoadComposableNodes( - condition=LaunchConfigurationNotEquals(target_container, ""), composable_node_descriptions=composable_nodes, - target_container=target_container, + target_container=LaunchConfiguration("lidar_container_name"), ) return [load_composable_nodes] @@ -115,11 +106,10 @@ def add_launch_arg(name: str, default_value=None, description=None): "path to the parameter file of random_downsample_filter", ) add_launch_arg("use_intra_process", "true", "use ROS 2 component container communication") - add_launch_arg("use_pointcloud_container", "True", "use pointcloud container") add_launch_arg( - "pointcloud_container_name", - "/pointcloud_container", - "container name", + "lidar_container_name", + "/sensing/lidar/top/pointcloud_preprocessor/pointcloud_container", + "container name of main lidar used for localization", ) add_launch_arg( diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index d269144067e0e..4cb648852a03c 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -6,7 +6,7 @@ - + @@ -62,7 +62,7 @@ - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index 4838187ef8fbe..ba86bc1e334ff 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -6,7 +6,7 @@ - + @@ -91,7 +91,7 @@ - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml index 68d5ea944e6cb..885fa80ed7004 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -8,7 +8,7 @@ - + @@ -59,7 +59,7 @@ - + @@ -96,7 +96,7 @@ - + @@ -111,7 +111,7 @@ - + @@ -126,7 +126,7 @@ - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index 2c8b7d6581c53..04c4264b70e5f 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -6,7 +6,7 @@ - + @@ -25,7 +25,7 @@ - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml index ed37f6270c913..adedc2312677f 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml @@ -5,7 +5,7 @@ - + @@ -23,7 +23,7 @@ - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py b/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py index 93d395ca3e466..1dcb9cfc90daf 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py @@ -141,7 +141,7 @@ def launch_setup(context, *args, **kwargs): components = [] components.extend(pipeline.create_pipeline()) individual_container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), + name=LaunchConfiguration("individual_container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), @@ -151,7 +151,7 @@ def launch_setup(context, *args, **kwargs): ) pointcloud_container_loader = LoadComposableNodes( composable_node_descriptions=components, - target_container=LaunchConfiguration("container_name"), + target_container=LaunchConfiguration("pointcloud_container_name"), condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), ) return [individual_container, pointcloud_container_loader] @@ -168,7 +168,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("use_multithread", "False") add_launch_arg("use_intra_process", "True") add_launch_arg("use_pointcloud_container", "False") - add_launch_arg("container_name", "pointcloud_map_filter_pipeline_container") + add_launch_arg("pointcloud_container_name", "pointcloud_container") + add_launch_arg("individual_container_name", "pointcloud_map_filter_container") add_launch_arg("use_pointcloud_map", "true") set_container_executable = SetLaunchConfiguration( "container_executable", 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 fecdd29bcb7e9..b54172acd4afc 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 @@ -511,7 +511,7 @@ def launch_setup(context, *args, **kwargs): ) ) individual_container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), + name=LaunchConfiguration("individual_container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), @@ -521,7 +521,7 @@ def launch_setup(context, *args, **kwargs): ) pointcloud_container_loader = LoadComposableNodes( composable_node_descriptions=components, - target_container=LaunchConfiguration("container_name"), + target_container=LaunchConfiguration("pointcloud_container_name"), condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), ) return [individual_container, pointcloud_container_loader] @@ -537,7 +537,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("use_multithread", "False") add_launch_arg("use_intra_process", "True") add_launch_arg("use_pointcloud_container", "False") - add_launch_arg("container_name", "perception_pipeline_container") + add_launch_arg("pointcloud_container_name", "pointcloud_container") + add_launch_arg("individual_container_name", "ground_segmentation_container") add_launch_arg("input/pointcloud", "/sensing/lidar/concatenated/pointcloud") set_container_executable = SetLaunchConfiguration( diff --git a/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml b/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml index 281a52a85af71..244e0940acb70 100644 --- a/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml +++ b/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml @@ -7,7 +7,7 @@ - + @@ -24,7 +24,7 @@ - + @@ -40,7 +40,7 @@ - + @@ -56,7 +56,7 @@ - + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 4e9f0daafa736..528038c5158b2 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -127,7 +127,7 @@ - + @@ -142,7 +142,7 @@ - + @@ -193,7 +193,7 @@ - + diff --git a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py index b99335b0e09ef..62cfa4bcb5228 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py @@ -115,7 +115,7 @@ def launch_setup(context, *args, **kwargs): ] occupancy_grid_map_container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), + name=LaunchConfiguration("individual_container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), @@ -126,7 +126,7 @@ def launch_setup(context, *args, **kwargs): load_composable_nodes = LoadComposableNodes( composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container_name"), + target_container=LaunchConfiguration("pointcloud_container_name"), condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), ) @@ -174,7 +174,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("input_obstacle_pointcloud", "false"), add_launch_arg("input_obstacle_and_raw_pointcloud", "true"), add_launch_arg("use_pointcloud_container", "false"), - add_launch_arg("container_name", "occupancy_grid_map_container"), + add_launch_arg("pointcloud_container_name", "pointcloud_container"), + add_launch_arg("individual_container_name", "occupancy_grid_map_container"), set_container_executable, set_container_mt_executable, ] diff --git a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py index 49bf228905dcc..29435c4ea8e24 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py @@ -64,7 +64,7 @@ def launch_setup(context, *args, **kwargs): ] occupancy_grid_map_container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), + name=LaunchConfiguration("individual_container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), @@ -75,7 +75,7 @@ def launch_setup(context, *args, **kwargs): load_composable_nodes = LoadComposableNodes( composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container_name"), + target_container=LaunchConfiguration("pointcloud_container_name"), condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), ) @@ -103,7 +103,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("use_multithread", "false"), add_launch_arg("use_intra_process", "true"), add_launch_arg("use_pointcloud_container", "false"), - add_launch_arg("container_name", "occupancy_grid_map_container"), + add_launch_arg("pointcloud_container_name", "pointcloud_container"), + add_launch_arg("individual_container_name", "occupancy_grid_map_container"), add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"), add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"), add_launch_arg("output", "occupancy_grid"), diff --git a/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md b/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md index e1046fa24719d..6f4d4e22aa26e 100644 --- a/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md +++ b/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md @@ -105,7 +105,7 @@ You need to generate OGMs in each sensor frame before achieving grid map fusion. - + @@ -146,7 +146,7 @@ You can include this launch file like the following. - + From b01488266e7d795a1cc9b49fdfd3e7efb58f5680 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Fri, 19 Jan 2024 13:16:52 +0900 Subject: [PATCH 275/276] feat(map_based_prediction): use obstacle acceleration for map prediction (#6072) * add acc filtering and decaying acc to model Signed-off-by: Daniel Sanchez * fixed compilation problem, acc is used to predict search_dist Signed-off-by: Daniel Sanchez * Use an equivalent velocity to calculate paths Signed-off-by: Daniel Sanchez * change decaying factor to T/4 Signed-off-by: Daniel Sanchez * coment out cerr for evaluation Signed-off-by: Daniel Sanchez * simplify code Signed-off-by: Daniel Sanchez * comments Signed-off-by: Daniel Sanchez * add missing constant to decaying acc model Signed-off-by: Daniel Sanchez * Use an equivalent velocity to calculate paths Signed-off-by: Daniel Sanchez * add missing constant to decaying acc model Signed-off-by: Daniel Sanchez * Implement lanelet speed limit for acc consideration Signed-off-by: Daniel Sanchez * add option to activate on and off acceleration feature Signed-off-by: Daniel Sanchez * add params Signed-off-by: Daniel Sanchez * add params Signed-off-by: Daniel Sanchez * delete unused class Signed-off-by: Daniel Sanchez * update docs Signed-off-by: Daniel Sanchez * delete comments Signed-off-by: Daniel Sanchez * fix comments Signed-off-by: Daniel Sanchez * update comments, refactor code Signed-off-by: Daniel Sanchez * remove unused line Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez Signed-off-by: Daniel Sanchez Signed-off-by: karishma --- perception/map_based_prediction/README.md | 48 ++++++++-- .../config/map_based_prediction.param.yaml | 3 + .../map_based_prediction_node.hpp | 9 +- .../map_based_prediction/path_generator.hpp | 20 ++++- .../src/map_based_prediction_node.cpp | 86 +++++++++++++++--- .../src/path_generator.cpp | 87 +++++++++++++++++-- 6 files changed, 224 insertions(+), 29 deletions(-) diff --git a/perception/map_based_prediction/README.md b/perception/map_based_prediction/README.md index ec2f57963332f..2419cdb010799 100644 --- a/perception/map_based_prediction/README.md +++ b/perception/map_based_prediction/README.md @@ -124,7 +124,7 @@ See paper [2] for more details. `lateral_control_time_horizon` parameter supports the tuning of the lateral path shape. This parameter is used to calculate the time to reach the reference path. The smaller the value, the more the path will be generated to reach the reference path quickly. (Mostly the center of the lane.) -#### Pruning predicted paths with lateral acceleration constraint +#### Pruning predicted paths with lateral acceleration constraint (for vehicle obstacles) It is possible to apply a maximum lateral acceleration constraint to generated vehicle paths. This check verifies if it is possible for the vehicle to perform the predicted path without surpassing a lateral acceleration threshold `max_lateral_accel` when taking a curve. If it is not possible, it checks if the vehicle can slow down on time to take the curve with a deceleration of `min_acceleration_before_curve` and comply with the constraint. If that is also not possible, the path is eliminated. @@ -136,11 +136,47 @@ Currently we provide three parameters to tune the lateral acceleration constrain You can change these parameters in rosparam in the table below. -| param name | default value | -| ----------------------------------------- | -------------- | -| `check_lateral_acceleration_constraints_` | `false` [bool] | -| `max_lateral_accel` | `2.0` [m/s^2] | -| `min_acceleration_before_curve` | `-2.0` [m/s^2] | +| param name | default value | +| ---------------------------------------- | -------------- | +| `check_lateral_acceleration_constraints` | `false` [bool] | +| `max_lateral_accel` | `2.0` [m/s^2] | +| `min_acceleration_before_curve` | `-2.0` [m/s^2] | + +## Using Vehicle Acceleration for Path Prediction (for Vehicle Obstacles) + +By default, the `map_based_prediction` module uses the current obstacle's velocity to compute its predicted path length. However, it is possible to use the obstacle's current acceleration to calculate its predicted path's length. + +### Decaying Acceleration Model + +Since this module tries to predict the vehicle's path several seconds into the future, it is not practical to consider the current vehicle's acceleration as constant (it is not assumed the vehicle will be accelerating for `prediction_time_horizon` seconds after detection). Instead, a decaying acceleration model is used. With the decaying acceleration model, a vehicle's acceleration is modeled as: + +$\ a(t) = a\_{t0} \cdot e^{-\lambda \cdot t} $ + +where $\ a\_{t0} $ is the vehicle acceleration at the time of detection $\ t0 $, and $\ \lambda $ is the decay constant $\ \lambda = \ln(2) / hl $ and $\ hl $ is the exponential's half life. + +Furthermore, the integration of $\ a(t) $ over time gives us equations for velocity, $\ v(t) $ and distance $\ x(t) $ as: + +$\ v(t) = v*{t0} + a*{t0} \* (1/\lambda) \cdot (1 - e^{-\lambda \cdot t}) $ + +and + +$\ x(t) = x*{t0} + (v*{t0} + a*{t0} \* (1/\lambda)) \cdot t + a*{t0}(1/λ^2)(e^{-\lambda \cdot t} - 1) $ + +With this model, the influence of the vehicle's detected instantaneous acceleration on the predicted path's length is diminished but still considered. This feature also considers that the obstacle might not accelerate past its road's speed limit (multiplied by a tunable factor). + +Currently, we provide three parameters to tune the use of obstacle acceleration for path prediction: + +- `use_vehicle_acceleration`: to enable the feature. +- `acceleration_exponential_half_life`: The decaying acceleration model considers that the current vehicle acceleration will be halved after this many seconds. +- `speed_limit_multiplier`: Set the vehicle type obstacle's maximum predicted speed as the legal speed limit in that lanelet times this value. This value should be at least equal or greater than 1.0. + +You can change these parameters in `rosparam` in the table below. + +| Param Name | Default Value | +| ------------------------------------ | -------------- | +| `use_vehicle_acceleration` | `false` [bool] | +| `acceleration_exponential_half_life` | `2.5` [s] | +| `speed_limit_multiplier` | `1.5` [] | ### Path prediction for crosswalk users diff --git a/perception/map_based_prediction/config/map_based_prediction.param.yaml b/perception/map_based_prediction/config/map_based_prediction.param.yaml index fe4d2a51ec6f3..fdd64174de9be 100644 --- a/perception/map_based_prediction/config/map_based_prediction.param.yaml +++ b/perception/map_based_prediction/config/map_based_prediction.param.yaml @@ -16,6 +16,9 @@ check_lateral_acceleration_constraints: false # whether to check if the predicted path complies with lateral acceleration constraints max_lateral_accel: 2.0 # [m/ss] max acceptable lateral acceleration for predicted vehicle paths min_acceleration_before_curve: -2.0 # [m/ss] min acceleration a vehicle might take to decelerate before a curve + use_vehicle_acceleration: false # whether to consider current vehicle acceleration when predicting paths or not + speed_limit_multiplier: 1.5 # When using vehicle acceleration. Set vehicle's maximum predicted speed as the legal speed limit in that lanelet times this value + acceleration_exponential_half_life: 2.5 # [s] When using vehicle acceleration. The decaying acceleration model considers that the current vehicle acceleration will be halved after this many seconds # parameter for shoulder lane prediction prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8 diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 02db91b989116..f61dc75ffb85b 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -22,6 +22,7 @@ #include #include +#include #include #include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" @@ -89,6 +90,7 @@ struct LaneletData struct PredictedRefPath { float probability; + double speed_limit; PosePath path; Maneuver maneuver; }; @@ -175,6 +177,10 @@ class MapBasedPredictionNode : public rclcpp::Node double max_lateral_accel_; double min_acceleration_before_curve_; + bool use_vehicle_acceleration_; + double speed_limit_multiplier_; + double acceleration_exponential_half_life_; + // Stop watch StopWatch stop_watch_; @@ -231,7 +237,8 @@ class MapBasedPredictionNode : public rclcpp::Node void addReferencePaths( const TrackedObject & object, const lanelet::routing::LaneletPaths & candidate_paths, const float path_probability, const ManeuverProbability & maneuver_probability, - const Maneuver & maneuver, std::vector & reference_paths); + const Maneuver & maneuver, std::vector & reference_paths, + const double speed_limit = 0.0); std::vector convertPathType(const lanelet::routing::LaneletPaths & paths); void updateFuturePossibleLanelets( diff --git a/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp b/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp index 4da4f62be2ede..6dfc4a8db9e20 100644 --- a/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp @@ -91,7 +91,7 @@ class PathGenerator PredictedPath generatePathForOffLaneVehicle(const TrackedObject & object); PredictedPath generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_paths); + const TrackedObject & object, const PosePath & ref_paths, const double speed_limit = 0.0); PredictedPath generatePathForCrosswalkUser( const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk) const; @@ -99,17 +99,30 @@ class PathGenerator PredictedPath generatePathToTargetPoint( const TrackedObject & object, const Eigen::Vector2d & point) const; + void setUseVehicleAcceleration(const bool use_vehicle_acceleration) + { + use_vehicle_acceleration_ = use_vehicle_acceleration; + } + + void setAccelerationHalfLife(const double acceleration_exponential_half_life) + { + acceleration_exponential_half_life_ = acceleration_exponential_half_life; + } + private: // Parameters double time_horizon_; double lateral_time_horizon_; double sampling_time_interval_; double min_crosswalk_user_velocity_; + bool use_vehicle_acceleration_; + double acceleration_exponential_half_life_; // Member functions PredictedPath generateStraightPath(const TrackedObject & object) const; - PredictedPath generatePolynomialPath(const TrackedObject & object, const PosePath & ref_path); + PredictedPath generatePolynomialPath( + const TrackedObject & object, const PosePath & ref_path, const double speed_limit = 0.0); FrenetPath generateFrenetPath( const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length); @@ -125,7 +138,8 @@ class PathGenerator const TrackedObject & object, const FrenetPath & frenet_predicted_path, const PosePath & ref_path); - FrenetPoint getFrenetPoint(const TrackedObject & object, const PosePath & ref_path); + FrenetPoint getFrenetPoint( + const TrackedObject & object, const PosePath & ref_path, const double speed_limit = 0.0); }; } // namespace map_based_prediction diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index 6a6f24081655e..c949eae21aeff 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -24,7 +24,6 @@ #include #include #include -#include #include @@ -385,11 +384,7 @@ bool withinRoadLanelet( const TrackedObject & object, const lanelet::LaneletMapPtr & lanelet_map_ptr, const bool use_yaw_information = false) { - using Point = boost::geometry::model::d2::point_xy; - const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position; - const Point p_object{obj_pos.x, obj_pos.y}; - lanelet::BasicPoint2d search_point(obj_pos.x, obj_pos.y); // nearest lanelet constexpr double search_radius = 10.0; // [m] @@ -788,10 +783,18 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ prediction_time_horizon_rate_for_validate_lane_length_ = declare_parameter("prediction_time_horizon_rate_for_validate_shoulder_lane_length"); + use_vehicle_acceleration_ = declare_parameter("use_vehicle_acceleration"); + speed_limit_multiplier_ = declare_parameter("speed_limit_multiplier"); + acceleration_exponential_half_life_ = + declare_parameter("acceleration_exponential_half_life"); + path_generator_ = std::make_shared( prediction_time_horizon_, lateral_control_time_horizon_, prediction_sampling_time_interval_, min_crosswalk_user_velocity_); + path_generator_->setUseVehicleAcceleration(use_vehicle_acceleration_); + path_generator_->setAccelerationHalfLife(acceleration_exponential_half_life_); + sub_objects_ = this->create_subscription( "~/input/objects", 1, std::bind(&MapBasedPredictionNode::objectsCallback, this, std::placeholders::_1)); @@ -817,6 +820,13 @@ rcl_interfaces::msg::SetParametersResult MapBasedPredictionNode::onParam( updateParam(parameters, "min_acceleration_before_curve", min_acceleration_before_curve_); updateParam( parameters, "check_lateral_acceleration_constraints", check_lateral_acceleration_constraints_); + updateParam(parameters, "use_vehicle_acceleration", use_vehicle_acceleration_); + updateParam(parameters, "speed_limit_multiplier", speed_limit_multiplier_); + updateParam( + parameters, "acceleration_exponential_half_life", acceleration_exponential_half_life_); + + path_generator_->setUseVehicleAcceleration(use_vehicle_acceleration_); + path_generator_->setAccelerationHalfLife(acceleration_exponential_half_life_); rcl_interfaces::msg::SetParametersResult result; result.successful = true; @@ -1010,7 +1020,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); + yaw_fixed_transformed_object, ref_path.path, ref_path.speed_limit); if (predicted_path.path.empty()) continue; if (!check_lateral_acceleration_constraints_) { @@ -1555,14 +1565,63 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( object.kinematics.twist_with_covariance.twist.linear.x, object.kinematics.twist_with_covariance.twist.linear.y); + // Using a decaying acceleration model. Consult the README for more information about the model. + const double obj_acc = (use_vehicle_acceleration_) + ? std::hypot( + object.kinematics.acceleration_with_covariance.accel.linear.x, + object.kinematics.acceleration_with_covariance.accel.linear.y) + : 0.0; + const double t_h = prediction_time_horizon_; + const double λ = std::log(2) / acceleration_exponential_half_life_; + + auto get_search_distance_with_decaying_acc = [&]() -> double { + const double acceleration_distance = + obj_acc * (1.0 / λ) * t_h + obj_acc * (1.0 / std::pow(λ, 2)) * (std::exp(-λ * t_h) - 1); + double search_dist = acceleration_distance + obj_vel * t_h; + return search_dist; + }; + + auto get_search_distance_with_partial_acc = [&](const double final_speed) -> double { + constexpr double epsilon = 1E-5; + if (std::abs(obj_acc) < epsilon) { + // Assume constant speed + return obj_vel * t_h; + } + // Time to reach final speed + const double t_f = (-1.0 / λ) * std::log(1 - ((final_speed - obj_vel) * λ) / obj_acc); + // It is assumed the vehicle accelerates until final_speed is reached and + // then continues at constant speed for the rest of the time horizon + const double search_dist = + // Distance covered while accelerating + obj_acc * (1.0 / λ) * t_f + obj_acc * (1.0 / std::pow(λ, 2)) * (std::exp(-λ * t_f) - 1) + + obj_vel * t_f + + // Distance covered at constant speed + final_speed * (t_h - t_f); + return search_dist; + }; + std::vector all_ref_paths; + for (const auto & current_lanelet_data : current_lanelets_data) { - // parameter for lanelet::routing::PossiblePathsParams - const double search_dist = prediction_time_horizon_ * obj_vel + - lanelet::utils::getLaneletLength3d(current_lanelet_data.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()); + + double final_speed_after_acceleration = + obj_vel + obj_acc * (1.0 / λ) * (1.0 - std::exp(-λ * t_h)); + + const double final_speed_limit = legal_speed_limit * speed_limit_multiplier_; + const bool final_speed_surpasses_limit = final_speed_after_acceleration > final_speed_limit; + const bool object_has_surpassed_limit_already = obj_vel > final_speed_limit; + + double search_dist = (final_speed_surpasses_limit && !object_has_surpassed_limit_already) + ? get_search_distance_with_partial_acc(final_speed_limit) + : get_search_distance_with_decaying_acc(); + search_dist += lanelet::utils::getLaneletLength3d(current_lanelet_data.lanelet); + lanelet::routing::PossiblePathsParams possible_params{search_dist, {}, 0, false, true}; const double validate_time_horizon = - prediction_time_horizon_ * prediction_time_horizon_rate_for_validate_lane_length_; + t_h * prediction_time_horizon_rate_for_validate_lane_length_; // lambda function to get possible paths for isolated lanelet // isolated is often caused by lanelet with no connection e.g. shoulder-lane @@ -1644,7 +1703,8 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( // 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(object, paths, path_prob, maneuver_prob, maneuver, all_ref_paths); + addReferencePaths( + object, paths, path_prob, maneuver_prob, maneuver, all_ref_paths, final_speed_limit); }; addReferencePathsLocal(left_paths, Maneuver::LEFT_LANE_CHANGE); addReferencePathsLocal(right_paths, Maneuver::RIGHT_LANE_CHANGE); @@ -1966,7 +2026,8 @@ void MapBasedPredictionNode::updateFuturePossibleLanelets( void MapBasedPredictionNode::addReferencePaths( const TrackedObject & object, const lanelet::routing::LaneletPaths & candidate_paths, const float path_probability, const ManeuverProbability & maneuver_probability, - const Maneuver & maneuver, std::vector & reference_paths) + const Maneuver & maneuver, std::vector & reference_paths, + const double speed_limit) { if (!candidate_paths.empty()) { updateFuturePossibleLanelets(object, candidate_paths); @@ -1976,6 +2037,7 @@ void MapBasedPredictionNode::addReferencePaths( predicted_path.probability = maneuver_probability.at(maneuver) * path_probability; predicted_path.path = converted_path; predicted_path.maneuver = maneuver; + predicted_path.speed_limit = speed_limit; reference_paths.push_back(predicted_path); } } diff --git a/perception/map_based_prediction/src/path_generator.cpp b/perception/map_based_prediction/src/path_generator.cpp index d3f610583577c..413a0e233186b 100644 --- a/perception/map_based_prediction/src/path_generator.cpp +++ b/perception/map_based_prediction/src/path_generator.cpp @@ -149,13 +149,13 @@ PredictedPath PathGenerator::generatePathForOffLaneVehicle(const TrackedObject & } PredictedPath PathGenerator::generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_paths) + const TrackedObject & object, const PosePath & ref_paths, const double speed_limit) { if (ref_paths.size() < 2) { return generateStraightPath(object); } - return generatePolynomialPath(object, ref_paths); + return generatePolynomialPath(object, ref_paths, speed_limit); } PredictedPath PathGenerator::generateStraightPath(const TrackedObject & object) const @@ -178,11 +178,11 @@ PredictedPath PathGenerator::generateStraightPath(const TrackedObject & object) } PredictedPath PathGenerator::generatePolynomialPath( - const TrackedObject & object, const PosePath & ref_path) + const TrackedObject & object, const PosePath & ref_path, const double speed_limit) { // Get current Frenet Point const double ref_path_len = motion_utils::calcArcLength(ref_path); - const auto current_point = getFrenetPoint(object, ref_path); + const auto current_point = getFrenetPoint(object, ref_path, speed_limit); // Step1. Set Target Frenet Point // Note that we do not set position s, @@ -384,7 +384,8 @@ PredictedPath PathGenerator::convertToPredictedPath( return predicted_path; } -FrenetPoint PathGenerator::getFrenetPoint(const TrackedObject & object, const PosePath & ref_path) +FrenetPoint PathGenerator::getFrenetPoint( + const TrackedObject & object, const PosePath & ref_path, const double speed_limit) { FrenetPoint frenet_point; const auto obj_point = object.kinematics.pose_with_covariance.pose.position; @@ -400,10 +401,82 @@ FrenetPoint PathGenerator::getFrenetPoint(const TrackedObject & object, const Po 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) + : 0.0; + const float ay = + (use_vehicle_acceleration_) + ? static_cast(object.kinematics.acceleration_with_covariance.accel.linear.y) + : 0.0; + + // Using a decaying acceleration model. Consult the README for more information about the model. + const double t_h = time_horizon_; + const float λ = std::log(2) / acceleration_exponential_half_life_; + + auto have_same_sign = [](double a, double b) -> bool { + return (a >= 0.0 && b >= 0.0) || (a < 0.0 && b < 0.0); + }; + + auto get_acceleration_adjusted_velocity = [&](const double v, const double a) { + constexpr double epsilon = 1E-5; + if (std::abs(a) < epsilon) { + // Assume constant speed + return v; + } + // Get velocity after time horizon + const auto terminal_velocity = v + a * (1.0 / λ) * (1 - std::exp(-λ * t_h)); + + // 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)) { + // we assume a forwards moving vehicle will not decelerate to 0 and then move backwards + // if the velocities don't have the same sign, calculate when the vehicle reaches 0 speed -> + // time t_stop + + // 0 = Vo + acc(1/λ)(1-e^(-λt_stop)) + // e^(-λt_stop) = 1 - (-Vo* λ)/acc + // t_stop = (-1/λ)*ln(1 - (-Vo* λ)/acc) + // t_stop = (-1/λ)*ln(1 + (Vo* λ)/acc) + auto t_stop = (-1.0 / λ) * std::log(1 + (v * λ / a)); + + // Calculate the distance traveled until stopping + auto distance_to_reach_zero_speed = + v * t_stop + a * t_stop * (1.0 / λ) + a * (1.0 / std::pow(λ, 2)) * (std::exp(-λ * t_h) - 1); + // Output an equivalent constant speed + return distance_to_reach_zero_speed / t_h; + } + + // if the vehicle speed limit is not surpassed we return an equivalent speed = x(T) / T + // alternatively, if the vehicle is still accelerating and has surpassed the speed limit. + // 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 / λ) + (a / (t_h * std::pow(λ, 2))) * (std::exp(-λ * t_h) - 1); + + // It is assumed the vehicle accelerates until final_speed is reached and + // then continues at constant speed for the rest of the time horizon + // So, we calculate the time it takes to reach the speed limit and compute how far the vehicle + // would go if it accelerated until reaching the speed limit, and then continued at a constant + // speed. + const double t_f = (-1.0 / λ) * std::log(1 - ((speed_limit - v) * λ) / a); + const double distance_covered = + // Distance covered while accelerating + a * (1.0 / λ) * t_f + a * (1.0 / std::pow(λ, 2)) * (std::exp(-λ * t_f) - 1) + 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; + }; + + 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 = motion_utils::calcSignedArcLength(ref_path, 0, nearest_segment_idx) + l; frenet_point.d = motion_utils::calcLateralOffset(ref_path, obj_point); - frenet_point.s_vel = vx * std::cos(delta_yaw) - vy * std::sin(delta_yaw); - frenet_point.d_vel = vx * std::sin(delta_yaw) + vy * std::cos(delta_yaw); + 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); frenet_point.s_acc = 0.0; frenet_point.d_acc = 0.0; From e9b674a127cb27a3744ff9bbf0df0ed21a3c5af9 Mon Sep 17 00:00:00 2001 From: karishma Date: Tue, 28 May 2024 15:01:27 +0530 Subject: [PATCH 276/276] perception/ground_segmentation Signed-off-by: karishma --- perception/ground_segmentation/schema/ground_segmentation.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/ground_segmentation/schema/ground_segmentation.json b/perception/ground_segmentation/schema/ground_segmentation.json index 9d4331a1179ed..edf3c01c71751 100644 --- a/perception/ground_segmentation/schema/ground_segmentation.json +++ b/perception/ground_segmentation/schema/ground_segmentation.json @@ -1,6 +1,6 @@ { "$schema": "http://json-schema.org/draft-07/schema#", - "title": "Parameters for ground_segmentation", + "title": "Parameters for ground_segmentation.", "type": "object", "definitions": { "ground_segmentation": {

dT*;Ysp>p+tIVOtMc$; z&;G=4aGLpwk{ebuWW{V1>V5sL<|qz6X4!t`?OFkegdqtQNMBvQ6Z6@1%tkk}S8G+P zRQIRfbd=)pl4};0rs+fiVpit7+GO|R5r#jy+XbRNraeha*zjCa!WO)A7e^0A95l+Z zSYo{?Kz`ta{kxh#FPGj=Zzo}yFb!?Ry*#KXS9+vWeL?lGtaEyqIhlLM=}?@%c%Mjhf7AYQs@i_WFitAR)wd+NR{cSvay0Rc z-~J8XgjBJS%FTOH{?Y+yiqWU= zs|g`~G%9kFaOua@fm7ua^!gr@S3vxTD#B$aFFf?GEJ5}n&~Akz*x)i?qA9|RDrWOs ztMo}1D%Oj4X{DokA`Xsx@~;Wx6L`2c;KqlbT3s%uqFm}u-<~h{S8|XDXfF0raz9r7 zg8&3zQ|aPpD02o_`vj^zK$FZ_J+`rPhnlpECKUZRPP^F&a$}Gs zE_2Cl+?@T09ySZ{*Kd`GJ9KPbt)L@wgW_{<=v=FGxetCh!}RspC9*^{f2~nuDoEja z)$$kp5p)G{I`h~&SY~eiqt~cKx1WzNeo6Mbq;N9RntgtJFP}k{#S?_oop~+0q-cq> zFlz|aO8$QF@>s04#^~p`%l42T8&mVjES&=x3bG2YLCB^U`aKI6$hP{7C*)2=<0_Ya zmsjh<{cE0y-jWz$ZJmFLF!bCNFhBdN+_5TDxis3;ewhB1C!j9*6Q6TfH}Woj>-E*- zr%Gu8=0X>4jS`m1@Yn{Zucc)c(-N@}LY-^xZ6Cal$Q_%}x<417*$Ogcw5K^_+uiw8 zo7=CLc&KTA1I zec^gQB&vWu7H47B721;CdMIjS1cWy3DvUf~Sf$DJVE%ibyy1y-a_hHlrhxZAoskG~ z%M+Pmz*?-hw`j^QlWyC9?bS;>cMcjvxV-Its;E^ELD=Bn=HqzsXSH+s{*Ru@*`#Zg z;@sh3VMihMufPCyYG@G3sdekMPuob|C?+0w2ozd%-t87q zZ8YxxOPu2X96}k_RJ7=&S7d;f&{m7;Ai~xP4gYUR8M+N;kt7)PO4|SKkS(J&j-V(! z6&TH9-#Dbedt2{h^$lM}4#QI9#~T98wJCKUg!{vUga@1CPP2 z=y}Hz)X4rfeAdS#)Is}7V*BzP%~zOT5~5t{M_Vh1L~Nan%onSzQJe;G)6>(xY7KcP zX5rYJJOk%YS5-mBMx{pgJ`pQW76BKgYLuRCdNxWgH)yy2TQPNQIc|S@?~VeWdu@G1 zyprC)1o9=ja zP&mmw_#2Ryd2!UW*>6d0uQP0;ay*MI`k$YYl-7;|3LfkF#(J)NX#d(zT$b6?Qdf;A z-ggk^?_t|_z@=d!^)%3R(@Y1&_|}JCzHvR=-|OL==MY;CygjqVCC+uxGs!P|Td&W@4L@fP5*{)9{2<9J#s?N7|7n}#628RW1 z8OKg6WgD=Jhzd!74Z!x+>*dg^v9p=K4m?u7hxzaey4Qk3jLtoJ#>RW3o*}%)A*V#* z;skFJiJNt}jZRVd`UW#!bZ*>`%L?wxcG!E5{yn>-fTV=v*0vs#FTY!|%XSwRW-8fv zwd^_b9Z2pc@957qZR~%;wiV4oZ`apj(IELD8gIb;tm2l+ev#hr6^i2>br8$K$_E@* zn3@zmBFxg^W+f>u9^B#d3-mr*y9l+LYCg1W_RX0UM8t{TuzTHEh4UZpJ?4?e-X%OD zEKd{Qlyfp_tc~yko>(I|c6@LSpc=#m?GP8*TJspU{Fwl^pHhsfiQ2j&23iUZjuOMY zs8q&Z$6CL%esjHD zeRTcP`f1&fYbP3Z{6fgL`%E4)J5w-fDd7Zo+eEaw-}NuO8nPS3G6s{EF9)r3E*9!IO>>-O)%<(1yM~;a(da`q$ zB7WO5v+K%$j*^a+*2vf7Y@1g?9EMt2!Q(3HMu_lH23`#0WPi;Kk>&ya&>lW zO0?+a^H%2Q0_cTl9nbdL6{SX={YI*VZ-RmO6dJfPbh0M%-^Fk# zW%pH(cDthyfKF5Y@jWRi_x}B!x45%AOBs$JvBX--a*bcEIk{bfx=W_p1q7&te16}w zZc2-1-AsEoE4dQwT!nY+1Qp7bnw(_QBddGrRB7lRDI6iUTAUTa6eM*OMfEEApP1ZI zFsy=eDac5 zQIa;?l4156fe$^#?)yi!PRJ=3Z>ZYsM;Y+ z$zibL(}+f!#8S2tA@?`VK$_!@DS|szpsYn2!mV-%ZGHNGR%(zpfokSNzH}t=)=SH7 zw?}}@?#AG5Le@Q1CwNKaifsvk-fBz#0G}ZV^5>0>CMkQa1=Dp0YqK!WjV-8CYz64& zwi)+g(gubT$%KlPYC@f6Vz)?>2G2a%+0S3Bh_raVw!it_>Z_n2&AtpAlI17n$q{em z>0&u%k4;NFHeX1s`tc#qYn1_mkFe%?5=$gbTY9zP+IO$amC~M`YUVIe?~1>6{Iof zx$q6CgfMMbz47V*eapIx*RgizE#1pbzoh%)vr;O5zz1_8+2C%@!9PkZ;tg&?VDxl+ zev994N6v#_XfS+LtBAin^S8gPxveJ@Pbk&#wZ&yOxpE~zlgkDL^w4MFpx z^3P>3FW^&?4)WF}EFkF4iCWI3MKXieN~|e5tf~219uLqNj(GE4W^+o!bMm3H&)2M+ z8yp2V_lx)zunsY+g~7T77@cbWEoke&;{$f;>YA6!^zV#tfXjcdE6{6p z+vAt!gOsG|IpbMowRp%FG9Ro0s1KK0-_OOEJ>QkOA|Ywq93+f{+r8eL`qm^`PNfI zP3^%K^1rf#)d^xzUN;(Wm;d-V^2Oi8rfT;Q8s5KsikEyUgk|5iCZ=+M->*EP4cx~Z zXV^#DLU25M<-hZy1UuDPdv9Fl$jl#hp2xk~oo{D7Po_QXk7D6yf^JWKr;Yq`ZTG`r z%XQF^-M#c5$}eALuQ2%rAX=Y34F6=NEJ<>@$&w=~w0KR|-#^l}p=Hi3jO;Lkso?kB zLjK6BX5#K?AW)DB{$;hQy|VLQXX8U#~s&L>u9kzh>t(5 zsj-3i1THPz>2Mk@kos{bFwh3~@kah^%mZmWm(J4KJYvVD3Q^tu<4Ba z)mE5fOran-4f_tEJ2?q&*IB&g7bAqh18~u7d3{na}p`J^dX<#wTGPl})K*V&VlWtC`fxsF7Z9Iu!MNjJ4 zH}CUO^u6{ENW3ttF&vH`&lHE(znb;2icnLwq-F+vlY(w=bZ$9$ezR zgSXZD#6Xpiq2U|La1%JS3LP>~#n6%8B`Nh+twJ(WQHIIy=_i;fHk&+KlwwGqp zF>;Q%k#kdzeCVum@tmGKHu3hI%HKyXCR3Y-FKvfIHAo8nhCnkdt%ixPM$oOYyS5s6Ryh|gzZOyIhb{!Gj6!| z7bA*kOC%HDUE&YR=%;Ti&e)3da9>DTO7LG8s_agK>5pX8MN?Pz%SF@au3M)Bm_$1u z7L)}#@rmxv&)|O~tCHYm_t9w1%08*_D(W1pgy~l+<^%G7g#`j%CJoGFrd%&}X z7vv-KQ7kPiRC0>JK|yNU20tzO&BG+&@k@qhxu-v$C|jKkGDv>*1Y!aq@f2c_+kPM@ zGV)t?+)NrK6a>}$P$}tl7p7&aL_~-___-NK`Cr8Mq-+e&qr zk}DJnPcGv;O_4Kud^mYlaQ*sQXV&Q?oeg()xd3TTdvI5CYY+@=MvmLn2*QQa$x&L)cq}UY>shXB>GB@ej`P#M2o40PAt?UU} zrJU9xzZ^c!H=T~+f=Cd5M&OhAl!LH!7FwHZc%vo_39r=ghbrjgot}J0EtkY_H7Kau z{ly6IbWNSF)GK})!H&e)zI4XjL_#VMI(f(;;?awZYiylyac!#O2-^r-u1A33t(q_C ze>4zvAwp)hBxO@$!BL5K`?LaQbThNlA4uC3xn>@G9jA2BqshPuSLXQ599fY-wR_ht zcybxRN%Sbi*gC?#S@izEMj@s^Rx2FDtreUIt=aY}ghozoowRAGF~x~Zj1AcXNxm`1 zxl3Ps-gCDEqrNhru&wL&2oRVc(C%v)d5{o{0=Ox>U zudqx_hr6EO^<`@`!ksor$t78R8~Ah{jeTRk&Cz9XF9)^b$ItoWLOO`XP7+Pr{6Z zQ+GA)lWs6-N;gs4?hLh{`mNL7*H9T)ACTzTZ!}c9I`BO#13wcIm%TmroxKiiNlG=xo!kRv6knp? zC-LSPct-tjy}pl2>cN2RH2&CPaMS+(koVpXIrjbkxYD4aof1v$XrQ8Hq^PtPr9IG) zgqF}e8&tGt&{An=P)d>Zph!j<+A4)YMXB%O$bG-x7q|QU`2)V!PZ!SfIFI9XyvB1p z1`!r;xZC9YVe#WUvEL#soJ&MZ_PU> zuUDDS)=lht*H!ho^bc>;)tHT+m6=&@wJK5|&S~D{LJuNgx!?noYVF6-Y1ZXYpBi#q&VI3ChX zQB_#RI_u8Zp{Vi4e4?bG#?Y3b2hG!aL9D;%>0D&;ndk2gE;W_%g0y_v(8b;&$YW(| zKugKdAJQms{JzJ0CeLsn$@T@lX)ZbJdCc5+*nY~6Bx^}+%SodCt?i7dOR3(*aH1+E zzU5yZHDVrVVK~9Fp;3lG=#P}VihsKmC3h{SBr|567%x?)i7QhTt*NE|gEjtH z>!8VF>M1JrlYCvrhci4c#h5y8BJP?Fm;O`JqH5jtD4K`P%R#iki)SE4M8?ZFA6|&| z!i(x{&Xc(!f!6Me^1HjqA8J11B60uaE%~mNm|H=*p{I=jHZOZw9k+YaKtmi^R?ND8 z;42{8Kt1C3={K!js&Hy9j|*3t2_S-yA4Q&$*z_uOUQiyS#J|~QeCH7^Jv>*mdT#oO z+?W4+S5?7fePUa-+{!A1*E4L*mv&g{r0hKqXr3qJN1dlMN%nU2U2bcW@h0^zWV$Z* zJ`a2KwNRZLXj#$G{7;Br0mTK*v_3-VHxh7)Wu@OW>;!{eAO;!YuRo#;hmo2d#3E*Fgjv*K zV1&#QTek$1`Orpr^$?0$SeYMh=j0!U{Rg2){$hT+pV5t(6_XTi>3@yGE)k4_TfD^5 z=BkeygotdY;`d#hA|>7Y$dQAcm8h$?FT7h>zfAH3s;rP3HV^yPew!$6Yo7v1$PL0=jzBAN|j-*!UNF4)4y<_P%h2d@`6l7BAlCS+wb9pYOI7i{2M{c4!g#ljol$ z9`OT2WCbfm`v#n)55O@P>q9Pbv?J>|a6Y4RI8!SILdC}4tr-Hsgj%PJG7(jovs64I z{~^IaV#x0XtkG<6ZsAMYoqgHsju0r&(wmGAPxZB~s7-Wj_)7bG@vuTzb^xZG!$6{{ zQ)B<*hJ1=61w?-cA&PC)XV-RfT!?4>81MTV+nC2sZCG_9z%d$>77!UjFQ<0>?!7$A z;suxf>&@{b8(c7}HKzDCyVSjQGA@lRnOR0040atVvu zw{M3JeonVmqD|GF3!Q^dmmG+@q*K)!Ur7AM9$zSeRs(;S$rYN7&pL0E`$75Szsjgw zut2L9^!g^IkR92C;dY0XL*9uMy1(>n$j>~~yhF&fko_swvKF0D)LgX)UMt`nXZ}Nf z1)O>yOq^!y{0?XJyk%VhHI&~EgcWk231ymHiHc&R2^{T%TLfWztgbF9AyImU^7+1H zA(B-?#dobxU4jGM^?A8x)sJA}pT$se18%bQc`B#>G9J*glcLaa&Q#`Bj>Xe^$e`KX{2D%!(&Uz|^#;xXeP zcO8{(R)(vM>sNgUWTdDO44rP4=2=G-^G!>Imtj|A4qt#Bd4S~ll_AU&s^sL1sSNAb zq6By-E*7w}9lQ3p;!(m@5wXnMJ9}QnXc>R|G_R)g((t8W=8we8)-UcmH`Yt*_7#lB zel!fUp%u&zi%DQEpe1P%cDft6xGo={JoK>Ql6r{Y3k9)K%NGEigl|}gmSxZ#EBxa- zjcxfBk9>h%@6mc*dcs0e6pjJcD;}3TlON?T>zc4B-G@ua@~@?}s>AD%bo;E|+qddW zgd@%22b;??ybb%`_=SA19v-2XAfJu^(xn1Dbu^RNxFyn81cz?hvgIQrWTNGz`wne? zTI_aJGGJrX!;=Shx7;=@H)g%OIsX0@BNwfzEjORCn^`x|)mUbSmbH96fYeWA=7+Atm$c zy5^^=-%uK)4h#;~)YL$Nha}&EbI;6{8;j*Sl=I5(fPO~3c0=R?8J*?ZV`i^jYxCm% zt($f)H}~YwG_Yx!trL?KvRtRLy3F^dm%IBmm-}$pQSzS2O;n0J2s*+#=Do-MwGS)mTb`B1~!NJhDIi$th*b1|i@UgA1*R5Lqre!|y&6+KL{U#2@e5B?J zHSF)V8LbgQ?`nBhd7{aAeo3ovwW= zT#8_K>2_wf*o;`RXXyV}=Dy&tH!Q;3Zxoin?)uCDV+w%kh z6MRwL39>JV>!O2Dx_JqRC>%RM&5A3H2|}En50{(i!^%HEV29s~(4B8gMLXT6x=uW* zw63F>ilN%EW5=|dupu$_hst8qSFPh*A4}K6q~|oKaa}+{tFPfNk1zfeUM7QU!wy-r z()!$N)lg{Dg>z4sBH{cU*IVrB?+AUhd&ghuyoFTE%Ca~w#{(}))LO2dt1z693hQ}n zIA=$NsKi*wBqk|obA-R1-OFvd)O!Mz`+eBv0Q*`BlKF=V|?RdV@JNN*$2@x z)NvdCHZRzi&c4BWZ1%iJ|HRN`|J(57duSPg`h+6mIG%ak7PI&rr|bcPrr)?TeL|;Q zp^Qd*X3D6rLHrE$uJ@sIZC|ph+j8;7i`~AMt|B~Im<2UG0B{MNIKJzwt#p2%b;O~G zwOi!>HWkE&tlpkQousj`5mr*&;F&;J>poJ++8;>s={ck+#*D!L0Vx5&o3hO?&WSC( z>A{fRIjYYvSxk7=;vT~s_Nl03MO-Ms-#aZXd>`kpK*}oTmm^vCz0aQ>%0m`;hqvcG zav!^r@QtvD!s%gn$9&@&cJvgAR11B<`U7=m@78e$m2-0DY^XK-8v2aOdH$t*4&l@Z zbM-1Ii2fA9{l!kUB51$f$#Rs@!tl~=eO#+ovv}%ND!Fn^@$u^p!y`cgyy3+>u4enx zZhee8-LPZuu(xK<#ze-~EO&GN*shBrgO3rhA|RA!LH7jd4UT65lONtaS^`7*YC?iH zWGe}5E~jj(;WmlqPrWO=UV+pRKz4q5=)myUXXHD*fT37xJMHU&ne&Bnk^50@YkKN6 ziXEw3E zEfjLDpFsj{QR&61OyH?!#Ao8`K3Z=2y!F?P=rYGuofQac(s$*j9gk7>@PD{`s{Y=; zJ~Q~2eTQv&)1*n(p<*R!(~rcGG7+xDDn zy}$PMUv~$E1M}${Xtf!eI>9*Er!Hi0$6RsKrrHerHA`)m1M7TmMTd;QmlsFwRI(NJ z8b(rQ7@w39QM+23!y?dz+Ey}*xYF(qf?4gT-u44MT-t9X5_g`aaRe~f1Irxy zhT~OZff})ycvboR64CipZJ)8c50!BgiU#QN7-s9C+p4B0eL5mnzLn#3^V-J@f1TPw z$GF|$ZwBrlfNoohVsUPSR8XKY7kMm6>D>Aj9GIq1o5<-qp&_YKN1df|dAhh68EWdh z`04R9CBK}$q`An*NI>M!W;UzvI0?o(JhVSRIis$)zyT$43C#F_X#mUOfh9=z_UxXc z@wQ#x9elK%!Tv*{T|EuHCE-UJcSJp6GvX_c5a7a(Q`QmGY$C< zAN$%XbPiwS{_6`3IX{>X9lc2@g=JO8j!2;o{*iMLmHVX>Z-_1+2vm|2E4@Htm2=sN z<&o+Kf1SS{eeT$|x~=r}^@l5NW`T&iiDV)NVk{^`GG``CJR|h1qnkML==VSgcXR-S za!)10xof|U@eHnNfs?jrbK4Jd|CgvB1r3_*+qSs_MeSy;(}6lP7p_lNrWA%nFZZPpIM=~lB~_@YrlL5n=0*<6aFt>g?7SPT3Y6%y|EicAmzcx$Oui0 zHA8f57`&rmvO%r|h5P>co3P+gdn*fl!X5HF^BM;a*3qqp4`L%n^8X`T8;<-E7##em z=Yg>nLt`ua>-{)VAr%ZnDiqWY`S|$g>9ymWC@wA@X4JV&9N{HyEe@-wnIHW1s6LA) zg_scLjTklngsmkYwo0C>udfGVfTzZ^(0U&tQK;v59pWO(XvR~;6HoQIK;th@m9+_G zjW^Nr126*4>;Z`)k!uif(42aYZX5#2s4m``y~)6@$0DpuNDw=FKD!7(;Yjo58@wAf zII;X?hKlmyDA_x*j)S8Nx)nPtc;@fB4TpLd`(g_sp1I5|;|ITCyb!j9p@$Mg%(mOS zYF3?$2Al0qz~v1}z}3DM@>zMYkl&Wn&O;j1(?=aG^+ z2^bo zKl_)XOlS4UGBeQP?nfY7036OHoUj^~mYzOPwDM~QIOQzN%>LbLMUv(?*=;>cv<@8D zeIwQ3`6IHq`U)a{l?^KR@<#SAfw+NN$2AM+UbzL%&CQ_{*_t5xiD=$^T!jp!E?pY* z3QvFMr#F<(Lyc(Qh5o=(53+N?Tq?>`9$w35@@8eZJtqAXCPu~He;X+kk!u$A_9JL~ zpxRl>S-F4R;>apkwN|D3-I%7z+@+oJ=$YfF{8yeIQdKYHmq*=iaIZ=K94`3R%r8CU ziG;koJpBDISFp*TU5;yhTm`4r$LZ2%Kbm>^>)*_LW-+?`>qakzpX_~ONy`HeSp0un zwUIuO0k3p;XsEBmPn?&Zf8|)U!)1nb>w*tZDi5#Gx|qD@e9G%*XGeE`wYiXa785VG zyJN$KYMO?IqU)1?3(9@@uRH=qdlL=Xp2~6r|4%X-$#^4YBDrGV;+{L50;S8r=B?pI z1|vD8*q2W0{<0wWEasH5Bk%cqVl;Aj+%y}tS0(m~qU1q?f23lK>mF*0+HQX59S~#c zI(=@4A!^u%UX%GBWdWXPBAY78O)}^(ZCbjkIItNP^Doq7>AQPzZ1eA*e1$+G=8(#D zgMtfrk3OmU{(8milCdG=iGSv!LwOYy6*whBLR1v9eb68_iO8E~Zj4wCH7Hl6nbd2e zz{2yN1s0;s+jY+|xJ>1m0VHl9_rtnzfQz)wsK74AzGE)LE;s5d zUuye*UIY`GT~jFQRkApU?Kh$4iIrv675TG9Mbcz`r%#Rt8J^{!Shaj_yD6u{d?$l$ zU|_1O{$pUypuLS`MpG1$t-N zPg;L9E^PrsCcW7)oHf@pznqt2{Q{J{fR48j%k}Olp`c4k#fo@H zHPk{JWZ7FjA_Z+(>esaW<1r&S`Pveo;}_P*LdT`-;Ek2tn$ykRI+O;fp}8H2A%7-( z($xwP;*6Y}VHdyRVQuu9o<6Nx@0oQ7hh?u7ahKv!0Gpf-+8Xue=##jrky zsGZPzBMn2spRd2B8m%!Rlk2ahEHpo)LtOqAarxoYw6xPToo`J9n@d0bULxI(F;FKZ z3^>Di1hNvnk5IX$TC<*1CL|#NrC7HJ7O$)ouL#q7!~>z>;kD19P9DuKj470)TPBs5 z9l*|df(?7a!_$A1xQ;*hlBL4IdIGNAo3E5XgJadPM3YlUtN}DS)VX`jYVMI~uoNF* zxk^-g_PYzC_g*q$)YYS1rtGc6A)$Bn_sV6uWwM&Dr9s6#WS3wX;mpvdvJGCl5iaPV z-D_JOE&j-vQ>y}1R0$!>8!HSBhgcbaqg_~aD0W!5H@q8TJAu3j##jBA0MSyOs3ZW&o{y`t zpO_1Auo_0Z0ejgHeM>vcCYa&r+ns-m0eKaZAk_cFWM){Wu0CmX9oLJv*E;f zH12p5i~eQ0G|!5+onl?sdINsoz#Ca|$dW*_<~&Q|DWt)g(0o6|*1J64yi)Xzbe{(2 zCN?g0-Q_Zt+W6q7?y{}&@|?7w;sT6h5%n{)o$UmI;!7bRQNg!niBU8y^JHobx8pwK zA-r$7VXHIT54kWLog<=&pCEkp{n=i6 zmS=h z;Mpa3<56wAw0cDgirybzWJctS9!hU*SM){b4&8=Sg${wx(xus@MQ;0z8#W{N!4!OO zE;c@%R5PG6y=yi;PfV7+=33zslQYM5YRt|h*B0dzcyPigV#_1&Ur^zR;=kI+^2hnW z)9Bn&&N^EQNw?-N1@)LI0O7EGyN<2`n3wMiBWWyI^2{sOx1iET3JsM$ygL3hGZRy7 zGuDVzKgu)MF_uu9s$FXmIlZ-z3&AVEDPplvj(odyWke$Vgd1Mldmn8FZ>Ba`Rc-Iv zi>Z6Wb2tY@-*Qa`k_P#oKbCIw+n_a({p{&XG;PB|2Q(hzrcSzZ<|^42%I|ld4Muy5 z@AN#x2qI-6r1~mjCn=#-k8n6W3nnTEuleTLM98ll8;;Yv(Wb{{Ca+t8&Y`|2tZ<^F zm?gPE`s+le{^h-VVROE}FZrSVgs+V=qDHw{=4q`nkz~MbN|>|)Zu{)!#pmi9R31zt z$m#Fzhxa+W(x~*br_7v7g72nb=b~TdRdC@=dgSFhPiI^nezz}tIeN6wUeqAVb-0;z zIKI3y`D37E&NNd$)nQ-^mo}tE%1HTPYB6N9x~UCiV;@g=bI^N38kHDPTMc=>NM5vr zYBYd_q~PY=-R`lj*yqD(Y(tyZ^Rv5Yvqf_(%|BWSOP7IEjH2Q>Q2e}oieZ58WNK8+ z^QQNchcTQ_lH^O@xY~>7#GRHO~kOEgQr^X0V04csk=csG1)e7bnCu4z<7=-45P$Tu&REv@0`b zBu?E8d5t3hJ5L1^Zp5L1^;*xruE^wAho#+n>$8#Ulk`Y;j=#$7L?t)BBJ7S5N!MXD zqFiu2jJeh`+I0b>fMVn{q_R*(>9c#%)O2#}-0Ax_I?LT!W^+Ak#Kl_5*QIj$AAegw z^VZ}HYpgSoMOV2BO6&fk5yqq-(krQ`42I-@=^C`+JCIdkQJ2x^k%gxc0i7qTp2j0M z4`3(Y*1TerEPr;bd>8?I`aa0Ll%;i>nD7F#;FKyR2RhXlMn+}nYwrV|scuS0J9$E| z>l6n!mYc!P)ncbPJJg<;lU!nN-8xwD*_vp${6_k4Tvp}R=}8@a!W>B$y4sYE-YvS0!N?(rZTuD82R`bfOi6NT*jO1Cc7F};l?$*?#YtIg*eRyC2=L(D1K2ggb zrfZ;`DyU=~pol|es-wf;G}TsU`KHGVNQ^|8(6LMI@_Dzyw>4gB??f7))+N9TX97-+ zv*gr`Nsf(c9_&+9l{wZ<5y!D{X>!wfwJHVg$2lo7FM|SR~HmW+PV>sJuK?wBl~X07E;lgl`9WeS>Ezm zo7KIdrsw`frTQWb!xBm-Ip%9w|A=-)AmzG6MA}PdHDh z8i>a_+wu$kv*AXgc~`tQYtx%7rDO zzT+Dd1y1~3QvaOHSMHlsM4fgrE*X~3LV;#VHP*UQ^^9%mKU%Em!|g052pQr7UZ@2| z-6vw~GaqXU3XgQge#&j$Y;nf}!LzkEx~0rDMVBTTRsPYm-XB-u!7u&zjGgJjLD5p5 z%7IIb6nGr9-yTP`qq7&sx;*Na5C*O=wA{(MUjB?Y({+?cnmCXCaHnIB>LBkc$%Y?%ToM-!;3%OfZN`rNw9bOU%{)i8D)b~x%TTy(s|pyd;TMwM=|c(FgX;SBPPf4*XshlDO@Q7MW* zq+qZNckSZ+UgL%m90HTtAAq{`VZql{!_1hPj$LQYiALq}o$mc{EG^$LgViMeIidJ0 zj*6Ay@C_YCnFg8|)U@b$N6SieQR;% z9asK2PZ+-YbtZo)aHG`ap7U&s0PvG2YoWX9j`2Rfv%3Q4T0?2Rlg!2<+?Kbtb5b$0g{#fVJP*GPCJQY01x* zoj2n}`gacGe`GasQBg4;T)M#LMpZA(*ttqfmXGg_R2Tn0{uq(9bpKGok@8zFvV zHrGf_p)s6{QECWnbJEZ1l>}2d{XA#PM`MZERwP1PkgKVsT8b4$6gll@>x7N9K z(Ns%ImX^6D6T#G7_05+^jr!nNStB5f>=o%W2OI7Jym3rav@;C15 z@--m?IR%9_Ht3urdyQv5d-e?d6x6$DEJ=p~T#=-zh~GI>Ox0pyDbB3RV>7I(GL#MP z#+wE(dAzfKx?lq%(RfJBZphjL-~_Gv8@m5Twy)2##d%wK{2 z<=d;2NYbO@IzSsm)tRAI3+DPv^xRP)hZ?G8KScMiL3El3tqjl7r61$m?8UB_M9Gap;3U{fOt_Q5bXzhcag2o z^?wsplWiasyYdx4R17V1A}4OHV7O4IX#h|PBW2?M;--uiSNM}EUP8_9{{8z1m~_`l zDpz+tr@E`+vVqZ)u9$a3~P1x8A4ykfE;Z~_L_^r5*~36(L8SaBHGb{@DWgm@h6 zujOC4khOav9O_!RyPTXRkQohIido6=w~DQogz!?mTa~pqwKQW({F=HO{MNp;;v&?X zx{_EpEW-bbnmVd*_G4lg$>$WX3!TLd{JBJ0+a^14a!VrP`#RiQ*&&r7fhQsH98$`B zxpOCGh2sm|_(kiXax`RU^k5k{^%b3k9T*xoQ#R|fF@Cp1Y8yWUyy^o)Zh#&DFq|9h z|7<6$+Fa0wM-J_3UM8Y4wDL&=C}Fi`-x1MHynFPHzF%`F?8<(gB%LzWpK{xxzM(J6 zPcN^L;`A>}Ri+4EQ8jjYw0d3Poi@FPNiF>r`0vCQ93>+uPrg=zl_SMV*Dp#Ka{2-s(+a zvZ>aV7cw$4<8-EClaheaQ}Ud)^)%<>%W>|l;OO75apRFabzP{Tkp>6Fr$a&-k0Yqw zrL}>Z`;&&;){E&(fn+5xQ*aEE#jCGlSgFZ!0w|T)sbY>Rh=PE=j5^e1uP*`}l zrk2)>K-Y`Y*mNN%1tl*tB>~2m6;Bdys6~W^f`TKpu~m~NTP1|7#Hxmh<%E$yWNtSp zG=)x5x1z4T{(1uMT^yDd{2Lk?G?r!g{EX9==PF<-E;*Jp|epQ_5gZwQj#H>qXE27?k z&6Wq|GNC5~R|g#ah_lhkGkZu`bb%ueFe|x-KI(j;9Px@k@nMy_>`c72OD{x^9(VdZ zc~=ppTF|yCaq(VEd7_woOq4H`X*&uZBoYY`9!?iTMtqT#=WduALs7`p_Pec$!4>?@ zE5IUOEWe~^d|#v&OObW2Jn?^@bFrZz%UA!xz!;N-RyuDMfkXlzV7Vn2C>%TZ0ylP~ zTI%Glt3k6~@ku&*tTO9b-+oVO-1C-f#CwWOJf`c`!35WOc-9}o$RM$5ZEA{|U9|$f zD>SQD@BTs*CQi^g4Gb%KPN!EqW^|{H|5Vq75{>H+G9^zwzSJuLU)QG0q8@q2q;QXq z;c9z|9ZHp$hf*7u)nc_(RRmUlXWDZDu%nUcLuY-BZDveT6O$B2)^CbbVmqbJCS z{^bbbjv_0EpQVw#gTpK=dN*yNpbiNQB@*iMC+x^7el%y}IOV^* z1mO=E#GiWtX^zgINaZ>MO2Vt#h97{SW+D?gV_NPmq7~5M0}$G?@VPk;Gl|PHsQw|f zJ-Cx`luJ}laO5I2m(I*?Ha!GJ2&jkFZ!rDmUwoG-FIa18l8Tn-pLkkHE1bOA4l2h0_2v zBIK`LQAM!UJ22_Y0>5{{YLnp#yA5g#V42Fqe!4%nR$NTp2U76hs@*ZldkcaCNRk3} zm2%RtCs2P7w`{b!ZzOU-3w8JfFbiFG-n9kw3UHd@H#Zil8Vt18)pRbgw+v11NIcEF z-#+3A*Uw1Bk?RL}lFZ6dXrGe-H~`VxC7>$=>$s@c*w92Rcn_~wyo~EPv-wRJwTGy0 zb^CpEf*KtlxzRl^B|it&;@!RULxL(_IS zmSjH$rn5A2Ef$M@#@gZ^WXzAJB&@6LS|=$ko(qV=sudFvF?IFkpmDlxUUkf@1x_=y zf<2BMlT&8?v|l%rd&77~&^jX9JbO<6B6c*MjGB!WxwS_DRBl5bS~4Djg)-ROjd!O8 zk$r)NEerry9V3Sh#!K!N4-N_vmG7&+B*fv}c(utSI2dfB>MO8eNEpZ(5hG@cW{D zVj>4%o%I~L2yNS4DmwP0ty9sPpcTHJndkztZR%?pdYu3{(#+xTeBIK9OIwI3i`B>c z?)dP_^W=87-=AmiLJ_!5QR{Gs)P*rM1;U+(0NWW`NeA}_+dbhnsZX{pgDiXV+Gb{{ ziWs5twwcx&$`ND{U6mfBV|}P#v$PCRE8X%cXK(ebHxYc?;QC51@(I^9MfDG-y}L)r zE3LO&baxt#O-{b7f76AH9^sjUm#$*%loyaG#@TuqU@i{OdfqJzK8NLFgigfqm$$97 zoe(|Uy_?`c^5-A#5Mr%u9uIWg(ESr!v9w+xV~LsQLB~6kHTxbUwA1wj`#n#w#NuNo z2pA{`?2)f~uwC`iYsGsm8Wmn-86zPUX%8Y4C-2=aQ+1BuJaY5RJ7$bSoP_ZJHDmIJ zPGhF6FTW^v$4Rkw-%)vFkazf{UF6;DxWc~g%rC_-BO-K-(-^4C_wV1|Z6b-f%tCdy`CYMpP7si+te!4E~4TBmqqs=>-mlobDzck&K zR0*GgDc#o*%8MqmJk8G-@u5fiS!=6Wm1h2XS3^Mh@phxz z1_yqAD=H`6afyJSc@;th95G425n(k!)Zkeq#cl;!n_0AV1`Z?45R@4+PjiWQzuxTT z`)57KKp^qGj-d@x{UbnPiVN!2x4be2P|H?5%m1PrWhqoaYnuVQRo%Bw81fi#CO~@OIKPxor=Cu4C3Y5zqK0n2=FI>m#3UFm zy{K-A>5}z&w>9nS&eV-$hhS|qwQpzhBZ&=Yf6cvo54iegSBQH67wH%yYKWpq;hQ&a ztb^B@e}#8K3SWahL;?Af?)d;|YeyK+E8@gn+NN7~Zo*0vlBbk;YY+p`)+I2wTu(Wd z^-M9k0PaT$!x$L-$^3ViZXZgpD>LwhCd7^2lYQq?ta(j3KEBR{X-a%*au*J^`n$J% z3L`#lU;pj?M@p}?PZ!}90tVn$^r`uRq=vvI51R@KA&ZJQu!rkTVElLt%_b8fGb68n z96tiiM3aydQUZ_OHadU!N$?ywK$Z+RtK{@SOx0*Vc8-#hlg9unlwpFhV^Z|Kf@8s&CP zQQG^f#!S4aPFc!M!}FHySDPA}VmLcDHuH`dzdZg{-hhW8a6|PNR8^|JUN}I0G0(J7 z>SeL~>7Dy!^qg)xkk@p+VsDwrSo8kp{H(X>?WmeJ0^YX6s#*oa3E=6EKmx+K9ZySh zskA1_`fo*QXldEsc5r+$>T4*XW6s2^J9#M)#HW!cP4}?w_u7U_7hQPJVO<*Jj%_fM!*`5#{QaJF<^|Kn6r;2%w z^|rA2wWa>Z?2&!sVYXu5s2bY*%G6u++w+Gab1omjSm;X!9J1yEOehT9XZaM4HG$o< z_&HelWPEPr^-|l8_*>_f=`f99XEM*$MN7of= zPmf(`GjqWuZU8o|lV+wkjg1?ns~7FqbxDZm&`FYX zOpAQ6s4S~&tE8GKdDvo4cVg>PL5t{TR+C{dri_C1!9v=PY11bLn-UQ^GBh)bf+!UtAdbre`f!Da-ABC(T(VdQ|?kr0;(lMXFFlH8e z|1=@k-_j0ou#JsPPp$#_9Gwf_zr1veJPY%rT0;-j;q%;9m2>aZ#$ywe&vVK1Td3&& zi6x~iIDA?xk2)sO(>Y~A*j!dnd0{|KGi9SJr_L<9a-;h8=p0as? zBdadCd`%?N(UW}N)YD=|XRgoOzUNM#rIa=k8agSTrtxYmZ`|&dOVLJHP4?ms!l_GK zRszLj(>Z)@_?BkFfWPEhiuQvegR8ZR_|x>+^CWm(wBFlamFV8^>gwyKsBr)M*cinR z>DF2i(RE<|2pU1T=q6S;Rzlszeq>qgmzlmrHn+CcuMt3!R{9*f!j$%p&+A2k>(=b| zrWw=0TXaS;M{toKc8l|HLuoh?@zC=_z+1=^X6okPPeEOLXX+KDcJ4ep8_J^Il0n&> z418C(kkZ2Enxhxq9GY!+QNxPJ$!<8TLE^BPsk@FM66TgY0%4PS zfg7dKoi`+zK-_^ae2fEb<>@ZoYA9%MvKByj6L8 zbI(dqhi&D2v*#S#o8IycNgpkX(#ysk5^h&tG+a0_ealT>@MwnbN|B2l_DW^-p4Y2| z<(s!R`neYi_ULP5S{h}~dxai6Q`?-k%I>a+>+|K$EeKRLdN*M4Qs9=1mj$<}0*LxOcj*vhq*qzPWp4cX)I#1PlV+=$9ITH2wGm zczbTNi)!*Nip^3ziCUaCI2@FG<|JDQgDuR}u%y!xPp@tb4Q3a6Lk1O*R#rB)SJ2ZA zka7_)@x1!fMl)`eLbP){Q#!q>`uVQd#KiFLD~qqsU16H&Q+l~FoTlO^5>94%sI=ht zIuwxQ#qAtKaX(}*e^S&#pINpRD|q;}o@!6baV+GTui|+sE}>0ThH`7dv`xwKKcH5? z_F6J^ zL41pvhS^+G^`B3U$>R%tS}zkFuQ#_3j~6H5+)EWu`dj zdi2(Op*B~n(DAr;(!cBe$+UTcwhYf3=CZ5x+pc4u;u@Jh4%3@lVWU(I(1>ynk$ZT^ zUGKNgNPROq_VTHY!^Knqz5{u>s~iBiJ?Z((*O}^q@c~@H`*i!_+l>^npI&I>wLg`h z9CLR`&TdegO`R8W8>_S~H%^fc z2tVwSZXhaKFKu&3e)x?OD$a{Jn<<D^fDscme zfCuz0+d!ey{lvdn!(A;?x*|H*<#6Eo6{U5E2kstyzQ-pdLn!mbmaMZ?96e@-3mvw3 zWj(+%4$StIT$Vb*_Zb3MBF!@5H|<|+epwsLCK+d`+BD1alKCSFLL1b?2gi_;8}`Pr zMjv3z=4FfILaWXhGh0vkB#J{%oN-WypUL=)RNZk&W(0lav#g0zf-mR4vTp|XkcpV; zV3SfV7%0v!jg~AC>74esp0yO}vQwo}<;I!5`5)K%&7835(2nk%H1eIiDX_h5G^BiU zRPU4euo1y7=8np=gdgnNL7P}P$}>f+aX(X|EKXM=-0NVM2vge1<2SM%rdrQy&0aaZ zJi*yBydHkul*oY%DeiHV%<&aAWhPuf#Vt1@UkFC(sSgTj>yO&+_Ba|%Irj0+kvsNZ zS;kTlUa=(%W*=i#NTZU>`AUgEW)U)jx8=>fxcRnhX&pVntgx@*Lt4ePln2`RBP_>N zYqY#foN`>lIFx-WJXY3ReQ|7EhkReS%a((#r&N1v%6F{$7%rRLyKy&Njs-;n!^KkY zbIo{sQ=Rs*jKv;j($-UCm$q$$gJMiD>QV%(Ppa@pnVTJ`<6B;)d!U+IQB4p#THhd+ zl9DH)TLA$|N6832?+4(Ig&V26YSXP=4YS3nkS*pFatIILEc6ZeW`4C3edc`}7x`2F zqN17H(QE@xX#X0-9Fw9)*+=LL&AS$H?(`i64l(NTg%rQ5)`AS@)lMdcC+A_db!_%|@*b;g6L;xPn+9%L;ZW;SK8iRa#@^AKkCOmS2{)y5_hfnuNH*ssgq+d z%P$VxU=KJ@#RSKkuO7A5Pc^rRB(ROfUyy5lw=7Tcu78$2R;2UEq znOyEZ=I6b8|Nd1nA@72-vKyLF4TcFz0H?5EGNLT+w|9@dJ?FMPQ|CU%nfARsM*Ug= z-h4(z;&aVB!xp~ly#M1JqUW4WJ79XD7m9~yZzL*u8%>O`kC4+pT>RmvVEp}SG$+zx z%>xIbUQ=?w{vaNiDg~ z!?mbSK8_$4hBTI-EgrsjJ3!c#;5UCo9P-}zN%_ftcWvyo!|jT~2#9zJVQd&r>u_E$ zQtPRode};H?NdanP;@usDi|KIy+f#i#z)Ng{Ju?iEFw_DyoESMBXgAEJ~g%1w+$VU zDNR#(?{puHoNFjL-p>7EzE#4@8^SqkmV137(s4waZ#tx`iWvmc%gxRJF;2Uy zs0i?b3Ma+M%xts8zK3wlzS{bu#V~cnERxn#H`DvBDPykod@>c+;)qE>>%1AOz* zKW|Il?4eH?Qk2FSbS{THLrCJtQt2q1@ZX+2UG0&9RszfmquZVg#zK|d{^ z`QXJ@gX>)dJXl{be2*%O1EtP@C74xuZC983=8(fs z06kSV&Fk=hTf-8p&9*Rdi92Ca(FXe_z&lG&?rKfkA>1Xt+Cd>~^`;oM6U_V3rDppq z^LZ0gDuA4rc#%oZ^bq?Spl5rNb4iWfj~1piU>IpHr}7G@_=~Y+JAV?fVmvF@n{rk=;0qd>XjEOoEgfC0_0(jo zX87=~psdFVq)vuYe5oSR(r)mIMUGt}lQ^X!7>WB+U%o#(yMA)eI;WTxE;U9-4oQBN zT&VT-oqi^Mxn;Qd>C=4^ye=m<1k|I~Cb^H*m*G08;uWSeoS8%f14z@jcQoEfed`W9ajoppigWcD9Ix_ecbw{T;vQ)v$-&vGeWcENiGzvkpR0wDl zNpt~`>xi6i*di7XzsHvMq0f^qp{PdQzc0twLic`GjmcVD(lAPLyF!MUXdD>xfG#lb zNZ7UWw%gw9&{t{p``FK`{`-g714fkcqV6=$FjS%PuwPxB>65s%@0E9{DeZy}r^ty{ z;lZ$*#IM3^O%s)&8F}lAg0^Jhq+cQ6RE(|h_pnfoP03tzHy940RsA~93>NWuo@su% z9lu_?#Rz@WWdG4sgD5rL%E*9ZfX%Oq%Q&=du=NJoAVyZFZ#M<+Wrl+!5f!$9mIj5k zy>t$ymf~F+2LiSxw*t8lR=PSpO;nbTnn9oRy2bKN;cBJ0)Aejc2H`H^vAnwR9!|TUFu983@LI(L@eH$c&SiR zMP?cCgvxH>!Dwe7YR;4)RUCNw7#KfW{^g6-JGDLTuuEV7*=u`znfP};c^Y8?7zQpT zkY+X|?+xA-9VBWiufQVupggzGmL`1jw_oJvh;jB4?lp(I6Wa-`Y7;>|PQZdxhPDHr zIQYUY2ohMo6$nwPBRVml%C38fJgHU9P}Y(NzwkiwCWmYNEB_UZGK z@0~jZ?~C-hvL#}nnadH%tULCTZ}{i!bW(O6w* zb@=!b4dFLK{#VxI9V%8`>&BN_RYPFX96|k4yz`%E#MVd>na}O5aoHRw+f<7mZf?8UwXpP`-Nx}(WP0eyiyq8336eZ?g z<3%0m6rU@;O}8Ae6`Hf2Q18U4nU&XV7P!P~iGm8a27ODXfX2!pMx8GcR7512c^@S@ z?*jdUE$6+})U7RDIt800c$7AW3}%VRk~#0vc*gZj9dsUMVp-_w)ZC4Wib7@?ZyhG< z+<9xEdX3t%MPnCyfEMipzSNsRZY@^_F4^IUVxTgnqQcUl^8NkoAM_BwW63NAlSslm$Y*F`2npQbH5juDvX}bVhQ#QR<)B-i)lGou zF&17rWhl?$Nd6bNH_%9z&A%H9L3E|J}E@LdRrL{4}m>y-V%+%Nx@Y>L;OHQxY29~v2H zt~1nSGj@>^7_URsyA5xWT-D5MgQzSafrrV!)p0N@S!XXO^B~SQ{rYeg%gI+06BFFT zhwA|=(kaUzDDU{AI{mnyfp%7kPDz>Bma_Yz%>%^f39p!XM9#n%)w4Vu-V+E>l{3q8 zDlvk151ku{(REWIrj_m4Is+FJb@nZF%0}6sk#-+opyj8XhcXU}XesibmgS$S#{wG~ zXqLt2>c1qMym+$-$<8}jN_)7B=#ZR6*0fCoS zR@S(;$y>m*3|Pg%vDj@Ldt43+IRAi@)ki2TgVktl_k1Ht`D8dAD_y$$+x1cJ0AO0T0(D1>d854Nop`@m`j~__YFP-ckpg4W75X$(33T5q zFf?fRAg6hNZXM=+CE%llO$T#`)CVxSF{sAWOasZOTU@!cIPZ~CDE;Vj$T|sg1Lb`^ zi@=L_yaIy9@Y79=b9}PyZCM&Ubp2?DM4c__KrBT?&*eh|_DC1cFAQ=6p>!iIF4O7s z7ryu2KHpUp&L1KGCc94qkudcc49#*x)Zwiy&6gS<6AL@)9cleIOd|9l^@cqV4uQxO zDz46wXSnUX7i7S-mDu{>^~?8ZC<6!K%R3g2(20NwrwUn+^jTo^Jo;;mv=37fOWFm1 zLY-HmY;@x@gcJv%*Wa4c`*>ZsLq~>7kSmI9o|y{^=YM{%m=@Ldg;cvi9nk{ZrQo|T z2dLOvG~dxF973ROO-*lMdkXiCESq)x`r8UBb)<1GByhKn_+mo-`__eHy523$ls;Pe z`3d%e99JAXg+6&2m-V3KhGT}XRDCM@&J0n@=;+ZxUvw-Q--;Pz=^z6nTS+A>a&PB3 zS+D%)fi$YBz0u|aDIcQS(Vq>`~WN|}dBL}kvD zC_#5oYCZgq z&tW*ifOs~-7^7jg$zC0t__^M#jEsDH*#`0G|Cl`kk!=`YSsa@>qrNH^@Fbc{TNba)EdAZ>`V3yNip2ynP)e_9A2Ug)7Iijqdd#>-hQO)49+YRqM?9(1BT-Ct9$$;g0i1>AQh> zhsr}$@ZSF{<4TobLIxjj=~C{|hhKrz6B12b!{8Z!VRkfzq>lVy3@0G$WsL6~d=Z{} zyLSYNP_~_RI)r{N^Xx_LGYrXlhnY69!cG@?2l5AG&~f9Q|#g@#~s!n-YMKre-4sq_iBQ z7ssw^S7_4qE1Y>zo@ zw?0H>ipD^~9ov<)^Spgted6@zDL>+Rw=!WJOZJ{{cHwF<4U=$Xk8mHTUZa18{}=DU zYy9q#ERt-Ggb6aNW*GaFa6gV0sVyt=Ot{~FVt~Mp#tmNLQJ;V2SJ@-#VKV z&UYuul>GC%*NpPcr=J_2{Rlq2U^l6~f89ZX@p4Sm{VDyo{FHaqq(&z-s`XJxAwL(a zd=)!paf?{V`<|Jml2kdqhsZqYotBr7m6w}i#jv%3kfdna-H0*}T2tEM(*7+d@Lu_} zCSqC5J(X@&FSJAIr@@MYL7-dusND!`$ZFUr*_-Zq!u(t38)6yvF&9-g=9J!akxhlC zVq&xQf%<+Hj7pn_d{R+gRY;xO*J;HL+S`wz#jLEPB+k*+thX`s$}8_)!Qq=^_u-rK zh1-*}SXEy5noi?z>lcqDs~4WYuG4%Xka81hHmiz>XK)#iId$JCH5}A(()7J|cctqMp>giFTs1dB zD6(YVCpSuOdMeAtADeXgN9P}l6H{s=3~3;g1)7?GB54lJ0b0S-dzCiNg{zV|>o(8u z&YW3h!1F34ZeNI)yt&zqCwKx*W#h%*xfgO0T^FI<-Gyr2wOAby<2<7M^Pmv#4QckF zuhB}*H2&@n1MldujTw@NzA=2BI#KzCg{@~j0TBX#tJgn`&ZBS`tf|`wA&lZGfj;YO z1zJ@`YU+>%6j%MJ;z}`}uIyxyOs){VEI<1O4HTYa9t(?d*t=UL+HBRGv>%6?c&4|3J23+W&;k37#AL+{x$CDRMRk2K6=TcRBE;hd{ zB7bY)$(O1N+$D&`z_D`ScEPVz{VSMF(l%`RTxw4n-q&1g4w=3IM!ag%~45;Ec*2Nwd|L8X&X zEeQ>C^ESW_pDc?#5&Uap7RK0+%k-mfR_c52|><4zZ$zw z8?3;<17;&l5{30d&=N%63j@@csoD_7;|35EA z{N1?`)#uO>^RHgYVg;@@hU2ePR5mWwHs1plYaxxLue4Z{B_iMk1^s{ef#1tTNs|iC zVul}yS7#m6;1VP1c{V69!v4G`>xv%Y8xoUaw&qqQXfzq@d*0@5{tq&&42{^6xTvDyz?%hG1QyyM^bB~4b zpEn!whoKg5fDn6abBZN(I0R9K3u}(ADh>7=Rs#C1(wiz*cyhS-zjP@3dS7l6r$BRl zY4H(GKSx0sdF`gfVL_P#HwaTKSJ%RFp^i(sT%tjGsh;L z6VM4N=+{{nSLsuVzB2h0!JVyE5r$$DL|^}a09zZIhO#Jaxlx~Ch%E?Y!3cVhKk|=E zRD4MC{4ZT1+*Jhy$B2CH2fshcC&Lnwxf~%ZQ7gJ}TYxI|Ww1X4K`Dk%)VA?JB<7OZmN-?uYWk$>b--ir32hSa>Jp#Gq<69*ZIU-OYn|t_H#CO(w`hdfW zl>;?CH^buRzUMaHxuwAb#q}he%~pmhnN52leG;;|e`_Jy_9G*JK#cOH4OHi_a1drv zFP-Wsm0EkN@3P)MHhYs{i+RcBBQc$=dqA)R>+}`Z;x5`+W2DcRInO-YkD0eO6&{@b zoJ!t<>H$ooPsk*QdT~bjhr!Klmb>m8p+wbeH9^&eBIh;IuK+*oh12xp_ltI5`J3os z%?u6WJQJ>7H3f@Bm=%0*P;rqd(tnWH4jM8~+!ol6ix^G(D)1O_HfRt2HSeOK%do5^ zQd4M~q_!jLcB<+Pbc~JnQZo~^GGlFR6RkxTyc6E3zSA?Mv~Xm(+K_tG1|23o9%0MkW#(67sW4 zM<8tUqMzRpbMqfRe$+^^g|qAweC;E!ormY9xR}_X^6nBR_R91GTk`FlyRIwz`tD-m z5dMHP@X7xQ_tINgL#)O{!4{qB*xr6!Im*o4eby((+bV7gJ^jwA{0ZAlg4P<6Ee!37c`g}+=;^lSx#zo>c&V0i-ND7h%PUQfLTyYd*aH4TQ zG6+Cpbm%O^w(7L=M#+i?&lkWw{|r2Mk)T#}U=H#nJeh?b7Gk_IWDfk<%qzo{YX1>z z7$4O75}FB6h{E?hF^gdy6TZ;QlyrC_er*Bu@Gq24Loxy53ElM<@JAy7DRRzjJTt^7 z*zBRwHD>GD-0q4fgQF-LP>=ZB)Z8p4AfR~jJMVp#=&iCe__Kyspdwcoqg5Bf>)zt2 z;HHzo_TjjIEn~u*_ha;$>Qh_qs-!y&ccyQ=%*xeG+;w&yc7oxtYHFIo&39Hpb_T|v z5_`_gJU=tgUb^SuaWXfbB{0hz zTO`TLSFE7z9a<)=>sWN6nJp}KFDRUag*(4hn(dD=!^XrTGdDMf8zKP!0fzx?1M=z= zr9nLuEAjDSgdH&qb7!w4Zf@=tFX1+5X;{X~Q zi281b>4kgGkp6D!s~xC$qPEu3OuvuKDlYZ;<_<9LiUyh_Fq#oxi+vHD~>{bq=!wctv)spb{moYg&3X(|(3Jp~* zf;@X@=(w9t(}sY+K+qVOO-M@#im0o)mPE>h}s zQCiZAop_qig7GgBcX;A_!1}+h8x;B`3j%Gy;m#r3olRHStYX5Zzkffg`;z7FmUxPU zk|<=n-fQZY0py)Sjv5gjE|2Tg);4pVPG{knbuL$fwupj4Z%s{&5>*l5ROUvg-b7V4 zDq7-fc~SrjfOwH4%v+M1n+psTSb#AAB)#?|ig|LRk7b90P` zH1*%bb*1nd1+toV8U!hg7bi`SjyPnhF}FeBYpJUn>CU)K&XdOFo_Se7+UVe*%a5;a zHgPJ#r(UX#KF==-G_?A2cn*pOJWjA6`T`GPb6pUKuuj>0to2#iY2h)|z?+rG){!o-%9hY+v|c{gj`=tXunKz_tzWS~dG+^xCvk{Naoh zyXQUQTz8BU+uBx<9miY9pC|%Nsha>PMorko;v0y`P}YnYFgccuPSm1>D-kX^G7)#6 zw2VNr*fB){MIbTu)QzH2c(0d#YQ!GxRQ?LjsZ{>DhLkRz(G1;9Mc!{T|L&WHM9CB4 zyy{w7(RFtWF3xDYJ(|tj@ND|X2a~>tsBYncM~Z<}Nz0wW5%Hlpl~Pb(6QkuDn!7Af z7TpC*S>l4_?zOaxD^{%7uTOK1iI_;^)lh~@nu>}l_-V@b>t?4>$;YZ&oIW3zT*<4^a4 zo%@k+;6fuHoy+Wd?~29;%}V&9bxOB&2Jm7k>!~l3lL?pyYiY^po>@^*p&Oq&${D@Y zKx#2&uBko5M2CyCY4BA}KikIcJNg)|jGod^s@|)T!!yxad+9w-mE*O+1RPiwjmviW zo7(W}W9Mpu*p=CZcc5v8Os780DYVV{E3n@Z)T(#y-o-3Q#YvsiO4Oq@C7&Qr;S@VY zeH{aFafiz=z@g*%e3H!eK#0alDHKGDn~~%jBEgPxpFb=6Ffzu&U{#|pPPjy|g|4YV z+hYswpkq8sb3=o!bOBNqI0bDU?lix&&2P7Q!9WIW%OlU?i5}`}GI$mm_nBJWE`?^8FBQcE&U> ziMF3m07AJGAVEVN0gA}7Om@$=%MJ)_A=(?n@a~?TAJ7kc1#dN$+>*Z|*Qq6yN}<t-}S1$k9l<85blAVo$FtT=i{|UiO=CFPrM)3+Au)Y>}VGub) z`!m79rZHZb9{B>xssNxB!E2csZu%woLRO8ZO1kOX^ev~`hbxP*)=5i)xd>+=p1h9HIs9+y?IFScS zg+AtG48GUHeT3aM)yMED)7(&oGCIK=HXX_3yD-dnNx6E{7j1g3{V6Z9rpR*!ly53J zVyR`R6 zQH5t2N?`?J=B3+@qMv^oTlHOjOij5c!v*tirX2R^`q>do}y4t!rp>-%TuvdJL z>A8@})lKLjLP}|TK&a8YtP?fW!-o%JJ0Pk5xWjrdw6&hJYhanXs)V4kly-niy>^zAZuMo zO>G#N6_=QpEtjUp$#(8odw18}uk-U9#UKv~@yr$Pb+`U|7vyS?;KWsz&_(9#baru( z+`3YHW+!j%F&%S$w%4!H*GDD9#~YbQ{<_%}w3BGd4YAMZiHeG*(x4Q0q3}+S2Ls4s zr3C3zy{Taug$Z5L@yC3bm46X)Gl+)=*(*v*-gjftce`TpMNiEJr}Rpe3JH4bz5T)X zWrRwZSz#cPGoc+cw${<1iHhC%`baNJY+9~&EsJA3ZDcpfaxi5dK&okx&iUgYi*5!o zz@;qkAU-^kOxqnZBg$uPb&t5hl8e=a(tEBy{HD+f>j~tPj-o$$IT~yFocjkj1qo|N z%~QtQnKkk|xrguKVSdOujf|FPe(Z5SkWHk*0K8nmUU>BAQ5N@Fp3)}4Q%etVr)SU} zZ%_vn7hE7Ag@Nv^%uG|eBOb@HUmHv)(8la{H9G#xH%=*rv`257)M)b7;u<^JYb$VS zL1d0yn23liQyu2tdi{QBmyHT#WEPIe_{u)@S2&j~TUOtT5kzm017e!HeEEoK(T4vV zV{P(9P&kl-S+{v39Rv~(Qi+%YgkE!jPI&lJcOm!5nL>4LA|@~h^YeR-W#4)STG%wK z6p&(|;T{_k1Ddds{`2N$HJc&Umeq!VrwxpagGSL^ndmAx6oXy7Cr;@iVW(jFVpT>Z zm2glMw(4S z=w+(kba^#qW$SjISV5oq1K^Dh;&-DTcnD9<;Ibh@im@^Q4q8RSl_o01{JU20uREN!No~S1Q zfi()J)fRoze0Y~U7o2ibrHrd!%Qusx#=>#C4_TZ6mfrW(QH2yX$CbN|>LH-zC1$-H z8HvaElQ=z(r_(I$Y9@1G?LDI0okQ+$|2Y27`cvo*p~a5D9D5gr=#Gz~4~w*gnBe8? zjP5RfA$NUjQg`DW3n52x^eLU#Cx1%0>-s;%oXyy}=?rKG;vdk`hDUYbb_aPyLWq}_ zS5VL%lpiQnJ<&Bkc4m}k%H_@U`>s^-;9<%Z2LtOUvkeb24F9v_+xPBexAsF`T|a1e z%aWXC&j~5HQ#deuv*>POzS?BK1-IkO!a|oHiRjhcLZb_KU1@14v^p63I1j}m&J}WH zMgLYcPU)lI)Rv!3#NIrZApWGTPOZD^02~(jVX^TdA}J}Uq+||&bmI>m(o^$7yGY!c zhMlSVL-FIB4`w8qu88N>PXKz{N>9)FmdPu~J&_uXvvLM~Ftt7k={OiQQTe4yQh&uhqIIU*>)^+fw~^)hsTt(9oQpik2g} zUA2$w7RBA+`@=;0%)tIwx8^cuJU!=O?QuU%HG;JR1Z;!X6I_Crm`2Y>Er^-%Iq18BTVZsR zkou=)`aitT&s!RQIHuV%TM=2<9$ ze3o&4N28Xe=7Eg97fsKeJ!@=K3Q^wIN=*sbE+e&b7^%lizfN>FF79r<$4IDD{Rw&3 zFwQ3e5Gg;QJI@?-HV8l+P)f(R$57(7R&S&o2K6!fSjD6K2P!$`@GmJR+{UK$JWNhH zSu}@|TQV>kECD#nK1L#M z#wL^$e({|M>o0PF}vJrw2%Y?onf7J8iPEt@3pkkGWau=|z>E zMwbJ%p9Biu%vOb!R8*GZKY#v&ADQ86u@XgH(W5N#*)?RF8Ld;Z0c{y*a)j2n$!ObG zm|Fa~gKUW*XqJll`Z026@NrbWoPjXSfki0EK=CNG}j`wEfLEyAw zA8%@PyU-mY>8qF2!*@}CLSDwk!euQf<6Mu7} zB#fD)VXG)8D2UVnmX1zz3)iimP7DQ%{;LcD@kwV#E$R??%{wr@I{Ik+ZduG|a&mGK z?u8%sl#CNn6?U*J5C`Jp8CeA8I-6@5jzTKvQQ!kURQY~n9*@Ublam5Ba#V^6 zA|e|WRD8Rb3Zy8JD;!~@b@oC*?cZmA7ZVM_ahi~!G+Z=E?d(TJfqVEYWVPa7E@Nzt ztuk5JSL?t5`pY~qeUh~a-GU}SDdq)7aiY;V-3yF~qUu)r=ZTtQL=Uv?Ta+&$d7X0V z%_?pH%YQNh{B%E++P zDFY;d4gKX)U&S8XXHq!e2r-{wEr%u5r#sgbz_}xHO7yY!vQMka#T-ieXUjfEC(ZVU zRD!XJ3PqT0Hp`|^pNjcT+k4uGgJY^2Uj4;)Sq=x5pu-Vn16ncK1B59EM9JsY$aXB@ z$>^pLpB!zm8j8rHEdr$cH3QGLK0jAx-SufslwxArr{{h+DrrJ_LFmp_sek@tYBQOa zO29jWdID{z;H|Vw&ws{VbAYCmDYgHY7qu+=^V8Qxc6B*FAADN3;N;=(?Rvu<`sk!I z@jrpho2z{I-8)chdHMMGaEj~dtap9eJ9HdRzM5tnbz97dE1&z<*Lg)0Y#Wh#e)ifg zUT=J)V!jdtdikkpy2d5|DD8L5=HP~(+3GQXy7?gjot)fn1oE)Sd~jG8knB65p;|<@ zL{Bel!p?0k*5g$M!N@IMaRrFtK?A(li;wgdUR zxJp&U^m?+wwfJl%1?wfcsTQ=S>j@QKO%Y6?vixKt)Z{J!-Y-3=M#*mt8 z*I19=!F3sOOpvahPfqSTtOwtZgHM34niCUBBjq`1;W~(7HsN`FJ;eB7XYP^;O7lXn zlY);GR+(NIfC@Hv6qpuVMy^gA6(|j#dAB$f%VV^4SYgnc)cHJ`_D>>tRe4AzY^!)_ z<>bVtq2q*1Gr$hK+@()Fz`S+KQwP604I2X1Gw*=s*8zG)#uE75!te6Q7s%`h2iD|d z(Xr~<+B4qXNsX14)eq<46eB(e4cDtPW$vuZu|8xj~KDr{Lt#2XvKg}s)wfq!;3RRJ2 z@kH^RYG+GPs)7BwT+i26VJ+=L@yaRw!HJ1p1a9C}J;LeF)vXjqS7m2VI&Iry+fl1a z07b+!7o_xD$pCp^URH!M1J$f#_EpRW*SqJ6t5WZt3S~lToSR?cPcEr)oR7DJrHY?| zNi4?iKYZBA%q(kF9Rx~RXeFSNu+zxJJUq;+Cb@fD;7#+&yfMp!cw&SfKc;|vfrnzh z4aoE(PZM9J?q4TS((O$GNZvYY*yS}9RrsIpT0LZF{U);eKt@S1Dhe=YUBQyeI1RrY zB>LyXd|vRRw&17c1@Df)6sd0Y89I|^(_&GMxjOzp^Vwy zSIwORl^>kU$!f^nUy*MBv`E98H^bGSO=?;t}Pc|D=qe*J&-m$7trq? z^2*4_h=_>5HV1x)E~#s)f-k*X!?)$2$b!S4b|&!+6a4)A!24bwK$Il!ehTSQy```G z-~TC7bi*Y}9ZUeMRmSoBrL4bfm;Y(5e%DG3|HE1eT|o~2d2_;YIwj>F?wg=I7Zw)& z;>r2vn$oVw)4TiAE39zeTm7|xU z*WQXdTTI&#fllG#)&LFtBmq_ieZ=CasKnx){PTmj9*T>aD3`ayVw*X*;TdNsoo;wB zx-|=qhun!a7V%z5$`mC*l;^UtfjqXFnE#nk&2wYaUP%W8BJ7oWE5 z%IK}S8+d!))-$bkf+n2Ex3qp9@bmfiFD6V=Gxm#Mtf*yG^`tH1zkfT^_hRT|@!17( zfXuh0*7QGV8*EIIy4zeD0IaJ>C48Yi;dy)MJ-2@BeP|YJuSc$0`R-?lph;jucoy}` zM^Bi0KO%F%lf8)68MG;pui6?m{7PkY8K%mT>%4GXn;;%r>P(@z*(e#5wf2S2Mal9G z{5BRy8dudgL>8%6qq4?*`bT%>gKi$wEZz~P^p?y%bf{V#ZdeIH0bgymRgSYg8~EV0JegSC1&~v zm(Qg&bm$J`Ss>_vrywMi;TjbrxZ3F#TD$002FRRRdH@ax08FRX!>ay!i3BhD?ZcYK zw>gsc_#Mq}atR<1mZ7iVBRmH`MS^c~_wE zF;kla|F8cl+mw2?XKpV6X-^k*7tvtb+OD>lPK*ciXC(9q^WfL&5LfXS1<&fBU&%SB zKj1A1ukhYv07l=1ix5xo*x4X#V!SVcjSi~9YDe;l_3v=hmk1RIm5!~|d;%2MW&}^8 zP{)*jx~xaLeJr;i!B0+3o|u?0rhSLd&Q*|YMpxLhIa2xU_%ERPLbBV1gqo_4)$Cl_ zkCy?@0>xgx2b|n_hp3Pj+9V}K#U~)o0|Jt`4ut7R6)x$T+=K)sH}c^L3LNUPf$}8m zf}Glah?n$%$n@pz9EWBpRm!52kIHLxcd6lzbc#v8QyzYjcC zt~PHFo;{H#u80&ij6-S)Sh4z_yIEPQ)2P_l+3C4%MIFAm{)yAL36Oc5gY706S4R;I_kBC-(KNRaHqV+?wpszg#wz~D33&NbuSth6Xo%an}f85nM z1c%ItkrDjHyMcjLxFSzEY6L|@kU%|zMU=P){yR3rn=FD}^B}-izy;cEH_*9O%LcQ{ zu3~DQaKwf8Tzh*FnCED0X_BiRL+ySaC2T_bQn@yk8N(2i87~n*^mTF3 zGs$_L*3o$Z@&Q~{+$7s|Fc{3&qvwf7@JLZX^i5aGJr^Z-ek2+*l(W!=W~k@y5c z0ZvdAzGU;FgiV%lVyiVH2C2HcyDKUxYG?#gmhVk&8dB9iB|#y`C%6yh5cg1Ig)vJ8 zlyurBp+>|RL$gduQc_YzhLKym;9-9_Lg_0jask2IpzRpN^CGAskUW0={CU_}zI{0` zl-jHhAOxV^di?&$aVO8Rzy|FFStqXmiE&B6aqG5-ZRX@4l#9sOFc!?%E9yj%3*n}F z?E5};1IFLqgKN+DoBJym&BNk`Xyw~km?ln9=G#e8G3pwY>K|oHMv|=S3m^!j3V0u9A$DL#7O_U7bwBjs!v}2dC4}&5<8B&e=HOc0-X-FOu1N`> z-dkP2#M168tv89l)@P@uD|tECLXR=Mo>+!!~Tkgp}e%1tyof3MABV-&gyE(KYu8ZWp zU1t3eKUQ~>A^}V)Ftr?-4qYJMn zi_3_LZhUEMPA2DP=dM8Nj5bqk9BPq#6uhaANQcl;Q8iz?ZXGeO%`lwbzc!LOmZ8mi zpH|5T@1PHtTWjT+*xd=Ct34*)Do&AMf&!~p+LxwQ9l$A%mb$Llv*BdkzmZ4MrlKTP zCZ=5wPO50?SN)84&-S-gG1w5Dq`i2&*_iAIbq-t2;X9Xt{Ak_v_32ZWD=k;uEZyT? zz)dLpgW`!6RTJ)?DKZ`d;F@1f<2#lvA71Sr_R!T<_uUxpdXdi=Z3pBFqj z(NO@Sv#-3`O`3-qweihLJ*TYDx`(!SzpUSVkknfJ@>jWz&K^nqNcXbmdSUs|nGzm& zP)PcI_dGz)z)%eT+#Ngg5_uxsJK;k;H4Q3#qt^XRJer%_HkGzkAu~`fYkSY63!K=N zj>t0dI{*QNHH`!09^#a1*JRqgYUN6f+c13G&dVD@TX43O3E=R6nHNW_)&i%1z#1_; zyy_-wT28m1lPlNk-MjbDp+o5I85tSrD?fhmit(cFl-{~<0-SUPQE%$S{|8hdq`A?cL~=0zc?e+cDFRd!q4!FMA*+|Pf$2N zYP1XAi^!qpl}RGTF$YnPbiC2a=_6*@W(7qy*VgP} zM{6hNtmO`R6DmY_DdK8d5gG>H3mnR6yXOhgB};_K;JsdBn5+aDfQ~0-&FfbM z(Y)Mc4n9fjeQzC|D|&s+&CQhwKbJBBl@NYG!O9d^_|~P5p5MLY{p?C9P}KfK#dKtm z7;8PhYz1z`8oE8SlP{PZi7nb)sSw%OW`1wJi(n@ToRWxD&`HO(AuRP!Z?_L`Ubjd4 zM{8DKr}oCxtC_GFQ2TS;caJwc`rpsi@<>pVBj`tRm+me9y$X1;Cv5!k z3~AZ@E!Z9=Xy_ELD0THF?davxODg?9O!S{pjL&V~TBePY;@48Bm0o2r!CRmxA+=Un{0z`>|peVMXri=%P+`UPnxC2wI|&xODq-g z`~Lkqj%wPoIyUe1E=AuqtPtp-3J2L?_HtS(i-AqO*6IupSkUp`OeC*!_jl@xi2qJS z9Bj4!a6y{?2N#4x4rH`NDhP}CX79IM1O8k!XSeH*L&fW(Omye#+n ztU{5dXv~EspZmE0pw;>;(J==~^p_5z4nO&K_;@^b3A1WeRjnW=mDfVZb7|CSi4!NI{;DiOXC zyxSw(A#k)Au)&=RBvv?c%kW+EaR98ybsM!-wm@W)iZh9!m^r4u&|80lh9bm37Uxsx zb6yAeya)8OcKjeomH1xH^dPQt2@>|4oj)?mQmD8n$PFEF+pE8O(8!(JxS~){SW@z^ zS4@VI+^0t&WhL@+Q&WnI;J>EeoxKq846MsSJ%r@IFj-QgedC{t)OMJ+1jAvt*^EV1 zxJe|Et+p+VqLO_0nh%Wnj3Kv%qy#Q*2jXe)>gl=n(p=gQDzlliJd8mMs>)mmoZIS3oAaorB|_!IMWO zki2;{hX;lI-ExK`a@EWOWN?k%gXQyEfI*HoQ1JyWNg!mimZ2)V%|@H_yJhXt`VgYbI0E^g_Ee(zY268HNdI4XlU zW+QE!rk4f1ErUo#W{d6EU3FHfVe0GTX6=WfJyarBem-|Z3lqiKY6qgV3sP_-I2=JLeHNj#_<1P6%j|Za9SeIwIr6Tg1vd zhA)cQ;vkz5$A|EAf1{_%ueeVW9)Eu7K0tHeT&wn!`c#`XskKFxTB8(&Sxq!DMo3;WzTT|B)WSlPjY2XXd7h*^I?m$g~5ud)mkUfxF!B_vkQ zI&Cktq-l;{n4$fbl>K~e7wdQYJr_v$)M*J@^uWNtTen8A)GC~{{tt#YNM7FFL^rCX z$>ADZx_+9R*>nx#G5WcVfBfw#5WfjGru?_iQRnsYYF}mD>&t5Ssom(9(&v1>4{fjjjm+`D05c-?;za#*Jg>%63?U zBWXB0SIqD4SDHD2r@9(+Z(!$vqUcbO5IK?fryenh_bg6#SLDX7C%P`^ml%Sb8Z`^L z(Tgf@_76Z!Jo-Ab&*dUcIcIk2Z6L9`c20lP;|k_@wz}>Gya|lVrKdg66hMkoaHX!6j_GWHlo$<49PmU z1m&qzbU~9Xyv)nx1qHnxr6Bd|^U(BL-;*?v!&LvA=G0vqr_n4i63% z0O_A1+`-f@g8ebJ8#kHvKrmlSJmE43qMP(H{jclVmTH^n$;rq0$h#zC@6emILB0h3 z<`P+ge>hdr^V5L@@nyFe=Hy_oOW@b-{zV+*&{2HIRDby1Sh19KqLaSX7R{p%?YHB< z#y>&}IEby+$lZ)^J665UM;83MuTZoHH#tJiC3ndq;tyS-)>Qk9YG@B@7jXdKJ7F32 zI+ErJ7h!ck2?$4zgB1*mb8gXQrlwa{I|Y3OrW@lc29lf} z(TaJDclw(<8-?SM!Unant7|JQKOdjkUCSMuKRJhpzDb`Y&V0H4GVcetr&b#c3`35w zjg?h66Si(J<-TMaS%h#P;CtvmF2o0{kxWT@$wT$9#1tInQX%w-U7?3rULt@5y}-Tn zY^+jnGV}37&CXYT^d;nB%>ziCWH7PFbxyOzF&7Du7>0|R{8;KH(aCQ46Pnr3)(P`G zu(|~@-mr4c@P|4__4NEAnXUdIs~Z|JSW)MPNY{77bkppSxTHf;y?Onc<~hGl6Q-GP z+_l=D*?P==_VZ_$W+mt=CPWK>$Cq>sK#(}1X_r!)6t9mP|^Aw`@jZ3wIqD`;nP~h zgEAC>O^lI^cgjaH14L1ZtBZ>G>%WAB^Os}Ey42R1)wfW7)M2n9$MDEV8coYOpUMBF zEp;O8cUvm2IZ_>6T4JKZhNuo{tA5Zncvi+<+}~y8v#~v zi+!*}u04?1y47PKSU?rsv4|9=|7wo;y$Dqq`#-eC9{18b+zk+#w|c|w>_^j4Xf1{R z!G-w3_BgkggRmuc?N;Zq220$bXzi?a0GgvtLLIpOxTcm?mGFYAgzYKF{b~1Zd4np6 zuq6;M`ZfCnM_3@aFK9QCNad&BK22x97sJ2M9fL!r$bhN=@Wei<;}80DLgD||byGVO zLxmv*9z*rCGe>%CMc$*YAbt3IVjtLj7u@l?))HDh!d#;HcmKD3TM$%VO90{V3M7a9 zrDZUS_tH5eW$x?yld!e~6AiacEnwCHP6}rQT*5+b9jPA)kuU>j*Ut2(1pY;+H7Nsz@ii*qZ8~KP=S(mprw$4E?=0paKfyeJplDZa6 zcQl1?rG7xW_wwu8 z2VV99Q7Nh`+g4Q!ICY5+Rl33m^WZ;IIx0z|2S1>*(+_n!K`x*o;7)^>-Q`$JE8_~t z5I`2JIA*W$40oWDGnwn4CSI<+ywCOuHpaAR6*&W#%;HYU9{3@&Ut^nB-TuHqf`brGUHLJ{(7 z5`Uk1%TTsOffN{_>L&V<)7rka|UI^PN-L z@u4gRQ>5#!M@MtVn)Ue=bkIh#wtJ;bzzuC`S{B@ z`@4W0t=VJM_8>`?N~`ur%uk+6!&e2+N!#}bj6W%v`q?Pur~mxAsU~< zw4q370z=+TySe=siasQMv;t=g1sX_khpz3iB!AI#i%#-1feIAjE|^n1$7mrC$2>&b zWs*wU@UbD9QTLZFvQVsPUPb`CyPeu1w9Rwo+4zlka+UrhOS0>0Cs6!67#cM7Tjm2_ zN!8h3W-h4c*HmpJ0Q%9>#?Ggm;V0t!!1={^gk!}A9+~x;2)q+Q55?Lbn3Kpdhx8iV zG{BDMTgK55foSjJUm>1EBYisvNckK2yudIJ3r?Lt4PMNL0 zifU+vK1sa>;Xc?>O-ad5E-kala!b|AwYJiVN!( z?BZ>^T@w_1O7%8O4I=q|&lXS~B>$Hy+G>j6dvU+`c|*+?!e1{g6CzrNI*L8f2*| zjMo)kv7n@4sq5c&;tI10cbtr(y~>3PDaJ(&7Lr9;qlR?inJU|Lj;`%waJ`%+D%89z z+WFpfWqviF;{OtcRp^$X<5(1 zbo2cd7H^Rl(QMP*&?V&P=kH@B|2ur4$pRdX$=%`_Uo(f9abh=(Qnm1Q=5qa?+Z~pW zWuqK0DMF^v&+EOVY2#^9;p-!D=Wz~Xqmb?ZUHGZ4o!oTLkz4F^pG;Z)MwB%=1D`(KlUsARM2B;N(oe6)s5#dy z?2z_8M~(T*EdXKan!_Z&*^HD&BbjB1of)pTgH2v_yGZViD9t@)SYp)qb?)RrYN_%2 zFM9&*6ua_=3v>lui}DLHZ8I7F`Fe+G_H4$)(R_HRed-f)^c!wB0ZC%9SEu4`MRr+j z7M)Y9`9Re-Q#re$lhzse|x(eXs^ZYXA zr~f%$x0h%snD4;2)#qKwkp|WoG`K zgPqS}SR`_I-=Tj_(=f7EJ3i7>ocJLweA86vUM7;45=C45<<{rwV1Tq-M-SeK(gp?j<+LO0&^a<2O(JCpb6Uo%>cw%+9eP~@cmjsmTI z*_t?`6Ch+P<`V=R=^5uobrREaOdfuL9$!<_Dc~XluPzKbr?=$okd^It{o1I|LeM9- z51$lDtH^9r$3(X0RYnY#;<{jev`T7i`_mX+I;Q`f%>MuSH$f9B`k@jO6L8DH z0ss$h%r7Ak(0-R@jDQVHEywk2|z%qqBPYr_~_T^&9j3)h0|naii9X6pj~ zQCK^4Xq8~q-+w2_&kw|`df#>^fvq1@Y}UPVp+v5C-t*g_@;~fU)3;W{{^e$^NIby1 zUJ=Z7aR!Xxm}kdZPR7-3Wp_GvcJQES^n+;g?JHDy*E; zJnsHw z$OE%d*2Ndxipm656Cs6}2TAjc!{0ZU;75dm1s7KrI7UUNjf3np$rr(}IMOqegBRSm z*v~(n1Z0UT4<~Fd>Q*|C+SRVCTfG_!9CLd!h#spKzw$Ezyc=TJyxDJvn8Wma4}2#m z_;KXm68T9OJhhV|J9id(X9K2zQl>E$DI4n&SIibeeGgk$qy#y>DD!YqNV*ghbS-3w zPDEsR_wS&e{)_#Fwi3SNZvqfL6E&Ky6!5(!JGR4Z%3;%Bd38hA)nQY?yjZEY;Uw!NQz^Zw@{RW3!9y@xB$Q+X zzX6AC`b!RLjIKdwU6Cz6uYedcfcy3MM+@=1WKbI)~D2!ZZwTv5r`5*~h3qKnD8NeC}rfQmO$$ zzO0Azim%C4(0}^euWx-2X`!^f3^QYB{BT{@3AZRlm7uaicN)E^Uf9ZYUYhhi>4`;ZCYz0_8*R zKl2g}l;NRprn|w*QBaWBb6J{;XR!_#!<_Oa`7fx|1$iJOHOsSDMrO(UHFf!1P+!0! zbikDSvaVdcN{p7sP_RxaFj?({(*v&&V$$Oe#|GF5ST0xl?9X^qhk=tTwQ(_wMbIwV z;s`mrr~-zs#h*@m8j8z_?^u`%mB7wCKD^ps`Hw#?;BRxE7-L21q=!O44x{K(g#$iV z=ID+As}jn|cQ8;k7WIFKD6B_j08zi2?yTcdm(sIzcAf$krj5t0ABq3iW`EMUIHMe` zhpk{E;<<#3;^bJF+hTsnEA7SmiVen>o$9kyHL&asN#s~^*o%F-+0y8@N;?RS0qOQ`m!kISKe z1Cm{>a^}n#66r2w=W}@=JepMIs{Pn%Ip|HKn&#x?iAzh*;>y1jB=`{=2Jqfg-8Hqf zV@FIZabkySrQI+v*mDX7me@&qikt`3inJGLD(HcoipF@lC|JTQk`^1V&6i>|+*8Nih5 zIvj%wCo$9;n`Dj1$k33wkO)6NlPr1rJF7J6^-LUskI~#vQdXv|6<=p`=wt?e;@)$Q zvIIExaXru0at)rG1qF|2`GL%<8aSM$q;GPXr*dYs5zm6seiaW8k8?6kCw@GrZ*wUy zu&HB!q*?!D@-84-IP_lUudBx85A-+dZkQY~RX#Z5G(|Dt$roUUw23M=qvElPeTKNQ z^RTNBf$ORaZKugP+dH+6qr*Oo$#f8LReQieTfdpt-Uw?9!hxjAotLCY8F7h)8-;!(1*v#yaLpNtKIs1wrGRGsc( zJcRv8VC2#Gr}`8I94GuOExv*miB628+8W)lFIgl`Nl79Cq~?=u+TFw!0vX|YldG_e zXm~axA`jd?#MzlV3_1;?PZcQ%0+M!^0YxX4!eHTKeWL;nkMMPq$hQMqP*1NF42fZD z<)O0!=Qb1Lde&{B?IGBA#2jn-yD<-rgQ7g)PyY2>yYvYrM<0U^i5hA^HW?DD=9Qzu zXU+8JtxSKks~zB=efXtS3lyL7(ic!Y*r^E{L=FX9a!2D0jKm-Y`e9y~;jZK>Nl732 z`)@wY-&b7>@eCT~BTPF9S(Q1`5An~Ndfy*?I}=n-kgbd8@5Si18*g;dw1RyNb>{wl z$OqVbzUaD)UgYuq@}4tUhm4iP!~QkybndViPi9f@x;s)%y|79$FrR;8eVHKl(LFeL zl2Nyl_M~>T;3bW8UeK6o=0xD%aO-Drda=$)oR3HRYI_p!L2kryK**Yczdw_4{)PWq zE5gxOWj)51B0_4Q(`NC@os* z`@Zt{JfG+H`n|q?ef{%1pS%0I?(;gY^E}SuINtB$eMne$h)$eQ>~{DB<0r39zj*`o zh7D-M!#L0?cmKtQ561<(RK#QFBc=IVL-rNmB$0Ut{daxCJW7_JFf>>}V+$Axdx^-F z!eRjO;dv)+_x0_r4OK64Zak5mZafTxG2+508o_dOh#+TBSYJABQ+zIA>Q?tRmM{N) z&1-f`>xTR|@qAyQw%)7%8TBEjvrhI0UWsRZagt%rrv=Af@FhQ&o|gGdiCZR@k~4$a zIN13KZYn!d67Po&{#2K}?`2F;7_bG`q&pQQ`mjCQemaNJ8ZX4)YISg=z6ii5gGo{nNbu`kYKb~ZNNRc}M5a5orZYr=} zWYCR;brO1N_U#~UvRn5$*4ow-9K)+Ym|RfcvNCk z25-jF?ljffwfs?>np4p6QCUB#)lZtdnr_rFNU`w70|W@jKC`CDG< zJKpQ?^(Jhq{oqShi>Y=wJg+Ke*{TmmSeKcABmn9a>!46THy$#!x_&sKF3UVa^&NXD zGlYc-39b1D>Fb>k1=^(oPb!r59$Ql`)L*oItK{}P6}=ZQ$$u^=Wpt9stc&hS&j*69 zIj1bOmD z&kT5a1{9j!!!)D1%=I9oPCz+LPf>3`k0?RB~IhJ4o`7cdBkh?niajR_(;-9jtUZslc+&`|6`i+6T0~kM&N&MIs@vBcoQh7JrDid)e1GVj8#3n!z;VlY^-nRrbf1Yofi)JdZiN&hxqiWS%&x8 z9A7J7n=Ga^^t0Oe=4Mu+j|Py!zWx_4^Ai)FHn3`OlhYt}=Q|Q|H!4M>b^3Y~XKLg8 zrc*u2RxwTAy~Dt3jBHEhyImW=_YRdUKvkAN_V~m>VqIV7A&NQX6&0PHc+EQAoI&@N zX6E$=WWG_+(sBRrS~kUVIfBDS8Y&w3{9jh3=J`xpg`%j+&um3SDSmG4bpNTM4Oy0 zlN>g?%1=5W45i%spG&M38Pn6#a=(X;p2|dEik$Xv%=-6_P$EqColv?jz5OlsHxl+p zSpO!v(*sn}FD_8MC7*2r0QcfBPKBN#+l2JAGkKylTe6NZ4m-&IYE@HHd9l#S6nNKe)W=p)y|~j(5)v? zwEz$NTJFw>t7PWokPs7WUcX*vI9g2O^J6L05F3^5UtGKR(VZcEPe!y>A!TAIm&WqK1Y z)9Lyvbpz|s|F~?EA@`S@Iv$a~z;4-d zwZT#722HcgjcwaXpoOL+maJ4@6=k{O4EK{;q^#o(QnJTUkJS*(PI4f|y z)pxET`1Kkn5pkBu^n!H^^-Xw#o(&=fZg&^4Ur>x5hemTlXfMAf;r*=Q0;+su=f5Sx zQ4M02ID#i_V@l3TJ2l&^{QAdT109_tfjy_bJrotZ1j(brl#i>5?29sLb8~Zh zS#Y-3tZ9hW@~UoI7kUPU&r<`)#zwnCivPvyMr13F zDd@_AK?7QCrr_2O>qUE#RW?t2{e;AVWq0WenvqD@52-M}eGcgEJRzRiVXHp6*`LCWboO#KUJgw%2u-kBBBR??-Q7t)V_wH&uAD|xFq%+tweofWjKG#*v zGT-+dFoZ&uXyMZPO(a8xvNUST;~p2(^$!gXgW02RKa_CvVxD~Iu0|QrNTD$EinMU0 zg4knY_k}x@ho<)}FMsd8=1Si(H#<>y`a2_kVouI!O6}&>4JUZT7+3jpt*f5zOIo8y z8NoNHN3SctYFoA^6}`}&)MFRdT|R#2dg7z^C#&gwnQo-|PYRx3WcCUt(NgIDcA1l@ zievpSF?v<}+TDA<%a=d4nGQBI3^q6q)`nHYk>0gNDXQ4mjDa7_;vYzs?B@OZDpcy+wT4KhE2 zW$!@1d3$gq8?X>+!OwKxgk4VU*=^Tu7InsXAOgPW%$f6XFZVf)8I~wH*#2HW2=-n^ z#IRx|>smBsOtxf`r~_PV>!8G%3MtD7Di%PO*WsIPvV8QxOJe!x0CyLPM}T-OthIN)LhO39!p<6rk~ici#_U; z`PKEDS=W~eQ0%YV_Erq8Lsnj;3+gfT^z=Z_)=XKg80EY}Vl^+XW=cvp`8kb5aM0+@IvQaB zH{PeLE?tsd%F$l#1tWPzImCacI+=?%-jod`ND)rXqmN$SkrG)Rq)fWuO79_DvHSJ( zr}v@sN1KGi9x>0=oJjB5Vn1kMPojMN!bW~HILPyd@S|87?ULPv1^CqG1wIuB4kBem ze|%$u?;3OzNRkejm`Jc~t5NaP(;PKN3oT#4DN!5JvufhI7e5qJtn>5hUKwA%W5-U? zZsAAFTh8=zu!-Q?{P_0nstzBRv;;Fun+eT?B_@n#5iOz4t~wp)dfnye%(8mnFqGH)C(3d$t`_aD>r*| zlwy{9a%E%>H`0^ZKb zH?JT&=(|{v9*M?z3(2g%zu^ea@9OH320RBjH)Gd{m!WHL-sf~QKpoa=!`|Z2{Cd-h z(X109)|(m~u5&wtm48I?6Wq^@aCm=TOsPdEYjpV~LzE%eFXbb8@2cidhMw#^PCK{m zVi_A%Bj33u=A%|>Etd9Zm;F08SilAg9ol}#S(_qTF^evTC;6}UxBLu$vGV1+ z9|OYakLud|IFI$Wk~du%UyiqbD`_c@YVL zltlJsC1M8CYEV0lOeUP3!inVZtE^XVcV>uY334kJ;+@lstK5M!&Bfp~eVdSa6dS_L z#epY(iR!=yc=fJdP5 zB9jVG?ZNT#sY>%55^R~SJPrgiSuch@e-d*gRwXuoG(^-IzgDC=G9%>kZy(?i4q)D* zojP((0aAv0I>hiY(&phP6e z*6O#8c~m|4!>foTzz!&s$d#3vhX+q5^IeEPmdWs|(D`a#;`F41#rtS>i3 zFlTEYk3nu}<||qpHN1QG)g!L<3wWDn9-C_+gCTY0TcWM^y~ST1%Z~6|SY1%&0y1vK zgLpn6AuNZAt&YRvZSZ@CKCeHpW3EQ6My2+U37?cytZVolU7LsI$n(&K(Z|^m* zyexb2tOxR%NYBmSKm$XR{6R~irL}cf@GSGNy$#~>1uzmCdcT=bo~cQv+{xQt^VQx) z?Ye8YV)NIo8Wn2A0V=CQuQ+=JEj+LiCBMem1KT9{_8N7~63@-C3^>!`U50sU!?7k` z(Wfgn-ngUwG~`gA>tx99kf6}p^EPUe+N-ons$=X-Lg%_J*}!-s+-PolmfLR|W0hO- zYJeQVOYzuFS$3+VedpYs62hgnr26L~9p%shXCNLkzH85hya-YJ0G3F7eZ8~e`m@{K z)}Z4V1NOlB$&g*gR(@j=bRSg6qoYhT%QQ*A1$ZmGVw6%Etr!cItgI~N9XlG1fAgV> z@SO75KUu3HU!b}(B#1V!j;7UTdl-m)yaEE!C^TUCMS8})H5^Ae&Xr>H8dTA!48PIQ z(Sco7R8YY5d7HWJs!eo*H3r`)_T*dtv2VBxjyYX7w9VHOv3dW{Mi2U82ipof*H0)Kp;-qIiF>o^vnUR zZ;)snhuR{|WNUcd^FZ~d=br7H3k{n8HGWifRmUOrJrWX8uHklA1Kf+zPqnX=#^n@L~sLQ_FF;IBpRR*|cT5SU@KP7QA5t ztoXI552(#@B)C!*+=zJ<;A*-ScYdX#8Ms5t-|vcN4bz8W0*x0*?XQoC*-_M)Q-Oe7NPHx?@ea@apF7$IqC6c|xB29EEE!<2W3ItNJ-`;t^jaWAziqyL{}cH`1Roe#QRlyIGruiG#Pm0xQ%{2`e=FRX@6Z zy~fSC&K>D9f4C#UbN{JbbHBRmH_xqm$k|}gwedtU?Fp>H9a+K|+@y2tyVzX+{mp)k zrgI88*QJlCT84z1-sk`d!*{l8gA2FZRi~dl&JzJS88|GVV>kHyL zpEr2ykT^_<2bZVhNWjVc~61gA1>lmctx8MzxDZOpSdp^AH`bVv;AT4B>v|+ z`O&8E8Z=kFBfxjvl(D_$!oNP)D$6HvicVis1PA>ljSquN?6=j~+Lgp7?|!6Nw|1^3 z9+pYVRQRqJT^Z4W5d^Y*LW(zfljqKCH~ev?-$iEjllT1T+g=IJ*xnqG`+Y_K;-yPq zkTyyb`PWTRf53irpSW#oNUr5#G_=eyy&Wiq6CSk&gGZ!+zF+O$Ro^?9km{W~0v`yRnjsoH&8t4(^cehfgM_8q zW?Jcr+VN}EYZwjT*+WrS_ij_yl4I2Z=#$-hk))L*6tJFrrTb=xvd}8jqF6545?vOF zVq71dqeeDTJ*2AJ#u1PfGL=6wCbFB(@KZo%NtWw3D5$oW- z5ifuaUO|_dSxxPhUxn@`b&&T#1)#IO5d=|7=llt`O0d{47YVs1i?8LDw098Qwa5mW zCzYBi7v|rDlkKBWx(gP;RS37{{{X^m==AwUK4et0vvNz-E7l%f4=ACxPF7$+i~HR{rc!oe42HVZHJn!^2v*L z$!N_%l;B;K*Kgc3@XK)0lryg;Uz)2nIrI7z3#c5^CurThph!%+;j(s=db!zF;1jDBh7ph$aTDy z6#~mYZprD^gB%c=vZq$l=8N3?`=C2+DuFxajF)GO5jwouVT>6tuLC%ux{8niH*5dy zkU;o+#`?kHvN~GuU)>WR`D+$Xv{<8X z>Ko!U&uAWEQB1yiBa(MO1Vlykx6%7A96595o^#ljUxsA2mJ@w3>aS#mQo>NuZ!*gC z&GG$C8J7aMYm;9?DtAY+BmQZO#1=VepzOX1E;_44jf%oNkM>**u}caSxt=M&)OFB? zQOBvicFl6@omO@@KL?=P2C`NVela7OOe=dIm7PmLbuHmOP6P=XyZ@q*JKkgWoCcrw zb43|`vHs1IE&vfyzM6Axn@!>lk-bfYN*-l$tUWhM`%OUEam~TB60I8Vi$p4f?QTR{AmEw}wjF6Hb7@^YQ{7t%FS{;Nl}(+>oQPlUiIxlUwJ~ z^(gTYJ7^=;t;I^UIIqcVX(CbOs53Q*0t?%cTT3Ix%b^3vdot0Wor4F$l$!BQNS#<@ zpRimU8;Rwu$nkralyqntMCsCc?tQU#3sOW#IUtaaX0a0W`PtOuQ+~U?vke{xoO!f0 zYk5#T#`faHVRHl#TDzj$7kofEeC!(Ov^5=mmGnxca4hgZ>>%`a@OkEIL_Y~ODlhmZ;@EDns` z)4aPcBkYHHR*hs7JRKeqa&GC?-MizJ?)y{6d7f3|ENh3^ox;8?nz_NK-viayAJ3`g z6pJ|{RuTYIr-=kWa;sHC*=+pF&iVK_Wb^Ybpzv;y<+z4Vv@s5J^M4pi~<^648`D_NuA4E4=niRbu1>Qcpqv#u^R3J%evgL)1i~K5H0WXWL zB<6^9aKG-W6+;{@{ebA}exd+n#GCT5v1Mp5XA7tg4!!XEcq&5PaQ>9!`8lfgVz@x^ zeSkWfKIM+NNv3KT$d~#i3HB!M;uVu3f^c+EstnwG*hQ`v1gV20+14_k)=%V8Y1*tg6;qHDl?B2daTt?nIN6sT#(7<<=3c!@F52D%opP z@N6r$6)>(eJoE^HS9_!Qb7o@00XspqqT8mZM|2}Z)R6XydVfM+KclkbqGa%7GtYX? zJ)ELmRboo|EG@YGjXQSRe?WZ6vj3#6ZcV;`qBy)zPob>2J*C=yY>43_F}x%|b7<&u z{QjPLuvnO7U5k76O82x1J+!=dF+C?IV&Ra!etUvvIL~#q&uj|2?{8hq;Z?tqOsmQc z$sv(XXy0MhU!N>czoSCi2?+_@{o6>oGM85(`Ec=A`P31=R|xRZo`kN6s!x?zZ(wi# zc%xVeM@@8AZtl|l;7QIcoI8n8AF32n^0U!hRhv{$pu4oUp{_3UoKR4{fYr3}ISy8e zn01rd_|fZFABIrZjh`Pmh5|RRFnnBRq}R0~DugH>ldG0I874jN?x?`KqUIZ~y*k zA)jf^bJvy#Xf07~fGcquCAxmK$cGPgk~mjs`-STrJI2Og%rZkmqV-9?BX;Yg4Fm?} zkmV?1b8!bIr=f{z8vR~R)!Ho)*E568D8_n^Q*8>Y>krtpHb`P2TGS%+j;nJsV(U}V)-?K)Wln*H*DXV8>l_tZ=D!Qfy-sTz4L|;BV;DECljK(`Bi0}Z@3{15W*&>a;iRcdM#o zv?UThbo_H+@Imd2FN9?6aG}sIkJ?r9>wGCx^lTtb3~3C2_i+%CMaWz(uhU-TQT5^+ z7|eIhnJZXuj8SbmKlSZw`EG`f(i^`km#Q9AFV#4xReEGx>%a|S=t6C$^W}FMg*zM> zC`57tfC4Hwod8C;JXlqG9=<*y^a_oANV4^~{W>ES;V&^d-v6?#izco<{(ZI6Vf9BB zm^$jvx>*(#NJB{ww;tMCvG%hfc{$2569fu)EPfWp4y2Gf(UuRuA3Bh{lauZkC`2B_-|5u?C(~m}hANrL}!D8MP=nzNoD$$Hp);A<>PKa34s3Mv zZa#O5n8cUuyEj_D?3*w(H{Zs{I3jZ+eD`*R$!EZOaSt`)5;rhK+6?XAfQ2?4zd97N zw*agP*8d?qZl>;4aXw`V>S|6`_VsxB+`8Y5!+=*vDCk{bYH_DcnIJ&H%uK#*3L(=G zouKvzq~=@+=&|s*5kX*;+Wo4>H+$O1wXJkspg8 zICqbrV9UZfUgb%zJCwZkCR>S7)ha;OBWRaYnj`b4b-=sETe8|PLc_f$t*vu9zuQ<^ zPAZQlNE~_gzxM-B3!`GPill1vt+#3!M9Dw5V_;x-gZ$O_{-+8yXiJOg{-&lT9)M$2@wkPPs$=W5#-mvJ^OHHVtoT0f;@oQ?xO(f2kbH5DBd zb;kESRftE+dIF$C0|1EGiHV8X6qS{f=x@Fm{<@n@jEj$W%-z~}%%;sv)C4VZrbj_N zbd*if1WKaXoBjK9yO1g6`pqtr753g3ix{>{P+<`yHB2#g7j6d zJ-~G#5;~F3rHe1`oT{w8(c5%0smE6P!b}Z-vdGIwTn6PKigx?-1cvg@AmY5G#%+Sr zzp0Koeefw)c7J`8a*^fM<%@dFWx~VRERw|Fuoj!B;k&e4<54(t^G-|FPT$_X0yF7b zu7fv!7`#d_UAuiVG9ag#z1d6nC3w%#%~D*h@@~0=mD2PHt$HVKzW;dg$C+nxPCs(0 zpP2P3QZL2zeXy-;P-IJ~kj$8EiWSJ; zw_k|c?I+*6Q+c&kQWD3bzBhbTZEwfxK6#CYD)#Mr%uBP zWfck*po2ifV{C^zEdP#k6k3S$e5~$y_j)6$*YtAvy*g*IW|`s3hk%u*?^nEWKj-7u z_)i0cTS8Wb_ZWuYIlshJL6mT-WdyxL4h){-Rp4X!u1Kub=UYyp6rm;!%VK7xoZC6CqdR7;}!3Ro3rPywgJHoSBZxxn!A zb$QNpybo$3WTzVTx8(m=@L?1<^&>1{QPDwiB>OSaisflM1kd-Fct)*Ji@L^IiTDSF zTT%?}L{ zBd5c}IA<5lGf5|tajHY5skymF1ceNXA0orp+r?6Pom>0;xmy!Z*h+ePPfCOF?yZF0 zg`nOEx=F8tPCH|6NIxl}Ia$XXWivfr_MM5w)jptC;ZUe$axh-;owdwGH{?||9j_Us z%fGHa>h)|cA~x>gWPdH962ZNDBX7$oV>2PGr zi=X*jkX6ljWJs0qAb=GuPxqD}>n&8FYx1;tSnkesGPoE71cCxH9M zMD%^{N)s9owMdWn&(+qC6HRC`BPySZ&Q`nqnH)t-OhdMj*X*=GFflK4-}@_xCOBEI zaHdj+(?8ke?R#cXirR5?vRSbA!WeD7fvY3f^WQtU4&Gtyw)w^TAkL%%izZJ|N#)t= z*qwGrkh}^SZlWw%riAvAq|;8zL-8FA!x8>RC8$ci&&KbmVG~Yhb9~K4%W$)hb~64` zz{J_(Yrht5xx2FCwEnCa=NIYKnSx-kf554~l#x@3AU`7_DL-E)KIM{F>%}|XRSRQf zO-<>2X43Z@IxGgMI`WNy3&P*ew>39Ua}jGD5Bnvh>CM{Z$XKN!F0^31{qBEv$vGqA zt4WSM&aZcNiYWf(R_gudG0$5OkNM?S&7fJ8AP3!~N91niS#{kjA5F_G>4 znPc^p-2+8triaWEf@wq_ZSdF4>q4tP4jR~q0YD!R9D0B8A)*V^&Y@GleD>qFq2iXQ zuMQN?5AK{vAXU-4fF3@>+w^(FxcwsFv$QjRs$JNXR=s%)XfH=>Q~;Gi;3ZSp0AkH| zkf}Ece=oAj&AZG#^G>kOBjJ@?QN!2Cvh!OW-S*)5Y?D|>C09JY*FETxk@yZu$$WRl z14nGz<|VIJVS8D&kAI~+B;Lr$ckq%(PXX)dZjVLTyKIcj4IzDv0{t1C4m-NX1!w~E59Ly-(Xb6YJV!=pb#<~ z5u16RPzjBUjD(;m6O9ef8^DEi&tNG`wfESP#3AG;8A_;K(9n|flMyF4%c9_=Ak)?I5D3ycA~6Iw z;un?Er2EgpPgdw&8D&`Y;lOqL%v2K#RDA8`zK;99G~fA^Ho&3<@PET5590Tk%z9| z>)^G&M+l#6_cxlp!t+a47dL^Ylxcmahpzm3o+`0t$PIGy6<@B$YX!s}J3~XsEW{m%=9u%TX=%#i``9k`A3a#&UH?pOdF~y5 zZZV+(<+9;+{IxO3?O%xwa#xa@32#3QPh|btpm|)*E^lc+@sH04ttWxsIwww~Ii4y&ZsA(*qG{hU2mg%2Io~h$U0+Ur@?-d5ELghM z7^U{$;}BJp9TpD)u=xRM6GH$~18yq{8I&c|cik+z&YiZlDCo~HD1WhLJ$T5845o$(o z(b0|il7JWc5I@mMyZvXtOZiS2vT?>v40~5^1z?5NxW}tWJ~=H z>>=BcCAc9bCdPdx%Xk2VCLhrTN@EcYd{Sm+W@V+3_|Q4e6J0bqK3YlM6E}6u!}b+K z0CQ(#U_h{Y%0+%$DCH)ouj)p7czOM_j~%#ArX#r8Hm8yG>+z5$TVA@f6WWkCv=hL5 ziK^!c5tMPyKOGpOdTU-p z1fOf#1vh?&yoZ=hIfxD#Dno8-Z-p*YxjeB3?TDBZoX)!=VhP*3T0M%0;<4%p4WFJ2 z&+pKcuz;wU$Q>?jq8u#iPH}mJKwE2TX}8S`%SIW}*=OBPLoP96QKf9^ym>!Ib#wXR zWIX}4TnWDtbtR@J2#fG*{XGxhhU5~E6prW>zTCSf?s$os;K+m%I-m-}6&xxTwm(0A3bEx^+j_GwX^c9r;%5iqY`q7y$yXAuB=^}8$s027fJDSf z3WnAgD+3IN%j?#E)wR*77nhKzf1H<>M^Ial#6fB`fr^uQdoIxu2cqVj&0LcM+7*XS ze=&|kmd5OC{f|fmmK=}H15A#qZ#{BGgdV*963fj(lS&?4J-yn5vaW4$>U&27i@Jzo zy?D(Hdr&T_w)5!>s`KpC&o_lZ+599X;9@k?zV9@{6CPsTk^$n#B5<$@mvd+I9Skij zGB%#y-tcIh`vr}Rm5h&m5=ZLaj8DGL{hZkzx|BSk_q)vo7e*=7Va3!JFJTY*Sm^^Z zyDG(RsDr&_ZEbC4mYV6A%DU`x5kN-ZixlZ$<}ETJhGva*jS&?Y|{E=Aza%G=cB6a>30l{9mpXs%sZt!NwXAno;i7vN6%JIFJihc zVJi(v0HdN^F>y0AzAW2wMJ}3st0P686Y!SYR-Le3r+?+XU%#n_{Jrm6+?Uts?|mPV z7fQu+v8k~k`=dg}vhwnx+!y(i&Y{$dHf%E8R(`t1E<%C-@JXtNekSE2FZddsMG-ZksLHNU}_NE!E*?f1g=x!LGy*bQtxcM_G|m z7g+cm^`J#GgOazWUx1v8G;pmm_}|Y}AFlp$A65v`me#2doayA)ATN4bKGxdp1Lb4~ z=S^vkcMJdXKsn(N5w!zE1`E_UbfPWra8{1wX6XH*6(|j>2vTvqAIi_6M6{hsTtSyz zOnA~-Y5jxjY=PQM=+j>J_HCev?4)2%^X*IIZIUOIm2bvH<-g(n&;7ww4v)T4VrX!7 zGwOHkP7`w4XB@k)BGn&S%PG}^u9{mPs3|en!tmHbl<(ZR`~9kFwfV{{W_N|pvXTY+ zOHtRX_J@(=@EG!V5!{MKMn(|Q5^FQ0i*QZxmxu_;t(+e&KQXLGR+h|L(hX+oPhMGh zeB2@Qptz=Akh`67_QU4&Wtr*ejn5hEL?^XrEw0I;bzBoZWdFl%YAqy1zcTkW?<1Dhd8x9rrvcc@~mkEEBHEKKnLRUR@jc{Lp-@fg0oA!zTe9 zO)s1=3SqF#yoA@&1u100%fP=gX9OQuSz2}=tA(QkIc|O$$PBARl1Q~{Ajuw5e(cz> z9}WB8&Aw4txw;I+KyFj-k;UydBr97yb=<|FbgYCzO-)A^G8jMEV~vq+E(#Y2$bU0H zo-s^lf5|~LT#W^`sC2Fnvs%i$?fRYIgaNw~)`*D&DovLfU`;I2V zvyMhp76~zA9e*wy)iSmzx`qvZj$6aNotv8M%s(?mFBvF#oNsbx|J|A?;XF!G$~pi> zpt5h;&w96Bd~$0dMzo1%_Zeej4-~%M(2T4!i=EhfMAB3X;j2xS&-G#OGV^`PAL8 zRND#Vb}EwZW_w~Q?CJFUl-}hTe)dS@;Fo}W8q$`d*Zn2x#MuD4vgyrkvqcf{5vzMW z1?A;&qSUym_lq@JAxt`TS{H=`c>+lDq&GPdSvB{@mQyPbeRlJc>q1i0Nb;`HQ}3}$ zxmeGj?=VaUm zBW0CzYjbljHwEePVcAsz_sOeuLO7qHa!D;s0OH$OSz$F%uW#O@YT_iZ#n-6F&l00~ z0$xmQII_-CK~qlB#8Bce(0$q^6ud-Z*U%LN*W^$PWj5m34<{)edbv^(Ob1nMzT;pU z>h+S?E)mSO7a=%|Nj?F8|7xn97@*rO4%(H!M4}*mEt>c>r8LTpLlM?fgKwr>DkfDY zs1!l9{Bt`~bvBd1d@VxK)-=FWqEesYq5r@BCW4m>2gFcc4mGFuTw^8Au9;g$P)>rA zYQp6yS4CL+^YvhH$ofmLxncq}u`~SHkFPqhMyN9!A?vYnibxQqS02n?(~q9VtOdef zP!64@q3}6g$a~_pg!86J&6Lzi3RRkaT`#hP?iyU%VcNBNe`vR03N85`#a>76xe z)+n;;Z2#{lJe>w2PC_9eB0gRgm`zmuz%Q-?S!S`cDNbRJYf5fz+Qs)39Z}gghJ5+g ze9-guz@$L65;7M*076*^RV$q+k^{%R!>)#GuHGv6XoA42qoIu@V!x18-gdd z2^k@08Q(g5vT9xrxdSdC^(PJx=T$T;uiv%a}hItk1ES)?^QpbmUf?qkJJmUWlB0AYW0{dXfd8(8&DIN z9_#L$-H;C`7zh;XNhM;(4;?>aVn_K^n1oGU1W5Gkd9cr@9ULNrQz28sN7tyzg!*xA zq2+HI;xtp@4s{U`AabVr+u>7YOz>OkHDs_gL2864B5mBOKx;dY_o+O4h^2B=8HYJ^2%8#r;`C9@ebiOnIsi$q$dP?r<@=fBfd z{#(%LkF9~zL?S(-P5)!5K!_xfKEwE+eIR=fI;C5|4*YYIhffX5yTL!vDGY!)$rRIj zykf?D@B}2QJ702OK=_K#0aQO&nlA|WQn)qA^Hd^vHR-8{UO5^GD)SW)yd0!3L(>WK zaf~p6*KxI{s_HrLi4SIU;mjNv9_I9}JAe4_YT}2t5u^2O1i>ejoRyK$?i}~J?>=Ev zR}n+q+L3Q|Th|6e(~H9Y`cx;P6LeER*d#^fm9HgX5HC<>K_YDvm5^YruZ)Ow<|mP~ zvF1pgYj7-xtBd83!`8IVC#2z`%`4vo`5isG(kwMERl;$= zDC32yN>l!nHq^C3=fwi&xwW>!D#mwVQ}Qgre3X8B;S?S z&5p(uf)Smd^XJ%-NNgR%unT{H_m0c2Y3P)|4?vy)+}q0Po|FVIayHPir#k)A^|NeEwN#B zz-gh0BN#MKbuG+2vWG>^-BmdYI|pfkk*Kw#v-|Ooo|J%B-=K08`NrwT9?R}RwC6ym zCnjZswyti$`PZ9%vr~{piDkFtBtcGqn*m)TsIdL|-uZx$&bJH<<;^=p)BoV&765cD zEJ7mY%~q2*5onOua#JqV*VLTKH}x};XSu-XMWyg?zra{8WK^?LfXQ^62t>dh~nZ?LOafGhFWA; zsS7Hg=xs@7Q6)w4JaAXkLdVF6CBgdfV;B&$yG6XKT~6WIO>E{b=MX&OhX9?s#ACAL zBAPE7E7cI9KP!iv01~+Tf`U2F^TqKjx523$qlafi+G4M>8LX9Ml*l$`QGR?^7r~F; zM1-sh7y0<{K8G@NHJ;&LPx6%_-fjbQfYpT`I($D}p>7upI@>r;oSj$UB)UqCHQx6= z?GBw2pyW;f^L8Gv`xKkABv+;4yIw;j(o$=0DLOv2>9Rx(m z{nE3UHy9a|FB4xUZ0avo;cJ+&7)Crb)Y$uUAd{-X%+zA`F<-25EoiL36 z*gz4KNRI%qbvqhy!D%JxV5G*1`+%4B^rhCIf2#8{{6~26jCWe z{>Ll}jjpw|KRc>aVIMyQ9U8lz(R|>i$LZh5j7Lt6+IlR+p4QjZy#k5=@>R!%!$6Tk zUy^GER!p@VkWZHd+dn(R%NmLqmXfel7ul{RjuvBjh`PO4ajl$RIb8)&DNvh6`l%7x zr;xqaj7%xE_$zLu_}ZeX-`0BUb&n&SHC$V~L-gW$uset-fH|EJn0>Epod4|LjC+E2 z?{Qx!@y%(;0i{SwO9Sz!*O;#{&>g3=rwnmao9vCNL)y}<|EiFZneY)9m z*tDYuhf+`ku3=`DEh@(~r*%|jM)!$`SDj!ZF`F$)L?aDL^jqH1Yg{)T2sYQh2K1eP zwAXXas!P5_mdP#esD6?q!&JV2PgSz>0M1|j?U~On>#U6j1owLL6syj9^9vX1Tk&ui z+2!{GFJ+K7Oz&Kbe^zwc)q}T6is}&T@=xN}@h!3AE5clkyMC2=m1XMxGsfUY)Z2!7 zkL5ut8=Oe8NdK7Y8c+3|M*pL+rj0)M?>x`p-&*EL$f7vQRXE;4OTX%dzKy-}XHGl)}f7g>pjmj(U0Nku1`qcz+ zCCevTEu-$ucLxn?ffc5HUhx-y$XpEzW~XOlgxr1tyYOwvj6}M~v0`%3SMvh;$rH4y zKbN8l{8i}BT7dfuriHl6^fyFox{ zdMd0nm-i%QC%|pEDQF&W0aM8ak4%&RX1lpn7z+J9y^8b&{8-W!IV^^nw{Ka5O%%_c zPd1WZyAO#kUbD_!j$NP0B`M}%by~wk|KJ72swDX?!mfO=L_Qyt5O3bS1HyFANQP}I zNa#sM)@7e>G7~*Z2{6EbYv7$%WaPHre1CuKB!(tbwMdjyrRp*v$APrYwEC)vNjN~j zrX7eRy&%CQ)hiUV9UzxjT3LYu>tdDV&VaBOWr8H%EZi{Y^%QmuIuSiiOq93031tN^ zqam#^36-Ibak?Nb3Z(`jpdHnk*N^{+&Rls01G)Fi%uvI9fPTu$%SB(DL`DlL7cdO`VzJ?t!;h_XN@~ehuRbx{ zRiaEzb*iQzUGgGk(suAm4nRM?TVRzbp~dW}ho2zr5OYtO`$*g#u14szPSgDS34Rv( zXq>9x*QuyUtI-R#+I`XoiHJ+Y5gJTVo@hlMR|5kBP<@SlhJ5*awDvq!Jbp2`a(9Mm zg2p?I<@*26MNFAa2>ro2L*Edb0hyWV{OWmFT|Ql9xTa(q zS!quv>FG`4NTcQ$P=JQ!@#A6rEE(IuCrovkwVEV+I9(fLyH)v`zBWxYEt47gPuDOI zp#U@C7js5u_9C=Oz4XILS}N={=EcSc;P#?#C7*u@``QmC=PL zB=aAi*mn!znxMKF5y=1T|I+H0%nW__NB$Arh-?^qBd43EoRmth#4|6)W2|_Yz2lUokq*-1q`bW z`U|P#Yb$62iS*)TvzCsG8qE`EbPNufR}|;JJv6}mAl&6qW#v*Hh7v)DtN$I!;bHEK z_>`OQqTxorzs)})0O*IePG5%Q-4Wu}|D9A4X$!NCgxUmh^seBFUo zmGqa8J=hziu??wO;D2H0F6&S>gE;Ra5gb0PB^wZE=0GbnJe_wQyprCtjzsEA#_BoH zPE6ZrL~0sVNRITQER|&-{jREwVk#<{+mrQKd zPnyPVGkVB1KrRsusxvr!#LEE*-L&FTizA8j^wr9*OcRw3s3|Aldx!_lpw4?4G%eyt zP|=SR%Qq@iXLiFaS#84HrVDO2LvNa?#Gb$RD!{y2`J%1iC}K(_xLdzUUD z6Y-f?5J&7ldL*jfUj-rhJ3tV1$!`=3G2Rasg&?C^)*Df0{g0T$;K3~7EKy=qYDI!Dw#5=)T~@&cM`@!xSJx)t>!-WvmsCf_T_J942R`rMLDElL=#uU@MI zgK-H3#F+2ODWaW*Er54qD6_Xq*cbvlEtxp#G5-N_Ek(oz@BE+Dft1`1t4cuXI8TtK z@0P(-6D#C&)lr?u2by>DEnE27Eel*R?Qg+skE%zpE9s#i@hFGOC+qkza!hfs^8g5D zGmx`nU}ThobPs0lRI%OtIjzt`9YihW4%LBI65*u(409*AQGnYQ(KZM9UDbMI0nt6! z-`{_7l5D;P_F@~c{v}grVMoHgPf^jY+3a(R{VUQ0K8QodoG=A@SA% z^Wi(AjQSoD8-wr4=R$L^IM6aDk*^cwBh9qnp%Z;KFunf%>j__ls~&4Kzij7=k(uFJ$QWK;`CWJd zUnZPDeJ8{vc$>gsLFS-h8c5AzYf&Xv5Tq($9T63kC83s?PdE_{;oZ(~ zEY3pkgG5r9aH&9c3p+a-h_t%q@FU#U>~%(4EB*OY(PL(@qwG?3W96SP?<*Gn1Jg@` ze*kwEYc0M4xw|z%`8wiit1Y+#cssF$h?iu?rdRI#9}xW{WHNCIGIS(p^{eRf#->~s z4SR)L<9`-ISo2xzCHQU_L-@075L5UHs$%~C?kS>IB?dRjdT_$Y;m;SeA0x38gvEz{ iqlC-(|KfkgmRHFcek?lEk|09dPfh8FV(y`{UjGNw@QG0X diff --git a/planning/behavior_path_planner/image/side_shift_fig1.png b/planning/behavior_path_planner/image/side_shift_fig1.png deleted file mode 100644 index e851e84ffb5555ede034d64ead6addd3f0d03e3b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 25998 zcmeFZby!s07X}J~fQYnoBO%f?G$P&7NOuk0jevwSB3;tb-JJu{-Cfc{H{1i?_x%-~>XZ)|MsU}ocZ1lKA6 zT*PLstnMgmZ>;ZVZevZRY;I)?d%FN2LSzpD>wUrXg3fhX#A!Fg%O7vr6-3$(7 z25sm4@X9{xf`K7}krWY9c1_t|w6fKj_S(Ka;=a6K`)d6H{uSmsQAM<$8@*^%#+u00 z6>C2YJ@}WpO1Qq0uBkUVo76hfX;v#WR;rvD)Y4T}b5wE|@+KO^C@V@@(4EXg@Hz8E z7?VlT4&wwChMIfMTT1Yk0@QF1b!H zU=4V>RMnVeS2(kZ9Vxz8Xo;d1Y`@qJBH%Bpl zei8l2SfWWz{(LBfu7xr=KZz#p|B7hdkbGI+$xAS4v-^pQAQffIv3srtU_1=gA}bTN%xhyl6Grsjudm`8 z2zE;=<74=JMWznuYbTP) z%&{L>StjiBmMB@nEANuvg7UlHGvjE^NR z#*b9OFGA(hdb_X)?|!dtqp(2jMR{Qup2pE=VL0Q-8z`sADC&tgjY9%+sLfHvIgugC z(yi)8?3Ly$Vmy6@x+#`2@;chtsm4tRtjAEy8$(oVoU6ab1mZy)37?-KvoZO(jj|%5 z{L3&JQ(%*4ef#WpI<|INyAkmXPgX93HZEI9_4Q`N-47S5YMwQG4Ly)Iwz6gU8y<|g z`u;{rxHR+l$=@ib@wp9Uz+LiMh(}Py4p;H0oz7}TLsHO>gX4Zm*QU<3cJZzu!zS?g z;!1dTf?mB%54D%Y&*Maja)$&H27LYv0~r&&>u&s*eZdGdc+iJQ-kO|A5R5bmeFHmF z-1yx^ZNc3@$(N-|_fBmOkdymAXg7Kb_!Ht>oYhiqqLaw&7dZapNi41wcw^|I^m)9* z8R4%qI*l||`*z1vd)EGJlgC1G5zBU9J)4Ow%WO!(cX-uvvi?Kx%Ge6#k@H) ze&fr5a*3ENEUY^<692|^RWbDux{;GD-vjlzpG!r#V9*^a2S4tqc`iNZ>=R7}=3!7R z+lZtwdHY0vP~)?_#kyJC)Ss=4t5H>l1a=Sk@JM450a+e;s;YwaChkb`~3@L69@ zSdn(a)gH$>aG>hCrlq&i{Hkh)q5j8bevyQYl#phqxI0`nbl8C^(Keh=tsSmvaE|@JJWg!rr{o#^=3}?)wcNZ?&C< z8xQx)a_l4&l%I7+dd}m+R*3xJGvmQ43r7CS_w#PlJwtlXgoQ&RBRQ?kD(={q$`ityJ**g zh`U6iRSf@Fu`J-wU$7fq`M1iSo@l`aAD6tE*^H(;P@q|YBj#|_`mn%^V4E_D`weU%}!}JpObjm ztGox~qqrJyOxN;7GS^x3E!2+HxL*`6*~I7w$)=URKO-ZmrD$_wmgn)BbV$exHRiBW zoI@r-^O)y5FEWp2sLQCm-IknPOpd~52A>O;_^T1P+bd|}a&PPXoV4dk+Iy0gemxIM z4%UB`V-1+di#zD2Hnh?+jC#D}_iMYS3BTSRR*C1!@K5YJcb&L=RZ zhlQ{pkgB*noS_V-%ld*(ZkJOwzMDE=SHOCN#alwx8IhQ>*d07iEz11Pb!JAn5d3-N3X0fB z^GFRzWTKd&j)2Yvp26SWIdBZ=hrV6ajcR0k&~vMjE_AJkjQ684t%UDcm#oNv5yyt~ zS$yeX^tv*6shiqy5otgF;MMdf`|=|0lb952cM4V6GzmlHXBW@AOS$zwxXks7SHA;g z-_|&<6u-o(i71v8!>sP8()FAdXt}$`N6sC1JYJTubFCFSe&XJsqnfr+kUiE%2aU5MtMS+jK1MAX&JFg99>$q-&oryqzB%MjkfzGzh0LNmJ` zu|q0E;k55{nm%7D6Go^}Qw$A?uy6*L@^LDyJwC*ekNM6rPwY&@mp2{i zeJ5>YpPtK`hjOcJ5{*dY+F#>gWyim$emp~4U+~h4Qo>F0e1O2+*&NZ@G!y@WP~wlU zzRjb44w>%6a3D=*-T8QHFX?IdtNQ_JE- ziD#&xlpE)dX=usHgX9k?7X59xy$*vQ4%Uk(@AK2KHl8skIU$g7|LSU&qP06h9WkWQ zdh=26@x(Z^RHuC-&~C7MiZ*T19~Oj9RDE;cW$1<+|BBnmjzqV9zyS-ciR-WqEFv2J z557voo+gQl^SWuXg#WHnUPn$faE>;?EbjebeQJBh){CIFq#O;NGQbOcp<7vC(FX7A z*-lRH2`-nIz_Ld#2?q zF1eA5CEy5!uc3{wzgD;8R8!OQp&4-(PF1c51?XcP_U z-^m+pOH}pp6IydU^RGLi+`J_aQMK%&4dA?YZ zBb#VJqMU$Dwnk*mD?&*wBTilw`R8fr0RFimi-D6q?W;v+t!hC7=W+r~<6aFzt(q0j z+Ml;F&bH=rDz#mcUkqwpq$#7tq>9(Z8KqRWL+BEeAGgvL>TQ=Bq<`lfD-@sGMulyd z^Dy!?#(Q|{uQlA#fg)(~+zASV`fNq>;l4z*!CSviV1qCn7*Pr_(%IB37nhEJ}z6}^>!<0 z%3H7~$mj!iMJ&;^2IdVgiHcbIovkVHKi{ADXP^CP5+Bqk5kg^?ug$H-hwBZGreeZy zdw6n5ouc0;y6Tnea#mx`Som@nAvgY3$@_sArY}pJs@AP%xjoq2$=cQ7D4}0w=RX&9 zK=wz3-slhgK3(Z`S~z`uH{W%@i~CLQo2}a&rc3a|a|+PQgAMJCmZHay?558 zV%%)~i!$fzpnWogf&jY7PqC6E^!zFLMmyK^BV(vMzuBU*Wp`)v1%Z{ZCivj1WpN|gidi49c}Wo!oPUL6Td&K zM4wNda_n9c#N29RLDtU9B%8Oc2X9UoP$?$h{Tl7o3eq>#4t@#v_n%mz~X{>9+jJTk(k$qKh#=21D z^rH2=xZ4#tBs2sg(mz!$LVP>Fy}XQ@sbbi&m!l|}*xY!}-pHTkVGNS8t2t*ZN8Q$= zIFr3Xy35SFaD;PtuVX#_v5blAa%j`3cQGvMX4)y3x1%bI{JsG@f4X|k(mivWCH$zk zfN8?CH?5bxS?QK;B0V1~{m^XO!*4Ze!GmWm#bM&1CZg1_Dv>k$5Ji&ICcu_O1eao0 zzQlsfrniYf)|HHVs$|#vp-$4#Vskk3{g;!YKF0IGL0$_VHOR1Y6+VIAJpC*p?@;@< ztc!3Jj#B%;vt-3=Ya8OohCH_d$y4#dIU;7G<;3=j>Y;YOyo*$xLwkr@EqVlk(QLe%G(V(%VMc}YuuOz3maFR~&en4X=^$y!pM3J3A zXyenM_)7oAxx|Euo=EUn{j;gnm_>t+EnFYfkqS9A?VT^aX z-i%kPN|egsa{PhzXPt$cyD#81E+Dsgn^v!# zIWRjxil9$gef=hQ7*9Ckv-1qgrbnwSp1Qg7mK&bBXseE`rN@$Uoe4MM;9yG;*hr+PKSr|?dU0y?H?igO+dmpH z#`D8iij!#~FCTJMaYEG6(B*a{QFRwpH{%W`$YW5vlJLf@(cA<@;T zPi6UtSL#Z_(lw5%c4)>1*WMBf@kanhinsbk3_x6MU+iqI%Si{k7+0ILk#cq56Ud@2_V*>e~5`$74Zy7v4g4r$=ybzJei3YujCF z<$i+$Zucw&oLb049sxZgV~M8)Q7IA>w{%OZC1Z7 zpbo=^kj$CjyUFRbaqK{H#Is~k+`fUr*}9Nh>Y?SP0>#jXgn6V87}I%08bujuBjukskkpJ8@Wni@gv;>tvP z#^6nM`-Ka<^x(TN&2f`<`taV4+BvNwqM!SJPIa8G#31Dy2r(w+*>9`hKDHV(kaBWA zP*1y|l5t>+fq2{6?qIsFDP~O~EIC72`kaTj3Br4llGi3P#CR=t?wF?Vgy~{6ZeDxd zQWvnHnAyY+n#6bbUxXj*Ca(?F;0Labg}d+){Z=gm&&lMCe_ORjS~O#yvZ_3Fbv??T zwD@5CaSr5}3Q8KPcbeblBZ*r0>k{Gp<;Yd*fCygbBWLm=)V0W(4M6+$FJjdy8?AZJ zO`%N}Xx?P|*lhW?OT-26$UY-ZONZvumK)b17t}Q_o!Y_4?R$%DviSaDuA_5zFQsk0 z!tF&3Y3i6ScEpw!u0;ZfQyP9`>UPAyQ!LNt3a9tLCH|AsOOta81KczF)zeEQl{U%s zOT6=1T3QpYdXgQ1;os0vY(BeAN5L~)zp1J0`Qn0b1SadoTIt0 zF(CM4F2tI;V>eI+`Al=71I%bf@T~Cozz>=3KIMv^xy~$H{JkalLLIbPc9ag2C0`m> zqi!zV=xxhRP1Z=~jqgQ7%t$34ynjnLE0cUc_!zDZ22F155~dX%?1`nq>5Xrb#q<^7 z6PL$w&V#-Z5=ZWtJFr0v*#NR165>Ug?G5KUTI4}YZoc4bK;@jLwtR412m_b$8(Z7i zMbFO8=DZg<@LK$R>YcUx$a%{)8_o&xK;;|`qW~xgJ&_?oroTkP(}0`m+O8+l-l$@a33M-YX3@7GGBu`CO5GI5n@H zT_feu#* zr@rjrqw*G`KFOrA58#q;G5`K}CI<+y%X97Bp4id!9k1p>+e-d4c;>8!Jn}oZYsjX4 z#J&eqXbn5dD;=j$0Ul>8(a5@i$%8=9 z5|acO8|oOsZ#{;Q`kkzyoIEq#ZsIWm*1R(7McP{wdhCASrN!lrN~jq!PKA&cG{eCy z;jJLbESg=bQm8^rO&w>UE-Nq3#>F*rVEsL~mwIPN!kHbc(XA!ZR;@PjLgs5BlWh(W zo8rP;j)R$6o5T8IdRikD~xJ#nq_O8MEpVL%ZS8P zbCbZlRlINKQDYNijV1{ADMas-S}&9_F`^H$XDwMdI7G8X+cc!HMP+1V->+a`?2td@ zWv}6+>k)*k(WkYVwyLNMU&th^)xQpBK;)}EKy|au{{$T@{^DSTKsu>2iIf(zO*m4d z=OBFL>b_26nfQ`OzEx{8`ZB1ku$1_nJ)1~kaNj+a%%OZ-^$^1rtsE7lr_^{O66JmT z2a0($Aeb7>a^_k7ghB3?cMwbx`l}x z?5G>2#HJk~ONY}-uuy>)gd_2b8f{p-@;Q8!yQ74J>TaZlGMI;Y!X~&h_;?W@&$M1= z1qS7OoPsb?sohKLty@~z1B2-^vYc7WseJFqU`w=v*fbLp6IH%ka}5fLW>KIlVZzld^9LtxuUZur3Lb{Q7sGb%Jwe~U>y&QxcFnZ z#OoR5eSRFlf(MQ{mQ~JI_8vhv0xpwI7k90J%D_bx!_y9Nv(VFw;J(N=W7uuC(EHSWKd`a} znKFgLb!u9aCR8SL=rp+`B&+;%jq%em@9)lJk^{x4RQh4N2ED5NtW|UWI-BJk*p5&} zk36F7TQRJVz;#M6oS=h=wAb6&xS~8hE_pZGwAU$}uENV&f^cl2&V%~~dbtvKd#z>| zZdUBcvOPULQ+!LmL3o6O>%GyG8XcM<*@%BrHJtfKr+50dK=sH!+oy9A3wc87i)BlD zFVK`U6XwPoY_QjfZFnorUz9P0gN{o$R0bhkblsfr>`RTo4mOgho{KKmKm;6$)ttrky_Zwv1`F3 z-T3%85R2!9He;vs`nvzu3xE+l_!$;v_Sj-llu=F`U4^r{xtzT96ja$|4KCEbKhZ?K z`m@Qve;H`!*ujy{F&zF9?MBn26Qt_qdg8EI`CCd`zDQ^pJM_0k* z*6&Ck2wvu`Bh&>yESMvR6=?33O31T*e$QyX0~Jm47>~Rj8s_g76u4p^UcM!YN7XXO zu*qn2niJiK8@1%bCneRzI;;{^=!*TI)-VE83F>uj9DeP)-m)p(ZH|+yCl%ZJf#uVY zPw!SH@C%OKkH*j55v%U=h0n0@;H_nCDPrg!#qa$odT3Bmw5?lQ`eVDZJN)Iy$yFv{ zePm>c@iCqeWEb0KL>GHmJjz?_T~7^A>1nW7R^Qgqr)dQK79P>4KIpOldwcZjpg59J zIc5C9u$c5AmXnj-I301OPsWSjte**-3N3Ib*X=O8*3exT5+E#fX-tf~oWd*ugXh@yZEq#=^nqDi?_ z6cvLz+8WMHyg`No(j-B?b13ldJrlrQpjSjZd1Q&qp_)Y7jZCWCb}kXW&ZkReJPZ&g z15Gowesl7L(_YukK?hU}yd7KGBN;iF^XXeS!_iLhrs0W}zPV!Qd47ZFnT0#EP+yZ& zJyg`t!5=fu2C?)HgMCU*o$&lwU`rIJX~XElKQ=7!07|yThbDB8cxrX#-o!=9Mrl`{ zJMA~}8~4-n_eLHr4vK>7o0Yfuui>C4C%Fy|4g*Ya?+1T!ot%vB?LHP4>6AKb4d7Fo zQgc5{*xA=Fj9nTKu7488X1DXDL8dey#LA;sBcnz&%p{{grqIH}n#IHI=@OE`7Ncj! zfep``lWRI3KpSKcWQR~O!bDkQ_r|{7z;(dJxuvB)Q&6XkvdC>%(8QRHSmWy9hP3-5 z!a|oSfsAxvfym=xpFE~-rI{wC4;@nef&?SlO73W^Vx4$?eFtQ`#Y!a;)d9kZ>kP!1 zmdUkY2w>vuKJvMK*ZO$A!L4^}M@%}&tdG+KH{Iod#?@xv39pYD*1Zu3Q_0@ZLtxud z?OFetS>Ou+pFVR>jTp4(uL^6*oTy~EAxKNa&xba2O_zz?u0I`_$Sync4ra7Wl}X7#3(iMqRmHor@oJkzBz2R zRApPt=4S7|8`%$mbc#uMXGD1_pKN>pikf`&QipUNn9-?ZNH0RVDZIS;NWq!329}m# zQaK$~wToi;$}fHhGQVE{>TwTeatypWG(+eeOg$mNs`I`k3 zCmaQd8_Vu3V*F|z;qD)-6nG50Z6mJR>p7PD=}r37PK-W$L7o(_59J=4M5za&lS1Y6 z-eN|S&KxK;(u)q}E<9nLRO*=78$T2Zij%pgO-w%5uG0gy*C|O1Ye~j1O`$xyOGQLE z1~TBcv{*Hy>Pd3dHDQY~W;~sA%`wRj98`j|6+Z8&20wT=lC_FzTdr zH3mO!@;Blgwz@C=nsJlU{qDLpE823cg}<#m25IvTwF`f#<9W@>)PkaW-G~%JXkg?T zeAyx}Eb;ywaYtX}8y!ASoD8D$B~5=;vTRcTJ#lh`g6Id(FXD^4nA*ej;#$*dwRE5F zmn2CmUV`I`IUB}%tdsPK7IAA@c8f>T_9_MS1l3yM7A2n;G;`t#75b-xSqG=k`A)c?cENOGFhsPGHxIZC2fU|GH{m54Rf5ci)=*6O4VSBz+# ztmQuA%op2&{2IPZPKG4hPpWeOkBU&70^7xy|(nXxA%B&+~kIa{kiq$akuWly~=(Xxtdlw%c*!^gvN z%2#)2gnT|ZQfwR&3+&FbrkY)(x< ztG-`l%&rPebN>!&6#2FkAf#XC>!&8j9A|MH0m2iQm1eMXMR-7&~~8w`bMHZiackpd(^$hZK(r-o}%Znu6&s7!*lpl@8NQ zTiC^aDm15CpZd0L(f&GzAAARWwH{?jC5;!9(2MDs3@^k;77XXd)zy=G?)KG=P#)hw zNTxap8y+pw=yCoF+oGPk5hmgLs~?9BZy=8B!gjxVt5UbXK9?L34>6Sc-kqOo8>y3j zmgI4}-f;Sf>eF6}s-!;?U5O*ss!KvZp+rb)`(Yj#E``jsct!E$btKk`I62+RtU(0GLH7JI29ol5#{ zk@=rv*ezJfVpXEMk=!?@I~N&Lr~Gw2`Vq}NR2}DgnN2TJY|ywQTHNC9xzN>Booy|@ zAQLCVwC^j1A2Yw`9@}z`dH=^?;)B@VB7*!%10(r8j~>0E_6CG_-D}v^s~+sj*5f&$ zsC~;sjW`*G{*{fBaDcH4Teya`?BeRzh(h5)f90&!Hgmnj$}>n}FX86-t7^*JCl$P8 z(6me3#|i8|GfmJE(SE)efm!!)OC-I|BQ2+y>rA`cms1UhvSMhB+HRW_Mt5nXp%{CE z>?$&4H!aboO*s-)p`6UE)1bII&%|`HW|U+xB2I}KtTsJYjsu3%B4Xe_)c$6NkW4~` zf4#2ZeF|h3&D0}E#d)TW}Jj3JFIrGm;qI#a-*y7DH_#>#oi5mE*l%=5E zBLz-gJQd3j<~4hJ;LJW*NqrQy!Uf3~TpzHDujTUlt*sj=Q}Mg0rFag`{L^)f?%%xP zT-6VO`AWTaZz|D5+LSE8s@qC_6SwtW$=ZyoS7kGNhVI?ZuQniY%p zcwZqPuh=+97&*O|;OJZGK`_i=&X;^Aw?bU^fu&^McDWLpjmqSJ9{2GCb26XqR*>&g z)M#(i!2n{?5Pd}qkn+_BDw|0J*xp5LUy=V7mt~aGT^&o=JacT@nPpdsjnbg(;0_I4 zi!hgBOkBgxmaM1qwL>@h@fD&`#KMJ!CrxgqXT~U>!-^mb!K_9~4Wad%0`(HFDdWEA*6lRxK3r*@3*8>q`J7GfTH)>Zor*<0X5&M|uWR zmIAN+y1FTEt_#&}B0;5a<-kvq1j3Y@G_}>w7#J|0n7M`56Q@YM_*}Qi1GoB+*5AOj z!w6C9Z5^2gZ&8Q|HbkBsI=b94P*CgvtYlBjnz8*i?Q53D3OuTWH8y|TjHbbM{HLV0 zPkNMN`eC8-S;p2A%HMvUkM3xEK&vnG6g2b7HWz_L>i*H=yW8(YdF=d7U*^6c%p3My zV|acb+#c(9$!T3KWiOagX}IEY49SBj9Om=zL?Us@7gW!ZEa$M`-r_EJ1YWaO7caZE z*NiTlZX+4PH%^s(LRJxjXyb11Z`Zi;1U=&X)A6W$Hf~fOu`!~P*n3qVLG|GBFQIR#% zMD9dSCeV0+i*v-!Y17xtFW&N#l0G2J%Q}TEogea`J1@Rd-0gHhOF^-i`BhvbICZ;E ziQ^&&t7%&Y@=+%XY_#1wQ5mK+2kFi6f}zL3Nu1>$JX^s&^>^T!WJ8bEOz6Y!XjFuT zSD*ipLGV+MX0~MU&3JV3`u2EFyRMtGvOuc+%e}m3=@QMbv?eSsIJhYn=ygW&<+$rd z+qd?aoNNhp)YLEks9)aZTZw4b!=jsF>TVWNpYa7J#JFjcPMgAhkJ*J8Ez;EIR&7f~^p_~I`zB@-_{UQcpalFR6ZdI$helI# zqdo1zjNsmLHaF>;H|7@07WAd7QU1^&^!Zk2VE-g=LN6pE2vPE_Frxrx&(3g)@fql1 z+^6WM`k*N|m|o$jC%i&*N6cNceaj*v2^+k`F}N^7uV8U*;X*+%A6c#^9S6OL+6tAm zMaO=@Y9nb_qNoGG6IMr}UDAE`7Y*-m&3NeHko)5PL?Do4?xo57Hc)9A%mQ>PvVqXY zu!W~hWPEl#5U<#+u`ctxd&$_gZqMU5HagaW=L&F6OPPK6b}w&Gx{oA z zyJ0niRkJtt$u3=Q)qCL>a+Zt5Q=KCO+$fKA6zkp z0074U?7a7AL*p`_#`!+04iLY0&pMdk_}xiTxn5`-)GRpJA$vJt?uwgOMz42YvU0n* zQSwNR<)OPjC6T-TFXSSIH=$WF6$c|)4)7f!A`Kaa--c-sVblkhSV3G6OY^{b?Mils za7GtJU?(2f$krvr)DA0$n-+8*QWsX2VR1FUUH#ab1L@&DoplI%xDh}&+-rTs|Gyj7 zeE*d5F+)-BG2kACy~1e=VJm@YNQs2D@^cC#prpSUJ6bb#kbu=j4r^(vL_^DsvgczI z8Z8Ma84(h`kEfqQtB-Fq+P?lJZ;-O*7m*EWfW!c#$mW3Y1Hm46X)|zNAxeE}wDDVs zqzPGC^p!KMNUBPSfX>VG5b1NFyGnS;HD`+|D{YVqmSa$i)=j9LMf~pmZEQ0<{^TZL zDEL6*1i|H!2a}hV*WzJduZnhq{0}xr0MX!qCvrE;|{Zm?vxFjs@%@ zfh?EvgX8xG3yz2}SDX{?R(vCc`jPZs~!RF#D=N#l+tds&>to2_fKA_x*7l@7g zlK9lhEJ6Qp>+o%)EK47i&v%xd1ZaGH$J-L-(HxSHUOD3;a{d&9D_rN8rPQr4AENCu z(_wokR@O%3M&n|$rW`u_{#lM^fFlDh!uU~1;WyZ{0yo6 zbw5_hedp=E*CTW1(Ng%E8uiI9A|i3LE72T`T6Jw38&5|L>{WmgE3l2p3hb*(Gc^MZ zzohAvOIpAcopJ$8rqafTFTiairW$+9_?5_@kG6{wv zMlYQ=KZXnS12oig^s9kHuEp^X=H#*v9{r)l{AB>ZjU9GJ9E|%7W}VrBFJZn3R;MQEY#6W^P|k2zqR3UjF|5 z6|ut?a`7~xz3I_lMGQN144|UI^HgG?SYxI}Ht_uW+X(l2ac59OuUOqkxq8Xx(7kL6 zbH#IZ#^CRrR~+8PrKv6T-Z$H~jf-!hr+>OI-{dOvEO0ULpJT@NFr7ABE(+`a9yusE zuX5z?++oXmmD0f)ohtEs7-s=npY5Gxpi#-Gn_7w1D$Q%b)d<|9m5-ZkvODw6tKl?K z=G|bqZ$f3wCBF=QrTBXo7Xd<5+ zu^+8)$gxbK42p~zG`e28Y=J2G++$xZ`v?Lp0(;KWA|mb)1&PmXQW9!-h7vi7VG$80 z&`vZqKE8q4)_bd#`vaSCv)^&?fI9)2ai6=owBJ5=fixXh*{m;l9Bl^R>Z~L$-%-DQ z{d(~*DOh6oe;1mDWhm3xEqh%aulS>}0<8jA@_g-2HOWN|jOaAr#KCj7T1~j8!0JJHTD3r=U19a? zWdYi^%F~YD_C+LFxtO=v-sp?rJD*UZYoVvGf2%>Q{m-MQzzmJf2W$Uw2jA%c8?dKN z;t3TB={9)2S@D18I4r>dpL`pST9UD7Ld6xcS=f1&r9Cr%|z2Q@{mkx z7kQuzuk8Pi6x_uCOJ8bEzCCJ92U>6B()jxB?)cCIuE-K)a_1MZFm?$3ee#%67z=i& z=waiL0MN4|c-4;fTbV9}%kEQmyr>am4Evv6@Eyr(&oo0wgxy-#tF5iAs~%8GJJ6}o zu*iTBUGkrX`1|mLsbf~5tDSsz&`x-vw%V3+2Je%Y^p)l#=SvY09i^m9Drqq>G1tq+ z<;4T*V9URE*QdY+j@{o8^7{d2b#?WX{JgXdk73G4zEAne4f?kaJMun%x43IpqvaMaPpChs zvNj3EEX%*A(IkdncSZsIGN&16Ucu4P7%dmor7SEg?KXEkHVY$y?!fkq8ZgCYjnu+} z8Gz#Ds`imPF6jd_$n9d*^m@Qlp!524yYUHe$^RYjT3{`z1|%q#!qrYAcrE!Pp0hl` z!OPaidutb2k&WDE&j#GI7TXX75F_AKPW$A&e<g&7f^hfS<_vU$RER6b9Wg~zkfnohc2;Fw24ORf^i^j~w z)jQq#;FOz}cRd3U=s8?$Y+U5Wh$a-HdwN0~V#bBLA=<4*>4T)SuhApL#5V_ql}7nR$5r+%7+QBOoGP|50n{7#Ki_6u9{f zgiI3hV@N<;28`M0Fcy?IZ;pptT4Llq*RWE!9RhtWj~{ef^9lJ zTBQ!g$H!l7KJsGfHi(9h`lR&rNs@S-DFD{c@T8=||JD?Z+Jh&RgL&i%;dMP56$f@- zw#U;Ss(^L(*5v*R5Tmz-C;^}J^RMjj0;Rj-n=cm+(}H^m{v`>KDg7{@=Kj=UcKSCf z(tdx2<>5^J@#nDDp#wWX_!ChWy`20<(Lff>jKb}C#Y}oL5`;%Yv_ZIhg}}zfc6U?y z$nzXGr3EAXN3BM}QyLeCi~YAtmjW02vz@pt(3d8rrq5slivCYv!;l^Q=Lpy=iXjTH zQh@G?Xj|^~D~FvM!4wq#&5*MnPgo#*d(g(4t@S#&RWe_B?b7?`(sk`S%~LSgAoZ_= zd!3{JQsi|Gd$NS4<8YgeatO&f@Fz>B)CIUXK?Kf36}0UGdp;SjHKbZ@AhFq7PR zO$h8zKRjL>^3jKUSR}owB_Nm;`l$M9gnc9!HeMmC{i^}CECm7O=*o+v1N=@WDm(U` ztEh$1W3eo@%Ov>lp1)474zVgF4YW%7!?LI&R*;b@vMejcw=WUV&f#WXS`xITZy&qu z9~L+)DXDB%-MjB%Q&3XsTUizFL4*Ik>cr=JHan3>iHy%}Lqn+RJ>i|;(&oVI?023w zJ9%|pw>2fgl$kUrSpQx~{OdEVp1!{CYG;t);X*wvJ$+YCIN|ZI&x6u*2F57Xw_3Aj zG-EhLy^~}Hi0dmXoSwP)cYj2*wbNliaaC0u9oN;D5*OKR{tg@=AL1*9_E|w#bO228PlA|)LiGO&cJ zvvK+8pFgwrMu513y?da^(2Sf-^2pKOg zVWr8SUwwUjNhc)*f5*Qfj7EKrjm*WxrPuN8Ras3<4`5{qpFe-)cG$8#Hm0y(Tgv?B zOh&fhk9X~Ja|G?}?FnqAs1+3zW!8&4cMrEm4XEM4XYl_4Z1LmbT0el6o@ASrS3vCZ z2so8?dBJ;l@^8R%Gp!^3Q;Bs~Z!Z$Cr|+;m6i`~qI?^PKH`WKr;j|eiJIvV*ee_L+gnojRfqoqq|#lnjAv` z)bk%oKsf;Dt*uez<>hIyn_&HelOX^5FKS85camdHcp?*nEH7oAFba(9?f)cB0cca^ zU!ejmAl%fh&(8#YoDuyu%cr0eSe3hhvYJ{}Ss8jxPEG@Aj*3Px4)8BpI=V3@T4F^d zCI60&PaE6Ydpy`<(Yw1A*l*uvG&N~WXFQ?(+{{yk2lxqmhl+}-_s^eCa&o94At5U} zJFfseYX?nb78KAew0IHL+ANC!)-{?ZPkOd9jtKN0G@ur%IQ8W(ENB^-m{5Q~xSX7v zc-;2cfCUh{LRVnDAMag$#>Tdfj$&L~XyJp}{_6#}C@U}bRm`6NAO;M6WMDlL>qz9E zRaFC@Zf0sq$`u32v$L~%YmERa0TO6p@mYaS zNZ7cz>$S_?ozKxZ+6EvUK(>@jOlUhhI}(zT?Lfz`g1S1A2y6B4UnC#_Yw@~$nuN2nb6Hi@gj2$kDBMEutA@C$%f+FKva znE)yAJ$#+dXlQ8Y3;4eG_)$(?KHi6{P?^rv!($z=Y;6)XK$k!s8w|9blL6WVCitet z?W#^qMP+rWSd;d{hrO|x-yQ`;MIu1okN@SaF6G;|ZzZIpIsmhKG9e}=CUs5C{%M{k z{;hrkKqkAkps-LuLj$>3^|iFL^w0SCCmT>vQIVx~f%yoyC7>Pw+$)lM?jpaWM9j|4 zt}=bPdKmb$rltn)FhZiDFX`y$8rVx3UjF<*M+bN(Sil!-Y;HcSW7d#S67#2&ajoFi z1P90Ir(;Tb5lZAHuiC2Yin((*@KpmF%Ugd=tL+T4-c=cqvOTJ#f7cC zyp>61I+4*|djw9*468nCuzke!=LK}Gcvz$IXe{uvn$C?0?t z7#NUATLd150-)gxFf`5T^;LLHDJf*@#fE^YDt2JH&esheC+_j_@O}XgV4$XbO4)xK zHViYtQ)J3z19WU`{L;tA=WK5p?d8jtfWbZ)6F?1)#5#q5`&-@J4FOIE2PxSh=`~iB*tT4VDJLq$-25a$9{M!0GbN&?LPV# z3X!H}W=H^;&q2%Cr3lo)=hAR2vvyRS^*)qU7pMJc%J}*!ydSgR?(=FRM!pO@&Diw# zaO((G8pTb^!0IpvfZzVZ1)TdybKAl zh<^TzesXe>6qZwOU!qn20-!OsxJkf^=@}aO17SNn0s;`>!vPVcI6&27q`Z$Yt59c5?k5C<71!2nJ~BTWu`}2&5+W-56+TzXDVU zJb|LsWoL{^T|*`E+STGyUO=CWX%p6QFu#4vv7JAaVZ# zOe`$B%|CCS0=$_@Q#4@J(<`S}SFQjvtyK;SbOPSucq`e4f}S2l@D3^*dS0s2On}R% z)drMOq7xF3fZ8R!P7@xCo}S)UpsJ&PbG9QPA<-7cpjif#H<8EzkVgnU97hI6MnWbF z)t=%RtvXv+1Ox>2CRY{&RH9%Y7e^xXI>Ufj=?Hj@gn}Xhm^`P=QW&6mc8QURYoJ7@ zXJFv>f7Ev7(OCBD9=}l{l%&Z#C6Z!?-Y8Sbt5PIn77ga9jF~EmkW_|DPe{m=Oqt1) zCMBWAScu4&ka2(S-p)Szth3i%>zuW=KY51x{tegl{eG_N{sF(`+ULfKydohXVe$BN zl%)Cn4_1yt&7wcc5T(r^mB}oQN4K`_FeqSFQ&Vdzaov@en0PBTc1PjYNE7d>FhNy^ zr3LrR92}ot?y9h1S3S}{HP+3G-5IsVp2v^XZGNOM=iF-!OlwVTZPmw*TR=T8=jQG{ z_bQ4eUq58HHMctg6c~$GML{#RIf%5b{uXIw`qG! zqp7JWA}VS*S*mYfAc!$+FR;DS-Hyk?kTqzvwBB#bW)v8b{l_jP-;D>zf=f&HsT@4m zpzw;fyi8P9mIJ}KwsxgeK8NdQ$Je`ay}iAX_Fem;qN5QsUQrZyftSJ*@IcdM*^43s zA0Hoqbf;)+%mb1{V`5^$%pt`A*L}U2kVVHwI?=?e z-AL@roHERcBOE(1{EUb>{d(IJM}mW8SNkWvZ?S23^QI0fD(B+Y6NE1-Egm?VwAGJ@ zh+r97Y1JCkfIJr$7q@T^kFOaT8O3A{e3~78;oer=UtChMN6#4X4pVf6g;R!nGRzGR z(w#nc?%KC+Hb|8+ZP}RV?cs;L7ad}vZzSbAL9wuMbBDAVUt&=W<+1%+9bQOSJg&S5 zeRTDs-j8mP zAfTo~%VKhsPMzBP>h)_H0(u3aasIjOO(q+SK@n zw^sQOm}3t6)<(8Bf8)3>V@b9I?mqvXKv?HN3g2w7>?Rq8%z6Z+)I-!cpe*R-^>jDP=r zsqabn;jN?H72QKFS`Uv_Jyef@Eukmc3hj9#cA0byd4sXm+gB`-q=Tr$#^Mwbqw4!; z^|y3ByBiY|1XZ%9WCRW==X5naoPqh&;5)(>l0r~ioQ08*k?>7S6i_*INI+6D#|U@& z=JwVj5-#6Pc>;(*y!l+MeQ@OPVGV8Vm9X!@9MXr6$$w~WHbn%UMbx8iVA3d=%}YuW z#1cvPV6~2ulSxo8>0E11+WIY90&!g%LG5qbH_Bf4!t9MT;!>}u!u{KHYOei(!a*e- zV}wmUgmH%y48#=lV9u}IyZ2ErQVw}1R^F?)DpO6}eXMMzXLy(iVhL0t!=!>IyL`?n zz5kNCJHL#~M)SI0B}GL-NbO2tVPS0FJz3}NS z#H{MCGKUWzc9`r_Gc0jo2@4BjX%QSug^K8@yi5nPD|BrwZxLK~_Vb-`P% z@*lW1D9a_#v@TPpy(fYfjuT;o4pRJEo>QS+=M8Q-m*=}JQx|bnl1_bps;H{MnVf zT@A^y3(#)T6aE#G?CP4E*$oP8lrCPBLS#LC_N+fLlT1mJgTX;nRkEN6g(4v(rSj*W z3=uo@n$$EE^x}P%+{t?-H;=!+e^xcWfW&WH)cMwraXl+L`-=P1mKxl8yHjuC>D2Ps z&rBz^wUurQiG&|U0&scSu}#y{bDx!!Ra6K6(4pTzBhfAe_9TRdrArgJqp9hM)=SS5 z&KG4itaFyn`u+L;Le++KX^OBz8;nd@wl|j+o74f~R$z@^gDOFglFPTjURwCH*2gy~$vh?ENb_BI8uP)o2@VbpZ=FTR zkMKCarp#cpN=Zc}F3IlCNFlZQuwO9nU2hGEI`=cImm^=Ma$NY|Tr3$~@bhnB4LL9P z+5cZ42nC6FQttot^WSLhe~*Pms1q994T~>+4a3?m+yz}A1}EWC3~A#T6=Y-WxtA&q=QgD9oc&4_U)#Jjt{nC3)tSs7wnzHBjQ&{ zMdVSj`|~Qo)pbTDq|xX{=M$I%;p}$>H@~Y}4!eUMCceR~{t&?`w4A(t0+1qo-ni5a zayWQUV-W!{RJ!W>Q>r!vUJ|UrpfjuJf>QHG4AEnsWp6?ekk)(l(<;Ln_b#EOQ=-*zwMJbKH<)=u4wdn(c2R#sVJZImeD=%#lv&0+z1FHZd_K z6sE50XI{gXJbU)+7KIXeT>j?@gvw{AB8H;O%WLBOb1Ny;N~fBRK=Z923@g03!5m3( zi!j#ZHDgrNahYxv4#OE+CI~b-s3QE8mX=C551qsg7L=9M?~;*}Tn7w{JkE{m9|nzq zYc_qCc#wSD9oex}WE4SkH7=%}9KOm*MTAxu8&X#^%FpkhrKNR%P9qd8Ek#L*7k+r9 ztE=nLXeq{-vF=sA!tMEIUv9)(NcSqHlTjJ4PVljPcRBsYVRd!v)s>$=e`bXpfUhZ? zsN+<}^DEIDxVCCIdKwy);-fZ}|_ zOIp|>V`JmD7E*xlB@24E4GcGF*a5u2TWJW$)IccTEw#0^lQw>^OQlP5!z@|V#UsAd zr9VzTTd~9NDJvrR`1JH4L&I1@-6LL)$|L3uFV0bA?Pw|~%M0fb@i7F<+_LO=Dr?2~ zpjUEfDHqem9loKVYjI6jIau{?`z9!m&`ZM=OX(jjXqp`H$}1|^XM@SXQzXhTVv;!V zv7^LwEzvVL7@(DMtf9SZak^doO`nyWjlGp20G28w4kRUs?zPi(;Nodhx#x%L(jtvL z7%|xDbq435j`49<;Ktw+S7ho0VP}~QHK(x@#7J4P$nY(z*4 zNKF;t_hZ%1)bX7CblnUp5OyZsYg#YIc~}R3XfL$igqnl^Kfh9!Yjdim8IE|sE3m8l zfeB|P>UsTHl|d>3u+|SU@cSJ~S_cEMNts~+`sqLv#0%&o6TcspJUg7z1^{8m-V@NY zM>CAe^cnbTkT7cDH)4Y45k@wGXs{usZ%}4f$IUIiLtMNzPR`YjRryuyUM*ZMzTs59 zRX9n6A{8>sA+c zBIWttyLWFERuXrP`s~T6p$|s@a0@wFVI{>#tbnf%3=Di$Q=-@Mg(GrFLq&u1=PrC@mdbEwUS^-v;~gpAS(LId*3N zCPX>Iu;>KtZqKEiJS~Q0;`v+m?$zT_^`85>4Lf%`*1kkODKy;HG#}s3FYhQ$m`Ll|Lj;sxRsidSt-VT-#iUKwFm9Ewx_h2w*=jLu;^jGuy zJ$3*75cQjg`lY#{&!K^V>##oIoJjcPI6HnCmRuw_I9SElINmcJm9YMtNAeIvKQEbRG@P#Rrm(QQ`1@o} z6`kb8L5&>HhC}@*ifOj?F!MCYWo2dkacO#o_rioKkiTjFi*SauYwh#mgw!4v7S^L= z&_7c?KPu;LOQ@=>x-xioImx&=Gw@4A2bye02u)Wm|bGf`ge66g|Jc-b2b=z$Ajm zE}P~6c^=R9Sxo;}pf%HyuDc63l7HvUH4P07z<-qq2d?9A76yVmb>#kuG=jiv+m5=v z*8HEo{nq*3{QTqj`Pq5S9Uf4ex1yt01Ah{gPaS(XLNrH4#3m*tNMM0>7k)LiFO8JY z{gpvwj`=Y&6ChI|fv99NzWDC$;GhL+o3NO{TXxf91Nk0Gs=~S)uUMY1 zaGJlyyhR{Xo7?ulUr>PDpoA}EVBJk_u||nILX5jA7XF6yNaQVeHEkTpT$>vA5!WFF zr}e15a}pg!&2d`_${96hCf~@7p@C5VUI&NCa0(xd^2LHrJdRjike{1tJwDf#V@^8P z8$m${8X~u%qS^*kb$~cvy-jWLh{M3>XqRcs97UAD zP*XR#}Q{Jty*R%KDpXRVS zPO-8!u^fJ?ee$H=*_RQY(B6a^IC2EboSK$nVRAMyw?=us8UxLN0|(gI*`@w?_+twP zM}gbUp}dp!2GkR}*C-Uq0=2E}X+xBLQ$$Xgcj=Ei)8G*#iT3vPzB+sPOXGQN?9ZQL zP@|KXXQ4G`7rr+lyM$nT%mLKmsMngCo9VlcoIQKiX>z^AEcZL=jG8sofLEg=Ld)HK zFH}mqAz7n$<~l!qt1C>15mr(LQ7#bW0S5kPui|5i%g&9BjrC}I%Q@4)hC_IG&Ns#% zTwYq_95J`G4Z*+wRzDw;mVTKm2B=3DA0LmpJ{L~m3DV0wCp}y0U4r1unUMnj9Tp$o zl`scaE558j^VY2C3IoO7PKWMPZ0{QS4wMHGOcf~bzP_YoJ~ohY-l4N6K%igly$ zMRld4)P238tyAVsQRZgh5T2Hn9B$vztXGI-{k`Ou#mYJ#K6c`R3FTqFpQF)HBKIDaE0FHD?zp{4nbgg=q@q1=C(l(bFxfh=ha$^7trV z*K6=6Wkx?RC-0Krbf(_Gd6SBT$X~uQ^5u*0GJ#0@dMA$_yb8+G?k)`g^bU)2Kj;Iw z?oa1@MrdyXpCo#4fXJj-R;Fdz()9C&hANmHM4K$*vKye=(l>J7pgC^>hb!@e1rU#s zAJ!<8?*Y#vArZs^W-F%5NC46A`#MD#x$Fl`exV}^ z_$@xL25X|v+8%qysRBavm(}|k2UpkwoK4y$^o%Yoj`_SizU`j?(H^rA(-8byf->@d z1W+5{G?piLmoKACoaD2-H0e!l7m)G35p;!<+`R%id3<7`3TsKiYi>$rt2)_m@jm7F zo~Ys_5gkwkp#LOHMnFhNEe4ZB>KUhU65kcTi;%wqnP+8XCDd-CI@_5b)QGDlksCBj zBHlImzL;m}^hO?@o7l%>)ejd0&zrFDAZ~6zVBbEjHEY&rAR|gyup+x$LCu!@B~r3@ z-6WJ;FV4zvaB-&3}tAL?UUF!|kHC6(^}0QJ`#??n$n(Z*(nj9o`S zPmd{7y6KC%qN!O~c8`6m&F8CoC;t^zL!37#v^!{M$c1x!9s^%P;paB=>1%6mc=hTP z*(#Mn@#Y|VZ_uSEaqiV-_ZV0eRMZN;PG?N#k=;B068AMcY5(rkba%Q%xBJRUrtxO2 zK8E+zU7ZU1=O?j^;c}hV9a-iC!HA9m3(lg=%Cp z31BqtLkAyJw56mbAtY>X^v2@_#cNWG?7B)BQ7s;)1mLsg{CB$rM8hKAK;4U$K#|LF zYEX0EOveS;n~yAEN*?FtR)h8v1Y*|y)l5vE#>TRHp9f5>pJ#VIiGBeT5+0jY(Uu(< zCGrcMKlq3cB=1=ze=sPOkt}F&+LvAi0I5Q~o-810Xxz%Gwz`dGepD^5K)KwFhsx4A9-9LRB-Ff+RT-cDg@RuFV>qF!N1^H-yerrg9v z@kC*0Te5osNfUE|Hii%$y7o9E5Pl#IwD6#ag|htT<#IM>VxE2fBeIa5oLq&o3J^rO zji;6z#Y9DwtgN=%*xGXLqmPFuEmrvF&Z5@e{a*iv?j!7b^5_2nw0;4${~Ry-kAD2} a+8d*H*(wOyujGG4Q9F1{B}>`#%HIL)u-usd diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_drivable_area_design.md b/planning/behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design.md similarity index 90% rename from planning/behavior_path_planner/docs/behavior_path_planner_drivable_area_design.md rename to planning/behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design.md index 84347dc067739..015ffcdfd8f3b 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_drivable_area_design.md +++ b/planning/behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design.md @@ -73,7 +73,7 @@ struct DrivalbleLanes The image of the sorted drivable lanes is depicted in the following picture. -![sorted_lanes](../image/drivable_area/sorted_lanes.drawio.svg) +![sorted_lanes](../images/drivable_area/sorted_lanes.drawio.svg) Note that, the order of drivable lanes become @@ -92,7 +92,7 @@ std::vector right_bound; and each point of right bound and left bound has a position in the absolute coordinate system. -![drivable_lines](../image/drivable_area/drivable_lines.drawio.svg) +![drivable_lines](../images/drivable_area/drivable_lines.drawio.svg) ### Drivable Area Expansion @@ -101,7 +101,7 @@ and each point of right bound and left bound has a position in the absolute coor Each module can statically expand the left and right bounds of the target lanes by the parameter defined values. This enables large vehicles to pass narrow curve. The image of this process can be described as -![expanded_lanes](../image/drivable_area/expanded_lanes.drawio.svg) +![expanded_lanes](../images/drivable_area/expanded_lanes.drawio.svg) Note that we only expand right bound of the rightmost lane and left bound of the leftmost lane. @@ -110,9 +110,9 @@ Note that we only expand right bound of the rightmost lane and left bound of the The drivable area can also be expanded dynamically based on a minimum width calculated from the path curvature and the ego vehicle's properties. If static expansion is also enabled, the dynamic expansion will be done after the static expansion such that both expansions are applied. -| Without dynamic expansion | With dynamic expansion | -| -------------------------------------------------------------------------- | ------------------------------------------------------------------------ | -| ![dynamic_expansion_off](../image/drivable_area/dynamic_expansion_off.png) | ![dynamic_expansion_on](../image/drivable_area/dynamic_expansion_on.png) | +| Without dynamic expansion | With dynamic expansion | +| --------------------------------------------------------------------------- | ------------------------------------------------------------------------- | +| ![dynamic_expansion_off](../images/drivable_area/dynamic_expansion_off.png) | ![dynamic_expansion_on](../images/drivable_area/dynamic_expansion_on.png) | Next we detail the algorithm used to expand the drivable area bounds. @@ -131,30 +131,30 @@ $$ W = \frac{a² + 2 al + 2kw + l² + w²}{2k + w}$$ Where $W$ is the minimum drivable area width, $a$, is the front overhang of ego, $l$ is the wheelbase of ego, $w$ is the width of ego, and $k$ is the path curvature. This equation was derived from the work of [Lim, H., Kim, C., and Jo, A., "Model Predictive Control-Based Lateral Control of Autonomous Large-Size Bus on Road with Large Curvature," SAE Technical Paper 2021-01-0099, 2021](https://www.sae.org/publications/technical-papers/content/2021-01-0099/). -![min width](../image/drivable_area/DynamicDrivableArea-MinWidth.drawio.svg) +![min width](../images/drivable_area/DynamicDrivableArea-MinWidth.drawio.svg) ##### 3 Calculate maximum expansion distances of each bound point based on dynamic objects and linestring of the vector map (optional) For each drivable area bound point, we calculate its maximum expansion distance as its distance to the closest "obstacle" (either a map linestring with type `avoid_linestrings.type`, or a dynamic object footprint if `dynamic_objects.avoid` is set to `true`). If `max_expansion_distance` is not `0.0`, it is use here if smaller than the distance to the closest obstacle. -![max distances](../image/drivable_area/DynamicDrivableArea-MaxWidth.drawio.svg) +![max distances](../images/drivable_area/DynamicDrivableArea-MaxWidth.drawio.svg) ##### 4 Calculate by how much each bound point should be pushed away from the path For each bound point, a shift distance is calculated. such that the resulting width between corresponding left and right bound points is as close as possible to the minimum width calculated in step 2 but the individual shift distance stays bellow the previously calculated maximum expansion distance. -![expansion distances](../image/drivable_area/DynamicDrivableArea-ExpDistances.drawio.svg) +![expansion distances](../images/drivable_area/DynamicDrivableArea-ExpDistances.drawio.svg) ##### 5 Shift bound points by the values calculated in step 4 and remove all loops in the resulting bound Finally, each bound point is shifted away from the path by the distance calculated in step 4. Once all points have been shifted, loops are removed from the bound and we obtain our final expanded drivable area. -| | | -| ----------------------------------------------------------------------------- | ----------------------------------------------------------------------- | -| ![expansion](../image/drivable_area/DynamicDrivableArea-Expansion.drawio.svg) | ![result](../image/drivable_area/DynamicDrivableArea-Result.drawio.svg) | +| | | +| ------------------------------------------------------------------------------ | ------------------------------------------------------------------------ | +| ![expansion](../images/drivable_area/DynamicDrivableArea-Expansion.drawio.svg) | ![result](../images/drivable_area/DynamicDrivableArea-Result.drawio.svg) | ### Visualizing maximum drivable area (Debug) @@ -164,9 +164,9 @@ For example, in the same area, one can perform avoidance and another cannot. Thi To debug the issue, the maximum drivable area boundary can be visualized. -![drivable_area_boundary_marker1](../image/drivable_area/drivable_area_boundary_marker_example1.png) +![drivable_area_boundary_marker1](../images/drivable_area/drivable_area_boundary_marker_example1.png) -![drivable_area_boundary_marker2](../image/drivable_area/drivable_area_boundary_marker_example2.png) +![drivable_area_boundary_marker2](../images/drivable_area/drivable_area_boundary_marker_example2.png) The maximum drivable area can be visualize by adding the marker from `/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/maximum_drivable_area` @@ -175,4 +175,4 @@ The maximum drivable area can be visualize by adding the marker from `/planning/ If the hatched road markings area is defined in the lanelet map, the area can be used as a drivable area. Since the area is expressed as a polygon format of Lanelet2, several steps are required for correct expansion. -![hatched_road_markings_drivable_area_expansion](../image/drivable_area/hatched_road_markings_drivable_area_expansion.drawio.svg) +![hatched_road_markings_drivable_area_expansion](../images/drivable_area/hatched_road_markings_drivable_area_expansion.drawio.svg) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_path_generation_design.md b/planning/behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md similarity index 97% rename from planning/behavior_path_planner/docs/behavior_path_planner_path_generation_design.md rename to planning/behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md index 7784f96543ea6..2a22db5597241 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_path_generation_design.md +++ b/planning/behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md @@ -1,6 +1,6 @@ # Path Generation design -This document explains how the path is generated for lane change and avoidance, etc. The implementation can be found in [path_shifter.hpp](https://github.com/autowarefoundation/autoware.universe/blob/main/planning/behavior_path_planner/include/behavior_path_planner/utils/path_shifter/path_shifter.hpp). +This document explains how the path is generated for lane change and avoidance, etc. The implementation can be found in [path_shifter.hpp](https://github.com/autowarefoundation/autoware.universe/blob/main/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp). ## Overview @@ -8,7 +8,7 @@ The base idea of the path generation in lane change and avoidance is to smoothly The figure below explains how the application of a constant lateral jerk $l^{'''}(s)$ can be used to induce lateral shifting. In order to comply with the limits on lateral acceleration and velocity, zero-jerk time is employed in the figure ( $T_a$ and $T_v$ ). In each interval where constant jerk is applied, the shift position $l(s)$ can be characterized by a third-degree polynomial. Therefore the shift length from the reference path can then be calculated by combining spline curves. -![path-shifter](../image/path_shifter.png) +![path-shifter](../images/path_shifter/path_shifter.png) Note that, due to the rarity of the $T_v$ in almost all cases of lane change and avoidance, $T_v$ is not considered in the current implementation. diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_safety_check.md b/planning/behavior_path_planner_common/docs/behavior_path_planner_safety_check.md similarity index 93% rename from planning/behavior_path_planner/docs/behavior_path_planner_safety_check.md rename to planning/behavior_path_planner_common/docs/behavior_path_planner_safety_check.md index 30e2093cb465e..4733fe7832da6 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_safety_check.md +++ b/planning/behavior_path_planner_common/docs/behavior_path_planner_safety_check.md @@ -22,7 +22,7 @@ Currently the yaw angle of each point of predicted paths of a target object does The flow of the safety check algorithm is described in the following explanations. -![safety_check_flow](../image/path_safety_checker/safety_check_flow.drawio.svg) +![safety_check_flow](../images/path_safety_checker/safety_check_flow.drawio.svg) Here we explain each step of the algorithm flow. @@ -38,7 +38,7 @@ With the interpolated pose obtained in the step.1, we check if the object and eg After the overlap check, it starts to perform the safety check for the broader range. In this step, it judges if ego or target object is in front of the other vehicle. We use arc length of the front point of each object along the given path to judge which one is in front of the other. In the following example, target object (red rectangle) is running in front of the ego vehicle (black rectangle). -![front_object](../image/path_safety_checker/front_object.drawio.svg) +![front_object](../images/path_safety_checker/front_object.drawio.svg) #### 4. Calculate RSS distance @@ -54,7 +54,7 @@ where $V_{front}$, $v_{rear}$ are front and rear vehicle velocity respectively a In this step, we compute extended ego and target object polygons. The extended polygons can be described as: -![extended_polygons](../image/path_safety_checker/extended_polygons.drawio.svg) +![extended_polygons](../images/path_safety_checker/extended_polygons.drawio.svg) As the picture shows, we expand the rear object polygon. For the longitudinal side, we extend it with the RSS distance, and for the lateral side, we extend it by the lateral margin diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_turn_signal_design.md b/planning/behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design.md similarity index 86% rename from planning/behavior_path_planner/docs/behavior_path_planner_turn_signal_design.md rename to planning/behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design.md index 8b64db997aec6..c183e0627a674 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_turn_signal_design.md +++ b/planning/behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design.md @@ -35,7 +35,7 @@ Note that the default values for `turn_signal_intersection_search_distance` and In this algorithm, it assumes that each blinker has two sections, which are `desired section` and `required section`. The image of these two sections are depicted in the following diagram. -![section_definition](../image/turn_signal_decider/sections_definition.drawio.svg) +![section_definition](../images/turn_signal_decider/sections_definition.drawio.svg) These two sections have the following meanings. @@ -51,7 +51,7 @@ These two sections have the following meanings. When turning on the blinker, it decides whether or not to turn on the specified blinker based on the distance from the front of the ego vehicle to the start point of each section. Conversely, when turning off the blinker, it calculates the distance from the base link of the ego vehicle to the end point of each section and decide whether or not to turn it off based on that. -![activation_distance](../image/turn_signal_decider/activation_distance.drawio.svg) +![activation_distance](../images/turn_signal_decider/activation_distance.drawio.svg) For left turn, right turn, avoidance, lane change, goal planner and pull out, we define these two sections, which are elaborated in the following part. @@ -71,7 +71,7 @@ Turn signal decider checks each lanelet on the map if it has `turn_direction` in - required end point The earliest point that satisfies the following condition. $\theta - \theta_{\textrm{end}} < \delta$, where $\theta_{\textrm{end}}$ is yaw angle of the terminal point of the lanelet, $\theta$ is the angle of a required end point and $\delta$ is the threshold defined by the user. -![section_turn_signal](../image/turn_signal_decider/left_right_turn.drawio.svg) +![section_turn_signal](../images/turn_signal_decider/left_right_turn.drawio.svg) #### 2. Avoidance @@ -91,7 +91,7 @@ First section - required end point Shift complete point same as the desired end point. -![section_first_avoidance](../image/turn_signal_decider/avoidance_first_section.drawio.svg) +![section_first_avoidance](../images/turn_signal_decider/avoidance_first_section.drawio.svg) Second section @@ -107,7 +107,7 @@ Second section - required end point Avoidance terminal point. -![section_second_avoidance](../image/turn_signal_decider/avoidance_second_section.drawio.svg) +![section_second_avoidance](../images/turn_signal_decider/avoidance_second_section.drawio.svg) #### 3. Lane Change @@ -123,7 +123,7 @@ Second section - required end point Cross point with lane change path and boundary line of the adjacent lane. -![section_lane_change](../image/turn_signal_decider/lane_change.drawio.svg) +![section_lane_change](../images/turn_signal_decider/lane_change.drawio.svg) #### 4. Pull out @@ -139,7 +139,7 @@ Second section - required end point Terminal point of the path of pull out. -![section_pull_out](../image/turn_signal_decider/pull_out.drawio.svg) +![section_pull_out](../images/turn_signal_decider/pull_out.drawio.svg) #### 5. Goal Planner @@ -155,24 +155,24 @@ Second section - required end point Terminal point of the path of pull over. -![section_pull_over](../image/turn_signal_decider/pull_over.drawio.svg) +![section_pull_over](../images/turn_signal_decider/pull_over.drawio.svg) When it comes to handle several blinkers, it gives priority to the first blinker that comes first. However, this rule sometimes activate unnatural blinkers, so turn signal decider uses the following five rules to decide the necessary turn signal. - pattern1 - ![pattern1](../image/turn_signal_decider/pattern1.drawio.svg) + ![pattern1](../images/turn_signal_decider/pattern1.drawio.svg) - pattern2 - ![pattern2](../image/turn_signal_decider/pattern2.drawio.svg) + ![pattern2](../images/turn_signal_decider/pattern2.drawio.svg) - pattern3 - ![pattern3](../image/turn_signal_decider/pattern3.drawio.svg) + ![pattern3](../images/turn_signal_decider/pattern3.drawio.svg) - pattern4 - ![pattern4](../image/turn_signal_decider/pattern4.drawio.svg) + ![pattern4](../images/turn_signal_decider/pattern4.drawio.svg) - pattern5 - ![pattern5](../image/turn_signal_decider/pattern5.drawio.svg) + ![pattern5](../images/turn_signal_decider/pattern5.drawio.svg) Based on these five rules, turn signal decider can solve `blinker conflicts`. The following pictures show some examples of this kind of conflicts. @@ -180,22 +180,22 @@ Based on these five rules, turn signal decider can solve `blinker conflicts`. Th In this scenario, ego vehicle has to pass several turns that are close each other. Since this pattern can be solved by the pattern1 rule, the overall result is depicted in the following picture. -![continuous_turns](../image/turn_signal_decider/continuous_turns.drawio.svg) +![continuous_turns](../images/turn_signal_decider/continuous_turns.drawio.svg) #### - Avoidance with left turn (1) In this scene, ego vehicle has to deal with the obstacle that is on its original path as well as make a left turn. The overall result can be varied by the position of the obstacle, but the image of the result is described in the following picture. -![avoidance_and_turn](../image/turn_signal_decider/avoidance_and_turn.drawio.svg) +![avoidance_and_turn](../images/turn_signal_decider/avoidance_and_turn.drawio.svg) #### - Avoidance with left turn (2) Same as the previous scenario, ego vehicle has to avoid the obstacle as well as make a turn left. However, in this scene, the obstacle is parked after the intersection. Similar to the previous one, the overall result can be varied by the position of the obstacle, but the image of the result is described in the following picture. -![avoidance_and_turn](../image/turn_signal_decider/avoidance_and_turn2.drawio.svg) +![avoidance_and_turn](../images/turn_signal_decider/avoidance_and_turn2.drawio.svg) #### - Lane change and left turn In this scenario, ego vehicle has to do lane change before making a left turn. In the following example, ego vehicle does not activate left turn signal until it reaches the end point of the lane change path. -![avoidance_and_turn](../image/turn_signal_decider/lane_change_and_turn.drawio.svg) +![avoidance_and_turn](../images/turn_signal_decider/lane_change_and_turn.drawio.svg) diff --git a/planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-ExpDistances.drawio.svg b/planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-ExpDistances.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-ExpDistances.drawio.svg rename to planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-ExpDistances.drawio.svg diff --git a/planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-Expansion.drawio.svg b/planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-Expansion.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-Expansion.drawio.svg rename to planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-Expansion.drawio.svg diff --git a/planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-Expansion_Input.drawio.svg b/planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-Expansion_Input.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-Expansion_Input.drawio.svg rename to planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-Expansion_Input.drawio.svg diff --git a/planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-MaxWidth.drawio.svg b/planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-MaxWidth.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-MaxWidth.drawio.svg rename to planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-MaxWidth.drawio.svg diff --git a/planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-MinWidth.drawio.svg b/planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-MinWidth.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-MinWidth.drawio.svg rename to planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-MinWidth.drawio.svg diff --git a/planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-Result.drawio.svg b/planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-Result.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/DynamicDrivableArea-Result.drawio.svg rename to planning/behavior_path_planner_common/images/drivable_area/DynamicDrivableArea-Result.drawio.svg diff --git a/planning/behavior_path_planner/image/drivable_area/drivable_area_boundary_marker_example1.png b/planning/behavior_path_planner_common/images/drivable_area/drivable_area_boundary_marker_example1.png similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/drivable_area_boundary_marker_example1.png rename to planning/behavior_path_planner_common/images/drivable_area/drivable_area_boundary_marker_example1.png diff --git a/planning/behavior_path_planner/image/drivable_area/drivable_area_boundary_marker_example2.png b/planning/behavior_path_planner_common/images/drivable_area/drivable_area_boundary_marker_example2.png similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/drivable_area_boundary_marker_example2.png rename to planning/behavior_path_planner_common/images/drivable_area/drivable_area_boundary_marker_example2.png diff --git a/planning/behavior_path_planner/image/drivable_area/drivable_lines.drawio.svg b/planning/behavior_path_planner_common/images/drivable_area/drivable_lines.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/drivable_lines.drawio.svg rename to planning/behavior_path_planner_common/images/drivable_area/drivable_lines.drawio.svg diff --git a/planning/behavior_path_planner/image/drivable_area/dynamic_expansion_off.png b/planning/behavior_path_planner_common/images/drivable_area/dynamic_expansion_off.png similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/dynamic_expansion_off.png rename to planning/behavior_path_planner_common/images/drivable_area/dynamic_expansion_off.png diff --git a/planning/behavior_path_planner/image/drivable_area/dynamic_expansion_on.png b/planning/behavior_path_planner_common/images/drivable_area/dynamic_expansion_on.png similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/dynamic_expansion_on.png rename to planning/behavior_path_planner_common/images/drivable_area/dynamic_expansion_on.png diff --git a/planning/behavior_path_planner/image/drivable_area/expanded_lanes.drawio.svg b/planning/behavior_path_planner_common/images/drivable_area/expanded_lanes.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/expanded_lanes.drawio.svg rename to planning/behavior_path_planner_common/images/drivable_area/expanded_lanes.drawio.svg diff --git a/planning/behavior_path_planner/image/drivable_area/hatched_road_markings_drivable_area_expansion.drawio.svg b/planning/behavior_path_planner_common/images/drivable_area/hatched_road_markings_drivable_area_expansion.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/hatched_road_markings_drivable_area_expansion.drawio.svg rename to planning/behavior_path_planner_common/images/drivable_area/hatched_road_markings_drivable_area_expansion.drawio.svg diff --git a/planning/behavior_path_planner/image/drivable_area/sorted_lanes.drawio.svg b/planning/behavior_path_planner_common/images/drivable_area/sorted_lanes.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/drivable_area/sorted_lanes.drawio.svg rename to planning/behavior_path_planner_common/images/drivable_area/sorted_lanes.drawio.svg diff --git a/planning/behavior_path_planner/image/path_safety_checker/extended_polygons.drawio.svg b/planning/behavior_path_planner_common/images/path_safety_checker/extended_polygons.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/path_safety_checker/extended_polygons.drawio.svg rename to planning/behavior_path_planner_common/images/path_safety_checker/extended_polygons.drawio.svg diff --git a/planning/behavior_path_planner/image/path_safety_checker/front_object.drawio.svg b/planning/behavior_path_planner_common/images/path_safety_checker/front_object.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/path_safety_checker/front_object.drawio.svg rename to planning/behavior_path_planner_common/images/path_safety_checker/front_object.drawio.svg diff --git a/planning/behavior_path_planner/image/path_safety_checker/safety_check_flow.drawio.svg b/planning/behavior_path_planner_common/images/path_safety_checker/safety_check_flow.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/path_safety_checker/safety_check_flow.drawio.svg rename to planning/behavior_path_planner_common/images/path_safety_checker/safety_check_flow.drawio.svg diff --git a/planning/behavior_path_planner/image/path_shifter.png b/planning/behavior_path_planner_common/images/path_shifter/path_shifter.png similarity index 100% rename from planning/behavior_path_planner/image/path_shifter.png rename to planning/behavior_path_planner_common/images/path_shifter/path_shifter.png diff --git a/planning/behavior_path_planner/image/turn_signal_decider/activation_distance.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/activation_distance.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/activation_distance.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/activation_distance.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/avoidance_and_turn.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/avoidance_and_turn.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn2.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/avoidance_and_turn2.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn2.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/avoidance_and_turn2.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/avoidance_first_section.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/avoidance_first_section.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/avoidance_first_section.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/avoidance_first_section.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/avoidance_second_section.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/avoidance_second_section.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/avoidance_second_section.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/avoidance_second_section.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/continuous_turns.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/continuous_turns.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/continuous_turns.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/continuous_turns.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/lane_change.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/lane_change.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/lane_change.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/lane_change.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/lane_change_and_turn.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/lane_change_and_turn.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/lane_change_and_turn.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/lane_change_and_turn.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/left_right_turn.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/left_right_turn.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/left_right_turn.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/left_right_turn.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pattern1.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/pattern1.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/pattern1.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/pattern1.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pattern2.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/pattern2.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/pattern2.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/pattern2.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pattern3.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/pattern3.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/pattern3.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/pattern3.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pattern4.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/pattern4.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/pattern4.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/pattern4.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pattern5.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/pattern5.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/pattern5.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/pattern5.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pull_out.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/pull_out.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/pull_out.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/pull_out.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pull_over.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/pull_over.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/pull_over.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/pull_over.drawio.svg diff --git a/planning/behavior_path_planner/image/turn_signal_decider/sections_definition.drawio.svg b/planning/behavior_path_planner_common/images/turn_signal_decider/sections_definition.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/turn_signal_decider/sections_definition.drawio.svg rename to planning/behavior_path_planner_common/images/turn_signal_decider/sections_definition.drawio.svg diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_side_shift_design.md b/planning/behavior_path_side_shift_module/README.md similarity index 100% rename from planning/behavior_path_planner/docs/behavior_path_planner_side_shift_design.md rename to planning/behavior_path_side_shift_module/README.md diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md b/planning/behavior_path_start_planner_module/README.md similarity index 96% rename from planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md rename to planning/behavior_path_start_planner_module/README.md index 28a1db649cf04..1a730212f828b 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md +++ b/planning/behavior_path_start_planner_module/README.md @@ -8,11 +8,11 @@ This module is activated when a new route is received. Use cases are as follows - start smoothly from the current ego position to centerline. - ![case1](../image/start_from_road_lane.drawio.svg) + ![case1](./images/start_from_road_lane.drawio.svg) - pull out from the side of the road lane to centerline. - ![case2](../image/start_from_road_side.drawio.svg) + ![case2](./images/start_from_road_side.drawio.svg) - pull out from the shoulder lane to the road lane centerline. - ![case3](../image/start_from_road_shoulder.drawio.svg) + ![case3](./images/start_from_road_shoulder.drawio.svg) ## Design @@ -78,14 +78,14 @@ PullOutPath --o PullOutPlannerBase 2. Calculate object's polygon 3. If a distance between the footprint and the polygon is lower than the threshold (default: `1.0 m`), that is judged as a unsafe path -![pull_out_collision_check](../image/pull_out_collision_check.drawio.svg) +![pull_out_collision_check](./images/pull_out_collision_check.drawio.svg) ## Safety check with dynamic obstacles ### **Basic concept of safety check against dynamic obstacles** This is based on the concept of RSS. For the logic used, refer to the link below. -See [safety check feature explanation](../docs/behavior_path_planner_safety_check.md) +See [safety check feature explanation](../behavior_path_planner_common/docs/behavior_path_planner_safety_check.md) ### **Collision check performed range** @@ -103,7 +103,7 @@ Since there's a stop at the midpoint during the shift, this becomes the endpoint During backward movement, no safety check is performed. Safety check begins at the point where the backward movement ends. -![collision_check_range](../image/start_planner/collision_check_range.drawio.svg) +![collision_check_range](./images/collision_check_range.drawio.svg) ### **Ego vehicle's velocity planning** @@ -198,7 +198,7 @@ Pull out distance is calculated by the speed, lateral deviation, and the lateral - In the section between merge start and end, path is shifted by a method that is used to generate avoidance path (four segmental constant jerk polynomials) - Combine this path with center line of road lane -![shift_pull_out](../image/shift_pull_out.drawio.svg) +![shift_pull_out](./images/shift_pull_out.drawio.svg) [shift pull out video](https://user-images.githubusercontent.com/39142679/187872468-6d5057ee-e039-499b-afc7-fe0dc8052a6b.mp4) @@ -220,7 +220,7 @@ Pull out distance is calculated by the speed, lateral deviation, and the lateral Generate two arc paths with discontinuous curvature. Ego-vehicle stops once in the middle of the path to control the steer on the spot. See also [[1]](https://www.sciencedirect.com/science/article/pii/S1474667015347431) for details of the algorithm. -![geometric_pull_out](../image/geometric_pull_out.drawio.svg) +![geometric_pull_out](./images/geometric_pull_out.drawio.svg) [geometric pull out video](https://user-images.githubusercontent.com/39142679/181024707-3e7ca5ee-62de-4334-b9e9-ded313de1ea1.mp4) @@ -239,7 +239,7 @@ See also [[1]](https://www.sciencedirect.com/science/article/pii/S14746670153474 If a safe path cannot be generated from the current position, search backwards for a pull out start point at regular intervals(default: `2.0`). -![pull_out_after_back](../image/pull_out_after_back.drawio.svg) +![pull_out_after_back](./images/pull_out_after_back.drawio.svg) [pull out after backward driving video](https://user-images.githubusercontent.com/39142679/181025149-8fb9fb51-9b8f-45c4-af75-27572f4fba78.mp4) @@ -257,7 +257,7 @@ If a safe path cannot be generated from the current position, search backwards f ### **freespace pull out** If the vehicle gets stuck with pull out along lanes, execute freespace pull out. -To run this feature, you need to set `parking_lot` to the map, `activate_by_scenario` of [costmap_generator](../../costmap_generator/README.md) to `false` and `enable_freespace_planner` to `true` +To run this feature, you need to set `parking_lot` to the map, `activate_by_scenario` of [costmap_generator](../costmap_generator/README.md) to `false` and `enable_freespace_planner` to `true` @@ -276,4 +276,4 @@ To run this feature, you need to set `parking_lot` to the map, `activate_by_scen | end_pose_search_end_distance | [m] | double | distance from ego to the end point of the search for the end point in the freespace_pull_out driving lane | 30.0 | | end_pose_search_interval | [m] | bool | interval to search for the end point in the freespace_pull_out driving lane | 2.0 | -See [freespace_planner](../../freespace_planner/README.md) for other parameters. +See [freespace_planner](../freespace_planner/README.md) for other parameters. diff --git a/planning/behavior_path_planner/image/start_planner/collision_check_range.drawio.svg b/planning/behavior_path_start_planner_module/images/collision_check_range.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/start_planner/collision_check_range.drawio.svg rename to planning/behavior_path_start_planner_module/images/collision_check_range.drawio.svg diff --git a/planning/behavior_path_planner/image/geometric_pull_out.drawio.svg b/planning/behavior_path_start_planner_module/images/geometric_pull_out.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/geometric_pull_out.drawio.svg rename to planning/behavior_path_start_planner_module/images/geometric_pull_out.drawio.svg diff --git a/planning/behavior_path_planner/image/pull_out_after_back.drawio.svg b/planning/behavior_path_start_planner_module/images/pull_out_after_back.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/pull_out_after_back.drawio.svg rename to planning/behavior_path_start_planner_module/images/pull_out_after_back.drawio.svg diff --git a/planning/behavior_path_planner/image/pull_out_collision_check.drawio.svg b/planning/behavior_path_start_planner_module/images/pull_out_collision_check.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/pull_out_collision_check.drawio.svg rename to planning/behavior_path_start_planner_module/images/pull_out_collision_check.drawio.svg diff --git a/planning/behavior_path_planner/image/shift_pull_out.drawio.svg b/planning/behavior_path_start_planner_module/images/shift_pull_out.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/shift_pull_out.drawio.svg rename to planning/behavior_path_start_planner_module/images/shift_pull_out.drawio.svg diff --git a/planning/behavior_path_planner/image/start_from_road_lane.drawio.svg b/planning/behavior_path_start_planner_module/images/start_from_road_lane.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/start_from_road_lane.drawio.svg rename to planning/behavior_path_start_planner_module/images/start_from_road_lane.drawio.svg diff --git a/planning/behavior_path_planner/image/start_from_road_shoulder.drawio.svg b/planning/behavior_path_start_planner_module/images/start_from_road_shoulder.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/start_from_road_shoulder.drawio.svg rename to planning/behavior_path_start_planner_module/images/start_from_road_shoulder.drawio.svg diff --git a/planning/behavior_path_planner/image/start_from_road_side.drawio.svg b/planning/behavior_path_start_planner_module/images/start_from_road_side.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/start_from_road_side.drawio.svg rename to planning/behavior_path_start_planner_module/images/start_from_road_side.drawio.svg From 57d2a49c1faa9acd0b1da331d67b891580d45c8b Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 27 Dec 2023 00:46:44 +0900 Subject: [PATCH 148/276] refactor(bpp): remove virtual qualifier (#5968) * refactor(bpp): hide module state as private Signed-off-by: satoshi-ota * fix(bpp): fix logger level Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../interface.hpp | 5 +- .../src/interface.cpp | 4 +- .../interface/scene_module_interface.hpp | 182 +++++++++--------- 3 files changed, 97 insertions(+), 94 deletions(-) diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp index f1072b87755b0..4e741a2b3db2c 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp @@ -67,7 +67,10 @@ class LaneChangeInterface : public SceneModuleInterface bool isExecutionReady() const override; - bool isRootLaneletToBeUpdated() const override { return current_state_ == ModuleStatus::SUCCESS; } + bool isRootLaneletToBeUpdated() const override + { + return getCurrentStatus() == ModuleStatus::SUCCESS; + } void updateData() override; diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index e5aa8e06ece4c..850aecf9a3b54 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -64,7 +64,7 @@ void LaneChangeInterface::processOnExit() bool LaneChangeInterface::isExecutionRequested() const { - if (current_state_ == ModuleStatus::RUNNING) { + if (getCurrentStatus() == ModuleStatus::RUNNING) { return true; } @@ -359,7 +359,7 @@ MarkerArray LaneChangeInterface::getModuleVirtualWall() return marker; } - if (isWaitingApproval() || current_state_ != ModuleStatus::RUNNING) { + if (isWaitingApproval() || getCurrentStatus() != ModuleStatus::RUNNING) { return marker; } const auto & start_pose = module_type_->getLaneChangePath().info.lane_changing_start; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index 82002ead9a2d1..1a8c8241abe1a 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -111,21 +111,6 @@ class SceneModuleInterface virtual void acceptVisitor(const std::shared_ptr & visitor) const = 0; - /** - * @brief Set the current_state_ based on updateState output. - */ - virtual void updateCurrentState() - { - const auto print = [this](const auto & from, const auto & to) { - RCLCPP_DEBUG( - getLogger(), "[%s] Transit from %s to %s.", name_.c_str(), from.data(), to.data()); - }; - - const auto & from = current_state_; - current_state_ = updateState(); - print(magic_enum::enum_name(from), magic_enum::enum_name(current_state_)); - } - /** * @brief Return true if the module has request for execution (not necessarily feasible) */ @@ -159,6 +144,21 @@ class SceneModuleInterface return isWaitingApproval() ? planWaitingApproval() : plan(); } + /** + * @brief Set the current_state_ based on updateState output. + */ + void updateCurrentState() + { + const auto print = [this](const auto & from, const auto & to) { + RCLCPP_DEBUG( + getLogger(), "[%s] Transit from %s to %s.", name_.c_str(), from.data(), to.data()); + }; + + const auto & from = current_state_; + current_state_ = updateState(); + print(magic_enum::enum_name(from), magic_enum::enum_name(current_state_)); + } + /** * @brief Called on the first time when the module goes into RUNNING. */ @@ -362,8 +362,84 @@ class SceneModuleInterface return existApprovedRequest(); } + /** + * @brief Return SUCCESS if plan is not needed or plan is successfully finished, + * FAILURE if plan has failed, RUNNING if plan is on going. + * These condition is to be implemented in each modules. + */ + ModuleStatus updateState() + { + auto log_debug_throttled = [&](std::string_view message) -> void { + RCLCPP_DEBUG(getLogger(), "%s", message.data()); + }; + if (current_state_ == ModuleStatus::IDLE) { + if (canTransitIdleToRunningState()) { + log_debug_throttled("transiting from IDLE to RUNNING"); + return ModuleStatus::RUNNING; + } + + log_debug_throttled("transiting from IDLE to IDLE"); + return ModuleStatus::IDLE; + } + + if (current_state_ == ModuleStatus::RUNNING) { + if (canTransitSuccessState()) { + log_debug_throttled("transiting from RUNNING to SUCCESS"); + return ModuleStatus::SUCCESS; + } + + if (canTransitFailureState()) { + log_debug_throttled("transiting from RUNNING to FAILURE"); + return ModuleStatus::FAILURE; + } + + if (canTransitWaitingApprovalState()) { + log_debug_throttled("transiting from RUNNING to WAITING_APPROVAL"); + return ModuleStatus::WAITING_APPROVAL; + } + + log_debug_throttled("transiting from RUNNING to RUNNING"); + return ModuleStatus::RUNNING; + } + + if (current_state_ == ModuleStatus::WAITING_APPROVAL) { + if (canTransitSuccessState()) { + log_debug_throttled("transiting from WAITING_APPROVAL to SUCCESS"); + return ModuleStatus::SUCCESS; + } + + if (canTransitFailureState()) { + log_debug_throttled("transiting from WAITING_APPROVAL to FAILURE"); + return ModuleStatus::FAILURE; + } + + if (canTransitWaitingApprovalToRunningState()) { + log_debug_throttled("transiting from WAITING_APPROVAL to RUNNING"); + return ModuleStatus::RUNNING; + } + + log_debug_throttled("transiting from WAITING_APPROVAL to WAITING APPROVAL"); + return ModuleStatus::WAITING_APPROVAL; + } + + if (current_state_ == ModuleStatus::SUCCESS) { + log_debug_throttled("already SUCCESS"); + return ModuleStatus::SUCCESS; + } + + if (current_state_ == ModuleStatus::FAILURE) { + log_debug_throttled("already FAILURE"); + return ModuleStatus::FAILURE; + } + + log_debug_throttled("already IDLE"); + return ModuleStatus::IDLE; + } + std::string name_; + ModuleStatus current_state_{ModuleStatus::IDLE}; + BehaviorModuleOutput previous_module_output_; StopReason stop_reason_; @@ -442,80 +518,6 @@ class SceneModuleInterface } } - /** - * @brief Return SUCCESS if plan is not needed or plan is successfully finished, - * FAILURE if plan has failed, RUNNING if plan is on going. - * These condition is to be implemented in each modules. - */ - virtual ModuleStatus updateState() - { - auto log_debug_throttled = [&](std::string_view message) -> void { - RCLCPP_WARN(getLogger(), "%s", message.data()); - }; - if (current_state_ == ModuleStatus::IDLE) { - if (canTransitIdleToRunningState()) { - log_debug_throttled("transiting from IDLE to RUNNING"); - return ModuleStatus::RUNNING; - } - - log_debug_throttled("transiting from IDLE to IDLE"); - return ModuleStatus::IDLE; - } - - if (current_state_ == ModuleStatus::RUNNING) { - if (canTransitSuccessState()) { - log_debug_throttled("transiting from RUNNING to SUCCESS"); - return ModuleStatus::SUCCESS; - } - - if (canTransitFailureState()) { - log_debug_throttled("transiting from RUNNING to FAILURE"); - return ModuleStatus::FAILURE; - } - - if (canTransitWaitingApprovalState()) { - log_debug_throttled("transiting from RUNNING to WAITING_APPROVAL"); - return ModuleStatus::WAITING_APPROVAL; - } - - log_debug_throttled("transiting from RUNNING to RUNNING"); - return ModuleStatus::RUNNING; - } - - if (current_state_ == ModuleStatus::WAITING_APPROVAL) { - if (canTransitSuccessState()) { - log_debug_throttled("transiting from WAITING_APPROVAL to SUCCESS"); - return ModuleStatus::SUCCESS; - } - - if (canTransitFailureState()) { - log_debug_throttled("transiting from WAITING_APPROVAL to FAILURE"); - return ModuleStatus::FAILURE; - } - - if (canTransitWaitingApprovalToRunningState()) { - log_debug_throttled("transiting from WAITING_APPROVAL to RUNNING"); - return ModuleStatus::RUNNING; - } - - log_debug_throttled("transiting from WAITING_APPROVAL to WAITING APPROVAL"); - return ModuleStatus::WAITING_APPROVAL; - } - - if (current_state_ == ModuleStatus::SUCCESS) { - log_debug_throttled("already SUCCESS"); - return ModuleStatus::SUCCESS; - } - - if (current_state_ == ModuleStatus::FAILURE) { - log_debug_throttled("already FAILURE"); - return ModuleStatus::FAILURE; - } - - log_debug_throttled("already IDLE"); - return ModuleStatus::IDLE; - } - /** * @brief Return true if the activation command is received from the RTC interface. * If no RTC interface is registered, return true. @@ -610,8 +612,6 @@ class SceneModuleInterface PlanResult path_candidate_; PlanResult path_reference_; - ModuleStatus current_state_{ModuleStatus::IDLE}; - std::unordered_map> rtc_interface_ptr_map_; std::unordered_map> From f7661703fe2ce33a86a288b3c3df7fec94328db8 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 27 Dec 2023 02:01:42 +0900 Subject: [PATCH 149/276] feat(start_planner): add static collision check end polygon marker (#5955) feat(start_planner): add static collision check end polygon Signed-off-by: kosuke55 --- .../src/start_planner_module.cpp | 30 +++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index c9fa15d855268..30dd48ab383b9 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -1283,6 +1283,7 @@ void StartPlannerModule::setDebugData() const using tier4_autoware_utils::createDefaultMarker; using tier4_autoware_utils::createMarkerColor; using tier4_autoware_utils::createMarkerScale; + using visualization_msgs::msg::Marker; const auto life_time = rclcpp::Duration::from_seconds(1.5); auto add = [&](MarkerArray added) { @@ -1299,6 +1300,35 @@ void StartPlannerModule::setDebugData() const add(createPathMarkerArray(getFullPath(), "full_path", 0, 0.0, 0.5, 0.9)); add(createPathMarkerArray(status_.backward_path, "backward_driving_path", 0, 0.0, 0.9, 0.0)); + // visualize collision_check_end_pose and footprint + { + const auto local_footprint = createVehicleFootprint(vehicle_info_); + const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose( + getFullPath().points, status_.pull_out_path.end_pose.position, + parameters_->collision_check_distance_from_end); + if (collision_check_end_pose) { + add(createPoseMarkerArray( + *collision_check_end_pose, "static_collision_check_end_pose", 0, 1.0, 0.0, 0.0)); + auto marker = tier4_autoware_utils::createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "static_collision_check_end_polygon", 0, + Marker::LINE_LIST, tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1), + tier4_autoware_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999)); + const auto footprint = transformVector( + local_footprint, tier4_autoware_utils::pose2transform(*collision_check_end_pose)); + const double ego_z = planner_data_->self_odometry->pose.pose.position.z; + for (size_t i = 0; i < footprint.size(); i++) { + const auto & current_point = footprint.at(i); + const auto & next_point = footprint.at((i + 1) % footprint.size()); + marker.points.push_back( + tier4_autoware_utils::createPoint(current_point.x(), current_point.y(), ego_z)); + marker.points.push_back( + tier4_autoware_utils::createPoint(next_point.x(), next_point.y(), ego_z)); + } + marker.lifetime = life_time; + debug_marker_.markers.push_back(marker); + } + } + // safety check if (parameters_->safety_check_params.enable_safety_check) { if (start_planner_data_.ego_predicted_path.size() > 0) { From e90bb3e17f2a4990afcb71ef973da437450638ea Mon Sep 17 00:00:00 2001 From: santosh-interplai <141418883+santosh-interplai@users.noreply.github.com> Date: Wed, 27 Dec 2023 05:08:42 +0530 Subject: [PATCH 150/276] refactor(updated-map-based-prediction): rework parameters (#5656) updated-schema-file Signed-off-by: santosh-interplai --- .../schema/map_based_pediction.schema.json | 169 ++++++++++++++++++ 1 file changed, 169 insertions(+) create mode 100644 perception/map_based_prediction/schema/map_based_pediction.schema.json diff --git a/perception/map_based_prediction/schema/map_based_pediction.schema.json b/perception/map_based_prediction/schema/map_based_pediction.schema.json new file mode 100644 index 0000000000000..8ddb122ebb56e --- /dev/null +++ b/perception/map_based_prediction/schema/map_based_pediction.schema.json @@ -0,0 +1,169 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Map Based Prediction", + "type": "object", + "definitions": { + "map_based_prediction": { + "type": "object", + "properties": { + "enable_delay_compensation": { + "type": "boolean", + "default": true, + "description": "flag to enable the time delay compensation for the position of the object" + }, + "prediction_time_horizon": { + "type": "number", + "default": "10.0", + "description": "predict time duration for predicted path" + }, + "lateral_control_time_horizon": { + "type": "number", + "default": "5.0", + "description": "time duration for predicted path will reach the reference path (mostly center of the lane)" + }, + "prediction_sampling_delta_time": { + "type": "number", + "default": "0.5", + "description": "sampling time for points in predicted path" + }, + "min_velocity_for_map_based_prediction": { + "type": "number", + "default": 1.39, + "description": "apply map-based prediction to the objects with higher velocity than this value" + }, + "min_crosswalk_user_velocity": { + "type": "number", + "default": 1.39, + "description": "minimum velocity use in path prediction for crosswalk users" + }, + "max_crosswalk_user_delta_yaw_threshold_for_lanelet": { + "type": "number", + "default": 0.785, + "description": "maximum yaw difference between crosswalk user and lanelet to use in path prediction for crosswalk users" + }, + "dist_threshold_for_searching_lanelet": { + "type": "number", + "default": 3.0, + "description": "The threshold of the angle used when searching for the lane to which the object belongs " + }, + "delta_yaw_threshold_for_searching_lanelet": { + "type": "number", + "default": 0.785, + "description": "The threshold of the distance used when searching for the lane to which the object belongs" + }, + "sigma_lateral_offset": { + "type": "number", + "default": 0.5, + "description": "Standard deviation for lateral position of objects " + }, + "sigma_yaw_angle_deg": { + "type": "number", + "default": 5.0, + "description": "Standard deviation yaw angle of objects " + }, + "object_buffer_time_length": { + "type": "number", + "default": 2.0, + "description": "Time span of object history to store the information" + }, + "history_time_length": { + "type": "number", + "default": 1.0, + "description": "Time span of object information used for prediction" + }, + "prediction_time_horizon_rate_for_validate_shoulder_lane_length": { + "type": "number", + "default": 0.8, + "description": "prediction path will disabled when the estimated path length exceeds lanelet length. This parameter control the estimated path length" + }, + "lane_change_detection": { + "type": "object", + "properties": { + "time_to_change_lane": { + "type": "object", + "properties": { + "dist_threshold_for_lane_change_detection": { + "type": "number", + "default": 1.0 + }, + "time_threshold_for_lane_change_detection": { + "type": "number", + "default": 5.0 + }, + "cutoff_freq_of_velocity_for_lane_change_detection": { + "type": "number", + "default": 0.1 + } + }, + "required": [ + "dist_threshold_for_lane_change_detection", + "time_threshold_for_lane_change_detection", + "cutoff_freq_of_velocity_for_lane_change_detection" + ] + }, + "lat_diff_distance": { + "type": "object", + "properties": { + "dist_ratio_threshold_to_left_bound": { + "type": "number", + "default": -0.5 + }, + "dist_ratio_threshold_to_right_bound": { + "type": "number", + "default": 0.5 + }, + "diff_dist_threshold_to_left_bound": { + "type": "number", + "default": 0.29 + }, + "diff_dist_threshold_to_right_bound": { + "type": "number", + "default": -0.29 + } + }, + "required": [ + "dist_ratio_threshold_to_left_bound", + "dist_ratio_threshold_to_right_bound", + "diff_dist_threshold_to_left_bound", + "diff_dist_threshold_to_right_bound" + ] + } + } + }, + "reference_path_resolution": { + "type": "number", + "default": 0.5, + "description": "Standard deviation for lateral position of objects " + } + }, + "required": [ + "enable_delay_compensation", + "prediction_time_horizon", + "lateral_control_time_horizon", + "prediction_sampling_delta_time", + "min_velocity_for_map_based_prediction", + "min_crosswalk_user_velocity", + "max_crosswalk_user_delta_yaw_threshold_for_lanelet", + "dist_threshold_for_searching_lanelet", + "delta_yaw_threshold_for_searching_lanelet", + "sigma_lateral_offset", + "sigma_yaw_angle_deg", + "object_buffer_time_length", + "history_time_length", + "prediction_time_horizon_rate_for_validate_shoulder_lane_length" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/map_based_prediction" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From 00521d9994b7ae686cd285b47382118668b27800 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 27 Dec 2023 09:19:30 +0900 Subject: [PATCH 151/276] fix(lane_change): change logger level to DEBUG (#5969) Signed-off-by: Muhammad Zulfaqar Azmi --- .../src/scene.cpp | 8 ++++---- .../behavior_path_lane_change_module/src/interface.cpp | 6 +++--- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 7d36c06a3482e..66d11d044966e 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -54,7 +54,7 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const const auto & data = avoidance_data_; if (data.target_objects.empty()) { - RCLCPP_WARN(logger_, "no empty objects"); + RCLCPP_DEBUG(logger_, "no empty objects"); return false; } @@ -74,13 +74,13 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const std::accumulate(object_parameters.begin(), object_parameters.end(), 0UL, count_target_object); if (num_of_avoidance_targets < 1) { - RCLCPP_WARN(logger_, "no avoidance target"); + RCLCPP_DEBUG(logger_, "no avoidance target"); return false; } const auto current_lanes = getCurrentLanes(); if (current_lanes.empty()) { - RCLCPP_WARN(logger_, "no empty lanes"); + RCLCPP_DEBUG(logger_, "no empty lanes"); return false; } @@ -109,7 +109,7 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const const auto maximum_avoid_distance = avoidance_helper_->getMaxAvoidanceDistance(shift_length); - RCLCPP_WARN( + RCLCPP_DEBUG( logger_, "nearest_object.longitudinal %.3f, minimum_lane_change_length %.3f, maximum_avoid_distance " "%.3f", diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 850aecf9a3b54..22d85a2a1fc2a 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -190,7 +190,7 @@ void LaneChangeInterface::setData(const std::shared_ptr & dat bool LaneChangeInterface::canTransitSuccessState() { auto log_debug_throttled = [&](std::string_view message) -> void { - RCLCPP_WARN(getLogger(), "%s", message.data()); + RCLCPP_DEBUG(getLogger(), "%s", message.data()); }; if (module_type_->specialExpiredCheck() && isWaitingApproval()) { @@ -222,7 +222,7 @@ bool LaneChangeInterface::canTransitSuccessState() bool LaneChangeInterface::canTransitFailureState() { auto log_debug_throttled = [&](std::string_view message) -> void { - RCLCPP_WARN(getLogger(), "%s", message.data()); + RCLCPP_DEBUG(getLogger(), "%s", message.data()); }; log_debug_throttled(__func__); @@ -293,7 +293,7 @@ bool LaneChangeInterface::canTransitIdleToRunningState() setObjectDebugVisualization(); auto log_debug_throttled = [&](std::string_view message) -> void { - RCLCPP_WARN(getLogger(), "%s", message.data()); + RCLCPP_DEBUG(getLogger(), "%s", message.data()); }; log_debug_throttled(__func__); From 8ad4683010c021b3350e5a053a5f18aad2b790ff Mon Sep 17 00:00:00 2001 From: Vincent Richard Date: Wed, 27 Dec 2023 10:05:54 +0900 Subject: [PATCH 152/276] feat(mission_planner): restrict enable_correct_goal_pose to poses within lanelets (#5882) --- .../src/lanelet2_plugins/default_planner.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 673519b6f7a0e..ed364f0987f4f 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -111,7 +111,11 @@ geometry_msgs::msg::Pose get_closest_centerline_pose( vehicle_info_util::VehicleInfo vehicle_info) { lanelet::Lanelet closest_lanelet; - lanelet::utils::query::getClosestLanelet(road_lanelets, point, &closest_lanelet); + if (!lanelet::utils::query::getClosestLaneletWithConstrains( + road_lanelets, point, &closest_lanelet, 0.0)) { + // point is not on any lanelet. + return point; + } const auto refined_center_line = lanelet::utils::generateFineCenterline(closest_lanelet, 1.0); closest_lanelet.setCenterline(refined_center_line); From f5c3d3a37dd7b2714f52478fb1343f7b74a36015 Mon Sep 17 00:00:00 2001 From: Ambroise Vincent Date: Wed, 27 Dec 2023 02:55:10 +0100 Subject: [PATCH 153/276] refactor(json-schema): align schema and config file names (#5798) The schema files need to follow a NODE_NAME.schema.json naming convention and the configuration files need to follow a NODE_NAME*.param.yaml naming convention. It allows to have one schema file per node in a package. Rename files that didn't match this pattern. Signed-off-by: Ambroise Vincent --- ...=> radar_object_fusion_to_detected_object.schema.json} | 4 ++-- ...nner_nodes.schema.json => mission_planner.schema.json} | 4 ++-- system/autoware_auto_msgs_adapter/README.md | 4 ++-- ...yaml => autoware_auto_msgs_adapter_control.param.yaml} | 0 ...ram.yaml => autoware_auto_msgs_adapter_map.param.yaml} | 0 ...l => autoware_auto_msgs_adapter_perception.param.yaml} | 0 ...aml => autoware_auto_msgs_adapter_planning.param.yaml} | 0 .../launch/autoware_auto_msgs_adapter.launch.xml | 8 ++++---- 8 files changed, 10 insertions(+), 10 deletions(-) rename perception/radar_fusion_to_detected_object/schema/{radar_fusion_to_detected_object.schema.json => radar_object_fusion_to_detected_object.schema.json} (97%) rename planning/mission_planner/schema/{mission_planner_nodes.schema.json => mission_planner.schema.json} (96%) rename system/autoware_auto_msgs_adapter/config/{adapter_control.param.yaml => autoware_auto_msgs_adapter_control.param.yaml} (100%) rename system/autoware_auto_msgs_adapter/config/{adapter_map.param.yaml => autoware_auto_msgs_adapter_map.param.yaml} (100%) rename system/autoware_auto_msgs_adapter/config/{adapter_perception.param.yaml => autoware_auto_msgs_adapter_perception.param.yaml} (100%) rename system/autoware_auto_msgs_adapter/config/{adapter_planning.param.yaml => autoware_auto_msgs_adapter_planning.param.yaml} (100%) diff --git a/perception/radar_fusion_to_detected_object/schema/radar_fusion_to_detected_object.schema.json b/perception/radar_fusion_to_detected_object/schema/radar_object_fusion_to_detected_object.schema.json similarity index 97% rename from perception/radar_fusion_to_detected_object/schema/radar_fusion_to_detected_object.schema.json rename to perception/radar_fusion_to_detected_object/schema/radar_object_fusion_to_detected_object.schema.json index 688414df56c1e..69c83503a2220 100644 --- a/perception/radar_fusion_to_detected_object/schema/radar_fusion_to_detected_object.schema.json +++ b/perception/radar_fusion_to_detected_object/schema/radar_object_fusion_to_detected_object.schema.json @@ -3,7 +3,7 @@ "title": "Parameters for Radar Fusion to Detected Object Node", "type": "object", "definitions": { - "radar_fusion_to_detected_object": { + "radar_object_fusion_to_detected_object": { "type": "object", "properties": { "node_params": { @@ -104,7 +104,7 @@ "type": "object", "properties": { "ros__parameters": { - "$ref": "#/definitions/radar_fusion_to_detected_object" + "$ref": "#/definitions/radar_object_fusion_to_detected_object" } }, "required": ["ros__parameters"] diff --git a/planning/mission_planner/schema/mission_planner_nodes.schema.json b/planning/mission_planner/schema/mission_planner.schema.json similarity index 96% rename from planning/mission_planner/schema/mission_planner_nodes.schema.json rename to planning/mission_planner/schema/mission_planner.schema.json index 3d0bdc41c5c34..4e302b703586d 100644 --- a/planning/mission_planner/schema/mission_planner_nodes.schema.json +++ b/planning/mission_planner/schema/mission_planner.schema.json @@ -3,7 +3,7 @@ "title": "Parameters for Mission Planner nodes", "type": "object", "definitions": { - "mission_planner_nodes": { + "mission_planner": { "type": "object", "properties": { "map_frame": { @@ -73,7 +73,7 @@ "type": "object", "properties": { "ros__parameters": { - "$ref": "#/definitions/mission_planner_nodes" + "$ref": "#/definitions/mission_planner" } }, "required": ["ros__parameters"] diff --git a/system/autoware_auto_msgs_adapter/README.md b/system/autoware_auto_msgs_adapter/README.md index 85c2797074f1f..67fabaaa46c9a 100644 --- a/system/autoware_auto_msgs_adapter/README.md +++ b/system/autoware_auto_msgs_adapter/README.md @@ -21,7 +21,7 @@ The `autoware_auto_msgs_adapter` package provides the following capabilities: ## Usage -Customize the adapter configuration by replicating and editing the `adapter_control.param.yaml` file located +Customize the adapter configuration by replicating and editing the `autoware_auto_msgs_adapter_control.param.yaml` file located in the `autoware_auto_msgs_adapter/config` directory. Example configuration: ```yaml @@ -90,7 +90,7 @@ To add a new message pair, - Add a new entry to the [schema/autoware_auto_msgs_adapter.schema.json](schema/autoware_auto_msgs_adapter.schema.json) file in the `definitions:autoware_auto_msgs_adapter:properties:msg_type_target:enum` section. - Learn more about JSON schema usage in [here](https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/parameters/#json-schema). - Create a new config file by replicating and editing: - - [adapter_control.param.yaml](config/adapter_control.param.yaml) + - [autoware_auto_msgs_adapter_control.param.yaml](config/autoware_auto_msgs_adapter_control.param.yaml) - Add a new test file by replicating and editing: - [test_msg_ackermann_control_command.cpp](test/test_msg_ackermann_control_command.cpp) - No need to edit the `CMakeLists.txt` file as it will automatically detect the new test file. diff --git a/system/autoware_auto_msgs_adapter/config/adapter_control.param.yaml b/system/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter_control.param.yaml similarity index 100% rename from system/autoware_auto_msgs_adapter/config/adapter_control.param.yaml rename to system/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter_control.param.yaml diff --git a/system/autoware_auto_msgs_adapter/config/adapter_map.param.yaml b/system/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter_map.param.yaml similarity index 100% rename from system/autoware_auto_msgs_adapter/config/adapter_map.param.yaml rename to system/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter_map.param.yaml diff --git a/system/autoware_auto_msgs_adapter/config/adapter_perception.param.yaml b/system/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter_perception.param.yaml similarity index 100% rename from system/autoware_auto_msgs_adapter/config/adapter_perception.param.yaml rename to system/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter_perception.param.yaml diff --git a/system/autoware_auto_msgs_adapter/config/adapter_planning.param.yaml b/system/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter_planning.param.yaml similarity index 100% rename from system/autoware_auto_msgs_adapter/config/adapter_planning.param.yaml rename to system/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter_planning.param.yaml diff --git a/system/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml b/system/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml index a15c25f38ef3d..58f2fb4e06238 100755 --- a/system/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml +++ b/system/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml @@ -1,9 +1,9 @@ - - - - + + + + From 775583b231f3d0fa8979f458126ea2203b6214c7 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Wed, 27 Dec 2023 11:18:28 +0900 Subject: [PATCH 154/276] feat(crosswalk): add interset makers (#5967) add interest makers Signed-off-by: Yuki Takagi --- .../src/scene_crosswalk.cpp | 26 +++++++++++++++++-- .../src/scene_crosswalk.hpp | 2 +- 2 files changed, 25 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index b8a34bf5a9d00..d10fc35a5a6f4 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -873,7 +873,7 @@ Polygon2d CrosswalkModule::getAttentionArea( std::optional CrosswalkModule::checkStopForStuckVehicles( const PathWithLaneId & ego_path, const std::vector & objects, const std::vector & path_intersects, - const std::optional & stop_pose) const + const std::optional & stop_pose) { const auto & p = planner_param_; @@ -938,6 +938,10 @@ std::optional CrosswalkModule::checkStopForStuckVehicles( continue; } + setObjectsOfInterestData( + object.kinematics.initial_pose_with_covariance.pose, object.shape, ColorName::RED); + + // early return may not appropriate because the nearest in range object should be handled return createStopFactor(*feasible_stop_pose, {obj_pos}); } } @@ -1018,11 +1022,29 @@ void CrosswalkModule::updateObjectState( has_traffic_light, collision_point, object.classification.front().label, planner_param_, crosswalk_.polygon2d().basicPolygon()); + const auto collision_state = object_info_manager_.getCollisionState(obj_uuid); if (collision_point) { - const auto collision_state = object_info_manager_.getCollisionState(obj_uuid); debug_data_.collision_points.push_back( std::make_tuple(obj_uuid, *collision_point, collision_state)); } + + const auto getLabelColor = [](const auto collision_state) { + if (collision_state == CollisionState::YIELD) { + return ColorName::RED; + } else if ( + collision_state == CollisionState::EGO_PASS_FIRST || + collision_state == CollisionState::EGO_PASS_LATER) { + return ColorName::GREEN; + } else if (collision_state == CollisionState::IGNORE) { + return ColorName::GRAY; + } else { + return ColorName::AMBER; + } + }; + + setObjectsOfInterestData( + object.kinematics.initial_pose_with_covariance.pose, object.shape, + getLabelColor(collision_state)); } object_info_manager_.finalize(); } diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 7f020fbe5422c..247907ad2dc80 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -331,7 +331,7 @@ class CrosswalkModule : public SceneModuleInterface std::optional checkStopForStuckVehicles( const PathWithLaneId & ego_path, const std::vector & objects, const std::vector & path_intersects, - const std::optional & stop_pose) const; + const std::optional & stop_pose); std::optional findEgoPassageDirectionAlongPath( const PathWithLaneId & sparse_resample_path) const; From baef124f6e771505839b63f1f36eb33d5b7c40a8 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Wed, 27 Dec 2023 11:29:55 +0900 Subject: [PATCH 155/276] feat(map_based_prediction): prediction with acc constraints (#5960) * WIP add acc constraints to discard paths Signed-off-by: Daniel Sanchez * Add lat acc constraints to predicted paths Signed-off-by: Daniel Sanchez * Delete debug print Signed-off-by: Daniel Sanchez * delete unused var Signed-off-by: Daniel Sanchez * delete unused var Signed-off-by: Daniel Sanchez * WIP Signed-off-by: Daniel Sanchez * make lat acc calculation with yaw rate Signed-off-by: Daniel Sanchez * eliminate debug prints Signed-off-by: Daniel Sanchez * delete unused variable Signed-off-by: Daniel Sanchez * refactor rename function Signed-off-by: Daniel Sanchez * keep a copy of the straightest path in case all paths are cleared Signed-off-by: Daniel Sanchez * refactor and add constraints check parameter Signed-off-by: Daniel Sanchez * update documentation Signed-off-by: Daniel Sanchez * add braces for readability (style guide) Signed-off-by: Daniel Sanchez * fix review issues Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez Signed-off-by: Daniel Sanchez --- perception/map_based_prediction/README.md | 20 ++- .../config/map_based_prediction.param.yaml | 3 + .../map_based_prediction_node.hpp | 125 +++++++++++++++++- .../src/map_based_prediction_node.cpp | 68 +++++++++- 4 files changed, 211 insertions(+), 5 deletions(-) diff --git a/perception/map_based_prediction/README.md b/perception/map_based_prediction/README.md index 6d3d7f5e035a9..ec2f57963332f 100644 --- a/perception/map_based_prediction/README.md +++ b/perception/map_based_prediction/README.md @@ -66,7 +66,7 @@ Lane change logics is illustrated in the figure below.An example of how to tune ### Tuning lane change detection logic -Currently we provide two parameters to tune lane change detection: +Currently we provide three parameters to tune lane change detection: - `dist_threshold_to_bound_`: maximum distance from lane boundary allowed for lane changing vehicle - `time_threshold_to_bound_`: maximum time allowed for lane change vehicle to reach the boundary @@ -124,6 +124,24 @@ See paper [2] for more details. `lateral_control_time_horizon` parameter supports the tuning of the lateral path shape. This parameter is used to calculate the time to reach the reference path. The smaller the value, the more the path will be generated to reach the reference path quickly. (Mostly the center of the lane.) +#### Pruning predicted paths with lateral acceleration constraint + +It is possible to apply a maximum lateral acceleration constraint to generated vehicle paths. This check verifies if it is possible for the vehicle to perform the predicted path without surpassing a lateral acceleration threshold `max_lateral_accel` when taking a curve. If it is not possible, it checks if the vehicle can slow down on time to take the curve with a deceleration of `min_acceleration_before_curve` and comply with the constraint. If that is also not possible, the path is eliminated. + +Currently we provide three parameters to tune the lateral acceleration constraint: + +- `check_lateral_acceleration_constraints_`: to enable the constraint check. +- `max_lateral_accel_`: max acceptable lateral acceleration for predicted paths (absolute value). +- `min_acceleration_before_curve_`: the minimum acceleration the vehicle would theoretically use to slow down before a curve is taken (must be negative). + +You can change these parameters in rosparam in the table below. + +| param name | default value | +| ----------------------------------------- | -------------- | +| `check_lateral_acceleration_constraints_` | `false` [bool] | +| `max_lateral_accel` | `2.0` [m/s^2] | +| `min_acceleration_before_curve` | `-2.0` [m/s^2] | + ### Path prediction for crosswalk users This module treats **Pedestrians** and **Bicycles** as objects using the crosswalk, and outputs prediction path based on map and estimated object's velocity, assuming the object has intention to cross the crosswalk, if the objects satisfies at least one of the following conditions: diff --git a/perception/map_based_prediction/config/map_based_prediction.param.yaml b/perception/map_based_prediction/config/map_based_prediction.param.yaml index 69ff96a263f4b..fe4d2a51ec6f3 100644 --- a/perception/map_based_prediction/config/map_based_prediction.param.yaml +++ b/perception/map_based_prediction/config/map_based_prediction.param.yaml @@ -13,6 +13,9 @@ sigma_yaw_angle_deg: 5.0 #[angle degree] object_buffer_time_length: 2.0 #[s] history_time_length: 1.0 #[s] + check_lateral_acceleration_constraints: false # whether to check if the predicted path complies with lateral acceleration constraints + max_lateral_accel: 2.0 # [m/ss] max acceptable lateral acceleration for predicted vehicle paths + min_acceleration_before_curve: -2.0 # [m/ss] min acceleration a vehicle might take to decelerate before a curve # parameter for shoulder lane prediction prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8 diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index bdd9ad89bc025..02ca62a61717c 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -16,11 +16,15 @@ #define MAP_BASED_PREDICTION__MAP_BASED_PREDICTION_NODE_HPP_ #include "map_based_prediction/path_generator.hpp" +#include "tf2/LinearMath/Quaternion.h" +#include "tier4_autoware_utils/geometry/geometry.hpp" +#include "tier4_autoware_utils/ros/update_param.hpp" #include #include #include +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" #include #include #include @@ -34,6 +38,7 @@ #include #include +#include #include #include #include @@ -99,9 +104,10 @@ using autoware_auto_perception_msgs::msg::PredictedPath; using autoware_auto_perception_msgs::msg::TrackedObject; using autoware_auto_perception_msgs::msg::TrackedObjectKinematics; using autoware_auto_perception_msgs::msg::TrackedObjects; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; using tier4_autoware_utils::StopWatch; using tier4_debug_msgs::msg::StringStamped; - +using TrajectoryPoints = std::vector; class MapBasedPredictionNode : public rclcpp::Node { public: @@ -123,6 +129,11 @@ class MapBasedPredictionNode : public rclcpp::Node std::shared_ptr routing_graph_ptr_; std::shared_ptr traffic_rules_ptr_; + // parameter update + OnSetParametersCallbackHandle::SharedPtr set_param_res_; + rcl_interfaces::msg::SetParametersResult onParam( + const std::vector & parameters); + // Pose Transform Listener tier4_autoware_utils::TransformListener transform_listener_{this}; @@ -160,6 +171,10 @@ class MapBasedPredictionNode : public rclcpp::Node bool consider_only_routable_neighbours_; double reference_path_resolution_; + bool check_lateral_acceleration_constraints_; + double max_lateral_accel_; + double min_acceleration_before_curve_; + // Stop watch StopWatch stop_watch_; @@ -237,6 +252,114 @@ class MapBasedPredictionNode : public rclcpp::Node Maneuver predictObjectManeuverByLatDiffDistance( const TrackedObject & object, const LaneletData & current_lanelet_data, const double object_detected_time); + + // NOTE: This function is copied from the motion_velocity_smoother package. + // TODO(someone): Consolidate functions and move them to a common + inline std::vector calcTrajectoryCurvatureFrom3Points( + const TrajectoryPoints & trajectory, size_t idx_dist) + { + using tier4_autoware_utils::calcCurvature; + using tier4_autoware_utils::getPoint; + + if (trajectory.size() < 3) { + const std::vector k_arr(trajectory.size(), 0.0); + return k_arr; + } + + // if the idx size is not enough, change the idx_dist + const auto max_idx_dist = static_cast(std::floor((trajectory.size() - 1) / 2.0)); + idx_dist = std::max(1ul, std::min(idx_dist, max_idx_dist)); + + if (idx_dist < 1) { + throw std::logic_error("idx_dist less than 1 is not expected"); + } + + // calculate curvature by circle fitting from three points + std::vector k_arr(trajectory.size(), 0.0); + + for (size_t i = 1; i + 1 < trajectory.size(); i++) { + double curvature = 0.0; + const auto p0 = getPoint(trajectory.at(i - std::min(idx_dist, i))); + const auto p1 = getPoint(trajectory.at(i)); + const auto p2 = getPoint(trajectory.at(i + std::min(idx_dist, trajectory.size() - 1 - i))); + try { + curvature = calcCurvature(p0, p1, p2); + } catch (std::exception const & e) { + // ...code that handles the error... + RCLCPP_WARN(rclcpp::get_logger("map_based_prediction"), "%s", e.what()); + if (i > 1) { + curvature = k_arr.at(i - 1); // previous curvature + } else { + curvature = 0.0; + } + } + k_arr.at(i) = curvature; + } + // copy curvatures for the last and first points; + k_arr.at(0) = k_arr.at(1); + k_arr.back() = k_arr.at((trajectory.size() - 2)); + + return k_arr; + } + + inline TrajectoryPoints toTrajectoryPoints(const PredictedPath & path, const double velocity) + { + TrajectoryPoints out_trajectory; + std::for_each( + path.path.begin(), path.path.end(), [&out_trajectory, velocity](const auto & pose) { + TrajectoryPoint p; + p.pose = pose; + p.longitudinal_velocity_mps = velocity; + out_trajectory.push_back(p); + }); + return out_trajectory; + }; + + inline bool isLateralAccelerationConstraintSatisfied( + const TrajectoryPoints & trajectory [[maybe_unused]], const double delta_time) + { + if (trajectory.size() < 3) return true; + const double max_lateral_accel_abs = std::fabs(max_lateral_accel_); + + double arc_length = 0.0; + for (size_t i = 1; i < trajectory.size(); ++i) { + const auto current_pose = trajectory.at(i).pose; + const auto next_pose = trajectory.at(i - 1).pose; + // Compute distance between poses + const double delta_s = std::hypot( + next_pose.position.x - current_pose.position.x, + next_pose.position.y - current_pose.position.y); + arc_length += delta_s; + + // Compute change in heading + tf2::Quaternion q_current, q_next; + tf2::convert(current_pose.orientation, q_current); + tf2::convert(next_pose.orientation, q_next); + double delta_theta = q_current.angleShortestPath(q_next); + // Handle wrap-around + if (delta_theta > M_PI) { + delta_theta -= 2.0 * M_PI; + } else if (delta_theta < -M_PI) { + delta_theta += 2.0 * M_PI; + } + + const double yaw_rate = std::max(delta_theta / delta_time, 1.0E-5); + + const double current_speed = std::abs(trajectory.at(i).longitudinal_velocity_mps); + // Compute lateral acceleration + const double lateral_acceleration = std::abs(current_speed * yaw_rate); + if (lateral_acceleration < max_lateral_accel_abs) continue; + + const double v_curvature_max = std::sqrt(max_lateral_accel_abs / yaw_rate); + const double t = + (v_curvature_max - current_speed) / min_acceleration_before_curve_; // acc is negative + const double distance_to_slow_down = + current_speed * t + 0.5 * min_acceleration_before_curve_ * std::pow(t, 2); + + if (distance_to_slow_down > arc_length) return false; + } + return true; + }; }; } // namespace map_based_prediction diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index f89c83e9c2d5a..0091fc6bc38cb 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -740,6 +740,12 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ sigma_yaw_angle_deg_ = declare_parameter("sigma_yaw_angle_deg"); object_buffer_time_length_ = declare_parameter("object_buffer_time_length"); history_time_length_ = declare_parameter("history_time_length"); + + check_lateral_acceleration_constraints_ = + declare_parameter("check_lateral_acceleration_constraints"); + max_lateral_accel_ = declare_parameter("max_lateral_accel"); + min_acceleration_before_curve_ = declare_parameter("min_acceleration_before_curve"); + { // lane change detection lane_change_detection_method_ = declare_parameter("lane_change_detection.method"); @@ -789,6 +795,25 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ pub_debug_markers_ = this->create_publisher("maneuver", rclcpp::QoS{1}); pub_calculation_time_ = create_publisher("~/debug/calculation_time", 1); + + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&MapBasedPredictionNode::onParam, this, std::placeholders::_1)); +} + +rcl_interfaces::msg::SetParametersResult MapBasedPredictionNode::onParam( + const std::vector & parameters) +{ + using tier4_autoware_utils::updateParam; + + updateParam(parameters, "max_lateral_accel", max_lateral_accel_); + updateParam(parameters, "min_acceleration_before_curve", min_acceleration_before_curve_); + updateParam( + parameters, "check_lateral_acceleration_constraints", check_lateral_acceleration_constraints_); + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + return result; } PredictedObjectKinematics MapBasedPredictionNode::convertToPredictedKinematics( @@ -972,16 +997,53 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt } // Generate Predicted Path std::vector predicted_paths; + double min_avg_curvature = std::numeric_limits::max(); + PredictedPath path_with_smallest_avg_curvature; + for (const auto & ref_path : ref_paths) { PredictedPath predicted_path = path_generator_->generatePathForOnLaneVehicle( yaw_fixed_transformed_object, ref_path.path); - if (predicted_path.path.empty()) { + if (predicted_path.path.empty()) continue; + + if (!check_lateral_acceleration_constraints_) { + predicted_path.confidence = ref_path.probability; + predicted_paths.push_back(predicted_path); continue; } - predicted_path.confidence = ref_path.probability; - predicted_paths.push_back(predicted_path); + + // Check lat. acceleration constraints + const auto trajectory_with_const_velocity = + toTrajectoryPoints(predicted_path, abs_obj_speed); + + if (isLateralAccelerationConstraintSatisfied( + trajectory_with_const_velocity, prediction_sampling_time_interval_)) { + predicted_path.confidence = ref_path.probability; + predicted_paths.push_back(predicted_path); + continue; + } + + // Calculate curvature assuming the trajectory points interval is constant + // In case all paths are deleted, a copy of the straightest path is kept + + constexpr double curvature_calculation_distance = 2.0; + constexpr double points_interval = 1.0; + const size_t idx_dist = static_cast( + std::max(static_cast((curvature_calculation_distance) / points_interval), 1)); + const auto curvature_v = + calcTrajectoryCurvatureFrom3Points(trajectory_with_const_velocity, idx_dist); + if (curvature_v.empty()) { + continue; + } + const auto curvature_avg = + std::accumulate(curvature_v.begin(), curvature_v.end(), 0.0) / curvature_v.size(); + if (curvature_avg < min_avg_curvature) { + min_avg_curvature = curvature_avg; + path_with_smallest_avg_curvature = predicted_path; + path_with_smallest_avg_curvature.confidence = ref_path.probability; + } } + if (predicted_paths.empty()) predicted_paths.push_back(path_with_smallest_avg_curvature); // Normalize Path Confidence and output the predicted object float sum_confidence = 0.0; From 5aeba236b8deac83fcf77f24c0d6aef7429ba80b Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Wed, 27 Dec 2023 06:41:38 +0100 Subject: [PATCH 156/276] fix(radar_fusion_to_detected_object): move headers to a separate directory (#5920) * fix(radar_fusion_to_detected_object): move headers to a separate directory Signed-off-by: Esteve Fernandez * style(pre-commit): autofix * fix: fix header name Signed-off-by: Esteve Fernandez * style(pre-commit): autofix --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../radar_fusion_to_detected_object.hpp | 6 +++--- .../radar_fusion_to_detected_object_node.hpp} | 8 ++++---- .../src/radar_fusion_to_detected_object.cpp | 2 +- .../radar_object_fusion_to_detected_object_node.cpp | 3 +-- 4 files changed, 9 insertions(+), 10 deletions(-) rename perception/radar_fusion_to_detected_object/include/{ => radar_fusion_to_detected_object}/radar_fusion_to_detected_object.hpp (94%) rename perception/radar_fusion_to_detected_object/include/{radar_object_fusion_to_detected_object/radar_object_fusion_to_detected_object_node.hpp => radar_fusion_to_detected_object/radar_fusion_to_detected_object_node.hpp} (89%) diff --git a/perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object.hpp b/perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp similarity index 94% rename from perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object.hpp rename to perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp index b5f2005a84baf..0d2f6fd10a6b6 100644 --- a/perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object.hpp +++ b/perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef RADAR_FUSION_TO_DETECTED_OBJECT_HPP_ -#define RADAR_FUSION_TO_DETECTED_OBJECT_HPP_ +#ifndef RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_HPP_ +#define RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_HPP_ #include "rclcpp/logger.hpp" #include "tier4_autoware_utils/geometry/boost_geometry.hpp" @@ -115,4 +115,4 @@ class RadarFusionToDetectedObject }; } // namespace radar_fusion_to_detected_object -#endif // RADAR_FUSION_TO_DETECTED_OBJECT_HPP_ +#endif // RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_HPP_ diff --git a/perception/radar_fusion_to_detected_object/include/radar_object_fusion_to_detected_object/radar_object_fusion_to_detected_object_node.hpp b/perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object/radar_fusion_to_detected_object_node.hpp similarity index 89% rename from perception/radar_fusion_to_detected_object/include/radar_object_fusion_to_detected_object/radar_object_fusion_to_detected_object_node.hpp rename to perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object/radar_fusion_to_detected_object_node.hpp index 1a90e9f6bd046..837ef45c65c60 100644 --- a/perception/radar_fusion_to_detected_object/include/radar_object_fusion_to_detected_object/radar_object_fusion_to_detected_object_node.hpp +++ b/perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object/radar_fusion_to_detected_object_node.hpp @@ -13,13 +13,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef RADAR_OBJECT_FUSION_TO_DETECTED_OBJECT__RADAR_OBJECT_FUSION_TO_DETECTED_OBJECT_NODE_HPP_ -#define RADAR_OBJECT_FUSION_TO_DETECTED_OBJECT__RADAR_OBJECT_FUSION_TO_DETECTED_OBJECT_NODE_HPP_ +#ifndef RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_NODE_HPP_ +#define RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_NODE_HPP_ #include "message_filters/subscriber.h" #include "message_filters/sync_policies/approximate_time.h" #include "message_filters/synchronizer.h" -#include "radar_fusion_to_detected_object.hpp" +#include "radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp" #include "rclcpp/rclcpp.hpp" #include "autoware_auto_perception_msgs/msg/detected_objects.hpp" @@ -89,4 +89,4 @@ class RadarObjectFusionToDetectedObjectNode : public rclcpp::Node } // namespace radar_fusion_to_detected_object -#endif // RADAR_OBJECT_FUSION_TO_DETECTED_OBJECT__RADAR_OBJECT_FUSION_TO_DETECTED_OBJECT_NODE_HPP_ +#endif // RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_NODE_HPP_ diff --git a/perception/radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp b/perception/radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp index 75684d51039fd..43057e685736c 100644 --- a/perception/radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp +++ b/perception/radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp @@ -13,7 +13,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "radar_fusion_to_detected_object.hpp" +#include "radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp" #include #include diff --git a/perception/radar_fusion_to_detected_object/src/radar_object_fusion_to_detected_object_node/radar_object_fusion_to_detected_object_node.cpp b/perception/radar_fusion_to_detected_object/src/radar_object_fusion_to_detected_object_node/radar_object_fusion_to_detected_object_node.cpp index b233bdf31adc6..23e6d43422fa1 100644 --- a/perception/radar_fusion_to_detected_object/src/radar_object_fusion_to_detected_object_node/radar_object_fusion_to_detected_object_node.cpp +++ b/perception/radar_fusion_to_detected_object/src/radar_object_fusion_to_detected_object_node/radar_object_fusion_to_detected_object_node.cpp @@ -13,8 +13,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "radar_object_fusion_to_detected_object/radar_object_fusion_to_detected_object_node.hpp" - +#include "radar_fusion_to_detected_object/radar_fusion_to_detected_object_node.hpp" #include "rclcpp/rclcpp.hpp" #include From 7a8ba32a2d7f0df8dd0762e156bc9121ff869595 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 27 Dec 2023 17:46:47 +0900 Subject: [PATCH 157/276] feat(multi_object_tracker, radar_object_tracker, tracker_object_merger): add glog to tracker node (#5770) * add glog to multi_object_tracker Signed-off-by: yoshiri * add glog to radar object trakcer Signed-off-by: yoshiri * feat: add glog to tracking object merger Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- perception/multi_object_tracker/CMakeLists.txt | 2 ++ perception/multi_object_tracker/package.xml | 1 + .../multi_object_tracker/src/multi_object_tracker_core.cpp | 5 +++++ perception/radar_object_tracker/CMakeLists.txt | 2 ++ perception/radar_object_tracker/package.xml | 1 + .../radar_object_tracker_node/radar_object_tracker_node.cpp | 5 +++++ perception/tracking_object_merger/CMakeLists.txt | 2 ++ perception/tracking_object_merger/package.xml | 1 + .../src/decorative_tracker_merger.cpp | 6 ++++++ 9 files changed, 25 insertions(+) diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt index 3e379bcfd1cf1..f5fbc8ff950e8 100644 --- a/perception/multi_object_tracker/CMakeLists.txt +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -12,6 +12,7 @@ endif() ### Find Eigen Dependencies find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED) +find_package(glog REQUIRED) include_directories( SYSTEM @@ -40,6 +41,7 @@ ament_auto_add_library(multi_object_tracker_node SHARED target_link_libraries(multi_object_tracker_node Eigen3::Eigen + glog::glog ) rclcpp_components_register_node(multi_object_tracker_node diff --git a/perception/multi_object_tracker/package.xml b/perception/multi_object_tracker/package.xml index e3172dfd22349..3d2e4662f7ea5 100644 --- a/perception/multi_object_tracker/package.xml +++ b/perception/multi_object_tracker/package.xml @@ -15,6 +15,7 @@ autoware_auto_perception_msgs eigen kalman_filter + libgoogle-glog-dev mussp object_recognition_utils rclcpp diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index d28833241bd5f..1d4d50c7eab4c 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -16,6 +16,7 @@ #include +#include #include #include @@ -177,6 +178,10 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { + // glog for debug + google::InitGoogleLogging("multi_object_tracker"); + google::InstallFailureSignalHandler(); + // Create publishers and subscribers detected_object_sub_ = create_subscription( "input", rclcpp::QoS{1}, diff --git a/perception/radar_object_tracker/CMakeLists.txt b/perception/radar_object_tracker/CMakeLists.txt index 54ef7b047bf17..7c1b98c10d14b 100644 --- a/perception/radar_object_tracker/CMakeLists.txt +++ b/perception/radar_object_tracker/CMakeLists.txt @@ -12,6 +12,7 @@ endif() find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED) find_package(nlohmann_json REQUIRED) # for debug +find_package(glog REQUIRED) include_directories( SYSTEM @@ -32,6 +33,7 @@ target_link_libraries(radar_object_tracker_node Eigen3::Eigen yaml-cpp nlohmann_json::nlohmann_json # for debug + glog::glog ) rclcpp_components_register_node(radar_object_tracker_node diff --git a/perception/radar_object_tracker/package.xml b/perception/radar_object_tracker/package.xml index ad71e613c1a18..6939c54b5be75 100644 --- a/perception/radar_object_tracker/package.xml +++ b/perception/radar_object_tracker/package.xml @@ -17,6 +17,7 @@ eigen kalman_filter lanelet2_extension + libgoogle-glog-dev mussp nlohmann-json-dev object_recognition_utils diff --git a/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp b/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp index 6d801302ab6c5..e4b394256101d 100644 --- a/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp +++ b/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp @@ -23,6 +23,7 @@ #include +#include #include #include @@ -194,6 +195,10 @@ RadarObjectTrackerNode::RadarObjectTrackerNode(const rclcpp::NodeOptions & node_ tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { + // glog for debug + google::InitGoogleLogging("radar_object_tracker"); + google::InstallFailureSignalHandler(); + // Create publishers and subscribers detected_object_sub_ = create_subscription( "input", rclcpp::QoS{1}, diff --git a/perception/tracking_object_merger/CMakeLists.txt b/perception/tracking_object_merger/CMakeLists.txt index 5e46b9403462d..9c8e5a321d9be 100644 --- a/perception/tracking_object_merger/CMakeLists.txt +++ b/perception/tracking_object_merger/CMakeLists.txt @@ -6,6 +6,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif() find_package(autoware_cmake REQUIRED) +find_package(glog REQUIRED) autoware_package() @@ -31,6 +32,7 @@ ament_auto_add_library(decorative_tracker_merger_node SHARED target_link_libraries(decorative_tracker_merger_node Eigen3::Eigen + glog::glog ) rclcpp_components_register_node(decorative_tracker_merger_node diff --git a/perception/tracking_object_merger/package.xml b/perception/tracking_object_merger/package.xml index d74a8449b20e6..58184c090a1e1 100644 --- a/perception/tracking_object_merger/package.xml +++ b/perception/tracking_object_merger/package.xml @@ -14,6 +14,7 @@ autoware_auto_perception_msgs eigen + libgoogle-glog-dev mussp object_recognition_utils rclcpp diff --git a/perception/tracking_object_merger/src/decorative_tracker_merger.cpp b/perception/tracking_object_merger/src/decorative_tracker_merger.cpp index 47a333691eabf..d2bc643a8eec1 100644 --- a/perception/tracking_object_merger/src/decorative_tracker_merger.cpp +++ b/perception/tracking_object_merger/src/decorative_tracker_merger.cpp @@ -20,6 +20,8 @@ #include +#include + #include #include @@ -85,6 +87,10 @@ DecorativeTrackerMergerNode::DecorativeTrackerMergerNode(const rclcpp::NodeOptio tf_buffer_(get_clock()), tf_listener_(tf_buffer_) { + // glog for debug + google::InitGoogleLogging("decorative_object_merger_node"); + google::InstallFailureSignalHandler(); + // Subscriber sub_main_objects_ = create_subscription( "input/main_object", rclcpp::QoS{1}, From 8586a15f721e985f3a39ba64e4af2f4e86273cbd Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 27 Dec 2023 18:04:04 +0900 Subject: [PATCH 158/276] feat(start_planner): visualize stop line for safety check feature (#5974) assign stop_pose_ to visualize stop line Signed-off-by: kyoichi-sugahara --- .../src/goal_planner_module.cpp | 2 +- .../utils/parking_departure/utils.hpp | 2 +- .../src/utils/parking_departure/utils.cpp | 2 +- .../start_planner_module.hpp | 2 +- .../src/start_planner_module.cpp | 13 +++++++------ 5 files changed, 11 insertions(+), 10 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 3a8a17c3b0966..493e7ec57f063 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -798,7 +798,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto stop_path = behavior_path_planner::utils::parking_departure::generateFeasibleStopPath( - current_path, planner_data_, *stop_pose_, parameters_->maximum_deceleration_for_stop, + current_path, planner_data_, stop_pose_, parameters_->maximum_deceleration_for_stop, parameters_->maximum_jerk_for_stop); if (stop_path) { output.path = *stop_path; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp index bdcc9dcb2cc6a..e1f3402e8dfdf 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp @@ -70,7 +70,7 @@ std::pair getPairsTerminalVelocityAndAccel( std::optional generateFeasibleStopPath( PathWithLaneId & current_path, std::shared_ptr planner_data, - geometry_msgs::msg::Pose & stop_pose, const double maximum_deceleration, + std::optional & stop_pose, const double maximum_deceleration, const double maximum_jerk); /** diff --git a/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp b/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp index a7b1df45c8150..97eba861f658a 100644 --- a/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp @@ -126,7 +126,7 @@ std::pair getPairsTerminalVelocityAndAccel( std::optional generateFeasibleStopPath( PathWithLaneId & current_path, std::shared_ptr planner_data, - geometry_msgs::msg::Pose & stop_pose, const double maximum_deceleration, + std::optional & stop_pose, const double maximum_deceleration, const double maximum_jerk) { if (current_path.points.empty()) { diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index a143f34ead649..055a46e0bbeae 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -68,7 +68,7 @@ struct PullOutStatus Pose pull_out_start_pose{}; bool prev_is_safe_dynamic_objects{false}; std::shared_ptr prev_stop_path_after_approval{nullptr}; - bool has_stop_point{false}; + std::optional stop_pose{std::nullopt}; PullOutStatus() {} }; diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 30dd48ab383b9..af2c063204cc9 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -371,11 +371,11 @@ BehaviorModuleOutput StartPlannerModule::plan() incrementPathIndex(); } - if (!status_.is_safe_dynamic_objects && !isWaitingApproval() && !status_.has_stop_point) { + if (!status_.is_safe_dynamic_objects && !isWaitingApproval() && !status_.stop_pose) { auto current_path = getCurrentPath(); const auto stop_path = behavior_path_planner::utils::parking_departure::generateFeasibleStopPath( - current_path, planner_data_, *stop_pose_, parameters_->maximum_deceleration_for_stop, + current_path, planner_data_, stop_pose_, parameters_->maximum_deceleration_for_stop, parameters_->maximum_jerk_for_stop); // Insert stop point in the path if needed @@ -384,17 +384,18 @@ BehaviorModuleOutput StartPlannerModule::plan() getLogger(), *clock_, 5000, "Insert stop point in the path because of dynamic objects"); path = *stop_path; status_.prev_stop_path_after_approval = std::make_shared(path); - status_.has_stop_point = true; + status_.stop_pose = stop_pose_; } else { path = current_path; } - } else if (!isWaitingApproval() && status_.has_stop_point) { + } else if (!isWaitingApproval() && status_.stop_pose) { // Delete stop point if conditions are met if (status_.is_safe_dynamic_objects && isStopped()) { - status_.has_stop_point = false; + status_.stop_pose = std::nullopt; path = getCurrentPath(); } path = *status_.prev_stop_path_after_approval; + stop_pose_ = status_.stop_pose; } else { path = getCurrentPath(); } @@ -1419,7 +1420,7 @@ void StartPlannerModule::logPullOutStatus(rclcpp::Logger::Level log_level) const status_.prev_is_safe_dynamic_objects ? "true" : "false"); logFunc(" Driving Forward: %s", status_.driving_forward ? "true" : "false"); logFunc(" Backward Driving Complete: %s", status_.backward_driving_complete ? "true" : "false"); - logFunc(" Has Stop Point: %s", status_.has_stop_point ? "true" : "false"); + logFunc(" Has Stop Pose: %s", status_.stop_pose ? "true" : "false"); logFunc("[Module State]"); logFunc(" isActivated: %s", isActivated() ? "true" : "false"); From 8baea5e9e40361d7364c32618929049cc772f97f Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 27 Dec 2023 19:46:50 +0900 Subject: [PATCH 159/276] fix(intersection): fix private condition (#5975) --- .../src/scene_intersection.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 5909d607f6351..631c03d923da0 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1058,8 +1058,10 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool is_first_conflicting_lane_private = (std::string(first_conflicting_lane.attributeOr("location", "else")).compare("private") == 0); if (stuck_detected) { - if (!(is_first_conflicting_lane_private && - planner_param_.stuck_vehicle.disable_against_private_lane)) { + if ( + is_first_conflicting_lane_private && + planner_param_.stuck_vehicle.disable_against_private_lane) { + // do nothing } else { std::optional stopline_idx = std::nullopt; if (stuck_stopline_idx_opt) { From 78952d679ec56cdb8bdca69eb472d4589f14e437 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 27 Dec 2023 20:16:39 +0900 Subject: [PATCH 160/276] feat(tier4_logging_level_configure_rviz_plugin): add goal/start planner (#5978) Signed-off-by: kosuke55 --- .../config/logger_config.yaml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml index 17955fc5d0b9b..a298967a31af9 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml @@ -38,6 +38,14 @@ Planning: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance + behavior_path_planner_goal_planner: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.goal_planner + + behavior_path_planner_start_planner: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.start_planner + behavior_path_avoidance_by_lane_change: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: lane_change.AVOIDANCE_BY_LANE_CHANGE From 3a2ac224722103cc22f8c071d1fa05e724c2b044 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 27 Dec 2023 23:27:16 +0900 Subject: [PATCH 161/276] refactor(planner_manager): apply clang-tidy (#5981) Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner/planner_manager.hpp | 2 +- .../src/planner_manager.cpp | 57 ++++++++++--------- 2 files changed, 30 insertions(+), 29 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 3ccc92d04025f..8411be45edace 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -435,7 +435,7 @@ class PlannerManager const std::vector & request_modules, const std::shared_ptr & data, const BehaviorModuleOutput & previous_module_output); - std::string getNames(const std::vector & modules) const; + static std::string getNames(const std::vector & modules); std::optional root_lanelet_{std::nullopt}; diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 1c8505c4de1be..cd1b0da702dac 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -130,7 +130,7 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da /** * STEP1: get approved modules' output */ - const auto approved_modules_output = runApprovedModules(data); + auto approved_modules_output = runApprovedModules(data); /** * STEP2: check modules that need to be launched @@ -272,22 +272,22 @@ std::vector PlannerManager::getRequestModules( // if there exists at least one approved module that is simultaneous but not always // executable. (only modules that are either always executable or simultaneous executable can // be added) - conditions.push_back( - {[&](const SceneModulePtr & m) { - return !getManager(m)->isAlwaysExecutableModule() && - getManager(m)->isSimultaneousExecutableAsApprovedModule(); - }, - [&]() { return manager_ptr->isSimultaneousExecutableAsApprovedModule(); }}); + conditions.emplace_back( + [&](const SceneModulePtr & m) { + return !getManager(m)->isAlwaysExecutableModule() && + getManager(m)->isSimultaneousExecutableAsApprovedModule(); + }, + [&]() { return manager_ptr->isSimultaneousExecutableAsApprovedModule(); }); // Condition 3: do not add modules that are not always executable if there exists // at least one approved module that is neither always nor simultaneous executable. // (only modules that are always executable can be added) - conditions.push_back( - {[&](const SceneModulePtr & m) { - return !getManager(m)->isAlwaysExecutableModule() && - !getManager(m)->isSimultaneousExecutableAsApprovedModule(); - }, - [&]() { return false; }}); + conditions.emplace_back( + [&](const SceneModulePtr & m) { + return !getManager(m)->isAlwaysExecutableModule() && + !getManager(m)->isSimultaneousExecutableAsApprovedModule(); + }, + [&]() { return false; }); bool skip_module = false; for (const auto & condition : conditions) { @@ -484,22 +484,22 @@ std::pair PlannerManager::runRequestModule // Condition 3: Only modules that are always executable can be added // if there exists at least one executable module that is neither always nor simultaneous // executable. - conditions.push_back( - {[this](const SceneModulePtr & m) { - return !getManager(m)->isAlwaysExecutableModule() && - !getManager(m)->isSimultaneousExecutableAsCandidateModule(); - }, - [&]() { return false; }}); + conditions.emplace_back( + [this](const SceneModulePtr & m) { + return !getManager(m)->isAlwaysExecutableModule() && + !getManager(m)->isSimultaneousExecutableAsCandidateModule(); + }, + [&]() { return false; }); // Condition 2: Only modules that are either always executable or simultaneous executable can be // added if there exists at least one executable module that is simultaneous but not always // executable. - conditions.push_back( - {[this](const SceneModulePtr & m) { - return !getManager(m)->isAlwaysExecutableModule() && - getManager(m)->isSimultaneousExecutableAsCandidateModule(); - }, - [&]() { return getManager(module_ptr)->isSimultaneousExecutableAsCandidateModule(); }}); + conditions.emplace_back( + [this](const SceneModulePtr & m) { + return !getManager(m)->isAlwaysExecutableModule() && + getManager(m)->isSimultaneousExecutableAsCandidateModule(); + }, + [&]() { return getManager(module_ptr)->isSimultaneousExecutableAsCandidateModule(); }); for (const auto & condition : conditions) { const auto & find_block_module = condition.first; @@ -933,8 +933,9 @@ void PlannerManager::print() const string_stream << "\n" << std::fixed << std::setprecision(1); string_stream << "processing time : "; for (const auto & t : processing_time_) { - string_stream << std::right << "[" << std::setw(max_string_num + 1) << std::left << t.first - << ":" << std::setw(4) << std::right << t.second << "ms]\n" + string_stream << std::right << "[" << std::setw(static_cast(max_string_num) + 1) + << std::left << t.first << ":" << std::setw(4) << std::right << t.second + << "ms]\n" << std::setw(21); } @@ -962,7 +963,7 @@ std::shared_ptr PlannerManager::getDebugMsg() return debug_msg_ptr_; } -std::string PlannerManager::getNames(const std::vector & modules) const +std::string PlannerManager::getNames(const std::vector & modules) { std::stringstream ss; for (const auto & m : modules) { From 4ce3c00176e9917a825e7872da746360550f6397 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 28 Dec 2023 02:58:04 +0900 Subject: [PATCH 162/276] feat(start_planner): visualize refined start pose and start pose candidates with idx (#5984) Add createFootprintMarkerArray function and update StartGoalPlannerData structure Signed-off-by: kyoichi-sugahara --- .../marker_utils/utils.hpp | 10 +++ .../parking_departure/common_module_data.hpp | 3 + .../src/marker_utils/utils.cpp | 65 ++++++++++++------- .../src/start_planner_module.cpp | 34 ++++++++++ 4 files changed, 87 insertions(+), 25 deletions(-) diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp index 1ce3dd3736276..f34c0266ac081 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp @@ -18,6 +18,8 @@ #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" +#include + #include #include #include @@ -56,6 +58,14 @@ inline int64_t bitShift(int64_t original_id) return original_id << (sizeof(int32_t) * 8 / 2); } +void addFootprintMarker( + visualization_msgs::msg::Marker & marker, const geometry_msgs::msg::Pose & pose, + const vehicle_info_util::VehicleInfo & vehicle_info); + +MarkerArray createFootprintMarkerArray( + const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info, + const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b); + MarkerArray createPoseMarkerArray( const Pose & pose, std::string && ns, const int32_t & id, const float & r, const float & g, const float & b); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp index 74f6b843803df..91683f4547659 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp @@ -38,6 +38,9 @@ struct StartGoalPlannerData std::vector ego_predicted_path; // collision check debug map CollisionCheckDebugMap collision_check; + + Pose refined_start_pose; + std::vector start_pose_candidates; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/behavior_path_planner_common/src/marker_utils/utils.cpp index 9e20b9c3f8714..7933c21305432 100644 --- a/planning/behavior_path_planner_common/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/marker_utils/utils.cpp @@ -40,6 +40,45 @@ using tier4_autoware_utils::createMarkerScale; using tier4_autoware_utils::createPoint; using visualization_msgs::msg::Marker; +void addFootprintMarker( + visualization_msgs::msg::Marker & marker, const geometry_msgs::msg::Pose & pose, + const vehicle_info_util::VehicleInfo & vehicle_info) +{ + const double half_width = vehicle_info.vehicle_width_m / 2.0; + const double base_to_front = vehicle_info.vehicle_length_m - vehicle_info.rear_overhang_m; + const double base_to_rear = vehicle_info.rear_overhang_m; + + marker.points.push_back( + tier4_autoware_utils::calcOffsetPose(pose, base_to_front, -half_width, 0.0).position); + marker.points.push_back( + tier4_autoware_utils::calcOffsetPose(pose, base_to_front, half_width, 0.0).position); + marker.points.push_back( + tier4_autoware_utils::calcOffsetPose(pose, -base_to_rear, half_width, 0.0).position); + marker.points.push_back( + tier4_autoware_utils::calcOffsetPose(pose, -base_to_rear, -half_width, 0.0).position); + marker.points.push_back(marker.points.front()); +} + +MarkerArray createFootprintMarkerArray( + const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info, + const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b) +{ + const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now(); + MarkerArray msg; + + Marker marker = createDefaultMarker( + "map", current_time, ns, id, Marker::LINE_STRIP, createMarkerScale(0.2, 0.2, 0.2), + createMarkerColor(r, g, b, 0.999)); + marker.lifetime = rclcpp::Duration::from_seconds(1.5); + + MarkerArray marker_array; + + addFootprintMarker(marker, base_link_pose, vehicle_info); + + msg.markers.push_back(marker); + return msg; +} + MarkerArray createPoseMarkerArray( const Pose & pose, std::string && ns, const int32_t & id, const float & r, const float & g, const float & b) @@ -347,7 +386,6 @@ MarkerArray createPredictedPathMarkerArray( Marker marker = createDefaultMarker( "map", current_time, ns, id, Marker::LINE_STRIP, createMarkerScale(0.1, 0.1, 0.1), - createMarkerColor(r, g, b, 0.999)); marker.lifetime = rclcpp::Duration::from_seconds(1.5); @@ -357,34 +395,11 @@ MarkerArray createPredictedPathMarkerArray( marker.points.clear(); const auto & predicted_path_pose = path.at(i); - const double half_width = vehicle_info.vehicle_width_m / 2.0; - const double base_to_front = vehicle_info.vehicle_length_m - vehicle_info.rear_overhang_m; - const double base_to_rear = vehicle_info.rear_overhang_m; - - marker.points.push_back( - tier4_autoware_utils::calcOffsetPose(predicted_path_pose, base_to_front, -half_width, 0.0) - .position); - marker.points.push_back( - tier4_autoware_utils::calcOffsetPose(predicted_path_pose, base_to_front, half_width, 0.0) - .position); - marker.points.push_back( - tier4_autoware_utils::calcOffsetPose(predicted_path_pose, -base_to_rear, half_width, 0.0) - .position); - marker.points.push_back( - tier4_autoware_utils::calcOffsetPose(predicted_path_pose, -base_to_rear, -half_width, 0.0) - .position); - marker.points.push_back(marker.points.front()); + addFootprintMarker(marker, predicted_path_pose, vehicle_info); marker_array.markers.push_back(marker); } return marker_array; - - marker.points.reserve(path.size()); - for (const auto & point : path) { - marker.points.push_back(point.position); - } - msg.markers.push_back(marker); - return msg; } MarkerArray showPolygon(const CollisionCheckDebugMap & obj_debug_vec, std::string && ns) diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index af2c063204cc9..80c08dea48922 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -816,6 +816,8 @@ void StartPlannerModule::updatePullOutStatus() planWithPriority( start_pose_candidates, *refined_start_pose, goal_pose, parameters_->search_priority); + start_planner_data_.refined_start_pose = *refined_start_pose; + start_planner_data_.start_pose_candidates = start_pose_candidates; const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); @@ -1274,6 +1276,8 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons void StartPlannerModule::setDebugData() const { + using marker_utils::addFootprintMarker; + using marker_utils::createFootprintMarkerArray; using marker_utils::createObjectsMarkerArray; using marker_utils::createPathMarkerArray; using marker_utils::createPoseMarkerArray; @@ -1298,6 +1302,8 @@ void StartPlannerModule::setDebugData() const add(createPoseMarkerArray(status_.pull_out_start_pose, "back_end_pose", 0, 0.9, 0.3, 0.3)); add(createPoseMarkerArray(status_.pull_out_path.start_pose, "start_pose", 0, 0.3, 0.9, 0.3)); add(createPoseMarkerArray(status_.pull_out_path.end_pose, "end_pose", 0, 0.9, 0.9, 0.3)); + add(createFootprintMarkerArray( + start_planner_data_.refined_start_pose, vehicle_info_, "refined_start_pose", 0, 0.9, 0.9, 0.3)); add(createPathMarkerArray(getFullPath(), "full_path", 0, 0.0, 0.5, 0.9)); add(createPathMarkerArray(status_.backward_path, "backward_driving_path", 0, 0.0, 0.9, 0.0)); @@ -1329,6 +1335,34 @@ void StartPlannerModule::setDebugData() const debug_marker_.markers.push_back(marker); } } + // start pose candidates + { + MarkerArray start_pose_footprint_marker_array{}; + MarkerArray start_pose_text_marker_array{}; + const auto purple = createMarkerColor(1.0, 0.0, 1.0, 0.99); + Marker footprint_marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "start_pose_candidates", 0, Marker::LINE_STRIP, + createMarkerScale(0.2, 0.2, 0.2), purple); + Marker text_marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "start_pose_candidates_idx", 0, + visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.3, 0.3, 0.3), purple); + footprint_marker.lifetime = rclcpp::Duration::from_seconds(1.5); + text_marker.lifetime = rclcpp::Duration::from_seconds(1.5); + for (size_t i = 0; i < start_planner_data_.start_pose_candidates.size(); ++i) { + footprint_marker.id = i; + text_marker.id = i; + footprint_marker.points.clear(); + text_marker.text = "idx[" + std::to_string(i) + "]"; + text_marker.pose = start_planner_data_.start_pose_candidates.at(i); + addFootprintMarker( + footprint_marker, start_planner_data_.start_pose_candidates.at(i), vehicle_info_); + start_pose_footprint_marker_array.markers.push_back(footprint_marker); + start_pose_text_marker_array.markers.push_back(text_marker); + } + + add(start_pose_footprint_marker_array); + add(start_pose_text_marker_array); + } // safety check if (parameters_->safety_check_params.enable_safety_check) { From f18cdcc59da53d1b049c19bf837da2dc5da5a510 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 28 Dec 2023 09:07:20 +0900 Subject: [PATCH 163/276] docs(surround_obstacle_checker): add descriptions of some parameters (#5977) Signed-off-by: tomoya.kimura --- planning/surround_obstacle_checker/README.md | 21 ++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/planning/surround_obstacle_checker/README.md b/planning/surround_obstacle_checker/README.md index 80bb56ff843c4..071701c024685 100644 --- a/planning/surround_obstacle_checker/README.md +++ b/planning/surround_obstacle_checker/README.md @@ -103,16 +103,17 @@ As mentioned in stop condition section, it prevents chattering by changing thres {{ json_to_markdown("planning/surround_obstacle_checker/schema/surround_obstacle_checker.schema.json") }} -| Name | Type | Description | Default value | -| :-------------------------------- | :------- | :------------------------------------------------------------------------------------- | :------------ | -| `use_pointcloud` | `bool` | Use pointcloud as obstacle check | `true` | -| `use_dynamic_object` | `bool` | Use dynamic object as obstacle check | `true` | -| `surround_check_distance` | `double` | If objects exist in this distance, transit to "exist-surrounding-obstacle" status [m] | 0.5 | -| `surround_check_recover_distance` | `double` | If no object exists in this distance, transit to "non-surrounding-obstacle" status [m] | 0.8 | -| `state_clear_time` | `double` | Threshold to clear stop state [s] | 2.0 | -| `stop_state_ego_speed` | `double` | Threshold to check ego vehicle stopped [m/s] | 0.1 | -| `stop_state_entry_duration_time` | `double` | Threshold to check ego vehicle stopped [s] | 0.1 | -| `publish_debug_footprints` | `bool` | Publish vehicle footprint with/without offsets | `true` | +| Name | Type | Description | Default value | +| :----------------------------------- | :------- | :----------------------------------------------------------------------------------------------------------------------------------------------- | :------------------------------------------- | +| `enable_check` | `bool` | Indicates whether each object is considered in the obstacle check target. | `true` for objects; `false` for point clouds | +| `surround_check_front_distance` | `bool` | If there are objects or point clouds within this distance in front, transition to the "exist-surrounding-obstacle" status [m]. | 0.5 | +| `surround_check_side_distance` | `double` | If there are objects or point clouds within this side distance, transition to the "exist-surrounding-obstacle" status [m]. | 0.5 | +| `surround_check_back_distance` | `double` | If there are objects or point clouds within this back distance, transition to the "exist-surrounding-obstacle" status [m]. | 0.5 | +| `surround_check_hysteresis_distance` | `double` | If no object exists within `surround_check_xxx_distance` plus this additional distance, transition to the "non-surrounding-obstacle" status [m]. | 0.3 | +| `state_clear_time` | `double` | Threshold to clear stop state [s] | 2.0 | +| `stop_state_ego_speed` | `double` | Threshold to check ego vehicle stopped [m/s] | 0.1 | +| `stop_state_entry_duration_time` | `double` | Threshold to check ego vehicle stopped [s] | 0.1 | +| `publish_debug_footprints` | `bool` | Publish vehicle footprint with/without offsets | `true` | ## Assumptions / Known limits From fd200951fd5613072c5d9ce832d29390f626b5bd Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 28 Dec 2023 09:13:07 +0900 Subject: [PATCH 164/276] fix(landmark_based_localizer): fix to for moving the definition code of landmarks (#5803) * Fixed to use lanelet extension landmark Signed-off-by: Shintaro Sakoda * Fixed to build Signed-off-by: Shintaro Sakoda * Fixed link Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda --- .../landmark_based_localizer/README.md | 63 +------------------ .../src/ar_tag_based_localizer.cpp | 14 ++--- .../src/ar_tag_based_localizer.hpp | 3 +- .../landmark_manager/landmark_manager.hpp | 8 ++- .../landmark_manager/src/landmark_manager.cpp | 34 ++-------- 5 files changed, 19 insertions(+), 103 deletions(-) diff --git a/localization/landmark_based_localizer/README.md b/localization/landmark_based_localizer/README.md index 86f3750ad11d9..49588a19ac620 100644 --- a/localization/landmark_based_localizer/README.md +++ b/localization/landmark_based_localizer/README.md @@ -43,68 +43,7 @@ So, if the 4 vertices are considered as forming a tetrahedron and its volume exc ## Map specifications -For this package to work correctly, the poses of the landmarks must be specified in the Lanelet2 map format that `map_loader` and `landmark_manager` can interpret. - -The four vertices of a landmark are defined counterclockwise. - -The order of the four vertices is defined as follows. In the coordinate system of a landmark, - -- the x-axis is parallel to the vector from the first vertex to the second vertex -- the y-axis is parallel to the vector from the second vertex to the third vertex - -![lanelet2 data structure](./doc_image/lanelet2_data_structure.drawio.svg) - -### Example of `lanelet2_map.osm` - -The values provided below are placeholders. -Ensure to input the correct coordinates corresponding to the actual location where the landmark is placed, such as `lat`, `lon`, `mgrs_code`, `local_x`, `local_y`. - -For example, when using the AR tag, it would look like this. - -```xml -... - - - - - - - - - - - - - - - - - - - - - - - - - - -... - - - - - - - - - - - - -... - -``` +See ## About `consider_orientation` diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index a1e2f3ec31dd3..43ac1e1098453 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -142,7 +142,7 @@ ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options) void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg) { - landmark_manager_.parse_landmarks(msg, "apriltag_16h5", this->get_logger()); + landmark_manager_.parse_landmarks(msg, "apriltag_16h5"); const MarkerArray marker_msg = landmark_manager_.get_landmarks_as_marker_array_msg(); mapped_tag_pose_pub_->publish(marker_msg); } @@ -173,7 +173,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) const Pose self_pose = interpolate_result.value().interpolated_pose.pose.pose; // detect - const std::vector landmarks = detect_landmarks(msg); + const std::vector landmarks = detect_landmarks(msg); if (landmarks.empty()) { return; } @@ -183,7 +183,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) PoseArray pose_array_msg; pose_array_msg.header.stamp = sensor_stamp; pose_array_msg.header.frame_id = "map"; - for (const landmark_manager::Landmark & landmark : landmarks) { + for (const Landmark & landmark : landmarks) { const Pose detected_marker_on_map = tier4_autoware_utils::transformPose(landmark.pose, self_pose); pose_array_msg.poses.push_back(detected_marker_on_map); @@ -293,7 +293,7 @@ std::vector ArTagBasedLocalizer::detect_landmarks( cv_ptr->image.copyTo(in_image); } catch (cv_bridge::Exception & e) { RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what()); - return std::vector{}; + return std::vector{}; } // get transform from base_link to camera @@ -303,7 +303,7 @@ std::vector ArTagBasedLocalizer::detect_landmarks( tf_buffer_->lookupTransform("base_link", msg->header.frame_id, sensor_stamp); } catch (tf2::TransformException & ex) { RCLCPP_INFO(this->get_logger(), "Could not transform base_link to camera: %s", ex.what()); - return std::vector{}; + return std::vector{}; } // detect @@ -311,7 +311,7 @@ std::vector ArTagBasedLocalizer::detect_landmarks( detector_.detect(in_image, markers, cam_param_, marker_size_, false); // parse - std::vector landmarks; + std::vector landmarks; for (aruco::Marker & marker : markers) { // convert marker pose to tf @@ -327,7 +327,7 @@ std::vector ArTagBasedLocalizer::detect_landmarks( const double distance = std::hypot(pose.position.x, pose.position.y, pose.position.z); if (distance <= distance_threshold_) { tf2::doTransform(pose, pose, transform_sensor_to_base_link); - landmarks.push_back(landmark_manager::Landmark{std::to_string(marker.id), pose}); + landmarks.push_back(Landmark{std::to_string(marker.id), pose}); } // for debug, drawing the detected markers diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp index eb7406f8c77f8..f70821a39ffe8 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp @@ -80,6 +80,7 @@ class ArTagBasedLocalizer : public rclcpp::Node using TransformStamped = geometry_msgs::msg::TransformStamped; using MarkerArray = visualization_msgs::msg::MarkerArray; using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + using Landmark = landmark_manager::Landmark; public: explicit ArTagBasedLocalizer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); @@ -89,7 +90,7 @@ class ArTagBasedLocalizer : public rclcpp::Node void image_callback(const Image::ConstSharedPtr & msg); void cam_info_callback(const CameraInfo::ConstSharedPtr & msg); void ekf_pose_callback(const PoseWithCovarianceStamped::ConstSharedPtr & msg); - std::vector detect_landmarks(const Image::ConstSharedPtr & msg); + std::vector detect_landmarks(const Image::ConstSharedPtr & msg); // Parameters float marker_size_{}; diff --git a/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp b/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp index fba419f746b5e..7e78ed713dddc 100644 --- a/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp +++ b/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp @@ -15,6 +15,8 @@ #ifndef LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_ #define LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_ +#include "lanelet2_extension/localization/landmark.hpp" + #include #include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp" @@ -40,13 +42,13 @@ class LandmarkManager public: void parse_landmarks( const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, - const std::string & target_subtype, const rclcpp::Logger & logger); + const std::string & target_subtype); [[nodiscard]] visualization_msgs::msg::MarkerArray get_landmarks_as_marker_array_msg() const; [[nodiscard]] geometry_msgs::msg::Pose calculate_new_self_pose( - const std::vector & detected_landmarks, - const geometry_msgs::msg::Pose & self_pose, const bool consider_orientation) const; + const std::vector & detected_landmarks, const geometry_msgs::msg::Pose & self_pose, + const bool consider_orientation) const; private: // To allow multiple landmarks with the same id to be registered on a vector_map, diff --git a/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp index 875f04edd8c47..7ddd66efea0a6 100644 --- a/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp +++ b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp @@ -29,32 +29,17 @@ namespace landmark_manager void LandmarkManager::parse_landmarks( const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, - const std::string & target_subtype, const rclcpp::Logger & logger) + const std::string & target_subtype) { - RCLCPP_INFO_STREAM(logger, "msg->format_version: " << msg->format_version); - RCLCPP_INFO_STREAM(logger, "msg->map_format: " << msg->map_format); - RCLCPP_INFO_STREAM(logger, "msg->map_version: " << msg->map_version); - RCLCPP_INFO_STREAM(logger, "msg->data.size(): " << msg->data.size()); - lanelet::LaneletMapPtr lanelet_map_ptr{std::make_shared()}; - lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr); - - for (const auto & poly : lanelet_map_ptr->polygonLayer) { - const std::string type{poly.attributeOr(lanelet::AttributeName::Type, "none")}; - if (type != "pose_marker") { - continue; - } - const std::string subtype{poly.attributeOr(lanelet::AttributeName::Subtype, "none")}; - if (subtype != target_subtype) { - continue; - } - + std::vector landmarks = + lanelet::localization::parseLandmarkPolygons(msg, target_subtype); + for (const lanelet::Polygon3d & poly : landmarks) { // Get landmark_id const std::string landmark_id = poly.attributeOr("marker_id", "none"); // Get 4 vertices const auto & vertices = poly.basicPolygon(); if (vertices.size() != 4) { - RCLCPP_WARN_STREAM(logger, "vertices.size() (" << vertices.size() << ") != 4"); continue; } @@ -65,12 +50,8 @@ void LandmarkManager::parse_landmarks( const auto & v2 = vertices[2]; const auto & v3 = vertices[3]; const double volume = (v1 - v0).cross(v2 - v0).dot(v3 - v0) / 6.0; - RCLCPP_INFO_STREAM(logger, "volume = " << volume); const double volume_threshold = 1e-5; if (volume > volume_threshold) { - RCLCPP_WARN_STREAM( - logger, - "volume (" << volume << ") > threshold (" << volume_threshold << "), This is not plane."); continue; } @@ -99,13 +80,6 @@ void LandmarkManager::parse_landmarks( // Add landmarks_map_[landmark_id].push_back(pose); - RCLCPP_INFO_STREAM(logger, "id: " << landmark_id); - RCLCPP_INFO_STREAM( - logger, - "(x, y, z) = " << pose.position.x << ", " << pose.position.y << ", " << pose.position.z); - RCLCPP_INFO_STREAM( - logger, "q = " << pose.orientation.x << ", " << pose.orientation.y << ", " - << pose.orientation.z << ", " << pose.orientation.w); } } From 5cae0de5cd0203d0133fb365fde527642a6ddec3 Mon Sep 17 00:00:00 2001 From: karishma1911 <95741784+karishma1911@users.noreply.github.com> Date: Thu, 28 Dec 2023 07:04:18 +0530 Subject: [PATCH 165/276] refactor(perception-tensortt-yolo): rework parameters (#5918) perception-tensortt-yolo Signed-off-by: karishma --- .../tensorrt_yolo/schema/tensortt_yolo.json | 108 ++++++++++++++++++ perception/tensorrt_yolo/src/nodelet.cpp | 16 +-- 2 files changed, 116 insertions(+), 8 deletions(-) create mode 100644 perception/tensorrt_yolo/schema/tensortt_yolo.json diff --git a/perception/tensorrt_yolo/schema/tensortt_yolo.json b/perception/tensorrt_yolo/schema/tensortt_yolo.json new file mode 100644 index 0000000000000..0b4724078c994 --- /dev/null +++ b/perception/tensorrt_yolo/schema/tensortt_yolo.json @@ -0,0 +1,108 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for tensorrt_yolo", + "type": "object", + "definitions": { + "tensorrt_yolo": { + "type": "object", + "properties": { + "num_anchors": { + "type": "number", + "default": [ + 10.0, 13.0, 16.0, 30.0, 33.0, 23.0, 30.0, 61.0, 62.0, 45.0, 59.0, 119.0, 116.0, 90.0, + 156.0, 198.0, 373.0, 326.0 + ], + "description": "The anchors to create bounding box candidates." + }, + "scale_x_y": { + "type": "number", + "default": [1.0, 1.0, 1.0], + "description": "scale parameter to eliminate grid sensitivity." + }, + "score_thresh": { + "type": "number", + "default": 0.1, + "description": "If the objectness score is less than this value, the object is ignored in yolo layer." + }, + "iou_thresh": { + "type": "number", + "default": 0.45, + "description": "The iou threshold for NMS method." + }, + "detections_per_im": { + "type": "number", + "default": 100, + "description": " The maximum detection number for one frame." + }, + "use_darknet_layer": { + "type": "boolean", + "default": true, + "description": "The flag to use yolo layer in darknet." + }, + "ignore_thresh": { + "type": "number", + "default": 0.5, + "description": "If the output score is less than this value, this object is ignored." + }, + "onnx_file": { + "type": "string", + "description": "The onnx file name for yolo model." + }, + "engine_file": { + "type": "string", + "description": "The tensorrt engine file name for yolo model." + }, + "label_file": { + "type": "string", + "description": "The label file with label names for detected objects written on it." + }, + "calib_image_directory": { + "type": "string", + "description": "The directory name including calibration images for int8 inference." + }, + "calib_cache_file": { + "type": "string", + "description": "The calibration cache file for int8 inference." + }, + "mode": { + "type": "string", + "default": "FP32", + "description": "The inference mode: FP32, FP16, INT8." + }, + "gpu_id": { + "type": "number", + "default": 0, + "description": "GPU device ID that runs the model." + } + }, + "required": [ + "num_anchors", + "scale_x_y", + "score_thresh", + "iou_thresh", + "detections_per_im", + "use_darknet_layer", + "ignore_thresh", + "onnx_file", + "engine_file", + "label_file", + "calib_image_directory", + "calib_cache_file", + "mode", + "gpu_id" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/tensorrt_yolo" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/tensorrt_yolo/src/nodelet.cpp b/perception/tensorrt_yolo/src/nodelet.cpp index dcb65114ad88f..fdcd8bf12db72 100644 --- a/perception/tensorrt_yolo/src/nodelet.cpp +++ b/perception/tensorrt_yolo/src/nodelet.cpp @@ -50,9 +50,9 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options) std::string label_file = declare_parameter("label_file", ""); std::string calib_image_directory = declare_parameter("calib_image_directory", ""); std::string calib_cache_file = declare_parameter("calib_cache_file", ""); - std::string mode = declare_parameter("mode", "FP32"); - gpu_device_id_ = declare_parameter("gpu_id", 0); - yolo_config_.num_anchors = declare_parameter("num_anchors", 3); + std::string mode = declare_parameter("mode"); + gpu_device_id_ = declare_parameter("gpu_id"); + yolo_config_.num_anchors = declare_parameter("num_anchors"); auto anchors = declare_parameter( "anchors", std::vector{ 10, 13, 16, 30, 33, 23, 30, 61, 62, 45, 59, 119, 116, 90, 156, 198, 373, 326}); @@ -61,11 +61,11 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options) auto scale_x_y = declare_parameter("scale_x_y", std::vector{1.0, 1.0, 1.0}); std::vector scale_x_y_float(scale_x_y.begin(), scale_x_y.end()); yolo_config_.scale_x_y = scale_x_y_float; - yolo_config_.score_thresh = declare_parameter("score_thresh", 0.1); - yolo_config_.iou_thresh = declare_parameter("iou_thresh", 0.45); - yolo_config_.detections_per_im = declare_parameter("detections_per_im", 100); - yolo_config_.use_darknet_layer = declare_parameter("use_darknet_layer", true); - yolo_config_.ignore_thresh = declare_parameter("ignore_thresh", 0.5); + yolo_config_.score_thresh = declare_parameter("score_thresh"); + yolo_config_.iou_thresh = declare_parameter("iou_thresh"); + yolo_config_.detections_per_im = declare_parameter("detections_per_im"); + yolo_config_.use_darknet_layer = declare_parameter("use_darknet_layer"); + yolo_config_.ignore_thresh = declare_parameter("ignore_thresh"); if (!yolo::set_cuda_device(gpu_device_id_)) { RCLCPP_ERROR(this->get_logger(), "Given GPU not exist or suitable"); From 363a4a70b215c5371f0ab85cde83265eae50e5c6 Mon Sep 17 00:00:00 2001 From: Vincent Richard Date: Thu, 28 Dec 2023 10:47:37 +0900 Subject: [PATCH 166/276] fix(motion_velocity_smoother): front wheel steer rate calculation (#5965) #5964 Signed-off-by: Vincent Richard --- .../motion_velocity_smoother/src/smoother/smoother_base.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp index 61cc4e9fb1fcc..bcf981be4e493 100644 --- a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp @@ -224,8 +224,8 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit( auto & steer_back = output.at(i).front_wheel_angle_rad; // calculate the just 2 steering angle - steer_front = std::atan(base_param_.wheel_base * curvature_v.at(i)); - steer_back = std::atan(base_param_.wheel_base * curvature_v.at(i + 1)); + steer_front = std::atan(base_param_.wheel_base * curvature_v.at(i + 1)); + steer_back = std::atan(base_param_.wheel_base * curvature_v.at(i)); const auto mean_vel = 0.5 * (v_front + v_back); const auto dt = std::max(points_interval / mean_vel, std::numeric_limits::epsilon()); From 110bd2fa2c05deb1957e97cbb1fe2e044ad5341a Mon Sep 17 00:00:00 2001 From: OHMAE Takugo Date: Thu, 28 Dec 2023 11:32:18 +0900 Subject: [PATCH 167/276] fix(filt_vector): fix a problem of list index out of range in filt_vector (#5099) fix filt_vector Signed-off-by: tohmae --- .../src/lowpass_filter.cpp | 6 ++--- .../test/test_lowpass_filter.cpp | 24 +++++++++++++++++++ 2 files changed, 26 insertions(+), 4 deletions(-) diff --git a/control/mpc_lateral_controller/src/lowpass_filter.cpp b/control/mpc_lateral_controller/src/lowpass_filter.cpp index 07a6e2c6b0d21..8fbf3488c5a2e 100644 --- a/control/mpc_lateral_controller/src/lowpass_filter.cpp +++ b/control/mpc_lateral_controller/src/lowpass_filter.cpp @@ -120,10 +120,8 @@ bool filt_vector(const int num, std::vector & u) double tmp = 0.0; int num_tmp = 0; double count = 0; - if (i - num < 0) { - num_tmp = i; - } else if (i + num > static_cast(u.size()) - 1) { - num_tmp = static_cast(u.size()) - i - 1; + if ((i - num < 0) || (i + num > static_cast(u.size()) - 1)) { + num_tmp = std::min(i, static_cast(u.size()) - i - 1); } else { num_tmp = num; } diff --git a/control/mpc_lateral_controller/test/test_lowpass_filter.cpp b/control/mpc_lateral_controller/test/test_lowpass_filter.cpp index 2cd641c031265..c68513586847b 100644 --- a/control/mpc_lateral_controller/test/test_lowpass_filter.cpp +++ b/control/mpc_lateral_controller/test/test_lowpass_filter.cpp @@ -61,6 +61,30 @@ TEST(TestLowpassFilter, MoveAverageFilter) EXPECT_EQ(filtered_vec[4], 23.0 / 3); EXPECT_EQ(filtered_vec[5], original_vec[5]); } + { + const int window_size = 3; + const std::vector original_vec = {1.0, 1.0, 1.0, 1.0}; + std::vector filtered_vec = original_vec; + EXPECT_TRUE(MoveAverageFilter::filt_vector(window_size, filtered_vec)); + ASSERT_EQ(filtered_vec.size(), original_vec.size()); + EXPECT_EQ(filtered_vec[0], original_vec[0]); + EXPECT_EQ(filtered_vec[1], 1.0); + EXPECT_EQ(filtered_vec[2], 1.0); + EXPECT_EQ(filtered_vec[3], original_vec[3]); + } + { + const int window_size = 4; + const std::vector original_vec = {1.0, 3.0, 4.0, 6.0, 7.0, 10.0}; + std::vector filtered_vec = original_vec; + EXPECT_TRUE(MoveAverageFilter::filt_vector(window_size, filtered_vec)); + ASSERT_EQ(filtered_vec.size(), original_vec.size()); + EXPECT_EQ(filtered_vec[0], original_vec[0]); + EXPECT_EQ(filtered_vec[1], 8.0 / 3); + EXPECT_EQ(filtered_vec[2], 21.0 / 5); + EXPECT_EQ(filtered_vec[3], 30.0 / 5); + EXPECT_EQ(filtered_vec[4], 23.0 / 3); + EXPECT_EQ(filtered_vec[5], original_vec[5]); + } } TEST(TestLowpassFilter, Butterworth2dFilter) { From 949c740c1f8e8beee867b8c0da01338cf1094fd0 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Thu, 28 Dec 2023 11:32:43 +0900 Subject: [PATCH 168/276] feat: add support of overwriting signals if harsh backlight is detected (#5852) * feat: add support of overwriting signals if backlit is detected Signed-off-by: ktro2828 * feat: remove default parameter in nodelet and update lauch for composable node Signed-off-by: ktro2828 * docs: update README Signed-off-by: ktro2828 * docs: update README Signed-off-by: ktro2828 * feat: update confidence to 0.0 corresponding signals overwritten by unkonwn Signed-off-by: ktro2828 --------- Signed-off-by: ktro2828 --- .../traffic_light_node_container.launch.py | 19 +++++++++--- perception/traffic_light_classifier/README.md | 9 +++--- .../traffic_light_classifier/nodelet.hpp | 3 ++ .../traffic_light_classifier.launch.xml | 2 ++ .../traffic_light_classifier/src/nodelet.cpp | 30 ++++++++++++++++++- 5 files changed, 54 insertions(+), 9 deletions(-) diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py index a6bcb40e81252..30eeff04985e5 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py @@ -42,7 +42,8 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("input/image", "/sensing/camera/traffic_light/image_raw") add_launch_arg("output/rois", "/perception/traffic_light_recognition/rois") add_launch_arg( - "output/traffic_signals", "/perception/traffic_light_recognition/traffic_signals" + "output/traffic_signals", + "/perception/traffic_light_recognition/traffic_signals", ) # traffic_light_fine_detector @@ -64,14 +65,20 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("classifier_type", "1") add_launch_arg( "classifier_model_path", - os.path.join(classifier_share_dir, "data", "traffic_light_classifier_efficientNet_b1.onnx"), + os.path.join( + classifier_share_dir, + "data", + "traffic_light_classifier_efficientNet_b1.onnx", + ), ) add_launch_arg( - "classifier_label_path", os.path.join(classifier_share_dir, "data", "lamp_labels.txt") + "classifier_label_path", + os.path.join(classifier_share_dir, "data", "lamp_labels.txt"), ) add_launch_arg("classifier_precision", "fp16") add_launch_arg("classifier_mean", "[123.675, 116.28, 103.53]") add_launch_arg("classifier_std", "[58.395, 57.12, 57.375]") + add_launch_arg("backlight_threshold", "0.85") add_launch_arg("use_intra_process", "False") add_launch_arg("use_multithread", "False") @@ -102,6 +109,7 @@ def create_parameter_dict(*args): "classifier_precision", "classifier_mean", "classifier_std", + "backlight_threshold", ) ], remappings=[ @@ -122,7 +130,10 @@ def create_parameter_dict(*args): ("~/input/image", LaunchConfiguration("input/image")), ("~/input/rois", LaunchConfiguration("output/rois")), ("~/input/rough/rois", "detection/rough/rois"), - ("~/input/traffic_signals", LaunchConfiguration("output/traffic_signals")), + ( + "~/input/traffic_signals", + LaunchConfiguration("output/traffic_signals"), + ), ("~/output/image", "debug/rois"), ("~/output/image/compressed", "debug/rois/compressed"), ("~/output/image/compressedDepth", "debug/rois/compressedDepth"), diff --git a/perception/traffic_light_classifier/README.md b/perception/traffic_light_classifier/README.md index 2aecf66f8fb7b..758234f129f2a 100644 --- a/perception/traffic_light_classifier/README.md +++ b/perception/traffic_light_classifier/README.md @@ -52,10 +52,11 @@ These colors and shapes are assigned to the message as follows: ### Node Parameters -| Name | Type | Description | -| ----------------- | ---- | ------------------------------------------- | -| `classifier_type` | int | if the value is `1`, cnn_classifier is used | -| `data_path` | str | packages data and artifacts directory path | +| Name | Type | Description | +| --------------------- | ----- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `classifier_type` | int | if the value is `1`, cnn_classifier is used | +| `data_path` | str | packages data and artifacts directory path | +| `backlight_threshold` | float | If the intensity get grater than this overwrite with UNKNOWN in corresponding RoI. Note that, if the value is much higher, the node only overwrites in the harsher backlight situations. Therefore, If you wouldn't like to use this feature set this value to `1.0`. The value can be `[0.0, 1.0]`. The confidence of overwritten signal is set to `0.0`. | ### Core Parameters diff --git a/perception/traffic_light_classifier/include/traffic_light_classifier/nodelet.hpp b/perception/traffic_light_classifier/include/traffic_light_classifier/nodelet.hpp index e076ff5c69378..89b91c5fb666c 100644 --- a/perception/traffic_light_classifier/include/traffic_light_classifier/nodelet.hpp +++ b/perception/traffic_light_classifier/include/traffic_light_classifier/nodelet.hpp @@ -86,6 +86,9 @@ class TrafficLightClassifierNodelet : public rclcpp::Node rclcpp::Publisher::SharedPtr traffic_signal_array_pub_; std::shared_ptr classifier_ptr_; + + double backlight_threshold_; + bool is_harsh_backlight(const cv::Mat & img) const; }; } // namespace traffic_light diff --git a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml index 10aa04cc585af..8ba0990b3efc6 100644 --- a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml +++ b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml @@ -13,6 +13,7 @@ + @@ -24,5 +25,6 @@ + diff --git a/perception/traffic_light_classifier/src/nodelet.cpp b/perception/traffic_light_classifier/src/nodelet.cpp index 90cca87245d22..d0d7e13b928c8 100644 --- a/perception/traffic_light_classifier/src/nodelet.cpp +++ b/perception/traffic_light_classifier/src/nodelet.cpp @@ -26,6 +26,8 @@ TrafficLightClassifierNodelet::TrafficLightClassifierNodelet(const rclcpp::NodeO using std::placeholders::_1; using std::placeholders::_2; is_approximate_sync_ = this->declare_parameter("approximate_sync", false); + backlight_threshold_ = this->declare_parameter("backlight_threshold"); + if (is_approximate_sync_) { approximate_sync_.reset(new ApproximateSync(ApproximateSyncPolicy(10), image_sub_, roi_sub_)); approximate_sync_->registerCallback( @@ -94,19 +96,45 @@ void TrafficLightClassifierNodelet::imageRoiCallback( output_msg.signals.resize(input_rois_msg->rois.size()); std::vector images; + std::vector backlight_indices; for (size_t i = 0; i < input_rois_msg->rois.size(); i++) { output_msg.signals[i].traffic_light_id = input_rois_msg->rois.at(i).traffic_light_id; const sensor_msgs::msg::RegionOfInterest & roi = input_rois_msg->rois.at(i).roi; - images.emplace_back(cv_ptr->image, cv::Rect(roi.x_offset, roi.y_offset, roi.width, roi.height)); + auto roi_img = cv_ptr->image(cv::Rect(roi.x_offset, roi.y_offset, roi.width, roi.height)); + if (is_harsh_backlight(roi_img)) { + backlight_indices.emplace_back(i); + } + images.emplace_back(roi_img); } if (!classifier_ptr_->getTrafficSignals(images, output_msg)) { RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback"); return; } + + for (const auto & idx : backlight_indices) { + auto & elements = output_msg.signals.at(idx).elements; + for (auto & element : elements) { + element.color = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + element.shape = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + element.confidence = 0.0; + } + } + output_msg.header = input_image_msg->header; traffic_signal_array_pub_->publish(output_msg); } +bool TrafficLightClassifierNodelet::is_harsh_backlight(const cv::Mat & img) const +{ + cv::Mat y_cr_cb; + cv::cvtColor(img, y_cr_cb, cv::COLOR_RGB2YCrCb); + + const cv::Scalar mean_values = cv::mean(y_cr_cb); + const double intensity = (mean_values[0] - 112.5) / 112.5; + + return backlight_threshold_ <= intensity; +} + } // namespace traffic_light #include From a9a9bdf4702024c2b442929d438f59974b71c226 Mon Sep 17 00:00:00 2001 From: karishma1911 <95741784+karishma1911@users.noreply.github.com> Date: Thu, 28 Dec 2023 08:50:59 +0530 Subject: [PATCH 169/276] refactor(control-lane-departure-checker): rework parameters (#5789) * control-lane-departure-checker Signed-off-by: karishma * control-lane-departure-checker Signed-off-by: karishma --------- Signed-off-by: karishma Co-authored-by: KK --- .../schema/lane_departure_checker.json | 79 +++++++++++++++++++ 1 file changed, 79 insertions(+) create mode 100644 control/lane_departure_checker/schema/lane_departure_checker.json diff --git a/control/lane_departure_checker/schema/lane_departure_checker.json b/control/lane_departure_checker/schema/lane_departure_checker.json new file mode 100644 index 0000000000000..c7f39fbf7ef8a --- /dev/null +++ b/control/lane_departure_checker/schema/lane_departure_checker.json @@ -0,0 +1,79 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for lane_departure_checker", + "type": "object", + "definitions": { + "lane_departure_checker": { + "type": "object", + "properties": { + "footprint_margin_scale": { + "type": "number", + "default": 1.0, + "description": "Coefficient for expanding footprint margin. Multiplied by 1 standard deviation." + }, + "resample_interval": { + "type": "number", + "default": 0.3, + "description": "Minimum Euclidean distance between points when resample trajectory.[m]." + }, + "max_deceleration": { + "type": "number", + "default": 2.8, + "description": "Maximum deceleration when calculating braking distance." + }, + "delay_time": { + "type": "number", + "default": 1.3, + "description": "Delay time which took to actuate brake when calculating braking distance. [second]." + }, + "max_lateral_deviation": { + "type": "number", + "default": 2.0, + "description": "Maximum lateral deviation in vehicle coordinate. [m]." + }, + "max_longitudinal_deviation": { + "type": "number", + "default": 2.0, + "description": "Maximum longitudinal deviation in vehicle coordinate. [m]." + }, + "max_yaw_deviation_deg": { + "type": "number", + "default": 60.0, + "description": "Maximum ego yaw deviation from trajectory. [deg]." + }, + "ego_nearest_dist_threshold": { + "type": "number" + }, + "ego_nearest_yaw_threshold": { + "type": "number" + }, + "min_braking_distance": { + "type": "number" + } + }, + "required": [ + "footprint_margin_scale", + "resample_interval", + "max_deceleration", + "max_lateral_deviation", + "max_longitudinal_deviation", + "max_yaw_deviation_deg", + "ego_nearest_dist_threshold", + "ego_nearest_yaw_threshold", + "min_braking_distance" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/lane_departure_checker" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From 273383f3e421a211fa5253e04d6eefc9d7b7b379 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 28 Dec 2023 15:11:05 +0900 Subject: [PATCH 170/276] feat!: remove planning factor type (#5793) remove planning factor type Signed-off-by: Takagi, Isamu Co-authored-by: Hiroki OTA --- .../src/velocity_steering_factors_panel.cpp | 3 - .../src/behavior_path_planner_node.cpp | 8 +- system/default_ad_api/src/planning.cpp | 86 ------------------- 3 files changed, 1 insertion(+), 96 deletions(-) diff --git a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp index e27fc9b6cfa81..6ea142ed66a1b 100644 --- a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp @@ -174,9 +174,6 @@ void VelocitySteeringFactorsPanel::onSteeringFactors(const SteeringFactorArray:: case SteeringFactor::APPROACHING: label->setText("APPROACHING"); break; - case SteeringFactor::TRYING: - label->setText("TRYING"); - break; case SteeringFactor::TURNING: label->setText("TURNING"); break; diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 9fd397bb8a8b1..12715520e1146 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -490,16 +490,10 @@ void BehaviorPathPlannerNode::publish_steering_factor( const auto [intersection_pose, intersection_distance] = planner_data->turn_signal_decider.getIntersectionPoseAndDistance(); - const uint16_t steering_factor_state = std::invoke([&intersection_flag]() { - if (intersection_flag) { - return SteeringFactor::TURNING; - } - return SteeringFactor::TRYING; - }); steering_factor_interface_ptr_->updateSteeringFactor( {intersection_pose, intersection_pose}, {intersection_distance, intersection_distance}, - PlanningBehavior::INTERSECTION, steering_factor_direction, steering_factor_state, ""); + PlanningBehavior::INTERSECTION, steering_factor_direction, SteeringFactor::TURNING, ""); } else { steering_factor_interface_ptr_->clearSteeringFactors(); } diff --git a/system/default_ad_api/src/planning.cpp b/system/default_ad_api/src/planning.cpp index 17491482a18fe..ed2dcee92eb2b 100644 --- a/system/default_ad_api/src/planning.cpp +++ b/system/default_ad_api/src/planning.cpp @@ -63,82 +63,6 @@ T merge_factors(const rclcpp::Time stamp, const std::vector(now(), velocity_factors_); auto steering = merge_factors(now(), steering_factors_); - // Set velocity factor type for compatibility. - for (auto & factor : velocity.factors) { - factor.type = convert_velocity_behavior(factor.behavior); - } - - // Set steering factor type for compatibility. - for (auto & factor : steering.factors) { - factor.type = convert_steering_behavior(factor.behavior); - } - // Set the distance if it is nan. if (trajectory_ && kinematic_state_) { for (auto & factor : velocity.factors) { From b5e8949f1a234ed18cb24f89bf6ecc8dbcd5d2a8 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 28 Dec 2023 19:32:09 +0900 Subject: [PATCH 171/276] feat(start_planner): separate collision check and path planning (#5952) * remove collision check from pull out planner * change order of extract stop objects function Signed-off-by: kyoichi-sugahara --- .../start_planner_module.hpp | 7 +- .../src/geometric_pull_out.cpp | 10 --- .../src/shift_pull_out.cpp | 15 ---- .../src/start_planner_module.cpp | 79 +++++++++++-------- .../src/util.cpp | 1 - 5 files changed, 50 insertions(+), 62 deletions(-) diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index 055a46e0bbeae..9f559cabe8951 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -169,11 +169,10 @@ class StartPlannerModule : public SceneModuleInterface bool isMoving() const; PriorityOrder determinePriorityOrder( - const std::string & search_priority, const size_t candidates_size); + const std::string & search_priority, const size_t start_pose_candidates_num); bool findPullOutPath( - const std::vector & start_pose_candidates, const size_t index, - const std::shared_ptr & planner, const Pose & refined_start_pose, - const Pose & goal_pose); + const Pose & start_pose_candidate, const std::shared_ptr & planner, + const Pose & refined_start_pose, const Pose & goal_pose); void updateStatusWithCurrentPath( const behavior_path_planner::PullOutPath & path, const Pose & start_pose, const behavior_path_planner::PlannerType & planner_type); diff --git a/planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp b/planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp index 7d6dd60398e8e..d9ff155f36e6c 100644 --- a/planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp @@ -63,17 +63,7 @@ std::optional GeometricPullOut::plan(const Pose & start_pose, const // collision check with stop objects in pull out lanes const auto arc_path = planner_.getArcPath(); - const auto & stop_objects = utils::path_safety_checker::filterObjectsByVelocity( - *(planner_data_->dynamic_object), parameters_.th_moving_object_velocity); - const auto [pull_out_lane_stop_objects, others] = - utils::path_safety_checker::separateObjectsByLanelets( - stop_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); - if (utils::checkCollisionBetweenPathFootprintsAndObjects( - vehicle_footprint_, arc_path, pull_out_lane_stop_objects, - parameters_.collision_check_margin)) { - return {}; - } const double velocity = parallel_parking_parameters_.forward_parking_velocity; if (parameters_.divide_pull_out_path) { diff --git a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp index 35281d5bedbcf..1e1e47ba940e8 100644 --- a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -46,7 +46,6 @@ std::optional ShiftPullOut::plan(const Pose & start_pose, const Pos { const auto & route_handler = planner_data_->route_handler; const auto & common_parameters = planner_data_->parameters; - const auto & dynamic_objects = planner_data_->dynamic_object; const double backward_path_length = planner_data_->parameters.backward_path_length + parameters_.max_back_distance; @@ -64,13 +63,6 @@ std::optional ShiftPullOut::plan(const Pose & start_pose, const Pos return std::nullopt; } - // extract stop objects in pull out lane for collision check - const auto [pull_out_lane_objects, others] = - utils::path_safety_checker::separateObjectsByLanelets( - *dynamic_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); - const auto pull_out_lane_stop_objects = utils::path_safety_checker::filterObjectsByVelocity( - pull_out_lane_objects, parameters_.th_moving_object_velocity); - // get safe path for (auto & pull_out_path : pull_out_paths) { auto & shift_path = @@ -143,13 +135,6 @@ std::optional ShiftPullOut::plan(const Pose & start_pose, const Pos continue; } - // check collision - if (utils::checkCollisionBetweenPathFootprintsAndObjects( - vehicle_footprint_, path_start_to_end, pull_out_lane_stop_objects, - parameters_.collision_check_margin)) { - continue; - } - shift_path.header = planner_data_->route_handler->getRouteHeader(); return pull_out_path; diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 80c08dea48922..693029e57cb7b 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -586,7 +586,7 @@ void StartPlannerModule::planWithPriority( determinePriorityOrder(search_priority, start_pose_candidates.size()); for (const auto & [index, planner] : order_priority) { - if (findPullOutPath(start_pose_candidates, index, planner, refined_start_pose, goal_pose)) + if (findPullOutPath(start_pose_candidates[index], planner, refined_start_pose, goal_pose)) return; } @@ -594,17 +594,17 @@ void StartPlannerModule::planWithPriority( } PriorityOrder StartPlannerModule::determinePriorityOrder( - const std::string & search_priority, const size_t candidates_size) + const std::string & search_priority, const size_t start_pose_candidates_num) { PriorityOrder order_priority; if (search_priority == "efficient_path") { for (const auto & planner : start_planners_) { - for (size_t i = 0; i < candidates_size; i++) { + for (size_t i = 0; i < start_pose_candidates_num; i++) { order_priority.emplace_back(i, planner); } } } else if (search_priority == "short_back_distance") { - for (size_t i = 0; i < candidates_size; i++) { + for (size_t i = 0; i < start_pose_candidates_num; i++) { for (const auto & planner : start_planners_) { order_priority.emplace_back(i, planner); } @@ -617,43 +617,62 @@ PriorityOrder StartPlannerModule::determinePriorityOrder( } bool StartPlannerModule::findPullOutPath( - const std::vector & start_pose_candidates, const size_t index, - const std::shared_ptr & planner, const Pose & refined_start_pose, - const Pose & goal_pose) + const Pose & start_pose_candidate, const std::shared_ptr & planner, + const Pose & refined_start_pose, const Pose & goal_pose) { - // Ensure the index is within the bounds of the start_pose_candidates vector - if (index >= start_pose_candidates.size()) return false; + 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 = createVehicleFootprint(vehicle_info_); + // 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); + const auto [pull_out_lane_stop_objects, others] = + utils::path_safety_checker::separateObjectsByLanelets( + stop_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); - const Pose & pull_out_start_pose = start_pose_candidates.at(index); - const bool is_driving_forward = - tier4_autoware_utils::calcDistance2d(pull_out_start_pose, refined_start_pose) < 0.01; + // if start_pose_candidate is far from refined_start_pose, backward driving is necessary + const bool backward_is_unnecessary = + tier4_autoware_utils::calcDistance2d(start_pose_candidate, refined_start_pose) < 0.01; planner->setPlannerData(planner_data_); - const auto pull_out_path = planner->plan(pull_out_start_pose, goal_pose); + const auto pull_out_path = planner->plan(start_pose_candidate, goal_pose); // If no path is found, return false if (!pull_out_path) { return false; } - // If driving forward, update status with the current path and return true - if (is_driving_forward) { - updateStatusWithCurrentPath(*pull_out_path, pull_out_start_pose, planner->getPlannerType()); - return true; - } + // lambda function for combining partial_paths + const auto combine_partial_path = [pull_out_lanes](const auto & path) { + PathWithLaneId combined_path; + for (const auto & partial_path : path.partial_paths) { + combined_path.points.insert( + combined_path.points.end(), partial_path.points.begin(), partial_path.points.end()); + } + // remove the point behind of shift end pose + const auto shift_end_pose_idx = + motion_utils::findNearestIndex(combined_path.points, path.end_pose); + combined_path.points.erase( + combined_path.points.begin() + *shift_end_pose_idx + 1, combined_path.points.end()); + return combined_path; + }; - // If this is the last start pose candidate, return false - if (index == start_pose_candidates.size() - 1) return false; + // check collision + if (utils::checkCollisionBetweenPathFootprintsAndObjects( + vehicle_footprint, combine_partial_path(*pull_out_path), pull_out_lane_stop_objects, + parameters_->collision_check_margin)) { + return false; + } - const Pose & next_pull_out_start_pose = start_pose_candidates.at(index + 1); - const auto next_pull_out_path = planner->plan(next_pull_out_start_pose, goal_pose); + // If start pose candidate + if (backward_is_unnecessary) { + updateStatusWithCurrentPath(*pull_out_path, start_pose_candidate, planner->getPlannerType()); + return true; + } - // If no next path is found, return false - if (!next_pull_out_path) return false; + updateStatusWithNextPath(*pull_out_path, start_pose_candidate, planner->getPlannerType()); - // Update status with the next path and return true - updateStatusWithNextPath( - *next_pull_out_path, next_pull_out_start_pose, planner->getPlannerType()); return true; } @@ -776,13 +795,9 @@ std::vector StartPlannerModule::generateDrivableLanes( void StartPlannerModule::updatePullOutStatus() { - const bool has_received_new_route = - !planner_data_->prev_route_id || - *planner_data_->prev_route_id != planner_data_->route_handler->getRouteUuid(); - // skip updating if enough time has not passed for preventing chattering between back and // start_planner - if (!has_received_new_route) { + if (!receivedNewRoute()) { if (!last_pull_out_start_update_time_) { last_pull_out_start_update_time_ = std::make_unique(clock_->now()); } diff --git a/planning/behavior_path_start_planner_module/src/util.cpp b/planning/behavior_path_start_planner_module/src/util.cpp index 9a9466936c422..73a1e94399503 100644 --- a/planning/behavior_path_start_planner_module/src/util.cpp +++ b/planning/behavior_path_start_planner_module/src/util.cpp @@ -92,7 +92,6 @@ lanelet::ConstLanelets getPullOutLanes( const auto start_pose = planner_data->route_handler->getOriginalStartPose(); lanelet::ConstLanelet current_shoulder_lane; - lanelet::ConstLanelets shoulder_lanes; if (route_handler->getPullOutStartLane( route_handler->getShoulderLanelets(), start_pose, vehicle_width, ¤t_shoulder_lane)) { // pull out from shoulder lane From 035e13a3e6d4966a91e28a7f610a6e969839aa65 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 29 Dec 2023 00:05:30 +0900 Subject: [PATCH 172/276] feat(start_planner): apply offset colission check section (#5982) refactor collision check in GeometricPullOut::plan() Signed-off-by: kyoichi-sugahara Co-authored-by: Kosuke Takeuchi --- .../start_planner_module.hpp | 6 +- .../src/shift_pull_out.cpp | 2 +- .../src/start_planner_module.cpp | 67 +++++++++++++------ 3 files changed, 51 insertions(+), 24 deletions(-) diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index 9f559cabe8951..a451a92c16ff1 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -173,6 +173,8 @@ class StartPlannerModule : public SceneModuleInterface bool findPullOutPath( const Pose & start_pose_candidate, const std::shared_ptr & planner, const Pose & refined_start_pose, const Pose & goal_pose); + + PathWithLaneId extractCollisionCheckPath(const PullOutPath & path); void updateStatusWithCurrentPath( const behavior_path_planner::PullOutPath & path, const Pose & start_pose, const behavior_path_planner::PlannerType & planner_type); @@ -226,7 +228,9 @@ class StartPlannerModule : public SceneModuleInterface void updatePullOutStatus(); void updateStatusAfterBackwardDriving(); PredictedObjects filterStopObjectsInPullOutLanes( - const lanelet::ConstLanelets & pull_out_lanes, const double velocity_threshold) const; + const lanelet::ConstLanelets & pull_out_lanes, const geometry_msgs::msg::Point & current_pose, + const double velocity_threshold, const double object_check_backward_distance, + const double object_check_forward_distance) const; bool hasFinishedPullOut() const; bool hasFinishedBackwardDriving() const; bool hasCollisionWithDynamicObjects() const; diff --git a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp index 1e1e47ba940e8..51673410199b8 100644 --- a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -68,7 +68,7 @@ std::optional ShiftPullOut::plan(const Pose & start_pose, const Pos auto & shift_path = pull_out_path.partial_paths.front(); // shift path is not separate but only one. - // check lane_departure and collision with path between pull_out_start to pull_out_end + // check lane_departure with path between pull_out_start to pull_out_end PathWithLaneId path_start_to_end{}; { const size_t pull_out_start_idx = findNearestIndex(shift_path.points, start_pose.position); diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 693029e57cb7b..9870a324caf64 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -643,29 +643,13 @@ bool StartPlannerModule::findPullOutPath( return false; } - // lambda function for combining partial_paths - const auto combine_partial_path = [pull_out_lanes](const auto & path) { - PathWithLaneId combined_path; - for (const auto & partial_path : path.partial_paths) { - combined_path.points.insert( - combined_path.points.end(), partial_path.points.begin(), partial_path.points.end()); - } - // remove the point behind of shift end pose - const auto shift_end_pose_idx = - motion_utils::findNearestIndex(combined_path.points, path.end_pose); - combined_path.points.erase( - combined_path.points.begin() + *shift_end_pose_idx + 1, combined_path.points.end()); - return combined_path; - }; - // check collision if (utils::checkCollisionBetweenPathFootprintsAndObjects( - vehicle_footprint, combine_partial_path(*pull_out_path), pull_out_lane_stop_objects, + vehicle_footprint, extractCollisionCheckPath(*pull_out_path), pull_out_lane_stop_objects, parameters_->collision_check_margin)) { return false; } - // If start pose candidate if (backward_is_unnecessary) { updateStatusWithCurrentPath(*pull_out_path, start_pose_candidate, planner->getPlannerType()); return true; @@ -676,6 +660,33 @@ bool StartPlannerModule::findPullOutPath( return true; } +PathWithLaneId StartPlannerModule::extractCollisionCheckPath(const PullOutPath & path) +{ + PathWithLaneId combined_path; + for (const auto & partial_path : path.partial_paths) { + combined_path.points.insert( + combined_path.points.end(), partial_path.points.begin(), partial_path.points.end()); + } + + // calculate collision check end idx + size_t collision_check_end_idx = 0; + const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose( + combined_path.points, path.end_pose.position, parameters_->collision_check_distance_from_end); + + if (collision_check_end_pose) { + collision_check_end_idx = + motion_utils::findNearestIndex(combined_path.points, collision_check_end_pose->position); + } + + // remove the point behind of collision check end pose + if (collision_check_end_idx + 1 < combined_path.points.size()) { + combined_path.points.erase( + combined_path.points.begin() + collision_check_end_idx + 1, combined_path.points.end()); + } + + return combined_path; +} + void StartPlannerModule::updateStatusWithCurrentPath( const behavior_path_planner::PullOutPath & path, const Pose & start_pose, const behavior_path_planner::PlannerType & planner_type) @@ -892,9 +903,12 @@ std::vector StartPlannerModule::searchPullOutStartPoseCandidates( const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_); const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); + const double backward_path_length = + planner_data_->parameters.backward_path_length + parameters_->max_back_distance; - const auto stop_objects_in_pull_out_lanes = - filterStopObjectsInPullOutLanes(pull_out_lanes, parameters_->th_moving_object_velocity); + const auto stop_objects_in_pull_out_lanes = filterStopObjectsInPullOutLanes( + pull_out_lanes, start_pose.position, parameters_->th_moving_object_velocity, + backward_path_length, std::numeric_limits::max()); // Set the maximum backward distance less than the distance from the vehicle's base_link to the // lane's rearmost point to prevent lane departure. @@ -937,16 +951,25 @@ std::vector StartPlannerModule::searchPullOutStartPoseCandidates( } PredictedObjects StartPlannerModule::filterStopObjectsInPullOutLanes( - const lanelet::ConstLanelets & pull_out_lanes, const double velocity_threshold) const + const lanelet::ConstLanelets & pull_out_lanes, const geometry_msgs::msg::Point & current_point, + const double velocity_threshold, const double object_check_forward_distance, + const double object_check_backward_distance) const { const auto stop_objects = utils::path_safety_checker::filterObjectsByVelocity( *planner_data_->dynamic_object, velocity_threshold); - // filter for objects located in pull_out_lanes and moving at a speed below the threshold - const auto [stop_objects_in_pull_out_lanes, others] = + // filter for objects located in pull out lanes and moving at a speed below the threshold + auto [stop_objects_in_pull_out_lanes, others] = utils::path_safety_checker::separateObjectsByLanelets( stop_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); + const auto path = planner_data_->route_handler->getCenterLinePath( + pull_out_lanes, object_check_backward_distance, object_check_forward_distance); + + utils::path_safety_checker::filterObjectsByPosition( + stop_objects_in_pull_out_lanes, path.points, current_point, object_check_forward_distance, + object_check_backward_distance); + return stop_objects_in_pull_out_lanes; } From 691a60eb50a764b7b8c2edbe5cbf73dbedbfc047 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 29 Dec 2023 01:27:49 +0900 Subject: [PATCH 173/276] chore(pid_longitudinal_controller): change INFO printing frequency (#5890) Signed-off-by: Takayuki Murooka --- .../src/pid_longitudinal_controller.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 698d4a8403069..31c48fb5060a8 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -555,9 +555,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d return; }; - const auto info_throttle = [this](const auto & s) { - RCLCPP_INFO_SKIPFIRST_THROTTLE(logger_, *clock_, 5000, "%s", s); - }; + const auto info_once = [this](const auto & s) { RCLCPP_INFO_ONCE(logger_, "%s", s); }; const bool is_under_control = m_current_operation_mode.is_autoware_control_enabled && m_current_operation_mode.mode == OperationModeState::AUTONOMOUS; @@ -623,10 +621,10 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d if (m_control_state == ControlState::STOPPED) { // -- debug print -- if (has_nonzero_target_vel && !departure_condition_from_stopped) { - info_throttle("target speed > 0, but departure condition is not met. Keep STOPPED."); + info_once("target speed > 0, but departure condition is not met. Keep STOPPED."); } if (has_nonzero_target_vel && keep_stopped_condition) { - info_throttle("target speed > 0, but keep stop condition is met. Keep STOPPED."); + info_once("target speed > 0, but keep stop condition is met. Keep STOPPED."); } // --------------- From 42d262ca5c7409b3693a043c1dd85b073c1d512a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 29 Dec 2023 01:46:02 +0900 Subject: [PATCH 174/276] feat(behavior_path_planner): run keep last approved modules after candidate modules (#5970) Signed-off-by: kosuke55 --- .../behavior_path_planner/planner_manager.hpp | 9 ++++ .../src/planner_manager.cpp | 42 +++++++++++++++---- 2 files changed, 42 insertions(+), 9 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 8411be45edace..f6f95ae3b5e82 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -435,6 +435,15 @@ class PlannerManager const std::vector & request_modules, const std::shared_ptr & data, const BehaviorModuleOutput & previous_module_output); + /** + * @brief run keep last approved modules + * @param planner data. + * @param previous module output. + * @return planning result. + */ + BehaviorModuleOutput runKeepLastModules( + const std::shared_ptr & data, const BehaviorModuleOutput & previous_output) const; + static std::string getNames(const std::vector & modules); std::optional root_lanelet_{std::nullopt}; diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index cd1b0da702dac..262de4764fcfe 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -141,8 +141,9 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da * STEP3: if there is no module that need to be launched, return approved modules' output */ if (request_modules.empty()) { + const auto output = runKeepLastModules(data, approved_modules_output); processing_time_.at("total_time") = stop_watch_.toc("total_time", true); - return approved_modules_output; + return output; } /** @@ -150,24 +151,32 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da */ const auto [highest_priority_module, candidate_modules_output] = runRequestModules(request_modules, data, approved_modules_output); + + /** + * STEP5: run keep last approved modules after running candidate modules. + * NOTE: if no candidate module is launched, approved_modules_output used as input for keep + * last modules and return the result immediately. + */ + const auto output = runKeepLastModules( + data, highest_priority_module ? candidate_modules_output : approved_modules_output); if (!highest_priority_module) { processing_time_.at("total_time") = stop_watch_.toc("total_time", true); - return approved_modules_output; + return output; } /** - * STEP5: if the candidate module's modification is NOT approved yet, return the result. + * STEP6: if the candidate module's modification is NOT approved yet, return the result. * NOTE: the result is output of the candidate module, but the output path don't contains path * shape modification that needs approval. On the other hand, it could include velocity * profile modification. */ if (highest_priority_module->isWaitingApproval()) { processing_time_.at("total_time") = stop_watch_.toc("total_time", true); - return candidate_modules_output; + return output; } /** - * STEP6: if the candidate module is approved, push the module into approved_module_ptrs_ + * STEP7: if the candidate module is approved, push the module into approved_module_ptrs_ */ addApprovedModule(highest_priority_module); clearCandidateModules(); @@ -178,7 +187,7 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da logger_, clock_, 1000, "Reach iteration limit (max: %ld). Output current result.", max_iteration_num_); processing_time_.at("total_time") = stop_watch_.toc("total_time", true); - return candidate_modules_output; + return output; } } @@ -394,6 +403,19 @@ std::vector PlannerManager::getRequestModules( return request_modules; } +BehaviorModuleOutput PlannerManager::runKeepLastModules( + const std::shared_ptr & data, const BehaviorModuleOutput & previous_output) const +{ + auto output = previous_output; + std::for_each(approved_module_ptrs_.begin(), approved_module_ptrs_.end(), [&](const auto & m) { + if (getManager(m)->isKeepLast()) { + output = run(m, data, output); + } + }); + + return output; +} + BehaviorModuleOutput PlannerManager::getReferencePath( const std::shared_ptr & data) const { @@ -652,11 +674,13 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptrname(), output); + if (!getManager(m)->isKeepLast()) { + output = run(m, data, output); + results.emplace(m->name(), output); + } }); /** From d62f655786a933603955b84393ac27a8c83493a5 Mon Sep 17 00:00:00 2001 From: Tao Zhong <55872497+tzhong518@users.noreply.github.com> Date: Fri, 29 Dec 2023 13:39:26 +0900 Subject: [PATCH 175/276] feat(crosswalk_traffic_light): add detector and classifier for pedestrian traffic light (#5871) * add: crosswalk traffic light recognition Signed-off-by: tzhong518 * fix: set conf=0 when occluded Signed-off-by: tzhong518 * fix: clean code Signed-off-by: tzhong518 * fix: refactor Signed-off-by: tzhong518 * fix: occlusion predictor Signed-off-by: tzhong518 * fix: output not detected signals as unknown Signed-off-by: tzhong518 * Revert "fix: output not detected signals as unknown" This reverts commit 7a166596e760d7eb037570e28106dcd105860567. * Revert "fix: occlusion predictor" This reverts commit 47d8cdd7fee8b4432f7a440f87bc35b50a8bc897. * fix: occlusion predictor Signed-off-by: tzhong518 * fix: clean debug code Signed-off-by: tzhong518 * style(pre-commit): autofix * fix: launch file Signed-off-by: tzhong518 * fix: set max angle range for different type Signed-off-by: tzhong518 * fix: precommit Signed-off-by: tzhong518 * fix: cancel the judge of flashing for estimated crosswalk traffic light Signed-off-by: tzhong518 * delete: not necessary judgement on label Signed-off-by: tzhong518 * Update perception/traffic_light_classifier/src/nodelet.cpp Co-authored-by: Yusuke Muramatsu * Update perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp Co-authored-by: Yusuke Muramatsu * Update perception/crosswalk_traffic_light_estimator/src/node.cpp Co-authored-by: Yusuke Muramatsu * style(pre-commit): autofix * fix: topic names and message attribute name Signed-off-by: tzhong518 * style(pre-commit): autofix * fix: model names Signed-off-by: tzhong518 * style(pre-commit): autofix * Update perception/crosswalk_traffic_light_estimator/src/node.cpp Co-authored-by: Yusuke Muramatsu * Update perception/crosswalk_traffic_light_estimator/src/node.cpp Co-authored-by: Yusuke Muramatsu * Update perception/crosswalk_traffic_light_estimator/src/node.cpp Co-authored-by: Yusuke Muramatsu * Update perception/traffic_light_occlusion_predictor/src/nodelet.cpp Co-authored-by: Yusuke Muramatsu * Update perception/traffic_light_occlusion_predictor/src/nodelet.cpp Co-authored-by: Yusuke Muramatsu * Update perception/traffic_light_occlusion_predictor/src/nodelet.cpp Co-authored-by: Yusuke Muramatsu * fix: argument position Signed-off-by: tzhong518 * fix: set classifier type in launch file Signed-off-by: tzhong518 * fix: function and parameter name Signed-off-by: tzhong518 * fix: func name Signed-off-by: tzhong518 * Update launch/tier4_perception_launch/launch/perception.launch.xml Co-authored-by: Yusuke Muramatsu * Update perception/traffic_light_map_based_detector/src/node.cpp Co-authored-by: Yusuke Muramatsu * style(pre-commit): autofix * fix: move max angle range to config Signed-off-by: tzhong518 * Update launch/tier4_perception_launch/launch/perception.launch.xml * Update launch/tier4_perception_launch/launch/perception.launch.xml * Update launch/tier4_perception_launch/launch/perception.launch.xml * Update launch/tier4_perception_launch/launch/perception.launch.xml * Update launch/tier4_perception_launch/launch/perception.launch.xml * fix: model name Signed-off-by: tzhong518 * fix: conflict Signed-off-by: tzhong518 * fix: precommit Signed-off-by: tzhong518 * fix: CI test Signed-off-by: tzhong518 --------- Signed-off-by: tzhong518 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yusuke Muramatsu --- .../src/traffic_light_utils.cpp | 2 +- .../launch/perception.launch.xml | 15 +- .../traffic_light.launch.xml | 41 +++-- .../traffic_light_node_container.launch.py | 80 +++++++-- ...osswalk_traffic_light_estimator.param.yaml | 1 + .../node.hpp | 16 +- .../src/node.cpp | 162 ++++++++++++++++-- .../traffic_light_classifier/nodelet.hpp | 2 + .../traffic_light_classifier.launch.xml | 3 + .../traffic_light_classifier/src/nodelet.cpp | 16 +- .../traffic_light_fine_detector/nodelet.hpp | 6 +- .../src/nodelet.cpp | 16 +- ...raffic_light_map_based_detector.param.yaml | 2 + .../traffic_light_map_based_detector/node.hpp | 6 + .../src/node.cpp | 70 +++++++- .../nodelet.hpp | 10 +- ...affic_light_occlusion_predictor.launch.xml | 6 +- .../src/nodelet.cpp | 70 ++++++-- 18 files changed, 445 insertions(+), 79 deletions(-) diff --git a/common/traffic_light_utils/src/traffic_light_utils.cpp b/common/traffic_light_utils/src/traffic_light_utils.cpp index 5a68223afb5ff..e02798bb41767 100644 --- a/common/traffic_light_utils/src/traffic_light_utils.cpp +++ b/common/traffic_light_utils/src/traffic_light_utils.cpp @@ -46,7 +46,7 @@ void setSignalUnknown(tier4_perception_msgs::msg::TrafficSignal & signal, float signal.elements[0].shape = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; signal.elements[0].color = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; // the default value is -1, which means to not set confidence - if (confidence >= 0) { + if (confidence > 0) { signal.elements[0].confidence = confidence; } } diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 7f5f9d61c4bf0..1b5753fb4d5c4 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -86,13 +86,18 @@ default="$(var data_path)/traffic_light_fine_detector" description="options: `tlr_yolox_s_batch_**`. The batch number must be either one of 1, 4, 6" /> - + + @@ -231,6 +236,12 @@ + + + + + + diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml index 58e9e231e4aa0..7b81a42fdb79f 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -7,8 +7,10 @@ - - + + + + @@ -24,8 +26,10 @@ - - + + + + @@ -34,6 +38,8 @@ + + @@ -54,15 +60,18 @@ - - - + + + + + + @@ -72,11 +81,13 @@ - + + + @@ -84,6 +95,8 @@ + + @@ -104,15 +117,18 @@ - - - + + + + + + @@ -122,7 +138,8 @@ - + + diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py index 30eeff04985e5..dc5a2443d3f45 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py @@ -45,6 +45,13 @@ def add_launch_arg(name: str, default_value=None, description=None): "output/traffic_signals", "/perception/traffic_light_recognition/traffic_signals", ) + add_launch_arg( + "output/car/traffic_signals", "/perception/traffic_light_recognition/car/traffic_signals" + ) + add_launch_arg( + "output/pedestrian/traffic_signals", + "/perception/traffic_light_recognition/pedestrian/traffic_signals", + ) # traffic_light_fine_detector add_launch_arg( @@ -64,16 +71,21 @@ def add_launch_arg(name: str, default_value=None, description=None): # traffic_light_classifier add_launch_arg("classifier_type", "1") add_launch_arg( - "classifier_model_path", + "car_classifier_model_path", + os.path.join(classifier_share_dir, "data", "traffic_light_classifier_efficientNet_b1.onnx"), + ) + add_launch_arg( + "pedestrian_classifier_model_path", os.path.join( - classifier_share_dir, - "data", - "traffic_light_classifier_efficientNet_b1.onnx", + classifier_share_dir, "data", "pedestrian_traffic_light_classifier_efficientNet_b1.onnx" ), ) add_launch_arg( - "classifier_label_path", - os.path.join(classifier_share_dir, "data", "lamp_labels.txt"), + "car_classifier_label_path", os.path.join(classifier_share_dir, "data", "lamp_labels.txt") + ) + add_launch_arg( + "pedestrian_classifier_label_path", + os.path.join(classifier_share_dir, "data", "lamp_labels_ped.txt"), ) add_launch_arg("classifier_precision", "fp16") add_launch_arg("classifier_mean", "[123.675, 116.28, 103.53]") @@ -98,24 +110,56 @@ def create_parameter_dict(*args): ComposableNode( package="traffic_light_classifier", plugin="traffic_light::TrafficLightClassifierNodelet", - name="traffic_light_classifier", + name="car_traffic_light_classifier", + namespace="classification", + parameters=[ + { + "approximate_sync": LaunchConfiguration("approximate_sync"), + "classifier_type": LaunchConfiguration("classifier_type"), + "classify_traffic_light_type": 0, + "classifier_model_path": LaunchConfiguration("car_classifier_model_path"), + "classifier_label_path": LaunchConfiguration("car_classifier_label_path"), + "classifier_precision": LaunchConfiguration("classifier_precision"), + "classifier_mean": LaunchConfiguration("classifier_mean"), + "classifier_std": LaunchConfiguration("classifier_std"), + "backlight_threshold": LaunchConfiguration("backlight_threshold"), + } + ], + remappings=[ + ("~/input/image", LaunchConfiguration("input/image")), + ("~/input/rois", LaunchConfiguration("output/rois")), + ("~/output/traffic_signals", "classified/car/traffic_signals"), + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ), + ComposableNode( + package="traffic_light_classifier", + plugin="traffic_light::TrafficLightClassifierNodelet", + name="pedestrian_traffic_light_classifier", namespace="classification", parameters=[ - create_parameter_dict( - "approximate_sync", - "classifier_type", - "classifier_model_path", - "classifier_label_path", - "classifier_precision", - "classifier_mean", - "classifier_std", - "backlight_threshold", - ) + { + "approximate_sync": LaunchConfiguration("approximate_sync"), + "classifier_type": LaunchConfiguration("classifier_type"), + "classify_traffic_light_type": 1, + "classifier_model_path": LaunchConfiguration( + "pedestrian_classifier_model_path" + ), + "classifier_label_path": LaunchConfiguration( + "pedestrian_classifier_label_path" + ), + "classifier_precision": LaunchConfiguration("classifier_precision"), + "classifier_mean": LaunchConfiguration("classifier_mean"), + "classifier_std": LaunchConfiguration("classifier_std"), + "backlight_threshold": LaunchConfiguration("backlight_threshold"), + } ], remappings=[ ("~/input/image", LaunchConfiguration("input/image")), ("~/input/rois", LaunchConfiguration("output/rois")), - ("~/output/traffic_signals", "classified/traffic_signals"), + ("~/output/traffic_signals", "classified/pedestrian/traffic_signals"), ], extra_arguments=[ {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} diff --git a/perception/crosswalk_traffic_light_estimator/config/crosswalk_traffic_light_estimator.param.yaml b/perception/crosswalk_traffic_light_estimator/config/crosswalk_traffic_light_estimator.param.yaml index 33168c87de7eb..2be9074f8d71e 100644 --- a/perception/crosswalk_traffic_light_estimator/config/crosswalk_traffic_light_estimator.param.yaml +++ b/perception/crosswalk_traffic_light_estimator/config/crosswalk_traffic_light_estimator.param.yaml @@ -16,3 +16,4 @@ ros__parameters: use_last_detect_color: true last_detect_color_hold_time: 2.0 + last_colors_hold_time: 1.0 diff --git a/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp b/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp index 848293f6334bb..0578d671d27b9 100644 --- a/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp +++ b/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp @@ -34,11 +34,11 @@ #include #include +#include #include #include #include #include - namespace traffic_light { @@ -53,6 +53,8 @@ using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement using TrafficSignalAndTime = std::pair; using TrafficLightIdMap = std::unordered_map; +using TrafficLightIdArray = std::unordered_map>; + class CrosswalkTrafficLightEstimatorNode : public rclcpp::Node { public: @@ -76,8 +78,12 @@ class CrosswalkTrafficLightEstimatorNode : public rclcpp::Node void onTrafficLightArray(const TrafficSignalArray::ConstSharedPtr msg); void updateLastDetectedSignal(const TrafficLightIdMap & traffic_signals); + void updateLastDetectedSignals(const TrafficLightIdMap & traffic_signals); + void updateFlashingState(const TrafficSignal & signal); + uint8_t updateAndGetColorState(const TrafficSignal & signal); void setCrosswalkTrafficSignal( - const lanelet::ConstLanelet & crosswalk, const uint8_t color, TrafficSignalArray & msg) const; + const lanelet::ConstLanelet & crosswalk, const uint8_t color, const TrafficSignalArray & msg, + TrafficSignalArray & output); lanelet::ConstLanelets getNonRedLanelets( const lanelet::ConstLanelets & lanelets, const TrafficLightIdMap & traffic_light_id_map) const; @@ -97,9 +103,15 @@ class CrosswalkTrafficLightEstimatorNode : public rclcpp::Node // Node param bool use_last_detect_color_; double last_detect_color_hold_time_; + double last_colors_hold_time_; // Signal history TrafficLightIdMap last_detect_color_; + TrafficLightIdArray last_colors_; + + // State + std::map is_flashing_; + std::map current_color_state_; // Stop watch StopWatch stop_watch_; diff --git a/perception/crosswalk_traffic_light_estimator/src/node.cpp b/perception/crosswalk_traffic_light_estimator/src/node.cpp index 6527f0662bcbf..904a365786755 100644 --- a/perception/crosswalk_traffic_light_estimator/src/node.cpp +++ b/perception/crosswalk_traffic_light_estimator/src/node.cpp @@ -73,7 +73,6 @@ bool hasMergeLane( return false; } - } // namespace CrosswalkTrafficLightEstimatorNode::CrosswalkTrafficLightEstimatorNode( @@ -84,6 +83,7 @@ CrosswalkTrafficLightEstimatorNode::CrosswalkTrafficLightEstimatorNode( use_last_detect_color_ = declare_parameter("use_last_detect_color"); last_detect_color_hold_time_ = declare_parameter("last_detect_color_hold_time"); + last_colors_hold_time_ = declare_parameter("last_colors_hold_time"); sub_map_ = create_subscription( "~/input/vector_map", rclcpp::QoS{1}.transient_local(), @@ -164,19 +164,19 @@ void CrosswalkTrafficLightEstimatorNode::onTrafficLightArray( traffic_light_id_map[traffic_signal.traffic_signal_id] = std::pair(traffic_signal, get_clock()->now()); } - for (const auto & crosswalk : conflicting_crosswalks_) { constexpr int VEHICLE_GRAPH_ID = 0; const auto conflict_lls = overall_graphs_ptr_->conflictingInGraph(crosswalk, VEHICLE_GRAPH_ID); const auto non_red_lanelets = getNonRedLanelets(conflict_lls, traffic_light_id_map); const auto crosswalk_tl_color = estimateCrosswalkTrafficSignal(crosswalk, non_red_lanelets); - setCrosswalkTrafficSignal(crosswalk, crosswalk_tl_color, output); + setCrosswalkTrafficSignal(crosswalk, crosswalk_tl_color, *msg, output); } removeDuplicateIds(output); updateLastDetectedSignal(traffic_light_id_map); + updateLastDetectedSignals(traffic_light_id_map); pub_traffic_light_array_->publish(output); pub_processing_time_->publish("processing_time_ms", stop_watch.toc("Total")); @@ -221,24 +221,160 @@ void CrosswalkTrafficLightEstimatorNode::updateLastDetectedSignal( } } } - for (const auto id : erase_id_list) last_detect_color_.erase(id); + for (const auto id : erase_id_list) { + last_detect_color_.erase(id); + is_flashing_.erase(id); + current_color_state_.erase(id); + } +} + +void CrosswalkTrafficLightEstimatorNode::updateLastDetectedSignals( + const TrafficLightIdMap & traffic_light_id_map) +{ + for (const auto & input_traffic_signal : traffic_light_id_map) { + const auto & elements = input_traffic_signal.second.first.elements; + + if (elements.empty()) { + continue; + } + + if ( + elements.front().color == TrafficSignalElement::UNKNOWN && elements.front().confidence == 1) { + continue; + } + + const auto & id = input_traffic_signal.second.first.traffic_signal_id; + + if (last_colors_.count(id) == 0) { + std::vector signal{input_traffic_signal.second}; + last_colors_.insert(std::make_pair(id, signal)); + continue; + } + + last_colors_.at(id).push_back(input_traffic_signal.second); + } + + std::vector erase_id_list; + for (auto & last_traffic_signal : last_colors_) { + const auto & id = last_traffic_signal.first; + for (auto it = last_traffic_signal.second.begin(); it != last_traffic_signal.second.end();) { + auto sig = (*it).first; + rclcpp::Time t = (*it).second; + + // hold signal recognition results for [last_colors_hold_time_] seconds. + const auto time_from_last_detected = (get_clock()->now() - t).seconds(); + if (time_from_last_detected > last_colors_hold_time_) { + it = last_traffic_signal.second.erase(it); + } else { + ++it; + } + } + if (last_traffic_signal.second.empty()) { + erase_id_list.emplace_back(id); + } + } + for (const auto id : erase_id_list) last_colors_.erase(id); } void CrosswalkTrafficLightEstimatorNode::setCrosswalkTrafficSignal( - const lanelet::ConstLanelet & crosswalk, const uint8_t color, TrafficSignalArray & msg) const + const lanelet::ConstLanelet & crosswalk, const uint8_t color, const TrafficSignalArray & msg, + TrafficSignalArray & output) { const auto tl_reg_elems = crosswalk.regulatoryElementsAs(); + std::unordered_map valid_id2idx_map; // detected traffic light + + for (size_t i = 0; i < msg.signals.size(); ++i) { + auto signal = msg.signals[i]; + valid_id2idx_map[signal.traffic_signal_id] = i; + } + for (const auto & tl_reg_elem : tl_reg_elems) { - TrafficSignal output_traffic_signal; - TrafficSignalElement output_traffic_signal_element; - output_traffic_signal_element.color = color; - output_traffic_signal_element.shape = TrafficSignalElement::CIRCLE; - output_traffic_signal_element.confidence = 1.0; - output_traffic_signal.elements.push_back(output_traffic_signal_element); - output_traffic_signal.traffic_signal_id = tl_reg_elem->id(); - msg.signals.push_back(output_traffic_signal); + auto id = tl_reg_elem->id(); + // if valid prediction exists, overwrite the estimation; else, use the estimation + if (valid_id2idx_map.count(id)) { + size_t idx = valid_id2idx_map[id]; + auto signal = msg.signals[idx]; + updateFlashingState(signal); // check if it is flashing + // update output msg according to flashing and current state + output.signals[idx].elements[0].color = updateAndGetColorState(signal); + } else { + TrafficSignal output_traffic_signal; + TrafficSignalElement output_traffic_signal_element; + output_traffic_signal_element.color = color; + output_traffic_signal_element.shape = TrafficSignalElement::CIRCLE; + output_traffic_signal_element.confidence = 1.0; + output_traffic_signal.elements.push_back(output_traffic_signal_element); + output_traffic_signal.traffic_signal_id = id; + output.signals.push_back(output_traffic_signal); + } + } +} + +void CrosswalkTrafficLightEstimatorNode::updateFlashingState(const TrafficSignal & signal) +{ + const auto id = signal.traffic_signal_id; + + // no record of detected color in last_detect_color_hold_time_ + if (is_flashing_.count(id) == 0) { + is_flashing_.insert(std::make_pair(id, false)); + return; + } + + // flashing green + if ( + signal.elements.front().color == TrafficSignalElement::UNKNOWN && + signal.elements.front().confidence != 0 && // not due to occlusion + current_color_state_.at(id) != TrafficSignalElement::UNKNOWN) { + is_flashing_.at(id) = true; + return; + } + + // history exists + if (last_colors_.count(id) > 0) { + std::vector history = last_colors_.at(id); + for (const auto & h : history) { + if (h.first.elements.front().color != signal.elements.front().color) { + // keep the current value if not same with input signal + return; + } + } + // all history is same with input signal + is_flashing_.at(id) = false; + } + + // no record of detected color in last_color_hold_time_ + // keep the current value + return; +} + +uint8_t CrosswalkTrafficLightEstimatorNode::updateAndGetColorState(const TrafficSignal & signal) +{ + const auto id = signal.traffic_signal_id; + const auto color = signal.elements[0].color; + + if (current_color_state_.count(id) == 0) { + current_color_state_.insert(std::make_pair(id, color)); + } else if (is_flashing_.at(id) == false) { + current_color_state_.at(id) = color; + } else if (is_flashing_.at(id) == true) { + if ( + current_color_state_.at(id) == TrafficSignalElement::GREEN && + color == TrafficSignalElement::RED) { + current_color_state_.at(id) = TrafficSignalElement::RED; + } else if ( + current_color_state_.at(id) == TrafficSignalElement::RED && + color == TrafficSignalElement::GREEN) { + current_color_state_.at(id) = TrafficSignalElement::GREEN; + } else if (current_color_state_.at(id) == TrafficSignalElement::UNKNOWN) { + if (color == TrafficSignalElement::GREEN || color == TrafficSignalElement::UNKNOWN) + current_color_state_.at(id) = TrafficSignalElement::GREEN; + if (color == TrafficSignalElement::RED) + current_color_state_.at(id) = TrafficSignalElement::RED; + } } + + return current_color_state_.at(id); } lanelet::ConstLanelets CrosswalkTrafficLightEstimatorNode::getNonRedLanelets( diff --git a/perception/traffic_light_classifier/include/traffic_light_classifier/nodelet.hpp b/perception/traffic_light_classifier/include/traffic_light_classifier/nodelet.hpp index 89b91c5fb666c..1281285ee53dd 100644 --- a/perception/traffic_light_classifier/include/traffic_light_classifier/nodelet.hpp +++ b/perception/traffic_light_classifier/include/traffic_light_classifier/nodelet.hpp @@ -66,6 +66,8 @@ class TrafficLightClassifierNodelet : public rclcpp::Node CNN = 1, }; + uint8_t classify_traffic_light_type_; + private: void connectCb(); diff --git a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml index 8ba0990b3efc6..343531f4a00f1 100644 --- a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml +++ b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml @@ -11,6 +11,8 @@ + + @@ -21,6 +23,7 @@ + diff --git a/perception/traffic_light_classifier/src/nodelet.cpp b/perception/traffic_light_classifier/src/nodelet.cpp index d0d7e13b928c8..3a00bb013d867 100644 --- a/perception/traffic_light_classifier/src/nodelet.cpp +++ b/perception/traffic_light_classifier/src/nodelet.cpp @@ -23,6 +23,8 @@ namespace traffic_light TrafficLightClassifierNodelet::TrafficLightClassifierNodelet(const rclcpp::NodeOptions & options) : Node("traffic_light_classifier_node", options) { + classify_traffic_light_type_ = this->declare_parameter("classify_traffic_light_type", 0); + using std::placeholders::_1; using std::placeholders::_2; is_approximate_sync_ = this->declare_parameter("approximate_sync", false); @@ -96,16 +98,28 @@ void TrafficLightClassifierNodelet::imageRoiCallback( output_msg.signals.resize(input_rois_msg->rois.size()); std::vector images; + size_t num_valid_roi = 0; std::vector backlight_indices; for (size_t i = 0; i < input_rois_msg->rois.size(); i++) { - output_msg.signals[i].traffic_light_id = input_rois_msg->rois.at(i).traffic_light_id; + // skip if not the expected type of roi + if (input_rois_msg->rois.at(i).traffic_light_type != classify_traffic_light_type_) { + continue; + } + output_msg.signals[num_valid_roi].traffic_light_id = + input_rois_msg->rois.at(i).traffic_light_id; + output_msg.signals[num_valid_roi].traffic_light_type = + input_rois_msg->rois.at(i).traffic_light_type; const sensor_msgs::msg::RegionOfInterest & roi = input_rois_msg->rois.at(i).roi; + auto roi_img = cv_ptr->image(cv::Rect(roi.x_offset, roi.y_offset, roi.width, roi.height)); if (is_harsh_backlight(roi_img)) { backlight_indices.emplace_back(i); } images.emplace_back(roi_img); + num_valid_roi++; } + output_msg.signals.resize(num_valid_roi); + if (!classifier_ptr_->getTrafficSignals(images, output_msg)) { RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback"); return; diff --git a/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp b/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp index f2f1f17be6894..5c89c76a11833 100644 --- a/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp +++ b/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp @@ -115,6 +115,7 @@ class TrafficLightFineDetectorNodelet : public rclcpp::Node void detectionMatch( std::map & id2expectRoi, std::map & id2detections, TrafficLightRoiArray & out_rois); + /** * @brief convert image message to cv::Mat * @@ -137,7 +138,8 @@ class TrafficLightFineDetectorNodelet : public rclcpp::Node * @return true succeed * @return false failed */ - bool readLabelFile(const std::string & filepath, int & tlr_id, int & num_class); + bool readLabelFile( + const std::string & filepath, std::vector & tlr_label_id_, int & num_class); // variables image_transport::SubscriberFilter image_sub_; @@ -162,7 +164,7 @@ class TrafficLightFineDetectorNodelet : public rclcpp::Node bool is_approximate_sync_; double score_thresh_; - int tlr_id_; + std::vector tlr_label_id_; int batch_size_; std::unique_ptr trt_yolox_; diff --git a/perception/traffic_light_fine_detector/src/nodelet.cpp b/perception/traffic_light_fine_detector/src/nodelet.cpp index 86e77bc31cd71..257e9fc7ea99d 100644 --- a/perception/traffic_light_fine_detector/src/nodelet.cpp +++ b/perception/traffic_light_fine_detector/src/nodelet.cpp @@ -73,7 +73,7 @@ TrafficLightFineDetectorNodelet::TrafficLightFineDetectorNodelet( float nms_threshold = declare_parameter("fine_detector_nms_thresh", 0.65); is_approximate_sync_ = this->declare_parameter("approximate_sync", false); - if (!readLabelFile(label_path, tlr_id_, num_class)) { + if (!readLabelFile(label_path, tlr_label_id_, num_class)) { RCLCPP_ERROR(this->get_logger(), "Could not find tlr id"); } @@ -157,6 +157,7 @@ void TrafficLightFineDetectorNodelet::callback( tensorrt_yolox::ObjectArrays inference_results; std::vector lts; std::vector roi_ids; + for (size_t roi_i = 0; roi_i < rough_roi_msg->rois.size(); roi_i++) { const auto & rough_roi = rough_roi_msg->rois[roi_i]; cv::Point lt(rough_roi.roi.x_offset, rough_roi.roi.y_offset); @@ -178,7 +179,7 @@ void TrafficLightFineDetectorNodelet::callback( trt_yolox_->doMultiScaleInference(original_image, inference_results, rois); for (size_t batch_i = 0; batch_i < true_batch_size; batch_i++) { for (const tensorrt_yolox::Object & detection : inference_results[batch_i]) { - if (detection.score < score_thresh_ || detection.type != tlr_id_) { + if (detection.score < score_thresh_) { continue; } cv::Point lt_roi( @@ -190,6 +191,7 @@ void TrafficLightFineDetectorNodelet::callback( det.y_offset = lt_roi.y; det.width = rb_roi.x - lt_roi.x; det.height = rb_roi.y - lt_roi.y; + det.type = detection.type; id2detections[roi_ids[batch_i]].push_back(det); } } @@ -273,6 +275,7 @@ void TrafficLightFineDetectorNodelet::detectionMatch( for (const auto & p : bestDetections) { TrafficLightRoi tlr; tlr.traffic_light_id = p.first; + tlr.traffic_light_type = id2expectRoi[p.first].traffic_light_type; tlr.roi.x_offset = p.second.x_offset; tlr.roi.y_offset = p.second.y_offset; tlr.roi.width = p.second.width; @@ -318,9 +321,8 @@ bool TrafficLightFineDetectorNodelet::fitInFrame( } bool TrafficLightFineDetectorNodelet::readLabelFile( - const std::string & filepath, int & tlr_id, int & num_class) + const std::string & filepath, std::vector & tlr_label_id_, int & num_class) { - tlr_id = -1; std::ifstream labelsFile(filepath); if (!labelsFile.is_open()) { RCLCPP_ERROR(this->get_logger(), "Could not open label file. [%s]", filepath.c_str()); @@ -329,13 +331,13 @@ bool TrafficLightFineDetectorNodelet::readLabelFile( std::string label; int idx = 0; while (getline(labelsFile, label)) { - if (label == "traffic_light") { - tlr_id = idx; + if (label == "traffic_light" || label == "pedestrian_traffic_light") { + tlr_label_id_.push_back(idx); } idx++; } num_class = idx; - return tlr_id != -1; + return tlr_label_id_.size() != 0; } } // namespace traffic_light diff --git a/perception/traffic_light_map_based_detector/config/traffic_light_map_based_detector.param.yaml b/perception/traffic_light_map_based_detector/config/traffic_light_map_based_detector.param.yaml index 2b8ff4aa737b7..2eb671c1f5150 100644 --- a/perception/traffic_light_map_based_detector/config/traffic_light_map_based_detector.param.yaml +++ b/perception/traffic_light_map_based_detector/config/traffic_light_map_based_detector.param.yaml @@ -6,3 +6,5 @@ max_vibration_width: 0.5 # -0.25 ~ 0.25 m max_vibration_depth: 0.5 # -0.25 ~ 0.25 m max_detection_range: 200.0 + car_traffic_light_max_angle_range: 40.0 + pedestrian_traffic_light_max_angle_range: 80.0 diff --git a/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp b/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp index e46431a7b199e..0d2b7ffeb7597 100644 --- a/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp +++ b/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp @@ -58,6 +58,8 @@ class MapBasedDetector : public rclcpp::Node double max_timestamp_offset; double timestamp_sample_len; double max_detection_range; + double car_traffic_light_max_angle_range; + double pedestrian_traffic_light_max_angle_range; }; struct IdLessThan @@ -93,10 +95,14 @@ class MapBasedDetector : public rclcpp::Node std::shared_ptr all_traffic_lights_ptr_; std::shared_ptr route_traffic_lights_ptr_; + std::set pedestrian_tl_id_; + lanelet::LaneletMapPtr lanelet_map_ptr_; lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_; lanelet::routing::RoutingGraphPtr routing_graph_ptr_; + std::shared_ptr overall_graphs_ptr_; + Config config_; /** * @brief Calculated the transform from map to frame_id at timestamp t diff --git a/perception/traffic_light_map_based_detector/src/node.cpp b/perception/traffic_light_map_based_detector/src/node.cpp index f0a5d7b7b1fde..5689e55dca316 100644 --- a/perception/traffic_light_map_based_detector/src/node.cpp +++ b/perception/traffic_light_map_based_detector/src/node.cpp @@ -137,6 +137,10 @@ MapBasedDetector::MapBasedDetector(const rclcpp::NodeOptions & node_options) config_.max_timestamp_offset = declare_parameter("max_timestamp_offset", 0.0); config_.timestamp_sample_len = declare_parameter("timestamp_sample_len", 0.01); config_.max_detection_range = declare_parameter("max_detection_range", 200.0); + config_.car_traffic_light_max_angle_range = + declare_parameter("car_traffic_light_max_angle_range", 40.0); + config_.pedestrian_traffic_light_max_angle_range = + declare_parameter("pedestrian_traffic_light_max_angle_range", 80.0); if (config_.max_detection_range <= 0) { RCLCPP_ERROR_STREAM( @@ -287,6 +291,11 @@ bool MapBasedDetector::getTrafficLightRoi( tier4_perception_msgs::msg::TrafficLightRoi & roi) const { roi.traffic_light_id = traffic_light.id(); + if (pedestrian_tl_id_.find(traffic_light.id()) != pedestrian_tl_id_.end()) { + roi.traffic_light_type = tier4_perception_msgs::msg::TrafficLightRoi::PEDESTRIAN_TRAFFIC_LIGHT; + } else { + roi.traffic_light_type = tier4_perception_msgs::msg::TrafficLightRoi::CAR_TRAFFIC_LIGHT; + } // for roi.x_offset and roi.y_offset { @@ -392,7 +401,6 @@ void MapBasedDetector::mapCallback( for (auto tl_itr = all_lanelet_traffic_lights.begin(); tl_itr != all_lanelet_traffic_lights.end(); ++tl_itr) { lanelet::AutowareTrafficLightConstPtr tl = *tl_itr; - auto lights = tl->trafficLights(); for (auto lsp : lights) { if (!lsp.isLineString()) { // traffic lights must be linestrings @@ -401,6 +409,28 @@ void MapBasedDetector::mapCallback( all_traffic_lights_ptr_->insert(static_cast(lsp)); } } + + auto crosswalk_lanelets = lanelet::utils::query::crosswalkLanelets(all_lanelets); + for (const auto & tl : lanelet::utils::query::autowareTrafficLights(crosswalk_lanelets)) { + for (const auto & lsp : tl->trafficLights()) { + if (lsp.isLineString()) { // traffic lights must be linestrings + pedestrian_tl_id_.insert(lsp.id()); + } + } + } + + // crosswalk + const auto traffic_rules = lanelet::traffic_rules::TrafficRulesFactory::create( + lanelet::Locations::Germany, lanelet::Participants::Vehicle); + const auto pedestrian_rules = lanelet::traffic_rules::TrafficRulesFactory::create( + lanelet::Locations::Germany, lanelet::Participants::Pedestrian); + lanelet::routing::RoutingGraphConstPtr vehicle_graph = + lanelet::routing::RoutingGraph::build(*lanelet_map_ptr_, *traffic_rules); + lanelet::routing::RoutingGraphConstPtr pedestrian_graph = + lanelet::routing::RoutingGraph::build(*lanelet_map_ptr_, *pedestrian_rules); + lanelet::routing::RoutingGraphContainer overall_graphs({vehicle_graph, pedestrian_graph}); + overall_graphs_ptr_ = + std::make_shared(overall_graphs); } void MapBasedDetector::routeCallback( @@ -436,6 +466,34 @@ void MapBasedDetector::routeCallback( route_traffic_lights_ptr_->insert(static_cast(lsp)); } } + + // crosswalk trafficlights + lanelet::ConstLanelets conflicting_crosswalks; + pedestrian_tl_id_.clear(); + + for (const auto & route_lanelet : route_lanelets) { + constexpr int PEDESTRIAN_GRAPH_ID = 1; + const auto conflict_lls = + overall_graphs_ptr_->conflictingInGraph(route_lanelet, PEDESTRIAN_GRAPH_ID); + for (const auto & lanelet : conflict_lls) { + conflicting_crosswalks.push_back(lanelet); + } + } + std::vector crosswalk_lanelet_traffic_lights = + lanelet::utils::query::autowareTrafficLights(conflicting_crosswalks); + for (auto tl_itr = crosswalk_lanelet_traffic_lights.begin(); + tl_itr != crosswalk_lanelet_traffic_lights.end(); ++tl_itr) { + lanelet::AutowareTrafficLightConstPtr tl = *tl_itr; + + auto lights = tl->trafficLights(); + for (auto lsp : lights) { + if (!lsp.isLineString()) { // traffic lights must be linestrings + continue; + } + route_traffic_lights_ptr_->insert(static_cast(lsp)); + pedestrian_tl_id_.insert(lsp.id()); + } + } } void MapBasedDetector::getVisibleTrafficLights( @@ -445,12 +503,19 @@ void MapBasedDetector::getVisibleTrafficLights( std::vector & visible_traffic_lights) const { for (const auto & traffic_light : all_traffic_lights) { - // some "Traffic Light" are actually not traffic lights if ( traffic_light.hasAttribute("subtype") == false || traffic_light.attribute("subtype").value() == "solid") { continue; } + // set different max angle range for ped and car traffic light + double max_angle_range; + if (pedestrian_tl_id_.find(traffic_light.id()) != pedestrian_tl_id_.end()) { + max_angle_range = + tier4_autoware_utils::deg2rad(config_.pedestrian_traffic_light_max_angle_range); + } else { + max_angle_range = tier4_autoware_utils::deg2rad(config_.car_traffic_light_max_angle_range); + } // traffic light bottom left const auto & tl_bl = traffic_light.front(); // traffic light bottom right @@ -467,7 +532,6 @@ void MapBasedDetector::getVisibleTrafficLights( // check angle range const double tl_yaw = tier4_autoware_utils::normalizeRadian( std::atan2(tl_br.y() - tl_bl.y(), tl_br.x() - tl_bl.x()) + M_PI_2); - constexpr double max_angle_range = tier4_autoware_utils::deg2rad(40.0); // get direction of z axis tf2::Vector3 camera_z_dir(0, 0, 1); diff --git a/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp index 71930c65f88c9..ae6ba8c1feedb 100644 --- a/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp +++ b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp @@ -37,6 +37,7 @@ #include #include #include +#include namespace traffic_light { @@ -71,7 +72,8 @@ class TrafficLightOcclusionPredictorNodelet : public rclcpp::Node const tier4_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr in_signal_msg, const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr in_roi_msg, const sensor_msgs::msg::CameraInfo::ConstSharedPtr in_cam_info_msg, - const sensor_msgs::msg::PointCloud2::ConstSharedPtr in_cloud_msg); + const sensor_msgs::msg::PointCloud2::ConstSharedPtr in_cloud_msg, + const uint8_t traffic_light_type); rclcpp::Subscription::SharedPtr map_sub_; /** @@ -89,7 +91,6 @@ class TrafficLightOcclusionPredictorNodelet : public rclcpp::Node * */ std::shared_ptr cloud_occlusion_predictor_; - typedef perception_utils::PrimeSynchronizer< tier4_perception_msgs::msg::TrafficSignalArray, tier4_perception_msgs::msg::TrafficLightRoiArray, sensor_msgs::msg::CameraInfo, @@ -97,6 +98,11 @@ class TrafficLightOcclusionPredictorNodelet : public rclcpp::Node SynchronizerType; std::shared_ptr synchronizer_; + std::shared_ptr synchronizer_ped_; + + std::vector subscribed_; + std::vector occlusion_ratios_; + tier4_perception_msgs::msg::TrafficSignalArray out_msg_; }; } // namespace traffic_light #endif // TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__NODELET_HPP_ diff --git a/perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml b/perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml index 795267b920e24..aa7e34f8a4a09 100644 --- a/perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml +++ b/perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml @@ -4,7 +4,8 @@ - + + @@ -13,7 +14,8 @@ - + + diff --git a/perception/traffic_light_occlusion_predictor/src/nodelet.cpp b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp index c460f6a623bc4..97fa98ab18a72 100644 --- a/perception/traffic_light_occlusion_predictor/src/nodelet.cpp +++ b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp @@ -18,6 +18,7 @@ #include #include #include +#include #include #include @@ -57,6 +58,7 @@ TrafficLightOcclusionPredictorNodelet::TrafficLightOcclusionPredictorNodelet( // publishers signal_pub_ = create_publisher("~/output/traffic_signals", 1); + // configuration parameters config_.azimuth_occlusion_resolution_deg = declare_parameter("azimuth_occlusion_resolution_deg", 0.15); @@ -72,12 +74,26 @@ TrafficLightOcclusionPredictorNodelet::TrafficLightOcclusionPredictorNodelet( config_.elevation_occlusion_resolution_deg); const std::vector topics{ - "~/input/traffic_signals", "~/input/rois", "~/input/camera_info", "~/input/cloud"}; + "~/input/car/traffic_signals", "~/input/rois", "~/input/camera_info", "~/input/cloud"}; const std::vector qos(topics.size(), rclcpp::SensorDataQoS()); synchronizer_ = std::make_shared( this, topics, qos, - std::bind(&TrafficLightOcclusionPredictorNodelet::syncCallback, this, _1, _2, _3, _4), + std::bind( + &TrafficLightOcclusionPredictorNodelet::syncCallback, this, _1, _2, _3, _4, + tier4_perception_msgs::msg::TrafficLightRoi::CAR_TRAFFIC_LIGHT), + config_.max_image_cloud_delay, config_.max_wait_t); + + const std::vector topics_ped{ + "~/input/pedestrian/traffic_signals", "~/input/rois", "~/input/camera_info", "~/input/cloud"}; + const std::vector qos_ped(topics_ped.size(), rclcpp::SensorDataQoS()); + synchronizer_ped_ = std::make_shared( + this, topics_ped, qos_ped, + std::bind( + &TrafficLightOcclusionPredictorNodelet::syncCallback, this, _1, _2, _3, _4, + tier4_perception_msgs::msg::TrafficLightRoi::PEDESTRIAN_TRAFFIC_LIGHT), config_.max_image_cloud_delay, config_.max_wait_t); + + subscribed_.resize(2, false); } void TrafficLightOcclusionPredictorNodelet::mapCallback( @@ -109,27 +125,53 @@ void TrafficLightOcclusionPredictorNodelet::syncCallback( const tier4_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr in_signal_msg, const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr in_roi_msg, const sensor_msgs::msg::CameraInfo::ConstSharedPtr in_cam_info_msg, - const sensor_msgs::msg::PointCloud2::ConstSharedPtr in_cloud_msg) + const sensor_msgs::msg::PointCloud2::ConstSharedPtr in_cloud_msg, + const uint8_t traffic_light_type) { - tier4_perception_msgs::msg::TrafficSignalArray out_msg = *in_signal_msg; std::vector occlusion_ratios; - if ( - in_cloud_msg == nullptr || in_cam_info_msg == nullptr || in_roi_msg == nullptr || - in_roi_msg->rois.size() != in_signal_msg->signals.size()) { - occlusion_ratios.resize(out_msg.signals.size(), 0); + if (in_cloud_msg == nullptr || in_cam_info_msg == nullptr || in_roi_msg == nullptr) { + occlusion_ratios.resize(in_signal_msg->signals.size(), 0); } else { - cloud_occlusion_predictor_->predict( - in_cam_info_msg, in_roi_msg, in_cloud_msg, tf_buffer_, traffic_light_position_map_, - occlusion_ratios); + tier4_perception_msgs::msg::TrafficLightRoiArray selected_roi_msg; + selected_roi_msg.rois.reserve(in_roi_msg->rois.size()); + for (size_t i = 0; i < in_roi_msg->rois.size(); ++i) { + if (in_roi_msg->rois.at(i).traffic_light_type == traffic_light_type) { + selected_roi_msg.rois.push_back(in_roi_msg->rois.at(i)); + } + } + + tier4_perception_msgs::msg::TrafficSignalArray out_msg = *in_signal_msg; + + if (selected_roi_msg.rois.size() != in_signal_msg->signals.size()) { + occlusion_ratios.resize(in_signal_msg->signals.size(), 0); + } else { + auto selected_roi_msg_ptr = + std::make_shared(selected_roi_msg); + cloud_occlusion_predictor_->predict( + in_cam_info_msg, selected_roi_msg_ptr, in_cloud_msg, tf_buffer_, + traffic_light_position_map_, occlusion_ratios); + } } + + size_t predicted_num = out_msg_.signals.size(); + for (size_t i = 0; i < occlusion_ratios.size(); i++) { + out_msg_.signals.push_back(in_signal_msg->signals.at(i)); + if (occlusion_ratios[i] >= config_.max_occlusion_ratio) { - traffic_light_utils::setSignalUnknown(out_msg.signals[i]); + traffic_light_utils::setSignalUnknown(out_msg_.signals.at(predicted_num + i), 0.0); } } - signal_pub_->publish(out_msg); + subscribed_.at(traffic_light_type) = true; + + if (std::all_of(subscribed_.begin(), subscribed_.end(), [](bool v) { return v; })) { + auto pub_msg = std::make_unique(out_msg_); + pub_msg->header = in_signal_msg->header; + signal_pub_->publish(std::move(pub_msg)); + out_msg_.signals.clear(); + std::fill(subscribed_.begin(), subscribed_.end(), false); + } } - } // namespace traffic_light #include From d3b447f24d2492603422bddfa6cd501865ef7964 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 29 Dec 2023 15:37:41 +0900 Subject: [PATCH 176/276] fix(surround_obstacle_checker): remove the virtual wall from the node (#5991) Signed-off-by: Takayuki Murooka --- .../debug_marker.hpp | 2 -- .../src/debug_marker.cpp | 23 ------------------- 2 files changed, 25 deletions(-) diff --git a/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp b/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp index e71ff302e1b60..07a23a4ac2e67 100644 --- a/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp +++ b/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp @@ -71,7 +71,6 @@ class SurroundObstacleCheckerDebugNode const double back_distance); private: - rclcpp::Publisher::SharedPtr debug_virtual_wall_pub_; rclcpp::Publisher::SharedPtr debug_viz_pub_; rclcpp::Publisher::SharedPtr stop_reason_pub_; rclcpp::Publisher::SharedPtr velocity_factor_pub_; @@ -89,7 +88,6 @@ class SurroundObstacleCheckerDebugNode double surround_check_hysteresis_distance_; geometry_msgs::msg::Pose self_pose_; - MarkerArray makeVirtualWallMarker(); MarkerArray makeVisualizationMarker(); StopReasonArray makeStopReasonArray(); VelocityFactorArray makeVelocityFactorArray(); diff --git a/planning/surround_obstacle_checker/src/debug_marker.cpp b/planning/surround_obstacle_checker/src/debug_marker.cpp index 6c005aea5d21c..a0ca15d490e9c 100644 --- a/planning/surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/surround_obstacle_checker/src/debug_marker.cpp @@ -15,7 +15,6 @@ #include "surround_obstacle_checker/debug_marker.hpp" #include -#include #include #include #ifdef ROS_DISTRO_GALACTIC @@ -52,7 +51,6 @@ Polygon2d createSelfPolygon( } } // namespace -using motion_utils::createStopVirtualWallMarker; using tier4_autoware_utils::appendMarkerArray; using tier4_autoware_utils::calcOffsetPose; using tier4_autoware_utils::createDefaultMarker; @@ -76,8 +74,6 @@ SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( self_pose_(self_pose), clock_(clock) { - debug_virtual_wall_pub_ = - node.create_publisher("~/virtual_wall", 1); debug_viz_pub_ = node.create_publisher("~/debug/marker", 1); stop_reason_pub_ = node.create_publisher("~/output/stop_reasons", 1); velocity_factor_pub_ = @@ -141,10 +137,6 @@ void SurroundObstacleCheckerDebugNode::publishFootprints() void SurroundObstacleCheckerDebugNode::publish() { - /* publish virtual_wall marker for rviz */ - const auto virtual_wall_msg = makeVirtualWallMarker(); - debug_virtual_wall_pub_->publish(virtual_wall_msg); - /* publish debug marker for rviz */ const auto visualization_msg = makeVisualizationMarker(); debug_viz_pub_->publish(visualization_msg); @@ -160,21 +152,6 @@ void SurroundObstacleCheckerDebugNode::publish() stop_obstacle_point_ptr_ = nullptr; } -MarkerArray SurroundObstacleCheckerDebugNode::makeVirtualWallMarker() -{ - MarkerArray msg; - rclcpp::Time current_time = this->clock_->now(); - - // visualize stop line - if (stop_pose_ptr_ != nullptr) { - const auto p = calcOffsetPose(*stop_pose_ptr_, base_link2front_, 0.0, 0.0); - const auto markers = createStopVirtualWallMarker(p, "surround obstacle", current_time, 0); - appendMarkerArray(markers, &msg); - } - - return msg; -} - MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker() { MarkerArray msg; From b7d87dbf323c3e6836925a4a9fd83adb4b0bf057 Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Sun, 31 Dec 2023 13:55:04 +0100 Subject: [PATCH 177/276] feat(joy_controller): add xbox one joy mapping (#5999) * feat(joy_controller): add xbox one joy mapping Signed-off-by: amadeuszsz * fix(joy_controller): change to XBOX joy name Signed-off-by: amadeuszsz * fix(joy_controller): buttons naming Signed-off-by: amadeuszsz --------- Signed-off-by: amadeuszsz --- control/joy_controller/README.md | 22 +++++ .../joy_converter/xbox_joy_converter.hpp | 81 +++++++++++++++++++ .../launch/joy_controller.launch.xml | 2 +- .../schema/joy_controller.schema.json | 2 +- .../joy_controller/joy_controller_node.cpp | 3 + 5 files changed, 108 insertions(+), 2 deletions(-) create mode 100644 control/joy_controller/include/joy_controller/joy_converter/xbox_joy_converter.hpp diff --git a/control/joy_controller/README.md b/control/joy_controller/README.md index 4518de37b7034..d1215481188c7 100644 --- a/control/joy_controller/README.md +++ b/control/joy_controller/README.md @@ -85,3 +85,25 @@ | Autoware Disengage | ○ | | Vehicle Engage | △ | | Vehicle Disengage | △ | + +## XBOX Joystick Key Map + +| Action | Button | +| -------------------- | --------------------- | +| Acceleration | RT | +| Brake | LT | +| Steering | Left Stick Left Right | +| Shift up | Cursor Up | +| Shift down | Cursor Down | +| Shift Drive | Cursor Left | +| Shift Reverse | Cursor Right | +| Turn Signal Left | LB | +| Turn Signal Right | RB | +| Clear Turn Signal | A | +| Gate Mode | B | +| Emergency Stop | View | +| Clear Emergency Stop | Menu | +| Autoware Engage | X | +| Autoware Disengage | Y | +| Vehicle Engage | Left Stick Button | +| Vehicle Disengage | Right Stick Button | diff --git a/control/joy_controller/include/joy_controller/joy_converter/xbox_joy_converter.hpp b/control/joy_controller/include/joy_controller/joy_converter/xbox_joy_converter.hpp new file mode 100644 index 0000000000000..a009ee1e12975 --- /dev/null +++ b/control/joy_controller/include/joy_controller/joy_converter/xbox_joy_converter.hpp @@ -0,0 +1,81 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef JOY_CONTROLLER__JOY_CONVERTER__XBOX_JOY_CONVERTER_HPP_ +#define JOY_CONTROLLER__JOY_CONVERTER__XBOX_JOY_CONVERTER_HPP_ + +#include "joy_controller/joy_converter/joy_converter_base.hpp" + +#include + +namespace joy_controller +{ +class XBOXJoyConverter : public JoyConverterBase +{ +public: + explicit XBOXJoyConverter(const sensor_msgs::msg::Joy & j) : j_(j) {} + + float accel() const { return std::max(0.0f, -((RT() - 1.0f) / 2.0f)); } + + float brake() const { return std::max(0.0f, -((LT() - 1.0f) / 2.0f)); } + + float steer() const { return LStickLeftRight(); } + + bool shift_up() const { return CursorUpDown() == 1.0f; } + bool shift_down() const { return CursorUpDown() == -1.0f; } + bool shift_drive() const { return CursorLeftRight() == 1.0f; } + bool shift_reverse() const { return CursorLeftRight() == -1.0f; } + + bool turn_signal_left() const { return LB(); } + bool turn_signal_right() const { return RB(); } + bool clear_turn_signal() const { return A(); } + + bool gate_mode() const { return B(); } + + bool emergency_stop() const { return ChangeView(); } + bool clear_emergency_stop() const { return Menu(); } + + bool autoware_engage() const { return X(); } + bool autoware_disengage() const { return Y(); } + + bool vehicle_engage() const { return LStickButton(); } + bool vehicle_disengage() const { return RStickButton(); } + +private: + float LStickLeftRight() const { return j_.axes.at(0); } + float LStickUpDown() const { return j_.axes.at(1); } + float RStickLeftRight() const { return j_.axes.at(2); } + float RStickUpDown() const { return j_.axes.at(3); } + float RT() const { return j_.axes.at(4); } + float LT() const { return j_.axes.at(5); } + float CursorLeftRight() const { return j_.axes.at(6); } + float CursorUpDown() const { return j_.axes.at(7); } + + bool A() const { return j_.buttons.at(0); } + bool B() const { return j_.buttons.at(1); } + bool X() const { return j_.buttons.at(3); } + bool Y() const { return j_.buttons.at(4); } + bool LB() const { return j_.buttons.at(6); } + bool RB() const { return j_.buttons.at(7); } + bool Menu() const { return j_.buttons.at(11); } + bool LStickButton() const { return j_.buttons.at(13); } + bool RStickButton() const { return j_.buttons.at(14); } + bool ChangeView() const { return j_.buttons.at(15); } + bool Xbox() const { return j_.buttons.at(16); } + + const sensor_msgs::msg::Joy j_; +}; +} // namespace joy_controller + +#endif // JOY_CONTROLLER__JOY_CONVERTER__XBOX_JOY_CONVERTER_HPP_ diff --git a/control/joy_controller/launch/joy_controller.launch.xml b/control/joy_controller/launch/joy_controller.launch.xml index f719d8bd78cb5..d2804a7339046 100644 --- a/control/joy_controller/launch/joy_controller.launch.xml +++ b/control/joy_controller/launch/joy_controller.launch.xml @@ -1,5 +1,5 @@ - + diff --git a/control/joy_controller/schema/joy_controller.schema.json b/control/joy_controller/schema/joy_controller.schema.json index c67c575a6bd41..803997ced6dae 100644 --- a/control/joy_controller/schema/joy_controller.schema.json +++ b/control/joy_controller/schema/joy_controller.schema.json @@ -10,7 +10,7 @@ "type": "string", "description": "Joy controller type", "default": "DS4", - "enum": ["P65", "DS4", "G29"] + "enum": ["P65", "DS4", "G29", "XBOX"] }, "update_rate": { "type": "number", diff --git a/control/joy_controller/src/joy_controller/joy_controller_node.cpp b/control/joy_controller/src/joy_controller/joy_controller_node.cpp index 897986a7a41cf..d82967324aef7 100644 --- a/control/joy_controller/src/joy_controller/joy_controller_node.cpp +++ b/control/joy_controller/src/joy_controller/joy_controller_node.cpp @@ -16,6 +16,7 @@ #include "joy_controller/joy_converter/ds4_joy_converter.hpp" #include "joy_controller/joy_converter/g29_joy_converter.hpp" #include "joy_controller/joy_converter/p65_joy_converter.hpp" +#include "joy_controller/joy_converter/xbox_joy_converter.hpp" #include @@ -154,6 +155,8 @@ void AutowareJoyControllerNode::onJoy(const sensor_msgs::msg::Joy::ConstSharedPt joy_ = std::make_shared(*msg); } else if (joy_type_ == "DS4") { joy_ = std::make_shared(*msg); + } else if (joy_type_ == "XBOX") { + joy_ = std::make_shared(*msg); } else { joy_ = std::make_shared(*msg); } From e73ba2d845d9587ee7289b572e78875f2bbc2e3e Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Sun, 31 Dec 2023 13:58:31 +0100 Subject: [PATCH 178/276] feat(joy_controller): allow to control without odometry (#6000) * feat(joy_controller): allow to control without odometry Signed-off-by: amadeuszsz * style(pre-commit): autofix --------- Signed-off-by: amadeuszsz Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- control/joy_controller/README.md | 1 + .../config/joy_controller.param.yaml | 1 + .../include/joy_controller/joy_controller.hpp | 1 + .../schema/joy_controller.schema.json | 6 ++++++ .../src/joy_controller/joy_controller_node.cpp | 15 ++++++++++----- 5 files changed, 19 insertions(+), 5 deletions(-) diff --git a/control/joy_controller/README.md b/control/joy_controller/README.md index d1215481188c7..b8ee8ad79a33d 100644 --- a/control/joy_controller/README.md +++ b/control/joy_controller/README.md @@ -37,6 +37,7 @@ | `steering_angle_velocity` | double | steering angle velocity for operation | | `accel_sensitivity` | double | sensitivity to calculate acceleration for external API (commanded acceleration is pow(operation, 1 / sensitivity)) | | `brake_sensitivity` | double | sensitivity to calculate deceleration for external API (commanded acceleration is pow(operation, 1 / sensitivity)) | +| `raw_control` | bool | skip input odometry if true | | `velocity_gain` | double | ratio to calculate velocity by acceleration | | `max_forward_velocity` | double | absolute max velocity to go forward | | `max_backward_velocity` | double | absolute max velocity to go backward | diff --git a/control/joy_controller/config/joy_controller.param.yaml b/control/joy_controller/config/joy_controller.param.yaml index 8d48948a2d133..73a5d028985c5 100644 --- a/control/joy_controller/config/joy_controller.param.yaml +++ b/control/joy_controller/config/joy_controller.param.yaml @@ -9,6 +9,7 @@ accel_sensitivity: 1.0 brake_sensitivity: 1.0 control_command: + raw_control: false velocity_gain: 3.0 max_forward_velocity: 20.0 max_backward_velocity: 3.0 diff --git a/control/joy_controller/include/joy_controller/joy_controller.hpp b/control/joy_controller/include/joy_controller/joy_controller.hpp index c6de42afc38d9..22064f9cefaad 100644 --- a/control/joy_controller/include/joy_controller/joy_controller.hpp +++ b/control/joy_controller/include/joy_controller/joy_controller.hpp @@ -59,6 +59,7 @@ class AutowareJoyControllerNode : public rclcpp::Node double brake_sensitivity_; // ControlCommand Parameter + bool raw_control_; double velocity_gain_; double max_forward_velocity_; double max_backward_velocity_; diff --git a/control/joy_controller/schema/joy_controller.schema.json b/control/joy_controller/schema/joy_controller.schema.json index 803997ced6dae..d4c6351324935 100644 --- a/control/joy_controller/schema/joy_controller.schema.json +++ b/control/joy_controller/schema/joy_controller.schema.json @@ -55,6 +55,11 @@ "control_command": { "type": "object", "properties": { + "raw_control": { + "type": "boolean", + "description": "Whether to skip input odometry", + "default": false + }, "velocity_gain": { "type": "number", "description": "Ratio to calculate velocity by acceleration", @@ -79,6 +84,7 @@ } }, "required": [ + "raw_control", "velocity_gain", "max_forward_velocity", "max_backward_velocity", diff --git a/control/joy_controller/src/joy_controller/joy_controller_node.cpp b/control/joy_controller/src/joy_controller/joy_controller_node.cpp index d82967324aef7..5eec438032410 100644 --- a/control/joy_controller/src/joy_controller/joy_controller_node.cpp +++ b/control/joy_controller/src/joy_controller/joy_controller_node.cpp @@ -220,7 +220,7 @@ bool AutowareJoyControllerNode::isDataReady() } // Twist - { + if (!raw_control_) { if (!twist_) { RCLCPP_WARN_THROTTLE( get_logger(), *get_clock(), std::chrono::milliseconds(5000).count(), @@ -461,6 +461,7 @@ AutowareJoyControllerNode::AutowareJoyControllerNode(const rclcpp::NodeOptions & steering_angle_velocity_ = declare_parameter("steering_angle_velocity"); accel_sensitivity_ = declare_parameter("accel_sensitivity"); brake_sensitivity_ = declare_parameter("brake_sensitivity"); + raw_control_ = declare_parameter("control_command.raw_control"); velocity_gain_ = declare_parameter("control_command.velocity_gain"); max_forward_velocity_ = declare_parameter("control_command.max_forward_velocity"); max_backward_velocity_ = declare_parameter("control_command.max_backward_velocity"); @@ -480,10 +481,14 @@ AutowareJoyControllerNode::AutowareJoyControllerNode(const rclcpp::NodeOptions & sub_joy_ = this->create_subscription( "input/joy", 1, std::bind(&AutowareJoyControllerNode::onJoy, this, std::placeholders::_1), subscriber_option); - sub_odom_ = this->create_subscription( - "input/odometry", 1, - std::bind(&AutowareJoyControllerNode::onOdometry, this, std::placeholders::_1), - subscriber_option); + if (!raw_control_) { + sub_odom_ = this->create_subscription( + "input/odometry", 1, + std::bind(&AutowareJoyControllerNode::onOdometry, this, std::placeholders::_1), + subscriber_option); + } else { + twist_ = std::make_shared(); + } // Publisher pub_control_command_ = From c0e6a0255f93874f92c82907059152ec87ae751b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 4 Jan 2024 17:13:04 +0900 Subject: [PATCH 179/276] refactor(intersection): cleanup utility function (#5972) Signed-off-by: Mamoru Sobue --- .../src/scene_intersection.cpp | 1422 +++++++++++++++-- .../src/scene_intersection.hpp | 490 +++++- .../src/scene_merge_from_private_road.cpp | 77 +- .../src/scene_merge_from_private_road.hpp | 8 +- .../src/util.cpp | 1389 +--------------- .../src/util.hpp | 176 +- .../src/util_type.hpp | 172 +- 7 files changed, 1885 insertions(+), 1849 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 631c03d923da0..292a6e6a8843d 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -17,7 +17,11 @@ #include "util.hpp" #include +#include #include +#include +#include +#include #include #include #include @@ -37,10 +41,27 @@ #include #include +#include #include #include #include #include + +namespace tier4_autoware_utils +{ + +template <> +inline geometry_msgs::msg::Point getPoint(const lanelet::ConstPoint3d & p) +{ + geometry_msgs::msg::Point point; + point.x = p.x(); + point.y = p.y(); + point.z = p.z(); + return point; +} + +} // namespace tier4_autoware_utils + namespace behavior_velocity_planner { namespace bg = boost::geometry; @@ -71,6 +92,25 @@ Polygon2d createOneStepPolygon( } } // namespace +static bool isTargetStuckVehicleType( + const autoware_auto_perception_msgs::msg::PredictedObject & object) +{ + if ( + object.classification.at(0).label == + autoware_auto_perception_msgs::msg::ObjectClassification::CAR || + object.classification.at(0).label == + autoware_auto_perception_msgs::msg::ObjectClassification::BUS || + object.classification.at(0).label == + autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK || + object.classification.at(0).label == + autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER || + object.classification.at(0).label == + autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE) { + return true; + } + return false; +} + static bool isTargetCollisionVehicleType( const autoware_auto_perception_msgs::msg::PredictedObject & object) { @@ -376,7 +416,7 @@ void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, const T & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, - VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, DebugData * debug_data) { static_assert("Unsupported type passed to reactRTCByDecisionResult"); return; @@ -392,7 +432,7 @@ void reactRTCApprovalByDecisionResult( [[maybe_unused]] autoware_auto_planning_msgs::msg::PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason, [[maybe_unused]] VelocityFactorInterface * velocity_factor, - [[maybe_unused]] util::DebugData * debug_data) + [[maybe_unused]] DebugData * debug_data) { return; } @@ -403,7 +443,7 @@ void reactRTCApprovalByDecisionResult( const IntersectionModule::StuckStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + StopReason * stop_reason, VelocityFactorInterface * velocity_factor, DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -451,7 +491,7 @@ void reactRTCApprovalByDecisionResult( const IntersectionModule::YieldStuckStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + StopReason * stop_reason, VelocityFactorInterface * velocity_factor, DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -483,7 +523,7 @@ void reactRTCApprovalByDecisionResult( const IntersectionModule::NonOccludedCollisionStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + StopReason * stop_reason, VelocityFactorInterface * velocity_factor, DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -526,7 +566,7 @@ void reactRTCApprovalByDecisionResult( const IntersectionModule::FirstWaitBeforeOcclusion & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, - VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -577,7 +617,7 @@ void reactRTCApprovalByDecisionResult( const IntersectionModule::PeekingTowardOcclusion & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, - VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -634,7 +674,7 @@ void reactRTCApprovalByDecisionResult( const IntersectionModule::OccludedCollisionStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + StopReason * stop_reason, VelocityFactorInterface * velocity_factor, DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -681,7 +721,7 @@ void reactRTCApprovalByDecisionResult( const IntersectionModule::OccludedAbsenceTrafficLight & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + StopReason * stop_reason, VelocityFactorInterface * velocity_factor, DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -734,7 +774,7 @@ void reactRTCApprovalByDecisionResult( const IntersectionModule::Safe & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + StopReason * stop_reason, VelocityFactorInterface * velocity_factor, DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -776,7 +816,7 @@ void reactRTCApprovalByDecisionResult( const IntersectionModule::FullyPrioritized & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + StopReason * stop_reason, VelocityFactorInterface * velocity_factor, DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -818,7 +858,7 @@ void reactRTCApproval( const IntersectionModule::DecisionResult & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, - VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, DebugData * debug_data) { std::visit( VisitorSwitch{[&](const auto & decision) { @@ -868,7 +908,7 @@ static std::string formatDecisionResult(const IntersectionModule::DecisionResult bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) { - debug_data_ = util::DebugData(); + debug_data_ = DebugData(); *stop_reason = planning_utils::initializeStopReason(StopReason::INTERSECTION); // set default RTC @@ -938,6 +978,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto & assigned_lanelet = lanelet_map_ptr->laneletLayer.get(lane_id_); const std::string turn_direction = assigned_lanelet.attributeOr("turn_direction", "else"); const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + const auto footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0); + const auto & current_pose = planner_data_->current_odometry->pose; // spline interpolation const auto interpolated_path_info_opt = util::generateInterpolatedPath( @@ -952,25 +994,20 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } // cache intersection lane information because it is invariant - const auto & current_pose = planner_data_->current_odometry->pose; const auto lanelets_on_path = planning_utils::getLaneletsOnPath(*path, lanelet_map_ptr, current_pose); if (!intersection_lanelets_) { - intersection_lanelets_ = util::getObjectiveLanelets( - lanelet_map_ptr, routing_graph_ptr, assigned_lanelet, lanelets_on_path, associative_ids_, - planner_param_.common.attention_area_length, - planner_param_.occlusion.occlusion_attention_area_length, - planner_param_.collision_detection.consider_wrong_direction_vehicle); + intersection_lanelets_ = + getObjectiveLanelets(lanelet_map_ptr, routing_graph_ptr, assigned_lanelet, lanelets_on_path); } auto & intersection_lanelets = intersection_lanelets_.value(); - // at the very first time of registration of this module, the path may not be conflicting with the + // at the very first time of regisTration of this module, the path may not be conflicting with the // attention area, so update() is called to update the internal data as well as traffic light info const auto traffic_prioritized_level = - util::getTrafficPrioritizedLevel(assigned_lanelet, planner_data_->traffic_light_id_map); + getTrafficPrioritizedLevel(assigned_lanelet, planner_data_->traffic_light_id_map); const bool is_prioritized = - traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED; - const auto footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0); + traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED; intersection_lanelets.update(is_prioritized, interpolated_path_info, footprint, baselink2front); // this is abnormal @@ -985,21 +1022,15 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // generate all stop line candidates // see the doc for struct IntersectionStopLines - const auto & first_attention_area_opt = intersection_lanelets.first_attention_area(); /// even if the attention area is null, stuck vehicle stop line needs to be generated from /// conflicting lanes - const auto & dummy_first_attention_area = - first_attention_area_opt ? first_attention_area_opt.value() : first_conflicting_area; - const auto & dummy_first_attention_lane_centerline = - intersection_lanelets.first_attention_lane() - ? intersection_lanelets.first_attention_lane().value().centerline2d() - : first_conflicting_lane.centerline2d(); - const auto intersection_stoplines_opt = util::generateIntersectionStopLines( - first_conflicting_area, dummy_first_attention_area, dummy_first_attention_lane_centerline, - planner_data_, interpolated_path_info, planner_param_.stuck_vehicle.use_stuck_stopline, - planner_param_.common.default_stopline_margin, planner_param_.common.max_accel, - planner_param_.common.max_jerk, planner_param_.common.delay_response_time, - planner_param_.occlusion.peeking_offset, path); + const auto & dummy_first_attention_lane = intersection_lanelets.first_attention_lane() + ? intersection_lanelets.first_attention_lane().value() + : first_conflicting_lane; + + const auto intersection_stoplines_opt = generateIntersectionStopLines( + assigned_lanelet, first_conflicting_area, dummy_first_attention_lane, interpolated_path_info, + path); if (!intersection_stoplines_opt) { return IntersectionModule::Indecisive{"failed to generate intersection_stoplines"}; } @@ -1010,15 +1041,15 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( default_pass_judge_line_idx, occlusion_wo_tl_pass_judge_line_idx] = intersection_stoplines; // see the doc for struct PathLanelets + const auto & first_attention_area_opt = intersection_lanelets.first_attention_area(); const auto & conflicting_area = intersection_lanelets.conflicting_area(); - const auto path_lanelets_opt = util::generatePathLanelets( - lanelets_on_path, interpolated_path_info, associative_ids_, first_conflicting_area, - conflicting_area, first_attention_area_opt, intersection_lanelets.attention_area(), closest_idx, - planner_data_->vehicle_info_.vehicle_width_m); + const auto path_lanelets_opt = generatePathLanelets( + lanelets_on_path, interpolated_path_info, first_conflicting_area, conflicting_area, + first_attention_area_opt, intersection_lanelets.attention_area(), closest_idx); if (!path_lanelets_opt.has_value()) { return IntersectionModule::Indecisive{"failed to generate PathLanelets"}; } - const auto path_lanelets = path_lanelets_opt.value(); + const auto & path_lanelets = path_lanelets_opt.value(); // utility functions auto fromEgoDist = [&](const size_t index) { @@ -1054,7 +1085,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // stuck vehicle detection is viable even if attention area is empty // so this needs to be checked before attention area validation - const bool stuck_detected = checkStuckVehicle(planner_data_, path_lanelets); + const bool stuck_detected = checkStuckVehicleInIntersection(path_lanelets, &debug_data_); const bool is_first_conflicting_lane_private = (std::string(first_conflicting_lane.attributeOr("location", "else")).compare("private") == 0); if (stuck_detected) { @@ -1119,11 +1150,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // check occlusion on detection lane if (!occlusion_attention_divisions_) { - occlusion_attention_divisions_ = util::generateDetectionLaneDivisions( + occlusion_attention_divisions_ = generateDetectionLaneDivisions( occlusion_attention_lanelets, routing_graph_ptr, - planner_data_->occupancy_grid->info.resolution, - planner_param_.occlusion.attention_lane_crop_curvature_threshold, - planner_param_.occlusion.attention_lane_curvature_calculation_ds); + planner_data_->occupancy_grid->info.resolution); } const auto & occlusion_attention_divisions = occlusion_attention_divisions_.value(); @@ -1132,8 +1161,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // filter objects auto target_objects = generateTargetObjects(intersection_lanelets, intersection_area); - const bool yield_stuck_detected = checkYieldStuckVehicle( - target_objects, interpolated_path_info, intersection_lanelets.attention_non_preceding_); + const bool yield_stuck_detected = checkYieldStuckVehicleInIntersection( + target_objects, interpolated_path_info, intersection_lanelets.attention_non_preceding(), + &debug_data_); if (yield_stuck_detected) { std::optional stopline_idx = std::nullopt; const bool is_before_default_stopline = fromEgoDist(default_stopline_idx) >= 0.0; @@ -1159,15 +1189,13 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } const double is_amber_or_red = - (traffic_prioritized_level == util::TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) || - (traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED); + (traffic_prioritized_level == TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) || + (traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED); auto occlusion_status = (enable_occlusion_detection_ && !occlusion_attention_lanelets.empty() && !is_amber_or_red) ? getOcclusionStatus( - *planner_data_->occupancy_grid, occlusion_attention_area, adjacent_lanelets, - first_attention_area, interpolated_path_info, occlusion_attention_divisions, - target_objects, current_pose, - planner_param_.occlusion.occlusion_required_clearance_distance) + occlusion_attention_area, adjacent_lanelets, first_attention_area, interpolated_path_info, + occlusion_attention_divisions, target_objects) : OcclusionType::NOT_OCCLUDED; occlusion_stop_state_machine_.setStateWithMarginTime( occlusion_status == OcclusionType::NOT_OCCLUDED ? StateMachine::State::GO : StateMachine::STOP, @@ -1385,9 +1413,672 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } } -bool IntersectionModule::checkStuckVehicle( - const std::shared_ptr & planner_data, const util::PathLanelets & path_lanelets) +TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel( + lanelet::ConstLanelet lane, const std::map & tl_infos) +{ + using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement; + + std::optional tl_id = std::nullopt; + for (auto && tl_reg_elem : lane.regulatoryElementsAs()) { + tl_id = tl_reg_elem->id(); + break; + } + if (!tl_id) { + // this lane has no traffic light + return TrafficPrioritizedLevel::NOT_PRIORITIZED; + } + const auto tl_info_it = tl_infos.find(tl_id.value()); + if (tl_info_it == tl_infos.end()) { + // the info of this traffic light is not available + return TrafficPrioritizedLevel::NOT_PRIORITIZED; + } + const auto & tl_info = tl_info_it->second; + bool has_amber_signal{false}; + for (auto && tl_light : tl_info.signal.elements) { + if (tl_light.color == TrafficSignalElement::AMBER) { + has_amber_signal = true; + } + if (tl_light.color == TrafficSignalElement::RED) { + // NOTE: Return here since the red signal has the highest priority. + return TrafficPrioritizedLevel::FULLY_PRIORITIZED; + } + } + if (has_amber_signal) { + return TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED; + } + return TrafficPrioritizedLevel::NOT_PRIORITIZED; +} + +static std::vector getPolygon3dFromLanelets( + const lanelet::ConstLanelets & ll_vec) +{ + std::vector polys; + for (auto && ll : ll_vec) { + polys.push_back(ll.polygon3d()); + } + return polys; +} + +IntersectionLanelets IntersectionModule::getObjectiveLanelets( + lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr, + const lanelet::ConstLanelet assigned_lanelet, const lanelet::ConstLanelets & lanelets_on_path) +{ + const double detection_area_length = planner_param_.common.attention_area_length; + const double occlusion_detection_area_length = + planner_param_.occlusion.occlusion_attention_area_length; + const bool consider_wrong_direction_vehicle = + planner_param_.collision_detection.consider_wrong_direction_vehicle; + + // retrieve a stopline associated with a traffic light + bool has_traffic_light = false; + if (const auto tl_reg_elems = assigned_lanelet.regulatoryElementsAs(); + tl_reg_elems.size() != 0) { + const auto tl_reg_elem = tl_reg_elems.front(); + const auto stopline_opt = tl_reg_elem->stopLine(); + if (!!stopline_opt) has_traffic_light = true; + } + + // for low priority lane + // If ego_lane has right of way (i.e. is high priority), + // ignore yieldLanelets (i.e. low priority lanes) + lanelet::ConstLanelets yield_lanelets{}; + const auto right_of_ways = assigned_lanelet.regulatoryElementsAs(); + for (const auto & right_of_way : right_of_ways) { + if (lanelet::utils::contains(right_of_way->rightOfWayLanelets(), assigned_lanelet)) { + for (const auto & yield_lanelet : right_of_way->yieldLanelets()) { + yield_lanelets.push_back(yield_lanelet); + for (const auto & previous_lanelet : routing_graph_ptr->previous(yield_lanelet)) { + yield_lanelets.push_back(previous_lanelet); + } + } + } + } + + // get all following lanes of previous lane + lanelet::ConstLanelets ego_lanelets = lanelets_on_path; + for (const auto & previous_lanelet : routing_graph_ptr->previous(assigned_lanelet)) { + ego_lanelets.push_back(previous_lanelet); + for (const auto & following_lanelet : routing_graph_ptr->following(previous_lanelet)) { + if (lanelet::utils::contains(ego_lanelets, following_lanelet)) { + continue; + } + ego_lanelets.push_back(following_lanelet); + } + } + + // get conflicting lanes on assigned lanelet + const auto & conflicting_lanelets = + lanelet::utils::getConflictingLanelets(routing_graph_ptr, assigned_lanelet); + std::vector adjacent_followings; + + for (const auto & conflicting_lanelet : conflicting_lanelets) { + for (const auto & following_lanelet : routing_graph_ptr->following(conflicting_lanelet)) { + adjacent_followings.push_back(following_lanelet); + } + for (const auto & following_lanelet : routing_graph_ptr->previous(conflicting_lanelet)) { + adjacent_followings.push_back(following_lanelet); + } + } + + // final objective lanelets + lanelet::ConstLanelets detection_lanelets; + lanelet::ConstLanelets conflicting_ex_ego_lanelets; + // conflicting lanes is necessary to get stopline for stuck vehicle + for (auto && conflicting_lanelet : conflicting_lanelets) { + if (!lanelet::utils::contains(ego_lanelets, conflicting_lanelet)) + conflicting_ex_ego_lanelets.push_back(conflicting_lanelet); + } + + // exclude yield lanelets and ego lanelets from detection_lanelets + if (turn_direction_ == std::string("straight") && has_traffic_light) { + // if assigned lanelet is "straight" with traffic light, detection area is not necessary + } else { + if (consider_wrong_direction_vehicle) { + for (const auto & conflicting_lanelet : conflicting_lanelets) { + if (lanelet::utils::contains(yield_lanelets, conflicting_lanelet)) { + continue; + } + detection_lanelets.push_back(conflicting_lanelet); + } + for (const auto & adjacent_following : adjacent_followings) { + detection_lanelets.push_back(adjacent_following); + } + } else { + // otherwise we need to know the priority from RightOfWay + for (const auto & conflicting_lanelet : conflicting_lanelets) { + if ( + lanelet::utils::contains(yield_lanelets, conflicting_lanelet) || + lanelet::utils::contains(ego_lanelets, conflicting_lanelet)) { + continue; + } + detection_lanelets.push_back(conflicting_lanelet); + } + } + } + + // get possible lanelet path that reaches conflicting_lane longer than given length + lanelet::ConstLanelets detection_and_preceding_lanelets; + { + const double length = detection_area_length; + std::set detection_ids; + for (const auto & ll : detection_lanelets) { + // Preceding lanes does not include detection_lane so add them at the end + const auto & inserted = detection_ids.insert(ll.id()); + if (inserted.second) detection_and_preceding_lanelets.push_back(ll); + // get preceding lanelets without ego_lanelets + // to prevent the detection area from including the ego lanes and its' preceding lanes. + const auto lanelet_sequences = lanelet::utils::query::getPrecedingLaneletSequences( + routing_graph_ptr, ll, length, ego_lanelets); + for (const auto & ls : lanelet_sequences) { + for (const auto & l : ls) { + const auto & inserted = detection_ids.insert(l.id()); + if (inserted.second) detection_and_preceding_lanelets.push_back(l); + } + } + } + } + + lanelet::ConstLanelets occlusion_detection_and_preceding_lanelets; + { + const double length = occlusion_detection_area_length; + std::set detection_ids; + for (const auto & ll : detection_lanelets) { + // Preceding lanes does not include detection_lane so add them at the end + const auto & inserted = detection_ids.insert(ll.id()); + if (inserted.second) occlusion_detection_and_preceding_lanelets.push_back(ll); + // get preceding lanelets without ego_lanelets + // to prevent the detection area from including the ego lanes and its' preceding lanes. + const auto lanelet_sequences = lanelet::utils::query::getPrecedingLaneletSequences( + routing_graph_ptr, ll, length, ego_lanelets); + for (const auto & ls : lanelet_sequences) { + for (const auto & l : ls) { + const auto & inserted = detection_ids.insert(l.id()); + if (inserted.second) occlusion_detection_and_preceding_lanelets.push_back(l); + } + } + } + } + lanelet::ConstLanelets occlusion_detection_and_preceding_lanelets_wo_turn_direction; + for (const auto & ll : occlusion_detection_and_preceding_lanelets) { + const std::string turn_direction = ll.attributeOr("turn_direction", "else"); + if (turn_direction == "left" || turn_direction == "right") { + continue; + } + occlusion_detection_and_preceding_lanelets_wo_turn_direction.push_back(ll); + } + + auto [attention_lanelets, original_attention_lanelet_sequences] = + util::mergeLaneletsByTopologicalSort(detection_and_preceding_lanelets, routing_graph_ptr); + + IntersectionLanelets result; + result.attention_ = std::move(attention_lanelets); + for (const auto & original_attention_lanelet_seq : original_attention_lanelet_sequences) { + // NOTE: in mergeLaneletsByTopologicalSort(), sub_ids are empty checked, so it is ensured that + // back() exists. + std::optional stopline{std::nullopt}; + for (auto it = original_attention_lanelet_seq.rbegin(); + it != original_attention_lanelet_seq.rend(); ++it) { + const auto traffic_lights = it->regulatoryElementsAs(); + for (const auto & traffic_light : traffic_lights) { + const auto stopline_opt = traffic_light->stopLine(); + if (!stopline_opt) continue; + stopline = stopline_opt.get(); + break; + } + if (stopline) break; + } + result.attention_stoplines_.push_back(stopline); + } + result.attention_non_preceding_ = std::move(detection_lanelets); + for (unsigned i = 0; i < result.attention_non_preceding_.size(); ++i) { + std::optional stopline = std::nullopt; + const auto & ll = result.attention_non_preceding_.at(i); + const auto traffic_lights = ll.regulatoryElementsAs(); + for (const auto & traffic_light : traffic_lights) { + const auto stopline_opt = traffic_light->stopLine(); + if (!stopline_opt) continue; + stopline = stopline_opt.get(); + } + result.attention_non_preceding_stoplines_.push_back(stopline); + } + result.conflicting_ = std::move(conflicting_ex_ego_lanelets); + result.adjacent_ = planning_utils::getConstLaneletsFromIds(lanelet_map_ptr, associative_ids_); + // NOTE: occlusion_attention is not inverted here + // TODO(Mamoru Sobue): apply mergeLaneletsByTopologicalSort for occlusion lanelets as well and + // then trim part of them based on curvature threshold + result.occlusion_attention_ = + std::move(occlusion_detection_and_preceding_lanelets_wo_turn_direction); + + // NOTE: to properly update(), each element in conflicting_/conflicting_area_, + // attention_non_preceding_/attention_non_preceding_area_ need to be matched + result.attention_area_ = getPolygon3dFromLanelets(result.attention_); + result.attention_non_preceding_area_ = getPolygon3dFromLanelets(result.attention_non_preceding_); + result.conflicting_area_ = getPolygon3dFromLanelets(result.conflicting_); + result.adjacent_area_ = getPolygon3dFromLanelets(result.adjacent_); + result.occlusion_attention_area_ = getPolygon3dFromLanelets(result.occlusion_attention_); + return result; +} + +std::optional IntersectionModule::generateIntersectionStopLines( + lanelet::ConstLanelet assigned_lanelet, const lanelet::CompoundPolygon3d & first_conflicting_area, + const lanelet::ConstLanelet & first_attention_lane, + const util::InterpolatedPathInfo & interpolated_path_info, + autoware_auto_planning_msgs::msg::PathWithLaneId * original_path) +{ + const bool use_stuck_stopline = planner_param_.stuck_vehicle.use_stuck_stopline; + const double stopline_margin = planner_param_.common.default_stopline_margin; + const double max_accel = planner_param_.common.max_accel; + const double max_jerk = planner_param_.common.max_jerk; + const double delay_response_time = planner_param_.common.delay_response_time; + const double peeking_offset = planner_param_.occlusion.peeking_offset; + + const auto first_attention_area = first_attention_lane.polygon3d(); + const auto first_attention_lane_centerline = first_attention_lane.centerline2d(); + const auto & path_ip = interpolated_path_info.path; + const double ds = interpolated_path_info.ds; + const auto & lane_interval_ip = interpolated_path_info.lane_id_interval.value(); + const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + + const int stopline_margin_idx_dist = std::ceil(stopline_margin / ds); + const int base2front_idx_dist = + std::ceil(planner_data_->vehicle_info_.max_longitudinal_offset_m / ds); + + // find the index of the first point whose vehicle footprint on it intersects with detection_area + const auto local_footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0); + std::optional first_footprint_inside_detection_ip_opt = + getFirstPointInsidePolygonByFootprint( + first_attention_area, interpolated_path_info, local_footprint, baselink2front); + if (!first_footprint_inside_detection_ip_opt) { + return std::nullopt; + } + const auto first_footprint_inside_detection_ip = first_footprint_inside_detection_ip_opt.value(); + + std::optional first_footprint_attention_centerline_ip_opt = std::nullopt; + for (auto i = std::get<0>(lane_interval_ip); i < std::get<1>(lane_interval_ip); ++i) { + const auto & base_pose = path_ip.points.at(i).point.pose; + const auto path_footprint = tier4_autoware_utils::transformVector( + local_footprint, tier4_autoware_utils::pose2transform(base_pose)); + if (bg::intersects(path_footprint, first_attention_lane_centerline.basicLineString())) { + // NOTE: maybe consideration of braking dist is necessary + first_footprint_attention_centerline_ip_opt = i; + break; + } + } + if (!first_footprint_attention_centerline_ip_opt) { + return std::nullopt; + } + const size_t first_footprint_attention_centerline_ip = + first_footprint_attention_centerline_ip_opt.value(); + + // (1) default stop line position on interpolated path + bool default_stopline_valid = true; + int stop_idx_ip_int = -1; + if (const auto map_stop_idx_ip = + getStopLineIndexFromMap(interpolated_path_info, assigned_lanelet); + map_stop_idx_ip) { + stop_idx_ip_int = static_cast(map_stop_idx_ip.value()) - base2front_idx_dist; + } + if (stop_idx_ip_int < 0) { + stop_idx_ip_int = first_footprint_inside_detection_ip - stopline_margin_idx_dist; + } + if (stop_idx_ip_int < 0) { + default_stopline_valid = false; + } + const auto default_stopline_ip = stop_idx_ip_int >= 0 ? static_cast(stop_idx_ip_int) : 0; + + // (2) ego front stop line position on interpolated path + const geometry_msgs::msg::Pose & current_pose = planner_data_->current_odometry->pose; + const auto closest_idx_ip = motion_utils::findFirstNearestIndexWithSoftConstraints( + path_ip.points, current_pose, planner_data_->ego_nearest_dist_threshold, + planner_data_->ego_nearest_yaw_threshold); + + // (3) occlusion peeking stop line position on interpolated path + int occlusion_peeking_line_ip_int = static_cast(default_stopline_ip); + bool occlusion_peeking_line_valid = true; + // NOTE: if footprints[0] is already inside the detection area, invalid + { + const auto & base_pose0 = path_ip.points.at(default_stopline_ip).point.pose; + const auto path_footprint0 = tier4_autoware_utils::transformVector( + local_footprint, tier4_autoware_utils::pose2transform(base_pose0)); + if (bg::intersects( + path_footprint0, lanelet::utils::to2D(first_attention_area).basicPolygon())) { + occlusion_peeking_line_valid = false; + } + } + if (occlusion_peeking_line_valid) { + occlusion_peeking_line_ip_int = + first_footprint_inside_detection_ip + std::ceil(peeking_offset / ds); + } + + const auto occlusion_peeking_line_ip = static_cast( + std::clamp(occlusion_peeking_line_ip_int, 0, static_cast(path_ip.points.size()) - 1)); + const auto first_attention_stopline_ip = first_footprint_inside_detection_ip; + const bool first_attention_stopline_valid = true; + + // (4) pass judge line position on interpolated path + const double velocity = planner_data_->current_velocity->twist.linear.x; + const double acceleration = planner_data_->current_acceleration->accel.accel.linear.x; + const double braking_dist = planning_utils::calcJudgeLineDistWithJerkLimit( + velocity, acceleration, max_accel, max_jerk, delay_response_time); + int pass_judge_ip_int = + static_cast(first_footprint_inside_detection_ip) - std::ceil(braking_dist / ds); + const auto pass_judge_line_ip = static_cast( + std::clamp(pass_judge_ip_int, 0, static_cast(path_ip.points.size()) - 1)); + // TODO(Mamoru Sobue): maybe braking dist should be considered + const auto occlusion_wo_tl_pass_judge_line_ip = + static_cast(first_footprint_attention_centerline_ip); + + // (5) stuck vehicle stop line + int stuck_stopline_ip_int = 0; + bool stuck_stopline_valid = true; + if (use_stuck_stopline) { + // NOTE: when ego vehicle is approaching detection area and already passed + // first_conflicting_area, this could be null. + const auto stuck_stopline_idx_ip_opt = getFirstPointInsidePolygonByFootprint( + first_conflicting_area, interpolated_path_info, local_footprint, baselink2front); + if (!stuck_stopline_idx_ip_opt) { + stuck_stopline_valid = false; + stuck_stopline_ip_int = 0; + } else { + stuck_stopline_ip_int = stuck_stopline_idx_ip_opt.value() - stopline_margin_idx_dist; + } + } else { + stuck_stopline_ip_int = + std::get<0>(lane_interval_ip) - (stopline_margin_idx_dist + base2front_idx_dist); + } + if (stuck_stopline_ip_int < 0) { + stuck_stopline_valid = false; + } + const auto stuck_stopline_ip = static_cast(std::max(0, stuck_stopline_ip_int)); + + struct IntersectionStopLinesTemp + { + size_t closest_idx{0}; + size_t stuck_stopline{0}; + size_t default_stopline{0}; + size_t first_attention_stopline{0}; + size_t occlusion_peeking_stopline{0}; + size_t pass_judge_line{0}; + size_t occlusion_wo_tl_pass_judge_line{0}; + }; + + IntersectionStopLinesTemp intersection_stoplines_temp; + std::list> stoplines = { + {&closest_idx_ip, &intersection_stoplines_temp.closest_idx}, + {&stuck_stopline_ip, &intersection_stoplines_temp.stuck_stopline}, + {&default_stopline_ip, &intersection_stoplines_temp.default_stopline}, + {&first_attention_stopline_ip, &intersection_stoplines_temp.first_attention_stopline}, + {&occlusion_peeking_line_ip, &intersection_stoplines_temp.occlusion_peeking_stopline}, + {&pass_judge_line_ip, &intersection_stoplines_temp.pass_judge_line}, + {&occlusion_wo_tl_pass_judge_line_ip, + &intersection_stoplines_temp.occlusion_wo_tl_pass_judge_line}}; + stoplines.sort( + [](const auto & it1, const auto & it2) { return *(std::get<0>(it1)) < *(std::get<0>(it2)); }); + for (const auto & [stop_idx_ip, stop_idx] : stoplines) { + const auto & insert_point = path_ip.points.at(*stop_idx_ip).point.pose; + const auto insert_idx = util::insertPointIndex( + insert_point, original_path, planner_data_->ego_nearest_dist_threshold, + planner_data_->ego_nearest_yaw_threshold); + if (!insert_idx) { + return std::nullopt; + } + *stop_idx = insert_idx.value(); + } + if ( + intersection_stoplines_temp.occlusion_peeking_stopline < + intersection_stoplines_temp.default_stopline) { + intersection_stoplines_temp.occlusion_peeking_stopline = + intersection_stoplines_temp.default_stopline; + } + + IntersectionStopLines intersection_stoplines; + intersection_stoplines.closest_idx = intersection_stoplines_temp.closest_idx; + if (stuck_stopline_valid) { + intersection_stoplines.stuck_stopline = intersection_stoplines_temp.stuck_stopline; + } + if (default_stopline_valid) { + intersection_stoplines.default_stopline = intersection_stoplines_temp.default_stopline; + } + if (first_attention_stopline_valid) { + intersection_stoplines.first_attention_stopline = + intersection_stoplines_temp.first_attention_stopline; + } + if (occlusion_peeking_line_valid) { + intersection_stoplines.occlusion_peeking_stopline = + intersection_stoplines_temp.occlusion_peeking_stopline; + } + intersection_stoplines.pass_judge_line = intersection_stoplines_temp.pass_judge_line; + intersection_stoplines.occlusion_wo_tl_pass_judge_line = + intersection_stoplines_temp.occlusion_wo_tl_pass_judge_line; + return intersection_stoplines; +} + +/** + * @brief Get stop point from map if exists + * @param stop_pose stop point defined on map + * @return true when the stop point is defined on map. + */ +std::optional IntersectionModule::getStopLineIndexFromMap( + const util::InterpolatedPathInfo & interpolated_path_info, lanelet::ConstLanelet assigned_lanelet) +{ + const auto & path = interpolated_path_info.path; + const auto & lane_interval = interpolated_path_info.lane_id_interval.value(); + + const auto road_markings = + assigned_lanelet.regulatoryElementsAs(); + lanelet::ConstLineStrings3d stopline; + for (const auto & road_marking : road_markings) { + const std::string type = + road_marking->roadMarking().attributeOr(lanelet::AttributeName::Type, "none"); + if (type == lanelet::AttributeValueString::StopLine) { + stopline.push_back(road_marking->roadMarking()); + break; // only one stopline exists. + } + } + if (stopline.empty()) { + return std::nullopt; + } + + const auto p_start = stopline.front().front(); + const auto p_end = stopline.front().back(); + const LineString2d extended_stopline = + planning_utils::extendLine(p_start, p_end, planner_data_->stop_line_extend_length); + + for (size_t i = lane_interval.first; i < lane_interval.second; i++) { + const auto & p_front = path.points.at(i).point.pose.position; + const auto & p_back = path.points.at(i + 1).point.pose.position; + + const LineString2d path_segment = {{p_front.x, p_front.y}, {p_back.x, p_back.y}}; + std::vector collision_points; + bg::intersection(extended_stopline, path_segment, collision_points); + + if (collision_points.empty()) { + continue; + } + + return i; + } + + geometry_msgs::msg::Pose stop_point_from_map; + stop_point_from_map.position.x = 0.5 * (p_start.x() + p_end.x()); + stop_point_from_map.position.y = 0.5 * (p_start.y() + p_end.y()); + stop_point_from_map.position.z = 0.5 * (p_start.z() + p_end.z()); + + return motion_utils::findFirstNearestIndexWithSoftConstraints( + path.points, stop_point_from_map, planner_data_->ego_nearest_dist_threshold, + planner_data_->ego_nearest_yaw_threshold); +} + +static lanelet::ConstLanelets getPrevLanelets( + const lanelet::ConstLanelets & lanelets_on_path, const std::set & associative_ids) +{ + lanelet::ConstLanelets previous_lanelets; + for (const auto & ll : lanelets_on_path) { + if (associative_ids.find(ll.id()) != associative_ids.end()) { + return previous_lanelets; + } + previous_lanelets.push_back(ll); + } + return previous_lanelets; +} + +// end inclusive +static lanelet::ConstLanelet generatePathLanelet( + const PathWithLaneId & path, const size_t start_idx, const size_t end_idx, const double width, + const double interval) +{ + lanelet::Points3d lefts; + lanelet::Points3d rights; + size_t prev_idx = start_idx; + for (size_t i = start_idx; i <= end_idx; ++i) { + const auto & p = path.points.at(i).point.pose; + const auto & p_prev = path.points.at(prev_idx).point.pose; + if (i != start_idx && tier4_autoware_utils::calcDistance2d(p_prev, p) < interval) { + continue; + } + prev_idx = i; + const double yaw = tf2::getYaw(p.orientation); + const double x = p.position.x; + const double y = p.position.y; + // NOTE: maybe this is opposite + const double left_x = x + width / 2 * std::sin(yaw); + const double left_y = y - width / 2 * std::cos(yaw); + const double right_x = x - width / 2 * std::sin(yaw); + const double right_y = y + width / 2 * std::cos(yaw); + lefts.emplace_back(lanelet::InvalId, left_x, left_y, p.position.z); + rights.emplace_back(lanelet::InvalId, right_x, right_y, p.position.z); + } + lanelet::LineString3d left = lanelet::LineString3d(lanelet::InvalId, lefts); + lanelet::LineString3d right = lanelet::LineString3d(lanelet::InvalId, rights); + + return lanelet::Lanelet(lanelet::InvalId, left, right); +} + +static std::optional> +getFirstPointInsidePolygons( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, + const std::pair lane_interval, + const std::vector & polygons, const bool search_forward = true) +{ + if (search_forward) { + for (size_t i = lane_interval.first; i <= lane_interval.second; ++i) { + bool is_in_lanelet = false; + const auto & p = path.points.at(i).point.pose.position; + for (const auto & polygon : polygons) { + const auto polygon_2d = lanelet::utils::to2D(polygon); + is_in_lanelet = bg::within(to_bg2d(p), polygon_2d); + if (is_in_lanelet) { + return std::make_optional>( + i, polygon); + } + } + if (is_in_lanelet) { + break; + } + } + } else { + for (size_t i = lane_interval.second; i >= lane_interval.first; --i) { + bool is_in_lanelet = false; + const auto & p = path.points.at(i).point.pose.position; + for (const auto & polygon : polygons) { + const auto polygon_2d = lanelet::utils::to2D(polygon); + is_in_lanelet = bg::within(to_bg2d(p), polygon_2d); + if (is_in_lanelet) { + return std::make_optional>( + i, polygon); + } + } + if (is_in_lanelet) { + break; + } + if (i == 0) { + break; + } + } + } + return std::nullopt; +} + +std::optional IntersectionModule::generatePathLanelets( + const lanelet::ConstLanelets & lanelets_on_path, + const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::CompoundPolygon3d & first_conflicting_area, + const std::vector & conflicting_areas, + const std::optional & first_attention_area, + const std::vector & attention_areas, const size_t closest_idx) { + const double width = planner_data_->vehicle_info_.vehicle_width_m; + static constexpr double path_lanelet_interval = 1.5; + + const auto & assigned_lane_interval_opt = interpolated_path_info.lane_id_interval; + if (!assigned_lane_interval_opt) { + return std::nullopt; + } + const auto assigned_lane_interval = assigned_lane_interval_opt.value(); + const auto & path = interpolated_path_info.path; + + PathLanelets path_lanelets; + // prev + path_lanelets.prev = getPrevLanelets(lanelets_on_path, associative_ids_); + path_lanelets.all = path_lanelets.prev; + + // entry2ego if exist + const auto [assigned_lane_start, assigned_lane_end] = assigned_lane_interval; + if (closest_idx > assigned_lane_start) { + path_lanelets.all.push_back( + generatePathLanelet(path, assigned_lane_start, closest_idx, width, path_lanelet_interval)); + } + + // ego_or_entry2exit + const auto ego_or_entry_start = std::max(closest_idx, assigned_lane_start); + path_lanelets.ego_or_entry2exit = + generatePathLanelet(path, ego_or_entry_start, assigned_lane_end, width, path_lanelet_interval); + path_lanelets.all.push_back(path_lanelets.ego_or_entry2exit); + + // next + if (assigned_lane_end < path.points.size() - 1) { + const int next_id = path.points.at(assigned_lane_end).lane_ids.at(0); + const auto next_lane_interval_opt = util::findLaneIdsInterval(path, {next_id}); + if (next_lane_interval_opt) { + const auto [next_start, next_end] = next_lane_interval_opt.value(); + path_lanelets.next = + generatePathLanelet(path, next_start, next_end, width, path_lanelet_interval); + path_lanelets.all.push_back(path_lanelets.next.value()); + } + } + + const auto first_inside_conflicting_idx_opt = + first_attention_area.has_value() + ? util::getFirstPointInsidePolygon(path, assigned_lane_interval, first_attention_area.value()) + : util::getFirstPointInsidePolygon(path, assigned_lane_interval, first_conflicting_area); + const auto last_inside_conflicting_idx_opt = + first_attention_area.has_value() + ? getFirstPointInsidePolygons(path, assigned_lane_interval, attention_areas, false) + : getFirstPointInsidePolygons(path, assigned_lane_interval, conflicting_areas, false); + if (first_inside_conflicting_idx_opt && last_inside_conflicting_idx_opt) { + const auto first_inside_conflicting_idx = first_inside_conflicting_idx_opt.value(); + const auto last_inside_conflicting_idx = last_inside_conflicting_idx_opt.value().first; + lanelet::ConstLanelet conflicting_interval = generatePathLanelet( + path, first_inside_conflicting_idx, last_inside_conflicting_idx, width, + path_lanelet_interval); + path_lanelets.conflicting_interval_and_remaining.push_back(std::move(conflicting_interval)); + if (last_inside_conflicting_idx < assigned_lane_end) { + lanelet::ConstLanelet remaining_interval = generatePathLanelet( + path, last_inside_conflicting_idx, assigned_lane_end, width, path_lanelet_interval); + path_lanelets.conflicting_interval_and_remaining.push_back(std::move(remaining_interval)); + } + } + return path_lanelets; +} + +bool IntersectionModule::checkStuckVehicleInIntersection( + const PathLanelets & path_lanelets, DebugData * debug_data) +{ + using lanelet::utils::getArcCoordinates; + using lanelet::utils::getLaneletLength3d; + using lanelet::utils::getPolygonFromArcLength; + using lanelet::utils::to2D; + const bool stuck_detection_direction = [&]() { return (turn_direction_ == "left" && planner_param_.stuck_vehicle.turn_direction.left) || (turn_direction_ == "right" && planner_param_.stuck_vehicle.turn_direction.right) || @@ -1397,22 +2088,146 @@ bool IntersectionModule::checkStuckVehicle( return false; } - const auto & objects_ptr = planner_data->predicted_objects; + const auto & objects_ptr = planner_data_->predicted_objects; // considering lane change in the intersection, these lanelets are generated from the path - const auto stuck_vehicle_detect_area = util::generateStuckVehicleDetectAreaPolygon( - path_lanelets, planner_param_.stuck_vehicle.stuck_vehicle_detect_dist); + const double stuck_vehicle_detect_dist = planner_param_.stuck_vehicle.stuck_vehicle_detect_dist; + Polygon2d stuck_vehicle_detect_area{}; + if (path_lanelets.conflicting_interval_and_remaining.size() == 0) { + return false; + } + + double target_polygon_length = + getLaneletLength3d(path_lanelets.conflicting_interval_and_remaining); + lanelet::ConstLanelets targets = path_lanelets.conflicting_interval_and_remaining; + if (path_lanelets.next) { + targets.push_back(path_lanelets.next.value()); + const double next_arc_length = + std::min(stuck_vehicle_detect_dist, getLaneletLength3d(path_lanelets.next.value())); + target_polygon_length += next_arc_length; + } + const auto target_polygon = + to2D(getPolygonFromArcLength(targets, 0, target_polygon_length)).basicPolygon(); + + if (target_polygon.empty()) { + return false; + } + + for (const auto & p : target_polygon) { + stuck_vehicle_detect_area.outer().emplace_back(p.x(), p.y()); + } + + stuck_vehicle_detect_area.outer().emplace_back(stuck_vehicle_detect_area.outer().front()); + bg::correct(stuck_vehicle_detect_area); + debug_data_.stuck_vehicle_detect_area = toGeomPoly(stuck_vehicle_detect_area); - return util::checkStuckVehicleInIntersection( - objects_ptr, stuck_vehicle_detect_area, - planner_param_.stuck_vehicle.stuck_vehicle_velocity_threshold, &debug_data_); + for (const auto & object : objects_ptr->objects) { + if (!isTargetStuckVehicleType(object)) { + continue; // not target vehicle type + } + const auto obj_v_norm = std::hypot( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y); + if (obj_v_norm > planner_param_.stuck_vehicle.stuck_vehicle_velocity_threshold) { + continue; // not stop vehicle + } + + // check if the footprint is in the stuck detect area + const auto obj_footprint = tier4_autoware_utils::toPolygon2d(object); + const bool is_in_stuck_area = !bg::disjoint(obj_footprint, stuck_vehicle_detect_area); + if (is_in_stuck_area && debug_data) { + debug_data->stuck_targets.objects.push_back(object); + return true; + } + } + return false; } -bool IntersectionModule::checkYieldStuckVehicle( - const util::TargetObjects & target_objects, - const util::InterpolatedPathInfo & interpolated_path_info, - const lanelet::ConstLanelets & attention_lanelets) +static lanelet::LineString3d getLineStringFromArcLength( + const lanelet::ConstLineString3d & linestring, const double s1, const double s2) +{ + lanelet::Points3d points; + double accumulated_length = 0; + size_t start_index = linestring.size(); + for (size_t i = 0; i < linestring.size() - 1; i++) { + const auto & p1 = linestring[i]; + const auto & p2 = linestring[i + 1]; + const double length = boost::geometry::distance(p1.basicPoint(), p2.basicPoint()); + if (accumulated_length + length > s1) { + start_index = i; + break; + } + accumulated_length += length; + } + if (start_index < linestring.size() - 1) { + const auto & p1 = linestring[start_index]; + const auto & p2 = linestring[start_index + 1]; + const double residue = s1 - accumulated_length; + const auto direction_vector = (p2.basicPoint() - p1.basicPoint()).normalized(); + const auto start_basic_point = p1.basicPoint() + residue * direction_vector; + const auto start_point = lanelet::Point3d(lanelet::InvalId, start_basic_point); + points.push_back(start_point); + } + + accumulated_length = 0; + size_t end_index = linestring.size(); + for (size_t i = 0; i < linestring.size() - 1; i++) { + const auto & p1 = linestring[i]; + const auto & p2 = linestring[i + 1]; + const double length = boost::geometry::distance(p1.basicPoint(), p2.basicPoint()); + if (accumulated_length + length > s2) { + end_index = i; + break; + } + accumulated_length += length; + } + + for (size_t i = start_index + 1; i < end_index; i++) { + const auto p = lanelet::Point3d(linestring[i]); + points.push_back(p); + } + if (end_index < linestring.size() - 1) { + const auto & p1 = linestring[end_index]; + const auto & p2 = linestring[end_index + 1]; + const double residue = s2 - accumulated_length; + const auto direction_vector = (p2.basicPoint() - p1.basicPoint()).normalized(); + const auto end_basic_point = p1.basicPoint() + residue * direction_vector; + const auto end_point = lanelet::Point3d(lanelet::InvalId, end_basic_point); + points.push_back(end_point); + } + return lanelet::LineString3d{lanelet::InvalId, points}; +} + +static lanelet::ConstLanelet createLaneletFromArcLength( + const lanelet::ConstLanelet & lanelet, const double s1, const double s2) +{ + const double total_length = boost::geometry::length(lanelet.centerline2d().basicLineString()); + // make sure that s1, and s2 are between [0, lane_length] + const auto s1_saturated = std::max(0.0, std::min(s1, total_length)); + const auto s2_saturated = std::max(0.0, std::min(s2, total_length)); + + const auto ratio_s1 = s1_saturated / total_length; + const auto ratio_s2 = s2_saturated / total_length; + + const auto s1_left = + static_cast(ratio_s1 * boost::geometry::length(lanelet.leftBound().basicLineString())); + const auto s2_left = + static_cast(ratio_s2 * boost::geometry::length(lanelet.leftBound().basicLineString())); + const auto s1_right = + static_cast(ratio_s1 * boost::geometry::length(lanelet.rightBound().basicLineString())); + const auto s2_right = + static_cast(ratio_s2 * boost::geometry::length(lanelet.rightBound().basicLineString())); + + const auto left_bound = getLineStringFromArcLength(lanelet.leftBound(), s1_left, s2_left); + const auto right_bound = getLineStringFromArcLength(lanelet.rightBound(), s1_right, s2_right); + + return lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); +} + +bool IntersectionModule::checkYieldStuckVehicleInIntersection( + const TargetObjects & target_objects, const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::ConstLanelets & attention_lanelets, DebugData * debug_data) { const bool yield_stuck_detection_direction = [&]() { return (turn_direction_ == "left" && planner_param_.yield_stuck.turn_direction.left) || @@ -1423,20 +2238,74 @@ bool IntersectionModule::checkYieldStuckVehicle( return false; } - return util::checkYieldStuckVehicleInIntersection( - target_objects, interpolated_path_info, attention_lanelets, turn_direction_, - planner_data_->vehicle_info_.vehicle_width_m, - planner_param_.stuck_vehicle.stuck_vehicle_velocity_threshold, - planner_param_.yield_stuck.distance_threshold, &debug_data_); + const double width = planner_data_->vehicle_info_.vehicle_width_m; + const double stuck_vehicle_vel_thr = + planner_param_.stuck_vehicle.stuck_vehicle_velocity_threshold; + const double yield_stuck_distance_thr = planner_param_.yield_stuck.distance_threshold; + + LineString2d sparse_intersection_path; + const auto [start, end] = interpolated_path_info.lane_id_interval.value(); + for (unsigned i = start; i < end; ++i) { + const auto & point = interpolated_path_info.path.points.at(i).point.pose.position; + const auto yaw = tf2::getYaw(interpolated_path_info.path.points.at(i).point.pose.orientation); + if (turn_direction_ == "right") { + const double right_x = point.x - width / 2 * std::sin(yaw); + const double right_y = point.y + width / 2 * std::cos(yaw); + sparse_intersection_path.emplace_back(right_x, right_y); + } else if (turn_direction_ == "left") { + const double left_x = point.x + width / 2 * std::sin(yaw); + const double left_y = point.y - width / 2 * std::cos(yaw); + sparse_intersection_path.emplace_back(left_x, left_y); + } else { + // straight + sparse_intersection_path.emplace_back(point.x, point.y); + } + } + lanelet::ConstLanelets yield_stuck_detect_lanelets; + for (const auto & attention_lanelet : attention_lanelets) { + const auto centerline = attention_lanelet.centerline2d().basicLineString(); + std::vector intersects; + bg::intersection(sparse_intersection_path, centerline, intersects); + if (intersects.empty()) { + continue; + } + const auto intersect = intersects.front(); + const auto intersect_arc_coords = lanelet::geometry::toArcCoordinates( + centerline, lanelet::BasicPoint2d(intersect.x(), intersect.y())); + const double yield_stuck_start = + std::max(0.0, intersect_arc_coords.length - yield_stuck_distance_thr); + const double yield_stuck_end = intersect_arc_coords.length; + yield_stuck_detect_lanelets.push_back( + createLaneletFromArcLength(attention_lanelet, yield_stuck_start, yield_stuck_end)); + } + debug_data->yield_stuck_detect_area = getPolygon3dFromLanelets(yield_stuck_detect_lanelets); + for (const auto & object : target_objects.all_attention_objects) { + const auto obj_v_norm = std::hypot( + object.object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.object.kinematics.initial_twist_with_covariance.twist.linear.y); + + if (obj_v_norm > stuck_vehicle_vel_thr) { + continue; + } + for (const auto & yield_stuck_detect_lanelet : yield_stuck_detect_lanelets) { + const bool is_in_lanelet = lanelet::utils::isInLanelet( + object.object.kinematics.initial_pose_with_covariance.pose, yield_stuck_detect_lanelet); + if (is_in_lanelet) { + debug_data->yield_stuck_targets.objects.push_back(object.object); + return true; + } + } + } + return false; } -util::TargetObjects IntersectionModule::generateTargetObjects( - const util::IntersectionLanelets & intersection_lanelets, +TargetObjects IntersectionModule::generateTargetObjects( + const IntersectionLanelets & intersection_lanelets, const std::optional & intersection_area) const { const auto & objects_ptr = planner_data_->predicted_objects; // extract target objects - util::TargetObjects target_objects; + TargetObjects target_objects; target_objects.header = objects_ptr->header; const auto & attention_lanelets = intersection_lanelets.attention(); const auto & attention_lanelet_stoplines = intersection_lanelets.attention_stoplines(); @@ -1449,10 +2318,8 @@ util::TargetObjects IntersectionModule::generateTargetObjects( // check direction of objects const auto object_direction = util::getObjectPoseWithVelocityDirection(object.kinematics); - const auto belong_adjacent_lanelet_id = util::checkAngleForTargetLanelets( - object_direction, adjacent_lanelets, planner_param_.common.attention_area_angle_threshold, - planner_param_.collision_detection.consider_wrong_direction_vehicle, - planner_param_.common.attention_area_margin, false); + const auto belong_adjacent_lanelet_id = + checkAngleForTargetLanelets(object_direction, adjacent_lanelets, false); if (belong_adjacent_lanelet_id) { continue; } @@ -1466,33 +2333,28 @@ util::TargetObjects IntersectionModule::generateTargetObjects( const auto & obj_pos = object.kinematics.initial_pose_with_covariance.pose.position; const auto obj_poly = tier4_autoware_utils::toPolygon2d(object); const auto intersection_area_2d = intersection_area.value(); - const auto belong_attention_lanelet_id = util::checkAngleForTargetLanelets( - object_direction, attention_lanelets, planner_param_.common.attention_area_angle_threshold, - planner_param_.collision_detection.consider_wrong_direction_vehicle, - planner_param_.common.attention_area_margin, is_parked_vehicle); + const auto belong_attention_lanelet_id = + checkAngleForTargetLanelets(object_direction, attention_lanelets, is_parked_vehicle); if (belong_attention_lanelet_id) { const auto id = belong_attention_lanelet_id.value(); - util::TargetObject target_object; + TargetObject target_object; target_object.object = object; target_object.attention_lanelet = attention_lanelets.at(id); target_object.stopline = attention_lanelet_stoplines.at(id); container.push_back(target_object); } else if (bg::within(Point2d{obj_pos.x, obj_pos.y}, intersection_area_2d)) { - util::TargetObject target_object; + TargetObject target_object; target_object.object = object; target_object.attention_lanelet = std::nullopt; target_object.stopline = std::nullopt; target_objects.intersection_area_objects.push_back(target_object); } - } else if (const auto belong_attention_lanelet_id = util::checkAngleForTargetLanelets( - object_direction, attention_lanelets, - planner_param_.common.attention_area_angle_threshold, - planner_param_.collision_detection.consider_wrong_direction_vehicle, - planner_param_.common.attention_area_margin, is_parked_vehicle); + } else if (const auto belong_attention_lanelet_id = checkAngleForTargetLanelets( + object_direction, attention_lanelets, is_parked_vehicle); belong_attention_lanelet_id.has_value()) { // intersection_area is not available, use detection_area_with_margin as before const auto id = belong_attention_lanelet_id.value(); - util::TargetObject target_object; + TargetObject target_object; target_object.object = object; target_object.attention_lanelet = attention_lanelets.at(id); target_object.stopline = attention_lanelet_stoplines.at(id); @@ -1512,10 +2374,10 @@ util::TargetObjects IntersectionModule::generateTargetObjects( } bool IntersectionModule::checkCollision( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - util::TargetObjects * target_objects, const util::PathLanelets & path_lanelets, - const size_t closest_idx, const size_t last_intersection_stopline_candidate_idx, - const double time_delay, const util::TrafficPrioritizedLevel & traffic_prioritized_level) + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, TargetObjects * target_objects, + const PathLanelets & path_lanelets, const size_t closest_idx, + const size_t last_intersection_stopline_candidate_idx, const double time_delay, + const TrafficPrioritizedLevel & traffic_prioritized_level) { using lanelet::utils::getArcCoordinates; using lanelet::utils::getPolygonFromArcLength; @@ -1523,14 +2385,8 @@ bool IntersectionModule::checkCollision( // check collision between target_objects predicted path and ego lane // cut the predicted path at passing_time tier4_debug_msgs::msg::Float64MultiArrayStamped ego_ttc_time_array; - const auto time_distance_array = util::calcIntersectionPassingTime( - path, planner_data_, lane_id_, associative_ids_, closest_idx, - last_intersection_stopline_candidate_idx, time_delay, - planner_param_.collision_detection.velocity_profile.default_velocity, - planner_param_.collision_detection.velocity_profile.minimum_default_velocity, - planner_param_.collision_detection.velocity_profile.use_upstream, - planner_param_.collision_detection.velocity_profile.minimum_upstream_velocity, - &ego_ttc_time_array); + const auto time_distance_array = calcIntersectionPassingTime( + path, closest_idx, last_intersection_stopline_candidate_idx, time_delay, &ego_ttc_time_array); if ( std::find(planner_param_.debug.ttc.begin(), planner_param_.debug.ttc.end(), lane_id_) != @@ -1540,7 +2396,7 @@ bool IntersectionModule::checkCollision( } const double passing_time = time_distance_array.back().first; - util::cutPredictPathWithDuration(target_objects, clock_, passing_time); + cutPredictPathWithDuration(target_objects, passing_time); const auto & concat_lanelets = path_lanelets.all; const auto closest_arc_coords = getArcCoordinates( @@ -1551,12 +2407,12 @@ bool IntersectionModule::checkCollision( // change TTC margin based on ego traffic light color const auto [collision_start_margin_time, collision_end_margin_time] = [&]() { - if (traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED) { + if (traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED) { return std::make_pair( planner_param_.collision_detection.fully_prioritized.collision_start_margin_time, planner_param_.collision_detection.fully_prioritized.collision_end_margin_time); } - if (traffic_prioritized_level == util::TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) { + if (traffic_prioritized_level == TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) { return std::make_pair( planner_param_.collision_detection.partially_prioritized.collision_start_margin_time, planner_param_.collision_detection.partially_prioritized.collision_end_margin_time); @@ -1565,7 +2421,7 @@ bool IntersectionModule::checkCollision( planner_param_.collision_detection.not_prioritized.collision_start_margin_time, planner_param_.collision_detection.not_prioritized.collision_end_margin_time); }(); - const auto expectedToStopBeforeStopLine = [&](const util::TargetObject & target_object) { + const auto expectedToStopBeforeStopLine = [&](const TargetObject & target_object) { if (!target_object.dist_to_stopline) { return false; } @@ -1580,7 +2436,7 @@ bool IntersectionModule::checkCollision( .object_expected_deceleration)); return dist_to_stopline > braking_distance; }; - const auto isTolerableOvershoot = [&](const util::TargetObject & target_object) { + const auto isTolerableOvershoot = [&](const TargetObject & target_object) { if ( !target_object.attention_lanelet || !target_object.dist_to_stopline || !target_object.stopline) { @@ -1639,14 +2495,14 @@ bool IntersectionModule::checkCollision( // If the vehicle is expected to stop before their stopline, ignore const bool expected_to_stop_before_stopline = expectedToStopBeforeStopLine(target_object); if ( - traffic_prioritized_level == util::TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED && + traffic_prioritized_level == TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED && expected_to_stop_before_stopline) { debug_data_.amber_ignore_targets.objects.push_back(object); continue; } const bool is_tolerable_overshoot = isTolerableOvershoot(target_object); if ( - traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED && + traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED && !expected_to_stop_before_stopline && is_tolerable_overshoot) { debug_data_.red_overshoot_ignore_targets.objects.push_back(object); continue; @@ -1766,16 +2622,288 @@ bool IntersectionModule::checkCollision( return collision_detected; } +std::optional IntersectionModule::checkAngleForTargetLanelets( + + const geometry_msgs::msg::Pose & pose, const lanelet::ConstLanelets & target_lanelets, + const bool is_parked_vehicle) const +{ + const double detection_area_angle_thr = planner_param_.common.attention_area_angle_threshold; + const bool consider_wrong_direction_vehicle = + planner_param_.common.attention_area_angle_threshold; + const double dist_margin = planner_param_.common.attention_area_margin; + + for (unsigned i = 0; i < target_lanelets.size(); ++i) { + const auto & ll = target_lanelets.at(i); + if (!lanelet::utils::isInLanelet(pose, ll, dist_margin)) { + continue; + } + const double ll_angle = lanelet::utils::getLaneletAngle(ll, pose.position); + const double pose_angle = tf2::getYaw(pose.orientation); + const double angle_diff = tier4_autoware_utils::normalizeRadian(ll_angle - pose_angle, -M_PI); + if (consider_wrong_direction_vehicle) { + if (std::fabs(angle_diff) > 1.57 || std::fabs(angle_diff) < detection_area_angle_thr) { + return std::make_optional(i); + } + } else { + if (std::fabs(angle_diff) < detection_area_angle_thr) { + return std::make_optional(i); + } + // NOTE: sometimes parked vehicle direction is reversed even if its longitudinal velocity is + // positive + if ( + is_parked_vehicle && (std::fabs(angle_diff) < detection_area_angle_thr || + (std::fabs(angle_diff + M_PI) < detection_area_angle_thr))) { + return std::make_optional(i); + } + } + } + return std::nullopt; +} + +void IntersectionModule::cutPredictPathWithDuration( + TargetObjects * target_objects, const double time_thr) +{ + const rclcpp::Time current_time = clock_->now(); + for (auto & target_object : target_objects->all_attention_objects) { // each objects + for (auto & predicted_path : + target_object.object.kinematics.predicted_paths) { // each predicted paths + const auto origin_path = predicted_path; + predicted_path.path.clear(); + + for (size_t k = 0; k < origin_path.path.size(); ++k) { // each path points + const auto & predicted_pose = origin_path.path.at(k); + const auto predicted_time = + rclcpp::Time(target_objects->header.stamp) + + rclcpp::Duration(origin_path.time_step) * static_cast(k); + if ((predicted_time - current_time).seconds() < time_thr) { + predicted_path.path.push_back(predicted_pose); + } + } + } + } +} + +TimeDistanceArray IntersectionModule::calcIntersectionPassingTime( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, + const size_t last_intersection_stopline_candidate_idx, const double time_delay, + tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array) +{ + const double intersection_velocity = + planner_param_.collision_detection.velocity_profile.default_velocity; + const double minimum_ego_velocity = + planner_param_.collision_detection.velocity_profile.minimum_default_velocity; + const bool use_upstream_velocity = + planner_param_.collision_detection.velocity_profile.use_upstream; + const double minimum_upstream_velocity = + planner_param_.collision_detection.velocity_profile.minimum_upstream_velocity; + const double current_velocity = planner_data_->current_velocity->twist.linear.x; + + int assigned_lane_found = false; + + // crop intersection part of the path, and set the reference velocity to intersection_velocity + // for ego's ttc + PathWithLaneId reference_path; + std::optional upstream_stopline{std::nullopt}; + for (size_t i = 0; i < path.points.size() - 1; ++i) { + auto reference_point = path.points.at(i); + // assume backward velocity is current ego velocity + if (i < closest_idx) { + reference_point.point.longitudinal_velocity_mps = current_velocity; + } + if ( + i > last_intersection_stopline_candidate_idx && + std::fabs(reference_point.point.longitudinal_velocity_mps) < + std::numeric_limits::epsilon() && + !upstream_stopline) { + upstream_stopline = i; + } + if (!use_upstream_velocity) { + reference_point.point.longitudinal_velocity_mps = intersection_velocity; + } + reference_path.points.push_back(reference_point); + bool has_objective_lane_id = util::hasLaneIds(path.points.at(i), associative_ids_); + if (assigned_lane_found && !has_objective_lane_id) { + break; + } + assigned_lane_found = has_objective_lane_id; + } + if (!assigned_lane_found) { + return {{0.0, 0.0}}; // has already passed the intersection. + } + + std::vector> original_path_xy; + for (size_t i = 0; i < reference_path.points.size(); ++i) { + const auto & p = reference_path.points.at(i).point.pose.position; + original_path_xy.emplace_back(p.x, p.y); + } + + // apply smoother to reference velocity + PathWithLaneId smoothed_reference_path = reference_path; + if (!smoothPath(reference_path, smoothed_reference_path, planner_data_)) { + smoothed_reference_path = reference_path; + } + + // calculate when ego is going to reach each (interpolated) points on the path + TimeDistanceArray time_distance_array{}; + double dist_sum = 0.0; + double passing_time = time_delay; + time_distance_array.emplace_back(passing_time, dist_sum); + + // NOTE: `reference_path` is resampled in `reference_smoothed_path`, so + // `last_intersection_stopline_candidate_idx` makes no sense + const auto smoothed_path_closest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints( + smoothed_reference_path.points, path.points.at(closest_idx).point.pose, + planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); + + const std::optional upstream_stopline_idx_opt = [&]() -> std::optional { + if (upstream_stopline) { + const auto upstream_stopline_point = path.points.at(upstream_stopline.value()).point.pose; + return motion_utils::findFirstNearestIndexWithSoftConstraints( + smoothed_reference_path.points, upstream_stopline_point, + planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); + } else { + return std::nullopt; + } + }(); + const bool has_upstream_stopline = upstream_stopline_idx_opt.has_value(); + const size_t upstream_stopline_ind = upstream_stopline_idx_opt.value_or(0); + + for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size() - 1; ++i) { + const auto & p1 = smoothed_reference_path.points.at(i); + const auto & p2 = smoothed_reference_path.points.at(i + 1); + + const double dist = tier4_autoware_utils::calcDistance2d(p1, p2); + dist_sum += dist; + + // use average velocity between p1 and p2 + const double average_velocity = + (p1.point.longitudinal_velocity_mps + p2.point.longitudinal_velocity_mps) / 2.0; + const double passing_velocity = [=]() { + if (use_upstream_velocity) { + if (has_upstream_stopline && i > upstream_stopline_ind) { + return minimum_upstream_velocity; + } + return std::max(average_velocity, minimum_ego_velocity); + } else { + return std::max(average_velocity, minimum_ego_velocity); + } + }(); + passing_time += (dist / passing_velocity); + + time_distance_array.emplace_back(passing_time, dist_sum); + } + debug_ttc_array->layout.dim.resize(3); + debug_ttc_array->layout.dim.at(0).label = "lane_id_@[0][0], ttc_time, ttc_dist, path_x, path_y"; + debug_ttc_array->layout.dim.at(0).size = 5; + debug_ttc_array->layout.dim.at(1).label = "values"; + debug_ttc_array->layout.dim.at(1).size = time_distance_array.size(); + debug_ttc_array->data.reserve( + time_distance_array.size() * debug_ttc_array->layout.dim.at(0).size); + for (unsigned i = 0; i < time_distance_array.size(); ++i) { + debug_ttc_array->data.push_back(lane_id_); + } + for (const auto & [t, d] : time_distance_array) { + debug_ttc_array->data.push_back(t); + } + for (const auto & [t, d] : time_distance_array) { + debug_ttc_array->data.push_back(d); + } + for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size(); ++i) { + const auto & p = smoothed_reference_path.points.at(i).point.pose.position; + debug_ttc_array->data.push_back(p.x); + } + for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size(); ++i) { + const auto & p = smoothed_reference_path.points.at(i).point.pose.position; + debug_ttc_array->data.push_back(p.y); + } + return time_distance_array; +} + +static double getHighestCurvature(const lanelet::ConstLineString3d & centerline) +{ + std::vector points; + for (auto point = centerline.begin(); point != centerline.end(); point++) { + points.push_back(*point); + } + + SplineInterpolationPoints2d interpolation(points); + const std::vector curvatures = interpolation.getSplineInterpolatedCurvatures(); + std::vector curvatures_positive; + for (const auto & curvature : curvatures) { + curvatures_positive.push_back(std::fabs(curvature)); + } + return *std::max_element(curvatures_positive.begin(), curvatures_positive.end()); +} + +std::vector IntersectionModule::generateDetectionLaneDivisions( + lanelet::ConstLanelets detection_lanelets_all, + const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution) +{ + const double curvature_threshold = + planner_param_.occlusion.attention_lane_crop_curvature_threshold; + const double curvature_calculation_ds = + planner_param_.occlusion.attention_lane_curvature_calculation_ds; + + using lanelet::utils::getCenterlineWithOffset; + + // (0) remove left/right lanelet + lanelet::ConstLanelets detection_lanelets; + for (const auto & detection_lanelet : detection_lanelets_all) { + // TODO(Mamoru Sobue): instead of ignoring, only trim straight part of lanelet + const auto fine_centerline = + lanelet::utils::generateFineCenterline(detection_lanelet, curvature_calculation_ds); + const double highest_curvature = getHighestCurvature(fine_centerline); + if (highest_curvature > curvature_threshold) { + continue; + } + detection_lanelets.push_back(detection_lanelet); + } + + // (1) tsort detection_lanelets + const auto [merged_detection_lanelets, originals] = + util::mergeLaneletsByTopologicalSort(detection_lanelets, routing_graph_ptr); + + // (2) merge each branch to one lanelet + // NOTE: somehow bg::area() for merged lanelet does not work, so calculate it here + std::vector> merged_lanelet_with_area; + for (unsigned i = 0; i < merged_detection_lanelets.size(); ++i) { + const auto & merged_detection_lanelet = merged_detection_lanelets.at(i); + const auto & original = originals.at(i); + double area = 0; + for (const auto & partition : original) { + area += bg::area(partition.polygon2d().basicPolygon()); + } + merged_lanelet_with_area.emplace_back(merged_detection_lanelet, area); + } + + // (3) discretize each merged lanelet + std::vector detection_divisions; + for (const auto & [merged_lanelet, area] : merged_lanelet_with_area) { + const double length = bg::length(merged_lanelet.centerline()); + const double width = area / length; + for (int i = 0; i < static_cast(width / resolution); ++i) { + const double offset = resolution * i - width / 2; + detection_divisions.push_back( + getCenterlineWithOffset(merged_lanelet, offset, resolution).invert()); + } + detection_divisions.push_back( + getCenterlineWithOffset(merged_lanelet, width / 2, resolution).invert()); + } + return detection_divisions; +} + IntersectionModule::OcclusionType IntersectionModule::getOcclusionStatus( - const nav_msgs::msg::OccupancyGrid & occ_grid, const std::vector & attention_areas, const lanelet::ConstLanelets & adjacent_lanelets, const lanelet::CompoundPolygon3d & first_attention_area, const util::InterpolatedPathInfo & interpolated_path_info, const std::vector & lane_divisions, - const util::TargetObjects & target_objects, const geometry_msgs::msg::Pose & current_pose, - const double occlusion_dist_thr) + const TargetObjects & target_objects) { + const auto & occ_grid = *planner_data_->occupancy_grid; + const auto & current_pose = planner_data_->current_odometry->pose; + const double occlusion_dist_thr = planner_param_.occlusion.occlusion_required_clearance_distance; + const auto & path_ip = interpolated_path_info.path; const auto & lane_interval_ip = interpolated_path_info.lane_id_interval.value(); @@ -2094,6 +3222,76 @@ IntersectionModule::OcclusionType IntersectionModule::getOcclusionStatus( return OcclusionType::STATICALLY_OCCLUDED; } +static std::optional> +getFirstPointInsidePolygonsByFootprint( + const std::vector & polygons, + const util::InterpolatedPathInfo & interpolated_path_info, + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) +{ + const auto & path_ip = interpolated_path_info.path; + const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); + const size_t vehicle_length_idx = static_cast(vehicle_length / interpolated_path_info.ds); + const size_t start = + static_cast(std::max(0, static_cast(lane_start) - vehicle_length_idx)); + + for (size_t i = start; i <= lane_end; ++i) { + const auto & pose = path_ip.points.at(i).point.pose; + const auto path_footprint = + tier4_autoware_utils::transformVector(footprint, tier4_autoware_utils::pose2transform(pose)); + for (size_t j = 0; j < polygons.size(); ++j) { + const auto area_2d = lanelet::utils::to2D(polygons.at(j)).basicPolygon(); + const bool is_in_polygon = bg::intersects(area_2d, path_footprint); + if (is_in_polygon) { + return std::make_optional>(i, j); + } + } + } + return std::nullopt; +} + +void IntersectionLanelets::update( + const bool is_prioritized, const util::InterpolatedPathInfo & interpolated_path_info, + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) +{ + is_prioritized_ = is_prioritized; + // find the first conflicting/detection area polygon intersecting the path + if (!first_conflicting_area_) { + auto first = getFirstPointInsidePolygonsByFootprint( + conflicting_area_, interpolated_path_info, footprint, vehicle_length); + if (first) { + first_conflicting_lane_ = conflicting_.at(first.value().second); + first_conflicting_area_ = conflicting_area_.at(first.value().second); + } + } + if (!first_attention_area_) { + auto first = getFirstPointInsidePolygonsByFootprint( + attention_non_preceding_area_, interpolated_path_info, footprint, vehicle_length); + if (first) { + first_attention_lane_ = attention_non_preceding_.at(first.value().second); + first_attention_area_ = attention_non_preceding_area_.at(first.value().second); + } + } +} + +void TargetObject::calc_dist_to_stopline() +{ + if (!attention_lanelet || !stopline) { + return; + } + const auto attention_lanelet_val = attention_lanelet.value(); + const auto object_arc_coords = lanelet::utils::getArcCoordinates( + {attention_lanelet_val}, object.kinematics.initial_pose_with_covariance.pose); + const auto stopline_val = stopline.value(); + geometry_msgs::msg::Pose stopline_center; + stopline_center.position.x = (stopline_val.front().x() + stopline_val.back().x()) / 2.0; + stopline_center.position.y = (stopline_val.front().y() + stopline_val.back().y()) / 2.0; + stopline_center.position.z = (stopline_val.front().z() + stopline_val.back().z()) / 2.0; + const auto stopline_arc_coords = + lanelet::utils::getArcCoordinates({attention_lanelet_val}, stopline_center); + dist_to_stopline = (stopline_arc_coords.length - object_arc_coords.length); +} + /* bool IntersectionModule::checkFrontVehicleDeceleration( lanelet::ConstLanelets & ego_lane_with_next_lane, lanelet::ConstLanelet & closest_lanelet, diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 2f8c296a348b9..6a350e66706e6 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -30,6 +30,7 @@ #include #include +#include #include #include #include @@ -42,6 +43,259 @@ namespace behavior_velocity_planner using TimeDistanceArray = std::vector>; +struct DebugData +{ + std::optional collision_stop_wall_pose{std::nullopt}; + std::optional occlusion_stop_wall_pose{std::nullopt}; + std::optional occlusion_first_stop_wall_pose{std::nullopt}; + std::optional pass_judge_wall_pose{std::nullopt}; + std::optional> attention_area{std::nullopt}; + std::optional> occlusion_attention_area{std::nullopt}; + std::optional ego_lane{std::nullopt}; + std::optional> adjacent_area{std::nullopt}; + std::optional stuck_vehicle_detect_area{std::nullopt}; + std::optional> yield_stuck_detect_area{std::nullopt}; + std::optional candidate_collision_ego_lane_polygon{std::nullopt}; + std::vector candidate_collision_object_polygons; + autoware_auto_perception_msgs::msg::PredictedObjects conflicting_targets; + autoware_auto_perception_msgs::msg::PredictedObjects amber_ignore_targets; + autoware_auto_perception_msgs::msg::PredictedObjects red_overshoot_ignore_targets; + autoware_auto_perception_msgs::msg::PredictedObjects stuck_targets; + autoware_auto_perception_msgs::msg::PredictedObjects yield_stuck_targets; + std::vector occlusion_polygons; + std::optional> + nearest_occlusion_projection{std::nullopt}; + autoware_auto_perception_msgs::msg::PredictedObjects blocking_attention_objects; + std::optional absence_traffic_light_creep_wall{std::nullopt}; + std::optional static_occlusion_with_traffic_light_timeout{std::nullopt}; +}; + +/** + * @struct + * @brief see the document for more details of IntersectionLanelets + */ +struct IntersectionLanelets +{ +public: + /** + * update conflicting lanelets and traffic priority information + */ + void update( + const bool is_prioritized, const util::InterpolatedPathInfo & interpolated_path_info, + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length); + + const lanelet::ConstLanelets & attention() const + { + return is_prioritized_ ? attention_non_preceding_ : attention_; + } + const std::vector> & attention_stoplines() const + { + return is_prioritized_ ? attention_non_preceding_stoplines_ : attention_stoplines_; + } + const lanelet::ConstLanelets & conflicting() const { return conflicting_; } + const lanelet::ConstLanelets & adjacent() const { return adjacent_; } + const lanelet::ConstLanelets & occlusion_attention() const + { + return is_prioritized_ ? attention_non_preceding_ : occlusion_attention_; + } + const lanelet::ConstLanelets & attention_non_preceding() const + { + return attention_non_preceding_; + } + const std::vector & attention_area() const + { + return is_prioritized_ ? attention_non_preceding_area_ : attention_area_; + } + const std::vector & conflicting_area() const + { + return conflicting_area_; + } + const std::vector & adjacent_area() const { return adjacent_area_; } + const std::vector & occlusion_attention_area() const + { + return occlusion_attention_area_; + } + const std::optional & first_conflicting_lane() const + { + return first_conflicting_lane_; + } + const std::optional & first_conflicting_area() const + { + return first_conflicting_area_; + } + const std::optional & first_attention_lane() const + { + return first_attention_lane_; + } + const std::optional & first_attention_area() const + { + return first_attention_area_; + } + + /** + * the set of attention lanelets which is topologically merged + */ + lanelet::ConstLanelets attention_; + std::vector attention_area_; + + /** + * the stop lines for each attention_ lanelets + */ + std::vector> attention_stoplines_; + + /** + * the conflicting part of attention lanelets + */ + lanelet::ConstLanelets attention_non_preceding_; + std::vector attention_non_preceding_area_; + + /** + * the stop lines for each attention_non_preceding_ + */ + std::vector> attention_non_preceding_stoplines_; + + /** + * the conflicting lanelets of the objective intersection lanelet + */ + lanelet::ConstLanelets conflicting_; + std::vector conflicting_area_; + + /** + * + */ + lanelet::ConstLanelets adjacent_; + std::vector adjacent_area_; + + /** + * the set of attention lanelets for occlusion detection which is topologically merged + */ + lanelet::ConstLanelets occlusion_attention_; + std::vector occlusion_attention_area_; + + /** + * the vector of sum of each occlusion_attention lanelet + */ + std::vector occlusion_attention_size_; + + /** + * the attention lanelet which ego path points intersect for the first time + */ + std::optional first_conflicting_lane_{std::nullopt}; + std::optional first_conflicting_area_{std::nullopt}; + + /** + * the attention lanelet which ego path points intersect for the first time + */ + std::optional first_attention_lane_{std::nullopt}; + std::optional first_attention_area_{std::nullopt}; + + /** + * flag if the intersection is prioritized by the traffic light + */ + bool is_prioritized_{false}; +}; + +/** + * @struct + * @brief see the document for more details of IntersectionStopLines + */ +struct IntersectionStopLines +{ + size_t closest_idx{0}; + + /** + * stuck_stopline is null if ego path does not intersect with first_conflicting_area + */ + std::optional stuck_stopline{std::nullopt}; + + /** + * default_stopline is null if it is calculated negative from first_attention_stopline + */ + std::optional default_stopline{std::nullopt}; + + /** + * first_attention_stopline is null if ego footprint along the path does not intersect with + * attention area. if path[0] satisfies the condition, it is 0 + */ + std::optional first_attention_stopline{std::nullopt}; + + /** + * occlusion_peeking_stopline is null if path[0] is already inside the attention area + */ + std::optional occlusion_peeking_stopline{std::nullopt}; + + /** + * pass_judge_line is before first_attention_stop_line by the braking distance. if its value is + * calculated negative, it is 0 + */ + size_t pass_judge_line{0}; + + /** + * occlusion_wo_tl_pass_judge_line is null if ego footprint along the path does not intersect with + * the centerline of the first_attention_lane + */ + size_t occlusion_wo_tl_pass_judge_line{0}; +}; + +/** + * @struct + * @brief see the document for more details of PathLanelets + */ +struct PathLanelets +{ + lanelet::ConstLanelets prev; + // lanelet::ConstLanelet entry2ego; this is included in `all` if exists + lanelet::ConstLanelet + ego_or_entry2exit; // this is `assigned lane` part of the path(not from + // ego) if ego is before the intersection, otherwise from ego to exit + std::optional next = + std::nullopt; // this is nullopt is the goal is inside intersection + lanelet::ConstLanelets all; + lanelet::ConstLanelets + conflicting_interval_and_remaining; // the left/right-most interval of path conflicting with + // conflicting lanelets plus the next lane part of the + // path +}; + +/** + * @struct + * @brief see the document for more details of IntersectionStopLines + */ +struct TargetObject +{ + autoware_auto_perception_msgs::msg::PredictedObject object; + std::optional attention_lanelet{std::nullopt}; + std::optional stopline{std::nullopt}; + std::optional dist_to_stopline{std::nullopt}; + void calc_dist_to_stopline(); +}; + +/** + * @struct + * @brief categorize TargetObjects + */ +struct TargetObjects +{ + std_msgs::msg::Header header; + std::vector attention_objects; + std::vector parked_attention_objects; + std::vector intersection_area_objects; + std::vector all_attention_objects; // TODO(Mamoru Sobue): avoid copy +}; + +/** + * @struct + * @brief categorize traffic light priority + */ +enum class TrafficPrioritizedLevel { + //! The target lane's traffic signal is red or the ego's traffic signal has an arrow. + FULLY_PRIORITIZED = 0, + //! The target lane's traffic signal is amber + PARTIALLY_PRIORITIZED, + //! The target lane's traffic signal is green + NOT_PRIORITIZED +}; + class IntersectionModule : public SceneModuleInterface { public: @@ -159,33 +413,57 @@ class IntersectionModule : public SceneModuleInterface }; enum OcclusionType { + //! occlusion is not detected NOT_OCCLUDED, + //! occlusion is not caused by dynamic objects STATICALLY_OCCLUDED, + //! occlusion is caused by dynamic objects DYNAMICALLY_OCCLUDED, - RTC_OCCLUDED, // actual occlusion does not exist, only disapproved by RTC + //! actual occlusion does not exist, only disapproved by RTC + RTC_OCCLUDED, }; + /** + * @struct + * @brief Internal error or ego already passed pass_judge_line + */ struct Indecisive { std::string error; }; + /** + * @struct + * @brief detected stuck vehicle + */ struct StuckStop { size_t closest_idx{0}; size_t stuck_stopline_idx{0}; std::optional occlusion_stopline_idx{std::nullopt}; }; + /** + * @struct + * @brief yielded by vehicle on the attention area + */ struct YieldStuckStop { size_t closest_idx{0}; size_t stuck_stopline_idx{0}; }; + /** + * @struct + * @brief only collision is detected + */ struct NonOccludedCollisionStop { size_t closest_idx{0}; size_t collision_stopline_idx{0}; size_t occlusion_stopline_idx{0}; }; + /** + * @struct + * @brief occlusion is detected so ego needs to stop at the default stop line position + */ struct FirstWaitBeforeOcclusion { bool is_actually_occlusion_cleared{false}; @@ -193,23 +471,29 @@ class IntersectionModule : public SceneModuleInterface size_t first_stopline_idx{0}; size_t occlusion_stopline_idx{0}; }; - // A state peeking to occlusion limit line in the presence of traffic light + /** + * @struct + * @brief ego is approaching the boundary of attention area in the presence of traffic light + */ struct PeekingTowardOcclusion { - // NOTE: if intersection_occlusion is disapproved externally through RTC, - // it indicates "is_forcefully_occluded" + //! if intersection_occlusion is disapproved externally through RTC, it indicates + //! "is_forcefully_occluded" bool is_actually_occlusion_cleared{false}; bool temporal_stop_before_attention_required{false}; size_t closest_idx{0}; size_t collision_stopline_idx{0}; size_t first_attention_stopline_idx{0}; size_t occlusion_stopline_idx{0}; - // if null, it is dynamic occlusion and shows up intersection_occlusion(dyn) - // if valid, it contains the remaining time to release the static occlusion stuck and shows up - // intersection_occlusion(x.y) + //! if null, it is dynamic occlusion and shows up intersection_occlusion(dyn). if valid, it + //! contains the remaining time to release the static occlusion stuck and shows up + //! intersection_occlusion(x.y) std::optional static_occlusion_timeout{std::nullopt}; }; - // A state detecting both collision and occlusion in the presence of traffic light + /** + * @struct + * @brief both collision and occlusion are detected in the presence of traffic light + */ struct OccludedCollisionStop { bool is_actually_occlusion_cleared{false}; @@ -218,10 +502,14 @@ class IntersectionModule : public SceneModuleInterface size_t collision_stopline_idx{0}; size_t first_attention_stopline_idx{0}; size_t occlusion_stopline_idx{0}; - // if null, it is dynamic occlusion and shows up intersection_occlusion(dyn) - // if valid, it contains the remaining time to release the static occlusion stuck + //! if null, it is dynamic occlusion and shows up intersection_occlusion(dyn). if valid, it + //! contains the remaining time to release the static occlusion stuck std::optional static_occlusion_timeout{std::nullopt}; }; + /** + * @struct + * @brief at least occlusion is detected in the absence of traffic light + */ struct OccludedAbsenceTrafficLight { bool is_actually_occlusion_cleared{false}; @@ -231,13 +519,20 @@ class IntersectionModule : public SceneModuleInterface size_t first_attention_area_stopline_idx{0}; size_t peeking_limit_line_idx{0}; }; + /** + * @struct + * @brief both collision and occlusion are not detected + */ struct Safe { - // NOTE: if RTC is disapproved status, default stop lines are still needed. size_t closest_idx{0}; size_t collision_stopline_idx{0}; size_t occlusion_stopline_idx{0}; }; + /** + * @struct + * @brief traffic light is red or arrow signal + */ struct FullyPrioritized { bool collision_detected{false}; @@ -246,16 +541,16 @@ class IntersectionModule : public SceneModuleInterface size_t occlusion_stopline_idx{0}; }; using DecisionResult = std::variant< - Indecisive, // internal process error, or over the pass judge line - StuckStop, // detected stuck vehicle - YieldStuckStop, // detected yield stuck vehicle - NonOccludedCollisionStop, // detected collision while FOV is clear - FirstWaitBeforeOcclusion, // stop for a while before peeking to occlusion - PeekingTowardOcclusion, // peeking into occlusion while collision is not detected - OccludedCollisionStop, // occlusion and collision are both detected - OccludedAbsenceTrafficLight, // occlusion is detected in the absence of traffic light - Safe, // judge as safe - FullyPrioritized // only detect vehicles violating traffic rules + Indecisive, //! internal process error, or over the pass judge line + StuckStop, //! detected stuck vehicle + YieldStuckStop, //! detected yield stuck vehicle + NonOccludedCollisionStop, //! detected collision while FOV is clear + FirstWaitBeforeOcclusion, //! stop for a while before peeking to occlusion + PeekingTowardOcclusion, //! peeking into occlusion while collision is not detected + OccludedCollisionStop, //! occlusion and collision are both detected + OccludedAbsenceTrafficLight, //! occlusion is detected in the absence of traffic light + Safe, //! judge as safe + FullyPrioritized //! only detect vehicles violating traffic rules >; IntersectionModule( @@ -265,10 +560,6 @@ class IntersectionModule : public SceneModuleInterface const bool enable_occlusion_detection, rclcpp::Node & node, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); - /** - * @brief plan go-stop velocity at traffic crossing with collision check between reference path - * and object predicted path - */ bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; @@ -289,28 +580,27 @@ class IntersectionModule : public SceneModuleInterface const std::string turn_direction_; const bool has_traffic_light_; + // Parameter + PlannerParam planner_param_; + + std::optional intersection_lanelets_{std::nullopt}; + + // for pass judge decision bool is_go_out_{false}; bool is_permanent_go_{false}; DecisionResult prev_decision_result_{Indecisive{""}}; OcclusionType prev_occlusion_status_; - // Parameter - PlannerParam planner_param_; - - std::optional intersection_lanelets_{std::nullopt}; - // for occlusion detection const bool enable_occlusion_detection_; std::optional> occlusion_attention_divisions_{ - std::nullopt}; - StateMachine collision_state_machine_; //! for stable collision checking - StateMachine before_creep_state_machine_; //! for two phase stop - StateMachine occlusion_stop_state_machine_; + std::nullopt}; //! for caching discretized occlusion detection lanelets + StateMachine collision_state_machine_; //! for stable collision checking + StateMachine before_creep_state_machine_; //! for two phase stop + StateMachine occlusion_stop_state_machine_; //! for stable occlusion detection StateMachine temporal_stop_before_attention_state_machine_; StateMachine static_occlusion_timeout_state_machine_; - // for pseudo-collision detection when ego just entered intersection on green light and upcoming - // vehicles are very slow std::optional initial_green_light_observed_time_{std::nullopt}; // for RTC @@ -318,43 +608,135 @@ class IntersectionModule : public SceneModuleInterface bool occlusion_safety_{true}; double occlusion_stop_distance_{0.0}; bool occlusion_activated_{true}; - // for first stop in two-phase stop bool occlusion_first_stop_required_{false}; + /** + * @fn + * @brief set all RTC variable to safe and -inf + */ void initializeRTCStatus(); + /** + * @fn + * @brief analyze traffic_light/occupancy/objects context and return DecisionResult + */ + DecisionResult modifyPathVelocityDetail(PathWithLaneId * path, StopReason * stop_reason); + /** + * @fn + * @brief set RTC value according to calculated DecisionResult + */ void prepareRTCStatus( const DecisionResult &, const autoware_auto_planning_msgs::msg::PathWithLaneId & path); - DecisionResult modifyPathVelocityDetail(PathWithLaneId * path, StopReason * stop_reason); + /** + * @fn + * @brief find TrafficPrioritizedLevel + */ + TrafficPrioritizedLevel getTrafficPrioritizedLevel( + lanelet::ConstLanelet lane, const std::map & tl_infos); + + /** + * @fn + * @brief generate IntersectionLanelets + */ + IntersectionLanelets getObjectiveLanelets( + lanelet::LaneletMapConstPtr lanelet_map_ptr, + lanelet::routing::RoutingGraphPtr routing_graph_ptr, + const lanelet::ConstLanelet assigned_lanelet, const lanelet::ConstLanelets & lanelets_on_path); - bool checkStuckVehicle( - const std::shared_ptr & planner_data, - const util::PathLanelets & path_lanelets); + /** + * @fn + * @brief generate IntersectionStopLines + */ + std::optional generateIntersectionStopLines( + lanelet::ConstLanelet assigned_lanelet, + const lanelet::CompoundPolygon3d & first_conflicting_area, + const lanelet::ConstLanelet & first_attention_lane, + const util::InterpolatedPathInfo & interpolated_path_info, + autoware_auto_planning_msgs::msg::PathWithLaneId * original_path); - bool checkYieldStuckVehicle( - const util::TargetObjects & target_objects, + /** + * @fn + * @brief find the associated stopline road marking of assigned lanelet + */ + std::optional getStopLineIndexFromMap( const util::InterpolatedPathInfo & interpolated_path_info, - const lanelet::ConstLanelets & attention_lanelets); + lanelet::ConstLanelet assigned_lanelet); - util::TargetObjects generateTargetObjects( - const util::IntersectionLanelets & intersection_lanelets, + /** + * @fn + * @brief generate PathLanelets + */ + std::optional generatePathLanelets( + const lanelet::ConstLanelets & lanelets_on_path, + const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::CompoundPolygon3d & first_conflicting_area, + const std::vector & conflicting_areas, + const std::optional & first_attention_area, + const std::vector & attention_areas, const size_t closest_idx); + + /** + * @fn + * @brief check stuck + */ + bool checkStuckVehicleInIntersection(const PathLanelets & path_lanelets, DebugData * debug_data); + + /** + * @fn + * @brief check yield stuck + */ + bool checkYieldStuckVehicleInIntersection( + const TargetObjects & target_objects, const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::ConstLanelets & attention_lanelets, DebugData * debug_data); + + /** + * @fn + * @brief categorize target objects + */ + TargetObjects generateTargetObjects( + const IntersectionLanelets & intersection_lanelets, const std::optional & intersection_area) const; + /** + * @fn + * @brief check collision + */ bool checkCollision( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - util::TargetObjects * target_objects, const util::PathLanelets & path_lanelets, - const size_t closest_idx, const size_t last_intersection_stopline_candidate_idx, - const double time_delay, const util::TrafficPrioritizedLevel & traffic_prioritized_level); + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, TargetObjects * target_objects, + const PathLanelets & path_lanelets, const size_t closest_idx, + const size_t last_intersection_stopline_candidate_idx, const double time_delay, + const TrafficPrioritizedLevel & traffic_prioritized_level); + + std::optional checkAngleForTargetLanelets( + const geometry_msgs::msg::Pose & pose, const lanelet::ConstLanelets & target_lanelets, + const bool is_parked_vehicle) const; + + void cutPredictPathWithDuration(TargetObjects * target_objects, const double time_thr); + /** + * @fn + * @brief calculate ego vehicle profile along the path inside the intersection as the sequence of + * (time of arrival, traveled distance) from current ego position + */ + TimeDistanceArray calcIntersectionPassingTime( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, + const size_t last_intersection_stopline_candidate_idx, const double time_delay, + tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array); + + std::vector generateDetectionLaneDivisions( + lanelet::ConstLanelets detection_lanelets, + const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution); + + /** + * @fn + * @brief check occlusion status + */ OcclusionType getOcclusionStatus( - const nav_msgs::msg::OccupancyGrid & occ_grid, const std::vector & attention_areas, const lanelet::ConstLanelets & adjacent_lanelets, const lanelet::CompoundPolygon3d & first_attention_area, const util::InterpolatedPathInfo & interpolated_path_info, const std::vector & lane_divisions, - const util::TargetObjects & target_objects, const geometry_msgs::msg::Pose & current_pose, - const double occlusion_dist_thr); + const TargetObjects & target_objects); /* bool IntersectionModule::checkFrontVehicleDeceleration( @@ -364,7 +746,7 @@ class IntersectionModule : public SceneModuleInterface const double assumed_front_car_decel); */ - util::DebugData debug_data_; + DebugData debug_data_; rclcpp::Publisher::SharedPtr decision_state_pub_; rclcpp::Publisher::SharedPtr ego_ttc_pub_; rclcpp::Publisher::SharedPtr object_ttc_pub_; diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index b373f2cbc1c8a..f56d0a4adcff7 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -16,17 +16,16 @@ #include "util.hpp" -#include #include #include #include -#include #include #include #include #include +#include #include #include #include @@ -50,6 +49,32 @@ MergeFromPrivateRoadModule::MergeFromPrivateRoadModule( state_machine_.setState(StateMachine::State::STOP); } +static std::optional getFirstConflictingLanelet( + const lanelet::ConstLanelets & conflicting_lanelets, + const util::InterpolatedPathInfo & interpolated_path_info, + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) +{ + const auto & path_ip = interpolated_path_info.path; + const auto [lane_start, end] = interpolated_path_info.lane_id_interval.value(); + const size_t vehicle_length_idx = static_cast(vehicle_length / interpolated_path_info.ds); + const size_t start = + static_cast(std::max(0, static_cast(lane_start) - vehicle_length_idx)); + + for (size_t i = start; i <= end; ++i) { + const auto & pose = path_ip.points.at(i).point.pose; + const auto path_footprint = + tier4_autoware_utils::transformVector(footprint, tier4_autoware_utils::pose2transform(pose)); + for (const auto & conflicting_lanelet : conflicting_lanelets) { + const auto polygon_2d = conflicting_lanelet.polygon2d().basicPolygon(); + const bool intersects = bg::intersects(polygon_2d, path_footprint); + if (intersects) { + return std::make_optional(conflicting_lanelet); + } + } + } + return std::nullopt; +} + bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) { debug_data_ = DebugData(); @@ -83,41 +108,36 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR return false; } - /* get detection area */ - if (!intersection_lanelets_) { - const auto & assigned_lanelet = - planner_data_->route_handler_->getLaneletMapPtr()->laneletLayer.get(lane_id_); - const auto lanelets_on_path = planning_utils::getLaneletsOnPath( - *path, lanelet_map_ptr, planner_data_->current_odometry->pose); - intersection_lanelets_ = util::getObjectiveLanelets( - lanelet_map_ptr, routing_graph_ptr, assigned_lanelet, lanelets_on_path, associative_ids_, - planner_param_.attention_area_length, planner_param_.occlusion_attention_area_length, - planner_param_.consider_wrong_direction_vehicle); - } - auto & intersection_lanelets = intersection_lanelets_.value(); const auto local_footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0); - intersection_lanelets.update( - false, interpolated_path_info, local_footprint, - planner_data_->vehicle_info_.max_longitudinal_offset_m); - const auto & first_conflicting_area = intersection_lanelets.first_conflicting_area(); - if (!first_conflicting_area) { + if (!first_conflicting_lanelet_) { + const auto & assigned_lanelet = lanelet_map_ptr->laneletLayer.get(lane_id_); + const auto conflicting_lanelets = + lanelet::utils::getConflictingLanelets(routing_graph_ptr, assigned_lanelet); + first_conflicting_lanelet_ = getFirstConflictingLanelet( + conflicting_lanelets, interpolated_path_info, local_footprint, + planner_data_->vehicle_info_.max_longitudinal_offset_m); + } + if (!first_conflicting_lanelet_) { return false; } + const auto first_conflicting_lanelet = first_conflicting_lanelet_.value(); - /* set stop-line and stop-judgement-line for base_link */ - const auto stopline_idx_opt = util::generateStuckStopLine( - first_conflicting_area.value(), planner_data_, interpolated_path_info, - planner_param_.stopline_margin, false, path); - if (!stopline_idx_opt.has_value()) { - RCLCPP_WARN_SKIPFIRST_THROTTLE(logger_, *clock_, 1000 /* ms */, "setStopLineIdx fail"); + const auto first_conflicting_idx_opt = getFirstPointInsidePolygonByFootprint( + first_conflicting_lanelet.polygon3d(), interpolated_path_info, local_footprint, + planner_data_->vehicle_info_.max_longitudinal_offset_m); + if (!first_conflicting_idx_opt) { return false; } + const auto stopline_idx_ip = first_conflicting_idx_opt.value(); - const size_t stopline_idx = stopline_idx_opt.value(); - if (stopline_idx == 0) { - RCLCPP_DEBUG(logger_, "stop line is at path[0], ignore planning."); + const auto stopline_idx_opt = util::insertPointIndex( + interpolated_path_info.path.points.at(stopline_idx_ip).point.pose, path, + planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); + if (!stopline_idx_opt) { + RCLCPP_DEBUG(logger_, "failed to insert stopline, ignore planning."); return true; } + const auto stopline_idx = stopline_idx_opt.value(); debug_data_.virtual_wall_pose = planning_utils::getAheadPose( stopline_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); @@ -195,4 +215,5 @@ MergeFromPrivateRoadModule::extractPathNearExitOfPrivateRoad( std::reverse(private_path.points.begin(), private_path.points.end()); return private_path; } + } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp index fab0303640700..ab368e6b3106b 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp @@ -15,10 +15,7 @@ #ifndef SCENE_MERGE_FROM_PRIVATE_ROAD_HPP_ #define SCENE_MERGE_FROM_PRIVATE_ROAD_HPP_ -#include "scene_intersection.hpp" - #include -#include #include #include @@ -27,9 +24,6 @@ #include #include -#include -#include - #include #include #include @@ -89,7 +83,7 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface // Parameter PlannerParam planner_param_; - std::optional intersection_lanelets_; + std::optional first_conflicting_lanelet_; StateMachine state_machine_; //! for state diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index e491d2ce7c5ce..6afc2d61d77f2 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -18,15 +18,10 @@ #include #include -#include #include -#include -#include -#include #include #include #include -#include #include #include @@ -38,29 +33,12 @@ #include #include #include -#include #include #include #include -#include #include #include -namespace tier4_autoware_utils -{ - -template <> -inline geometry_msgs::msg::Point getPoint(const lanelet::ConstPoint3d & p) -{ - geometry_msgs::msg::Point point; - point.x = p.x(); - point.y = p.y(); - point.z = p.z(); - return point; -} - -} // namespace tier4_autoware_utils - namespace behavior_velocity_planner { namespace bg = boost::geometry; @@ -84,7 +62,7 @@ static std::optional getDuplicatedPointIdx( return std::nullopt; } -static std::optional insertPointIndex( +std::optional insertPointIndex( const geometry_msgs::msg::Pose & in_pose, autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path, const double ego_nearest_dist_threshold, const double ego_nearest_yaw_threshold) @@ -156,66 +134,7 @@ std::optional> findLaneIdsInterval( return found ? std::make_optional(std::make_pair(start, end)) : std::nullopt; } -/** - * @brief Get stop point from map if exists - * @param stop_pose stop point defined on map - * @return true when the stop point is defined on map. - */ -static std::optional getStopLineIndexFromMap( - const InterpolatedPathInfo & interpolated_path_info, - const std::shared_ptr & planner_data) -{ - const auto & path = interpolated_path_info.path; - const auto & lane_interval = interpolated_path_info.lane_id_interval.value(); - - lanelet::ConstLanelet lanelet = - planner_data->route_handler_->getLaneletMapPtr()->laneletLayer.get( - interpolated_path_info.lane_id); - const auto road_markings = lanelet.regulatoryElementsAs(); - lanelet::ConstLineStrings3d stopline; - for (const auto & road_marking : road_markings) { - const std::string type = - road_marking->roadMarking().attributeOr(lanelet::AttributeName::Type, "none"); - if (type == lanelet::AttributeValueString::StopLine) { - stopline.push_back(road_marking->roadMarking()); - break; // only one stopline exists. - } - } - if (stopline.empty()) { - return std::nullopt; - } - - const auto p_start = stopline.front().front(); - const auto p_end = stopline.front().back(); - const LineString2d extended_stopline = - planning_utils::extendLine(p_start, p_end, planner_data->stop_line_extend_length); - - for (size_t i = lane_interval.first; i < lane_interval.second; i++) { - const auto & p_front = path.points.at(i).point.pose.position; - const auto & p_back = path.points.at(i + 1).point.pose.position; - - const LineString2d path_segment = {{p_front.x, p_front.y}, {p_back.x, p_back.y}}; - std::vector collision_points; - bg::intersection(extended_stopline, path_segment, collision_points); - - if (collision_points.empty()) { - continue; - } - - return i; - } - - geometry_msgs::msg::Pose stop_point_from_map; - stop_point_from_map.position.x = 0.5 * (p_start.x() + p_end.x()); - stop_point_from_map.position.y = 0.5 * (p_start.y() + p_end.y()); - stop_point_from_map.position.z = 0.5 * (p_start.z() + p_end.z()); - - return motion_utils::findFirstNearestIndexWithSoftConstraints( - path.points, stop_point_from_map, planner_data->ego_nearest_dist_threshold, - planner_data->ego_nearest_yaw_threshold); -} - -static std::optional getFirstPointInsidePolygonByFootprint( +std::optional getFirstPointInsidePolygonByFootprint( const lanelet::CompoundPolygon3d & polygon, const InterpolatedPathInfo & interpolated_path_info, const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) { @@ -236,222 +155,6 @@ static std::optional getFirstPointInsidePolygonByFootprint( return std::nullopt; } -static std::optional> -getFirstPointInsidePolygonsByFootprint( - const std::vector & polygons, - const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) -{ - const auto & path_ip = interpolated_path_info.path; - const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); - const size_t vehicle_length_idx = static_cast(vehicle_length / interpolated_path_info.ds); - const size_t start = - static_cast(std::max(0, static_cast(lane_start) - vehicle_length_idx)); - - for (size_t i = start; i <= lane_end; ++i) { - const auto & pose = path_ip.points.at(i).point.pose; - const auto path_footprint = - tier4_autoware_utils::transformVector(footprint, tier4_autoware_utils::pose2transform(pose)); - for (size_t j = 0; j < polygons.size(); ++j) { - const auto area_2d = lanelet::utils::to2D(polygons.at(j)).basicPolygon(); - const bool is_in_polygon = bg::intersects(area_2d, path_footprint); - if (is_in_polygon) { - return std::make_optional>(i, j); - } - } - } - return std::nullopt; -} - -std::optional generateIntersectionStopLines( - const lanelet::CompoundPolygon3d & first_conflicting_area, - const lanelet::CompoundPolygon3d & first_attention_area, - const lanelet::ConstLineString2d & first_attention_lane_centerline, - const std::shared_ptr & planner_data, - const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, - const double stopline_margin, const double max_accel, const double max_jerk, - const double delay_response_time, const double peeking_offset, - autoware_auto_planning_msgs::msg::PathWithLaneId * original_path) -{ - const auto & path_ip = interpolated_path_info.path; - const double ds = interpolated_path_info.ds; - const auto & lane_interval_ip = interpolated_path_info.lane_id_interval.value(); - const double baselink2front = planner_data->vehicle_info_.max_longitudinal_offset_m; - - const int stopline_margin_idx_dist = std::ceil(stopline_margin / ds); - const int base2front_idx_dist = - std::ceil(planner_data->vehicle_info_.max_longitudinal_offset_m / ds); - - // find the index of the first point whose vehicle footprint on it intersects with detection_area - const auto local_footprint = planner_data->vehicle_info_.createFootprint(0.0, 0.0); - std::optional first_footprint_inside_detection_ip_opt = - getFirstPointInsidePolygonByFootprint( - first_attention_area, interpolated_path_info, local_footprint, baselink2front); - if (!first_footprint_inside_detection_ip_opt) { - return std::nullopt; - } - const auto first_footprint_inside_detection_ip = first_footprint_inside_detection_ip_opt.value(); - - std::optional first_footprint_attention_centerline_ip_opt = std::nullopt; - for (auto i = std::get<0>(lane_interval_ip); i < std::get<1>(lane_interval_ip); ++i) { - const auto & base_pose = path_ip.points.at(i).point.pose; - const auto path_footprint = tier4_autoware_utils::transformVector( - local_footprint, tier4_autoware_utils::pose2transform(base_pose)); - if (bg::intersects(path_footprint, first_attention_lane_centerline.basicLineString())) { - // NOTE: maybe consideration of braking dist is necessary - first_footprint_attention_centerline_ip_opt = i; - break; - } - } - if (!first_footprint_attention_centerline_ip_opt) { - return std::nullopt; - } - const size_t first_footprint_attention_centerline_ip = - first_footprint_attention_centerline_ip_opt.value(); - - // (1) default stop line position on interpolated path - bool default_stopline_valid = true; - int stop_idx_ip_int = -1; - if (const auto map_stop_idx_ip = getStopLineIndexFromMap(interpolated_path_info, planner_data); - map_stop_idx_ip) { - stop_idx_ip_int = static_cast(map_stop_idx_ip.value()) - base2front_idx_dist; - } - if (stop_idx_ip_int < 0) { - stop_idx_ip_int = first_footprint_inside_detection_ip - stopline_margin_idx_dist; - } - if (stop_idx_ip_int < 0) { - default_stopline_valid = false; - } - const auto default_stopline_ip = stop_idx_ip_int >= 0 ? static_cast(stop_idx_ip_int) : 0; - - // (2) ego front stop line position on interpolated path - const geometry_msgs::msg::Pose & current_pose = planner_data->current_odometry->pose; - const auto closest_idx_ip = motion_utils::findFirstNearestIndexWithSoftConstraints( - path_ip.points, current_pose, planner_data->ego_nearest_dist_threshold, - planner_data->ego_nearest_yaw_threshold); - - // (3) occlusion peeking stop line position on interpolated path - int occlusion_peeking_line_ip_int = static_cast(default_stopline_ip); - bool occlusion_peeking_line_valid = true; - // NOTE: if footprints[0] is already inside the detection area, invalid - { - const auto & base_pose0 = path_ip.points.at(default_stopline_ip).point.pose; - const auto path_footprint0 = tier4_autoware_utils::transformVector( - local_footprint, tier4_autoware_utils::pose2transform(base_pose0)); - if (bg::intersects( - path_footprint0, lanelet::utils::to2D(first_attention_area).basicPolygon())) { - occlusion_peeking_line_valid = false; - } - } - if (occlusion_peeking_line_valid) { - occlusion_peeking_line_ip_int = - first_footprint_inside_detection_ip + std::ceil(peeking_offset / ds); - } - - const auto occlusion_peeking_line_ip = static_cast( - std::clamp(occlusion_peeking_line_ip_int, 0, static_cast(path_ip.points.size()) - 1)); - const auto first_attention_stopline_ip = first_footprint_inside_detection_ip; - const bool first_attention_stopline_valid = true; - - // (4) pass judge line position on interpolated path - const double velocity = planner_data->current_velocity->twist.linear.x; - const double acceleration = planner_data->current_acceleration->accel.accel.linear.x; - const double braking_dist = planning_utils::calcJudgeLineDistWithJerkLimit( - velocity, acceleration, max_accel, max_jerk, delay_response_time); - int pass_judge_ip_int = - static_cast(first_footprint_inside_detection_ip) - std::ceil(braking_dist / ds); - const auto pass_judge_line_ip = static_cast( - std::clamp(pass_judge_ip_int, 0, static_cast(path_ip.points.size()) - 1)); - // TODO(Mamoru Sobue): maybe braking dist should be considered - const auto occlusion_wo_tl_pass_judge_line_ip = - static_cast(first_footprint_attention_centerline_ip); - - // (5) stuck vehicle stop line - int stuck_stopline_ip_int = 0; - bool stuck_stopline_valid = true; - if (use_stuck_stopline) { - // NOTE: when ego vehicle is approaching detection area and already passed - // first_conflicting_area, this could be null. - const auto stuck_stopline_idx_ip_opt = getFirstPointInsidePolygonByFootprint( - first_conflicting_area, interpolated_path_info, local_footprint, baselink2front); - if (!stuck_stopline_idx_ip_opt) { - stuck_stopline_valid = false; - stuck_stopline_ip_int = 0; - } else { - stuck_stopline_ip_int = stuck_stopline_idx_ip_opt.value() - stopline_margin_idx_dist; - } - } else { - stuck_stopline_ip_int = - std::get<0>(lane_interval_ip) - (stopline_margin_idx_dist + base2front_idx_dist); - } - if (stuck_stopline_ip_int < 0) { - stuck_stopline_valid = false; - } - const auto stuck_stopline_ip = static_cast(std::max(0, stuck_stopline_ip_int)); - - struct IntersectionStopLinesTemp - { - size_t closest_idx{0}; - size_t stuck_stopline{0}; - size_t default_stopline{0}; - size_t first_attention_stopline{0}; - size_t occlusion_peeking_stopline{0}; - size_t pass_judge_line{0}; - size_t occlusion_wo_tl_pass_judge_line{0}; - }; - - IntersectionStopLinesTemp intersection_stoplines_temp; - std::list> stoplines = { - {&closest_idx_ip, &intersection_stoplines_temp.closest_idx}, - {&stuck_stopline_ip, &intersection_stoplines_temp.stuck_stopline}, - {&default_stopline_ip, &intersection_stoplines_temp.default_stopline}, - {&first_attention_stopline_ip, &intersection_stoplines_temp.first_attention_stopline}, - {&occlusion_peeking_line_ip, &intersection_stoplines_temp.occlusion_peeking_stopline}, - {&pass_judge_line_ip, &intersection_stoplines_temp.pass_judge_line}, - {&occlusion_wo_tl_pass_judge_line_ip, - &intersection_stoplines_temp.occlusion_wo_tl_pass_judge_line}}; - stoplines.sort( - [](const auto & it1, const auto & it2) { return *(std::get<0>(it1)) < *(std::get<0>(it2)); }); - for (const auto & [stop_idx_ip, stop_idx] : stoplines) { - const auto & insert_point = path_ip.points.at(*stop_idx_ip).point.pose; - const auto insert_idx = insertPointIndex( - insert_point, original_path, planner_data->ego_nearest_dist_threshold, - planner_data->ego_nearest_yaw_threshold); - if (!insert_idx) { - return std::nullopt; - } - *stop_idx = insert_idx.value(); - } - if ( - intersection_stoplines_temp.occlusion_peeking_stopline < - intersection_stoplines_temp.default_stopline) { - intersection_stoplines_temp.occlusion_peeking_stopline = - intersection_stoplines_temp.default_stopline; - } - - IntersectionStopLines intersection_stoplines; - intersection_stoplines.closest_idx = intersection_stoplines_temp.closest_idx; - if (stuck_stopline_valid) { - intersection_stoplines.stuck_stopline = intersection_stoplines_temp.stuck_stopline; - } - if (default_stopline_valid) { - intersection_stoplines.default_stopline = intersection_stoplines_temp.default_stopline; - } - if (first_attention_stopline_valid) { - intersection_stoplines.first_attention_stopline = - intersection_stoplines_temp.first_attention_stopline; - } - if (occlusion_peeking_line_valid) { - intersection_stoplines.occlusion_peeking_stopline = - intersection_stoplines_temp.occlusion_peeking_stopline; - } - intersection_stoplines.pass_judge_line = intersection_stoplines_temp.pass_judge_line; - intersection_stoplines.occlusion_wo_tl_pass_judge_line = - intersection_stoplines_temp.occlusion_wo_tl_pass_judge_line; - return intersection_stoplines; -} - std::optional getFirstPointInsidePolygon( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const std::pair lane_interval, const lanelet::CompoundPolygon3d & polygon, @@ -490,105 +193,7 @@ std::optional getFirstPointInsidePolygon( return std::nullopt; } -static std::optional> -getFirstPointInsidePolygons( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const std::pair lane_interval, - const std::vector & polygons, const bool search_forward = true) -{ - if (search_forward) { - for (size_t i = lane_interval.first; i <= lane_interval.second; ++i) { - bool is_in_lanelet = false; - const auto & p = path.points.at(i).point.pose.position; - for (const auto & polygon : polygons) { - const auto polygon_2d = lanelet::utils::to2D(polygon); - is_in_lanelet = bg::within(to_bg2d(p), polygon_2d); - if (is_in_lanelet) { - return std::make_optional>( - i, polygon); - } - } - if (is_in_lanelet) { - break; - } - } - } else { - for (size_t i = lane_interval.second; i >= lane_interval.first; --i) { - bool is_in_lanelet = false; - const auto & p = path.points.at(i).point.pose.position; - for (const auto & polygon : polygons) { - const auto polygon_2d = lanelet::utils::to2D(polygon); - is_in_lanelet = bg::within(to_bg2d(p), polygon_2d); - if (is_in_lanelet) { - return std::make_optional>( - i, polygon); - } - } - if (is_in_lanelet) { - break; - } - if (i == 0) { - break; - } - } - } - return std::nullopt; -} - -std::optional generateStuckStopLine( - const lanelet::CompoundPolygon3d & conflicting_area, - const std::shared_ptr & planner_data, - const InterpolatedPathInfo & interpolated_path_info, const double stopline_margin, - const bool use_stuck_stopline, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path) -{ - const auto & path_ip = interpolated_path_info.path; - const double ds = interpolated_path_info.ds; - const auto & lane_interval_ip = interpolated_path_info.lane_id_interval.value(); - const auto lane_interval_ip_start = std::get<0>(lane_interval_ip); - size_t stuck_stopline_idx_ip = 0; - if (use_stuck_stopline) { - stuck_stopline_idx_ip = lane_interval_ip_start; - } else { - const auto stuck_stopline_idx_ip_opt = - getFirstPointInsidePolygon(path_ip, lane_interval_ip, conflicting_area); - if (!stuck_stopline_idx_ip_opt) { - return std::nullopt; - } - stuck_stopline_idx_ip = stuck_stopline_idx_ip_opt.value(); - } - - const int stopline_margin_idx_dist = std::ceil(stopline_margin / ds); - const int base2front_idx_dist = - std::ceil(planner_data->vehicle_info_.max_longitudinal_offset_m / ds); - const size_t insert_idx_ip = static_cast(std::max( - static_cast(stuck_stopline_idx_ip) - 1 - stopline_margin_idx_dist - base2front_idx_dist, - 0)); - const auto & insert_point = path_ip.points.at(insert_idx_ip).point.pose; - return insertPointIndex( - insert_point, original_path, planner_data->ego_nearest_dist_threshold, - planner_data->ego_nearest_yaw_threshold); -} - -static std::vector getPolygon3dFromLanelets( - const lanelet::ConstLanelets & ll_vec) -{ - std::vector polys; - for (auto && ll : ll_vec) { - polys.push_back(ll.polygon3d()); - } - return polys; -} - -static std::string getTurnDirection(lanelet::ConstLanelet lane) -{ - return lane.attributeOr("turn_direction", "else"); -} - -/** - * @param pair lanelets and the vector of original lanelets in topological order (not reversed as - *in generateDetectionLaneDivisions()) - **/ -static std::pair> +std::pair> mergeLaneletsByTopologicalSort( const lanelet::ConstLanelets & lanelets, const lanelet::routing::RoutingGraphPtr routing_graph_ptr) @@ -683,207 +288,9 @@ mergeLaneletsByTopologicalSort( return {merged, originals}; } -IntersectionLanelets getObjectiveLanelets( - lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr, - const lanelet::ConstLanelet assigned_lanelet, const lanelet::ConstLanelets & lanelets_on_path, - const std::set & associative_ids, const double detection_area_length, - const double occlusion_detection_area_length, const bool consider_wrong_direction_vehicle) -{ - const auto turn_direction = assigned_lanelet.attributeOr("turn_direction", "else"); - - // retrieve a stopline associated with a traffic light - bool has_traffic_light = false; - if (const auto tl_reg_elems = assigned_lanelet.regulatoryElementsAs(); - tl_reg_elems.size() != 0) { - const auto tl_reg_elem = tl_reg_elems.front(); - const auto stopline_opt = tl_reg_elem->stopLine(); - if (!!stopline_opt) has_traffic_light = true; - } - - // for low priority lane - // If ego_lane has right of way (i.e. is high priority), - // ignore yieldLanelets (i.e. low priority lanes) - lanelet::ConstLanelets yield_lanelets{}; - const auto right_of_ways = assigned_lanelet.regulatoryElementsAs(); - for (const auto & right_of_way : right_of_ways) { - if (lanelet::utils::contains(right_of_way->rightOfWayLanelets(), assigned_lanelet)) { - for (const auto & yield_lanelet : right_of_way->yieldLanelets()) { - yield_lanelets.push_back(yield_lanelet); - for (const auto & previous_lanelet : routing_graph_ptr->previous(yield_lanelet)) { - yield_lanelets.push_back(previous_lanelet); - } - } - } - } - - // get all following lanes of previous lane - lanelet::ConstLanelets ego_lanelets = lanelets_on_path; - for (const auto & previous_lanelet : routing_graph_ptr->previous(assigned_lanelet)) { - ego_lanelets.push_back(previous_lanelet); - for (const auto & following_lanelet : routing_graph_ptr->following(previous_lanelet)) { - if (lanelet::utils::contains(ego_lanelets, following_lanelet)) { - continue; - } - ego_lanelets.push_back(following_lanelet); - } - } - - // get conflicting lanes on assigned lanelet - const auto & conflicting_lanelets = - lanelet::utils::getConflictingLanelets(routing_graph_ptr, assigned_lanelet); - std::vector adjacent_followings; - - for (const auto & conflicting_lanelet : conflicting_lanelets) { - for (const auto & following_lanelet : routing_graph_ptr->following(conflicting_lanelet)) { - adjacent_followings.push_back(following_lanelet); - } - for (const auto & following_lanelet : routing_graph_ptr->previous(conflicting_lanelet)) { - adjacent_followings.push_back(following_lanelet); - } - } - - // final objective lanelets - lanelet::ConstLanelets detection_lanelets; - lanelet::ConstLanelets conflicting_ex_ego_lanelets; - // conflicting lanes is necessary to get stopline for stuck vehicle - for (auto && conflicting_lanelet : conflicting_lanelets) { - if (!lanelet::utils::contains(ego_lanelets, conflicting_lanelet)) - conflicting_ex_ego_lanelets.push_back(conflicting_lanelet); - } - - // exclude yield lanelets and ego lanelets from detection_lanelets - if (turn_direction == std::string("straight") && has_traffic_light) { - // if assigned lanelet is "straight" with traffic light, detection area is not necessary - } else { - if (consider_wrong_direction_vehicle) { - for (const auto & conflicting_lanelet : conflicting_lanelets) { - if (lanelet::utils::contains(yield_lanelets, conflicting_lanelet)) { - continue; - } - detection_lanelets.push_back(conflicting_lanelet); - } - for (const auto & adjacent_following : adjacent_followings) { - detection_lanelets.push_back(adjacent_following); - } - } else { - // otherwise we need to know the priority from RightOfWay - for (const auto & conflicting_lanelet : conflicting_lanelets) { - if ( - lanelet::utils::contains(yield_lanelets, conflicting_lanelet) || - lanelet::utils::contains(ego_lanelets, conflicting_lanelet)) { - continue; - } - detection_lanelets.push_back(conflicting_lanelet); - } - } - } - - // get possible lanelet path that reaches conflicting_lane longer than given length - lanelet::ConstLanelets detection_and_preceding_lanelets; - { - const double length = detection_area_length; - std::set detection_ids; - for (const auto & ll : detection_lanelets) { - // Preceding lanes does not include detection_lane so add them at the end - const auto & inserted = detection_ids.insert(ll.id()); - if (inserted.second) detection_and_preceding_lanelets.push_back(ll); - // get preceding lanelets without ego_lanelets - // to prevent the detection area from including the ego lanes and its' preceding lanes. - const auto lanelet_sequences = lanelet::utils::query::getPrecedingLaneletSequences( - routing_graph_ptr, ll, length, ego_lanelets); - for (const auto & ls : lanelet_sequences) { - for (const auto & l : ls) { - const auto & inserted = detection_ids.insert(l.id()); - if (inserted.second) detection_and_preceding_lanelets.push_back(l); - } - } - } - } - - lanelet::ConstLanelets occlusion_detection_and_preceding_lanelets; - { - const double length = occlusion_detection_area_length; - std::set detection_ids; - for (const auto & ll : detection_lanelets) { - // Preceding lanes does not include detection_lane so add them at the end - const auto & inserted = detection_ids.insert(ll.id()); - if (inserted.second) occlusion_detection_and_preceding_lanelets.push_back(ll); - // get preceding lanelets without ego_lanelets - // to prevent the detection area from including the ego lanes and its' preceding lanes. - const auto lanelet_sequences = lanelet::utils::query::getPrecedingLaneletSequences( - routing_graph_ptr, ll, length, ego_lanelets); - for (const auto & ls : lanelet_sequences) { - for (const auto & l : ls) { - const auto & inserted = detection_ids.insert(l.id()); - if (inserted.second) occlusion_detection_and_preceding_lanelets.push_back(l); - } - } - } - } - lanelet::ConstLanelets occlusion_detection_and_preceding_lanelets_wo_turn_direction; - for (const auto & ll : occlusion_detection_and_preceding_lanelets) { - const auto turn_direction = getTurnDirection(ll); - if (turn_direction == "left" || turn_direction == "right") { - continue; - } - occlusion_detection_and_preceding_lanelets_wo_turn_direction.push_back(ll); - } - - auto [attention_lanelets, original_attention_lanelet_sequences] = - mergeLaneletsByTopologicalSort(detection_and_preceding_lanelets, routing_graph_ptr); - - IntersectionLanelets result; - result.attention_ = std::move(attention_lanelets); - for (const auto & original_attention_lanelet_seq : original_attention_lanelet_sequences) { - // NOTE: in mergeLaneletsByTopologicalSort(), sub_ids are empty checked, so it is ensured that - // back() exists. - std::optional stopline{std::nullopt}; - for (auto it = original_attention_lanelet_seq.rbegin(); - it != original_attention_lanelet_seq.rend(); ++it) { - const auto traffic_lights = it->regulatoryElementsAs(); - for (const auto & traffic_light : traffic_lights) { - const auto stopline_opt = traffic_light->stopLine(); - if (!stopline_opt) continue; - stopline = stopline_opt.get(); - break; - } - if (stopline) break; - } - result.attention_stoplines_.push_back(stopline); - } - result.attention_non_preceding_ = std::move(detection_lanelets); - for (unsigned i = 0; i < result.attention_non_preceding_.size(); ++i) { - std::optional stopline = std::nullopt; - const auto & ll = result.attention_non_preceding_.at(i); - const auto traffic_lights = ll.regulatoryElementsAs(); - for (const auto & traffic_light : traffic_lights) { - const auto stopline_opt = traffic_light->stopLine(); - if (!stopline_opt) continue; - stopline = stopline_opt.get(); - } - result.attention_non_preceding_stoplines_.push_back(stopline); - } - result.conflicting_ = std::move(conflicting_ex_ego_lanelets); - result.adjacent_ = planning_utils::getConstLaneletsFromIds(lanelet_map_ptr, associative_ids); - // NOTE: occlusion_attention is not inverted here - // TODO(Mamoru Sobue): apply mergeLaneletsByTopologicalSort for occlusion lanelets as well and - // then trim part of them based on curvature threshold - result.occlusion_attention_ = - std::move(occlusion_detection_and_preceding_lanelets_wo_turn_direction); - - // NOTE: to properly update(), each element in conflicting_/conflicting_area_, - // attention_non_preceding_/attention_non_preceding_area_ need to be matched - result.attention_area_ = getPolygon3dFromLanelets(result.attention_); - result.attention_non_preceding_area_ = getPolygon3dFromLanelets(result.attention_non_preceding_); - result.conflicting_area_ = getPolygon3dFromLanelets(result.conflicting_); - result.adjacent_area_ = getPolygon3dFromLanelets(result.adjacent_); - result.occlusion_attention_area_ = getPolygon3dFromLanelets(result.occlusion_attention_); - return result; -} - bool isOverTargetIndex( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int closest_idx, - const geometry_msgs::msg::Pose & current_pose, const int target_idx) + const autoware_auto_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; @@ -893,8 +300,8 @@ bool isOverTargetIndex( } bool isBeforeTargetIndex( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int closest_idx, - const geometry_msgs::msg::Pose & current_pose, const int target_idx) + const autoware_auto_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; @@ -903,81 +310,13 @@ bool isBeforeTargetIndex( return static_cast(target_idx > closest_idx); } -/* -static std::vector getAllAdjacentLanelets( - const lanelet::routing::RoutingGraphPtr routing_graph, lanelet::ConstLanelet lane) -{ - std::set results; - - results.insert(lane.id()); - - auto it = routing_graph->adjacentRight(lane); - // take all lane on the right side - while (!!it) { - results.insert(it.get().id()); - it = routing_graph->adjacentRight(it.get()); - } - // take all lane on the left side - it = routing_graph->adjacentLeft(lane); - while (!!it) { - results.insert(it.get().id()); - it = routing_graph->adjacentLeft(it.get()); - - } - return std::vector(results.begin(), results.end()); -} -*/ - -/* -lanelet::ConstLanelets extendedAdjacentDirectionLanes( - lanelet::LaneletMapConstPtr map, const lanelet::routing::RoutingGraphPtr routing_graph, - lanelet::ConstLanelet lane) -{ - // some of the intersections are not well-formed, and "adjacent" turning - // lanelets are not sharing the LineStrings - const std::string turn_direction = getTurnDirection(lane); - if (turn_direction != "left" && turn_direction != "right" && turn_direction != "straight") - return {}; - - std::set previous_lanelet_ids; - for (auto && previous_lanelet : routing_graph->previous(lane)) { - previous_lanelet_ids.insert(previous_lanelet.id()); - } - - std::set besides_previous_lanelet_ids; - for (auto && previous_lanelet_id : previous_lanelet_ids) { - lanelet::ConstLanelet previous_lanelet = map->laneletLayer.get(previous_lanelet_id); - for (auto && beside_lanelet : getAllAdjacentLanelets(routing_graph, previous_lanelet)) { - besides_previous_lanelet_ids.insert(beside_lanelet); - } - } - - std::set following_turning_lanelets; - following_turning_lanelets.insert(lane.id()); - for (auto && besides_previous_lanelet_id : besides_previous_lanelet_ids) { - lanelet::ConstLanelet besides_previous_lanelet = - map->laneletLayer.get(besides_previous_lanelet_id); - for (auto && following_lanelet : routing_graph->following(besides_previous_lanelet)) { - // if this has {"turn_direction", "${turn_direction}"}, take this - if (getTurnDirection(following_lanelet) == turn_direction) - following_turning_lanelets.insert(following_lanelet.id()); - } - } - lanelet::ConstLanelets ret{}; - for (auto && id : following_turning_lanelets) { - ret.push_back(map->laneletLayer.get(id)); - } - return ret; -} -*/ - -std::optional getIntersectionArea( +std::optional getIntersectionArea( lanelet::ConstLanelet assigned_lane, lanelet::LaneletMapConstPtr lanelet_map_ptr) { const std::string area_id_str = assigned_lane.attributeOr("intersection_area", "else"); if (area_id_str == "else") return std::nullopt; - const int area_id = std::atoi(area_id_str.c_str()); + const lanelet::Id area_id = std::atoi(area_id_str.c_str()); const auto poly_3d = lanelet_map_ptr->polygonLayer.get(area_id); Polygon2d poly{}; for (const auto & p : poly_3d) poly.outer().emplace_back(p.x(), p.y()); @@ -994,111 +333,6 @@ bool hasAssociatedTrafficLight(lanelet::ConstLanelet lane) return tl_id.has_value(); } -TrafficPrioritizedLevel getTrafficPrioritizedLevel( - lanelet::ConstLanelet lane, const std::map & tl_infos) -{ - using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement; - - std::optional tl_id = std::nullopt; - for (auto && tl_reg_elem : lane.regulatoryElementsAs()) { - tl_id = tl_reg_elem->id(); - break; - } - if (!tl_id) { - // this lane has no traffic light - return TrafficPrioritizedLevel::NOT_PRIORITIZED; - } - const auto tl_info_it = tl_infos.find(tl_id.value()); - if (tl_info_it == tl_infos.end()) { - // the info of this traffic light is not available - return TrafficPrioritizedLevel::NOT_PRIORITIZED; - } - const auto & tl_info = tl_info_it->second; - bool has_amber_signal{false}; - for (auto && tl_light : tl_info.signal.elements) { - if (tl_light.color == TrafficSignalElement::AMBER) { - has_amber_signal = true; - } - if (tl_light.color == TrafficSignalElement::RED) { - // NOTE: Return here since the red signal has the highest priority. - return TrafficPrioritizedLevel::FULLY_PRIORITIZED; - } - } - if (has_amber_signal) { - return TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED; - } - return TrafficPrioritizedLevel::NOT_PRIORITIZED; -} - -double getHighestCurvature(const lanelet::ConstLineString3d & centerline) -{ - std::vector points; - for (auto point = centerline.begin(); point != centerline.end(); point++) { - points.push_back(*point); - } - - SplineInterpolationPoints2d interpolation(points); - const std::vector curvatures = interpolation.getSplineInterpolatedCurvatures(); - std::vector curvatures_positive; - for (const auto & curvature : curvatures) { - curvatures_positive.push_back(std::fabs(curvature)); - } - return *std::max_element(curvatures_positive.begin(), curvatures_positive.end()); -} - -std::vector generateDetectionLaneDivisions( - lanelet::ConstLanelets detection_lanelets_all, - const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution, - const double curvature_threshold, const double curvature_calculation_ds) -{ - using lanelet::utils::getCenterlineWithOffset; - - // (0) remove left/right lanelet - lanelet::ConstLanelets detection_lanelets; - for (const auto & detection_lanelet : detection_lanelets_all) { - // TODO(Mamoru Sobue): instead of ignoring, only trim straight part of lanelet - const auto fine_centerline = - lanelet::utils::generateFineCenterline(detection_lanelet, curvature_calculation_ds); - const double highest_curvature = getHighestCurvature(fine_centerline); - if (highest_curvature > curvature_threshold) { - continue; - } - detection_lanelets.push_back(detection_lanelet); - } - - // (1) tsort detection_lanelets - const auto [merged_detection_lanelets, originals] = - mergeLaneletsByTopologicalSort(detection_lanelets, routing_graph_ptr); - - // (2) merge each branch to one lanelet - // NOTE: somehow bg::area() for merged lanelet does not work, so calculate it here - std::vector> merged_lanelet_with_area; - for (unsigned i = 0; i < merged_detection_lanelets.size(); ++i) { - const auto & merged_detection_lanelet = merged_detection_lanelets.at(i); - const auto & original = originals.at(i); - double area = 0; - for (const auto & partition : original) { - area += bg::area(partition.polygon2d().basicPolygon()); - } - merged_lanelet_with_area.emplace_back(merged_detection_lanelet, area); - } - - // (3) discretize each merged lanelet - std::vector detection_divisions; - for (const auto & [merged_lanelet, area] : merged_lanelet_with_area) { - const double length = bg::length(merged_lanelet.centerline()); - const double width = area / length; - for (int i = 0; i < static_cast(width / resolution); ++i) { - const double offset = resolution * i - width / 2; - detection_divisions.push_back( - getCenterlineWithOffset(merged_lanelet, offset, resolution).invert()); - } - detection_divisions.push_back( - getCenterlineWithOffset(merged_lanelet, width / 2, resolution).invert()); - } - return detection_divisions; -} - std::optional generateInterpolatedPath( const lanelet::Id lane_id, const std::set & associative_lane_ids, const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path, const double ds, @@ -1116,7 +350,6 @@ std::optional generateInterpolatedPath( return interpolated_path_info; } -// from here geometry_msgs::msg::Pose getObjectPoseWithVelocityDirection( const autoware_auto_perception_msgs::msg::PredictedObjectKinematics & obj_state) { @@ -1134,609 +367,5 @@ geometry_msgs::msg::Pose getObjectPoseWithVelocityDirection( return obj_pose; } -static bool isTargetStuckVehicleType( - const autoware_auto_perception_msgs::msg::PredictedObject & object) -{ - if ( - object.classification.at(0).label == - autoware_auto_perception_msgs::msg::ObjectClassification::CAR || - object.classification.at(0).label == - autoware_auto_perception_msgs::msg::ObjectClassification::BUS || - object.classification.at(0).label == - autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK || - object.classification.at(0).label == - autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER || - object.classification.at(0).label == - autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE) { - return true; - } - return false; -} - -bool checkStuckVehicleInIntersection( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr, - const Polygon2d & stuck_vehicle_detect_area, const double stuck_vehicle_vel_thr, - DebugData * debug_data) -{ - for (const auto & object : objects_ptr->objects) { - if (!isTargetStuckVehicleType(object)) { - continue; // not target vehicle type - } - const auto obj_v_norm = std::hypot( - object.kinematics.initial_twist_with_covariance.twist.linear.x, - object.kinematics.initial_twist_with_covariance.twist.linear.y); - if (obj_v_norm > stuck_vehicle_vel_thr) { - continue; // not stop vehicle - } - - // check if the footprint is in the stuck detect area - const auto obj_footprint = tier4_autoware_utils::toPolygon2d(object); - const bool is_in_stuck_area = !bg::disjoint(obj_footprint, stuck_vehicle_detect_area); - if (is_in_stuck_area && debug_data) { - debug_data->stuck_targets.objects.push_back(object); - return true; - } - } - return false; -} - -static lanelet::LineString3d getLineStringFromArcLength( - const lanelet::ConstLineString3d & linestring, const double s1, const double s2) -{ - lanelet::Points3d points; - double accumulated_length = 0; - size_t start_index = linestring.size(); - for (size_t i = 0; i < linestring.size() - 1; i++) { - const auto & p1 = linestring[i]; - const auto & p2 = linestring[i + 1]; - const double length = boost::geometry::distance(p1.basicPoint(), p2.basicPoint()); - if (accumulated_length + length > s1) { - start_index = i; - break; - } - accumulated_length += length; - } - if (start_index < linestring.size() - 1) { - const auto & p1 = linestring[start_index]; - const auto & p2 = linestring[start_index + 1]; - const double residue = s1 - accumulated_length; - const auto direction_vector = (p2.basicPoint() - p1.basicPoint()).normalized(); - const auto start_basic_point = p1.basicPoint() + residue * direction_vector; - const auto start_point = lanelet::Point3d(lanelet::InvalId, start_basic_point); - points.push_back(start_point); - } - - accumulated_length = 0; - size_t end_index = linestring.size(); - for (size_t i = 0; i < linestring.size() - 1; i++) { - const auto & p1 = linestring[i]; - const auto & p2 = linestring[i + 1]; - const double length = boost::geometry::distance(p1.basicPoint(), p2.basicPoint()); - if (accumulated_length + length > s2) { - end_index = i; - break; - } - accumulated_length += length; - } - - for (size_t i = start_index + 1; i < end_index; i++) { - const auto p = lanelet::Point3d(linestring[i]); - points.push_back(p); - } - if (end_index < linestring.size() - 1) { - const auto & p1 = linestring[end_index]; - const auto & p2 = linestring[end_index + 1]; - const double residue = s2 - accumulated_length; - const auto direction_vector = (p2.basicPoint() - p1.basicPoint()).normalized(); - const auto end_basic_point = p1.basicPoint() + residue * direction_vector; - const auto end_point = lanelet::Point3d(lanelet::InvalId, end_basic_point); - points.push_back(end_point); - } - return lanelet::LineString3d{lanelet::InvalId, points}; -} - -static lanelet::ConstLanelet createLaneletFromArcLength( - const lanelet::ConstLanelet & lanelet, const double s1, const double s2) -{ - const double total_length = boost::geometry::length(lanelet.centerline2d().basicLineString()); - // make sure that s1, and s2 are between [0, lane_length] - const auto s1_saturated = std::max(0.0, std::min(s1, total_length)); - const auto s2_saturated = std::max(0.0, std::min(s2, total_length)); - - const auto ratio_s1 = s1_saturated / total_length; - const auto ratio_s2 = s2_saturated / total_length; - - const auto s1_left = - static_cast(ratio_s1 * boost::geometry::length(lanelet.leftBound().basicLineString())); - const auto s2_left = - static_cast(ratio_s2 * boost::geometry::length(lanelet.leftBound().basicLineString())); - const auto s1_right = - static_cast(ratio_s1 * boost::geometry::length(lanelet.rightBound().basicLineString())); - const auto s2_right = - static_cast(ratio_s2 * boost::geometry::length(lanelet.rightBound().basicLineString())); - - const auto left_bound = getLineStringFromArcLength(lanelet.leftBound(), s1_left, s2_left); - const auto right_bound = getLineStringFromArcLength(lanelet.rightBound(), s1_right, s2_right); - - return lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); -} - -bool checkYieldStuckVehicleInIntersection( - const util::TargetObjects & target_objects, - const util::InterpolatedPathInfo & interpolated_path_info, - const lanelet::ConstLanelets & attention_lanelets, const std::string & turn_direction, - const double width, const double stuck_vehicle_vel_thr, const double yield_stuck_distance_thr, - DebugData * debug_data) -{ - LineString2d sparse_intersection_path; - const auto [start, end] = interpolated_path_info.lane_id_interval.value(); - for (unsigned i = start; i < end; ++i) { - const auto & point = interpolated_path_info.path.points.at(i).point.pose.position; - const auto yaw = tf2::getYaw(interpolated_path_info.path.points.at(i).point.pose.orientation); - if (turn_direction == "right") { - const double right_x = point.x - width / 2 * std::sin(yaw); - const double right_y = point.y + width / 2 * std::cos(yaw); - sparse_intersection_path.emplace_back(right_x, right_y); - } else if (turn_direction == "left") { - const double left_x = point.x + width / 2 * std::sin(yaw); - const double left_y = point.y - width / 2 * std::cos(yaw); - sparse_intersection_path.emplace_back(left_x, left_y); - } else { - // straight - sparse_intersection_path.emplace_back(point.x, point.y); - } - } - lanelet::ConstLanelets yield_stuck_detect_lanelets; - for (const auto & attention_lanelet : attention_lanelets) { - const auto centerline = attention_lanelet.centerline2d().basicLineString(); - std::vector intersects; - bg::intersection(sparse_intersection_path, centerline, intersects); - if (intersects.empty()) { - continue; - } - const auto intersect = intersects.front(); - const auto intersect_arc_coords = lanelet::geometry::toArcCoordinates( - centerline, lanelet::BasicPoint2d(intersect.x(), intersect.y())); - const double yield_stuck_start = - std::max(0.0, intersect_arc_coords.length - yield_stuck_distance_thr); - const double yield_stuck_end = intersect_arc_coords.length; - yield_stuck_detect_lanelets.push_back( - createLaneletFromArcLength(attention_lanelet, yield_stuck_start, yield_stuck_end)); - } - debug_data->yield_stuck_detect_area = getPolygon3dFromLanelets(yield_stuck_detect_lanelets); - for (const auto & object : target_objects.all_attention_objects) { - const auto obj_v_norm = std::hypot( - object.object.kinematics.initial_twist_with_covariance.twist.linear.x, - object.object.kinematics.initial_twist_with_covariance.twist.linear.y); - - if (obj_v_norm > stuck_vehicle_vel_thr) { - continue; - } - for (const auto & yield_stuck_detect_lanelet : yield_stuck_detect_lanelets) { - const bool is_in_lanelet = lanelet::utils::isInLanelet( - object.object.kinematics.initial_pose_with_covariance.pose, yield_stuck_detect_lanelet); - if (is_in_lanelet) { - debug_data->yield_stuck_targets.objects.push_back(object.object); - return true; - } - } - } - return false; -} - -Polygon2d generateStuckVehicleDetectAreaPolygon( - const util::PathLanelets & path_lanelets, const double stuck_vehicle_detect_dist) -{ - using lanelet::utils::getArcCoordinates; - using lanelet::utils::getLaneletLength3d; - using lanelet::utils::getPolygonFromArcLength; - using lanelet::utils::to2D; - - Polygon2d polygon{}; - if (path_lanelets.conflicting_interval_and_remaining.size() == 0) { - return polygon; - } - - double target_polygon_length = - getLaneletLength3d(path_lanelets.conflicting_interval_and_remaining); - lanelet::ConstLanelets targets = path_lanelets.conflicting_interval_and_remaining; - if (path_lanelets.next) { - targets.push_back(path_lanelets.next.value()); - const double next_arc_length = - std::min(stuck_vehicle_detect_dist, getLaneletLength3d(path_lanelets.next.value())); - target_polygon_length += next_arc_length; - } - const auto target_polygon = - to2D(getPolygonFromArcLength(targets, 0, target_polygon_length)).basicPolygon(); - - if (target_polygon.empty()) { - return polygon; - } - - for (const auto & p : target_polygon) { - polygon.outer().emplace_back(p.x(), p.y()); - } - - polygon.outer().emplace_back(polygon.outer().front()); - bg::correct(polygon); - - return polygon; -} - -std::optional checkAngleForTargetLanelets( - const geometry_msgs::msg::Pose & pose, const lanelet::ConstLanelets & target_lanelets, - const double detection_area_angle_thr, const bool consider_wrong_direction_vehicle, - const double dist_margin, const bool is_parked_vehicle) -{ - for (unsigned i = 0; i < target_lanelets.size(); ++i) { - const auto & ll = target_lanelets.at(i); - if (!lanelet::utils::isInLanelet(pose, ll, dist_margin)) { - continue; - } - const double ll_angle = lanelet::utils::getLaneletAngle(ll, pose.position); - const double pose_angle = tf2::getYaw(pose.orientation); - const double angle_diff = tier4_autoware_utils::normalizeRadian(ll_angle - pose_angle, -M_PI); - if (consider_wrong_direction_vehicle) { - if (std::fabs(angle_diff) > 1.57 || std::fabs(angle_diff) < detection_area_angle_thr) { - return std::make_optional(i); - } - } else { - if (std::fabs(angle_diff) < detection_area_angle_thr) { - return std::make_optional(i); - } - // NOTE: sometimes parked vehicle direction is reversed even if its longitudinal velocity is - // positive - if ( - is_parked_vehicle && (std::fabs(angle_diff) < detection_area_angle_thr || - (std::fabs(angle_diff + M_PI) < detection_area_angle_thr))) { - return std::make_optional(i); - } - } - } - return std::nullopt; -} - -void cutPredictPathWithDuration( - util::TargetObjects * target_objects, const rclcpp::Clock::SharedPtr clock, const double time_thr) -{ - const rclcpp::Time current_time = clock->now(); - for (auto & target_object : target_objects->all_attention_objects) { // each objects - for (auto & predicted_path : - target_object.object.kinematics.predicted_paths) { // each predicted paths - const auto origin_path = predicted_path; - predicted_path.path.clear(); - - for (size_t k = 0; k < origin_path.path.size(); ++k) { // each path points - const auto & predicted_pose = origin_path.path.at(k); - const auto predicted_time = - rclcpp::Time(target_objects->header.stamp) + - rclcpp::Duration(origin_path.time_step) * static_cast(k); - if ((predicted_time - current_time).seconds() < time_thr) { - predicted_path.path.push_back(predicted_pose); - } - } - } - } -} - -TimeDistanceArray calcIntersectionPassingTime( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const std::shared_ptr & planner_data, const lanelet::Id lane_id, - const std::set & associative_ids, const size_t closest_idx, - const size_t last_intersection_stopline_candidate_idx, const double time_delay, - const double intersection_velocity, const double minimum_ego_velocity, - const bool use_upstream_velocity, const double minimum_upstream_velocity, - tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array) -{ - const double current_velocity = planner_data->current_velocity->twist.linear.x; - - int assigned_lane_found = false; - - // crop intersection part of the path, and set the reference velocity to intersection_velocity - // for ego's ttc - PathWithLaneId reference_path; - std::optional upstream_stopline{std::nullopt}; - for (size_t i = 0; i < path.points.size() - 1; ++i) { - auto reference_point = path.points.at(i); - // assume backward velocity is current ego velocity - if (i < closest_idx) { - reference_point.point.longitudinal_velocity_mps = current_velocity; - } - if ( - i > last_intersection_stopline_candidate_idx && - std::fabs(reference_point.point.longitudinal_velocity_mps) < - std::numeric_limits::epsilon() && - !upstream_stopline) { - upstream_stopline = i; - } - if (!use_upstream_velocity) { - reference_point.point.longitudinal_velocity_mps = intersection_velocity; - } - reference_path.points.push_back(reference_point); - bool has_objective_lane_id = hasLaneIds(path.points.at(i), associative_ids); - if (assigned_lane_found && !has_objective_lane_id) { - break; - } - assigned_lane_found = has_objective_lane_id; - } - if (!assigned_lane_found) { - return {{0.0, 0.0}}; // has already passed the intersection. - } - - std::vector> original_path_xy; - for (size_t i = 0; i < reference_path.points.size(); ++i) { - const auto & p = reference_path.points.at(i).point.pose.position; - original_path_xy.emplace_back(p.x, p.y); - } - - // apply smoother to reference velocity - PathWithLaneId smoothed_reference_path = reference_path; - if (!smoothPath(reference_path, smoothed_reference_path, planner_data)) { - smoothed_reference_path = reference_path; - } - - // calculate when ego is going to reach each (interpolated) points on the path - TimeDistanceArray time_distance_array{}; - double dist_sum = 0.0; - double passing_time = time_delay; - time_distance_array.emplace_back(passing_time, dist_sum); - - // NOTE: `reference_path` is resampled in `reference_smoothed_path`, so - // `last_intersection_stopline_candidate_idx` makes no sense - const auto smoothed_path_closest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints( - smoothed_reference_path.points, path.points.at(closest_idx).point.pose, - planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); - - const std::optional upstream_stopline_idx_opt = [&]() -> std::optional { - if (upstream_stopline) { - const auto upstream_stopline_point = path.points.at(upstream_stopline.value()).point.pose; - return motion_utils::findFirstNearestIndexWithSoftConstraints( - smoothed_reference_path.points, upstream_stopline_point, - planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); - } else { - return std::nullopt; - } - }(); - const bool has_upstream_stopline = upstream_stopline_idx_opt.has_value(); - const size_t upstream_stopline_ind = upstream_stopline_idx_opt.value_or(0); - - for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size() - 1; ++i) { - const auto & p1 = smoothed_reference_path.points.at(i); - const auto & p2 = smoothed_reference_path.points.at(i + 1); - - const double dist = tier4_autoware_utils::calcDistance2d(p1, p2); - dist_sum += dist; - - // use average velocity between p1 and p2 - const double average_velocity = - (p1.point.longitudinal_velocity_mps + p2.point.longitudinal_velocity_mps) / 2.0; - const double passing_velocity = [=]() { - if (use_upstream_velocity) { - if (has_upstream_stopline && i > upstream_stopline_ind) { - return minimum_upstream_velocity; - } - return std::max(average_velocity, minimum_ego_velocity); - } else { - return std::max(average_velocity, minimum_ego_velocity); - } - }(); - passing_time += (dist / passing_velocity); - - time_distance_array.emplace_back(passing_time, dist_sum); - } - debug_ttc_array->layout.dim.resize(3); - debug_ttc_array->layout.dim.at(0).label = "lane_id_@[0][0], ttc_time, ttc_dist, path_x, path_y"; - debug_ttc_array->layout.dim.at(0).size = 5; - debug_ttc_array->layout.dim.at(1).label = "values"; - debug_ttc_array->layout.dim.at(1).size = time_distance_array.size(); - debug_ttc_array->data.reserve( - time_distance_array.size() * debug_ttc_array->layout.dim.at(0).size); - for (unsigned i = 0; i < time_distance_array.size(); ++i) { - debug_ttc_array->data.push_back(lane_id); - } - for (const auto & [t, d] : time_distance_array) { - debug_ttc_array->data.push_back(t); - } - for (const auto & [t, d] : time_distance_array) { - debug_ttc_array->data.push_back(d); - } - for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size(); ++i) { - const auto & p = smoothed_reference_path.points.at(i).point.pose.position; - debug_ttc_array->data.push_back(p.x); - } - for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size(); ++i) { - const auto & p = smoothed_reference_path.points.at(i).point.pose.position; - debug_ttc_array->data.push_back(p.y); - } - return time_distance_array; -} - -double calcDistanceUntilIntersectionLanelet( - const lanelet::ConstLanelet & assigned_lanelet, - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx) -{ - const auto lane_id = assigned_lanelet.id(); - const auto intersection_first_itr = - std::find_if(path.points.cbegin(), path.points.cend(), [&](const auto & p) { - return std::find(p.lane_ids.begin(), p.lane_ids.end(), lane_id) != p.lane_ids.end(); - }); - if ( - intersection_first_itr == path.points.begin() || intersection_first_itr == path.points.end()) { - return 0.0; - } - const auto dst_idx = std::distance(path.points.begin(), intersection_first_itr) - 1; - - if (closest_idx > static_cast(dst_idx)) { - return 0.0; - } - - double distance = std::abs(motion_utils::calcSignedArcLength(path.points, closest_idx, dst_idx)); - const auto & lane_first_point = assigned_lanelet.centerline2d().front(); - distance += std::hypot( - path.points.at(dst_idx).point.pose.position.x - lane_first_point.x(), - path.points.at(dst_idx).point.pose.position.y - lane_first_point.y()); - return distance; -} - -void IntersectionLanelets::update( - const bool is_prioritized, const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) -{ - is_prioritized_ = is_prioritized; - // find the first conflicting/detection area polygon intersecting the path - if (!first_conflicting_area_) { - auto first = getFirstPointInsidePolygonsByFootprint( - conflicting_area_, interpolated_path_info, footprint, vehicle_length); - if (first) { - first_conflicting_lane_ = conflicting_.at(first.value().second); - first_conflicting_area_ = conflicting_area_.at(first.value().second); - } - } - if (!first_attention_area_) { - auto first = getFirstPointInsidePolygonsByFootprint( - attention_non_preceding_area_, interpolated_path_info, footprint, vehicle_length); - if (first) { - first_attention_lane_ = attention_non_preceding_.at(first.value().second); - first_attention_area_ = attention_non_preceding_area_.at(first.value().second); - } - } -} - -static lanelet::ConstLanelets getPrevLanelets( - const lanelet::ConstLanelets & lanelets_on_path, const std::set & associative_ids) -{ - lanelet::ConstLanelets previous_lanelets; - for (const auto & ll : lanelets_on_path) { - if (associative_ids.find(ll.id()) != associative_ids.end()) { - return previous_lanelets; - } - previous_lanelets.push_back(ll); - } - return previous_lanelets; -} - -// end inclusive -lanelet::ConstLanelet generatePathLanelet( - const PathWithLaneId & path, const size_t start_idx, const size_t end_idx, const double width, - const double interval) -{ - lanelet::Points3d lefts; - lanelet::Points3d rights; - size_t prev_idx = start_idx; - for (size_t i = start_idx; i <= end_idx; ++i) { - const auto & p = path.points.at(i).point.pose; - const auto & p_prev = path.points.at(prev_idx).point.pose; - if (i != start_idx && tier4_autoware_utils::calcDistance2d(p_prev, p) < interval) { - continue; - } - prev_idx = i; - const double yaw = tf2::getYaw(p.orientation); - const double x = p.position.x; - const double y = p.position.y; - // NOTE: maybe this is opposite - const double left_x = x + width / 2 * std::sin(yaw); - const double left_y = y - width / 2 * std::cos(yaw); - const double right_x = x - width / 2 * std::sin(yaw); - const double right_y = y + width / 2 * std::cos(yaw); - lefts.emplace_back(lanelet::InvalId, left_x, left_y, p.position.z); - rights.emplace_back(lanelet::InvalId, right_x, right_y, p.position.z); - } - lanelet::LineString3d left = lanelet::LineString3d(lanelet::InvalId, lefts); - lanelet::LineString3d right = lanelet::LineString3d(lanelet::InvalId, rights); - - return lanelet::Lanelet(lanelet::InvalId, left, right); -} - -std::optional generatePathLanelets( - const lanelet::ConstLanelets & lanelets_on_path, - const util::InterpolatedPathInfo & interpolated_path_info, - const std::set & associative_ids, - const lanelet::CompoundPolygon3d & first_conflicting_area, - const std::vector & conflicting_areas, - const std::optional & first_attention_area, - const std::vector & attention_areas, const size_t closest_idx, - const double width) -{ - static constexpr double path_lanelet_interval = 1.5; - - const auto & assigned_lane_interval_opt = interpolated_path_info.lane_id_interval; - if (!assigned_lane_interval_opt) { - return std::nullopt; - } - const auto assigned_lane_interval = assigned_lane_interval_opt.value(); - const auto & path = interpolated_path_info.path; - - PathLanelets path_lanelets; - // prev - path_lanelets.prev = getPrevLanelets(lanelets_on_path, associative_ids); - path_lanelets.all = path_lanelets.prev; - - // entry2ego if exist - const auto [assigned_lane_start, assigned_lane_end] = assigned_lane_interval; - if (closest_idx > assigned_lane_start) { - path_lanelets.all.push_back( - generatePathLanelet(path, assigned_lane_start, closest_idx, width, path_lanelet_interval)); - } - - // ego_or_entry2exit - const auto ego_or_entry_start = std::max(closest_idx, assigned_lane_start); - path_lanelets.ego_or_entry2exit = - generatePathLanelet(path, ego_or_entry_start, assigned_lane_end, width, path_lanelet_interval); - path_lanelets.all.push_back(path_lanelets.ego_or_entry2exit); - - // next - if (assigned_lane_end < path.points.size() - 1) { - const int next_id = path.points.at(assigned_lane_end).lane_ids.at(0); - const auto next_lane_interval_opt = findLaneIdsInterval(path, {next_id}); - if (next_lane_interval_opt) { - const auto [next_start, next_end] = next_lane_interval_opt.value(); - path_lanelets.next = - generatePathLanelet(path, next_start, next_end, width, path_lanelet_interval); - path_lanelets.all.push_back(path_lanelets.next.value()); - } - } - - const auto first_inside_conflicting_idx_opt = - first_attention_area.has_value() - ? getFirstPointInsidePolygon(path, assigned_lane_interval, first_attention_area.value()) - : getFirstPointInsidePolygon(path, assigned_lane_interval, first_conflicting_area); - const auto last_inside_conflicting_idx_opt = - first_attention_area.has_value() - ? getFirstPointInsidePolygons(path, assigned_lane_interval, attention_areas, false) - : getFirstPointInsidePolygons(path, assigned_lane_interval, conflicting_areas, false); - if (first_inside_conflicting_idx_opt && last_inside_conflicting_idx_opt) { - const auto first_inside_conflicting_idx = first_inside_conflicting_idx_opt.value(); - const auto last_inside_conflicting_idx = last_inside_conflicting_idx_opt.value().first; - lanelet::ConstLanelet conflicting_interval = generatePathLanelet( - path, first_inside_conflicting_idx, last_inside_conflicting_idx, width, - path_lanelet_interval); - path_lanelets.conflicting_interval_and_remaining.push_back(std::move(conflicting_interval)); - if (last_inside_conflicting_idx < assigned_lane_end) { - lanelet::ConstLanelet remaining_interval = generatePathLanelet( - path, last_inside_conflicting_idx, assigned_lane_end, width, path_lanelet_interval); - path_lanelets.conflicting_interval_and_remaining.push_back(std::move(remaining_interval)); - } - } - return path_lanelets; -} - -void TargetObject::calc_dist_to_stopline() -{ - if (!attention_lanelet || !stopline) { - return; - } - const auto attention_lanelet_val = attention_lanelet.value(); - const auto object_arc_coords = lanelet::utils::getArcCoordinates( - {attention_lanelet_val}, object.kinematics.initial_pose_with_covariance.pose); - const auto stopline_val = stopline.value(); - geometry_msgs::msg::Pose stopline_center; - stopline_center.position.x = (stopline_val.front().x() + stopline_val.back().x()) / 2.0; - stopline_center.position.y = (stopline_val.front().y() + stopline_val.back().y()) / 2.0; - stopline_center.position.z = (stopline_val.front().z() + stopline_val.back().z()) / 2.0; - const auto stopline_arc_coords = - lanelet::utils::getArcCoordinates({attention_lanelet_val}, stopline_center); - dist_to_stopline = (stopline_arc_coords.length - object_arc_coords.length); -} - } // namespace util } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 33e511d911b82..86a34d1e95114 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -15,12 +15,12 @@ #ifndef UTIL_HPP_ #define UTIL_HPP_ -#include "scene_intersection.hpp" #include "util_type.hpp" #include -#include +#include +#include #include #include @@ -35,88 +35,82 @@ namespace behavior_velocity_planner { namespace util { -std::optional insertPoint( + +/** + * @fn + * @brief insert a new pose to the path and return its index + * @return if insertion was successful return the inserted point index + */ +std::optional insertPointIndex( const geometry_msgs::msg::Pose & in_pose, - autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path); + autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path, + const double ego_nearest_dist_threshold, const double ego_nearest_yaw_threshold); +/** + * @fn + * @brief check if a PathPointWithLaneId contains any of the given lane ids + */ bool hasLaneIds( const autoware_auto_planning_msgs::msg::PathPointWithLaneId & p, const std::set & ids); -std::optional> findLaneIdsInterval( - const autoware_auto_planning_msgs::msg::PathWithLaneId & p, const std::set & ids); /** - * @brief get objective polygons for detection area + * @fn + * @brief find the first contiguous interval of the path points that contains the specified lane ids + * @return if no interval is found, return null. if the interval [start, end] (inclusive range) is + * found, returns the pair (start-1, end) */ -IntersectionLanelets getObjectiveLanelets( - lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr, - const lanelet::ConstLanelet assigned_lanelet, const lanelet::ConstLanelets & lanelets_on_path, - const std::set & associative_ids, const double detection_area_length, - const double occlusion_detection_area_length, const bool consider_wrong_direction_vehicle); +std::optional> findLaneIdsInterval( + const autoware_auto_planning_msgs::msg::PathWithLaneId & p, const std::set & ids); /** - * @brief Generate a stop line for stuck vehicle - * @param conflicting_areas used to generate stop line for stuck vehicle - * @param original_path ego-car lane - * @param target_path target lane to insert stop point (part of ego-car lane or same to ego-car - * lane) - " @param use_stuck_stopline if true, a stop line is generated at the beginning of intersection lane + * @fn + * @brief return the index of the first point which is inside the given polygon + * @param[in] lane_interval the interval of the path points on the intersection + * @param[in] search_forward flag for search direction */ -std::optional generateStuckStopLine( - const lanelet::CompoundPolygon3d & first_conflicting_area, - const std::shared_ptr & planner_data, - const InterpolatedPathInfo & interpolated_path_info, const double stopline_margin, - const bool use_stuck_stopline, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path); - -std::optional generateIntersectionStopLines( - const lanelet::CompoundPolygon3d & first_conflicting_area, - const lanelet::CompoundPolygon3d & first_attention_area, - const lanelet::ConstLineString2d & first_attention_lane_centerline, - const std::shared_ptr & planner_data, - const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, - const double stopline_margin, const double max_accel, const double max_jerk, - const double delay_response_time, const double peeking_offset, - autoware_auto_planning_msgs::msg::PathWithLaneId * original_path); - std::optional getFirstPointInsidePolygon( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const std::pair lane_interval, const lanelet::CompoundPolygon3d & polygon, const bool search_forward = true); /** + * @fn * @brief check if ego is over the target_idx. If the index is same, compare the exact pose - * @param path path - * @param closest_idx ego's closest index on the path - * @param current_pose ego's 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 isOverTargetIndex( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int closest_idx, - const geometry_msgs::msg::Pose & current_pose, const int target_idx); + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, + const geometry_msgs::msg::Pose & current_pose, const size_t target_idx); +/** + * @fn + * @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 autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int closest_idx, - const geometry_msgs::msg::Pose & current_pose, const int target_idx); - -/* -lanelet::ConstLanelets extendedAdjacentDirectionLanes( -lanelet::LaneletMapConstPtr map, const lanelet::routing::RoutingGraphPtr routing_graph, -lanelet::ConstLanelet lane); -*/ + const autoware_auto_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( +std::optional getIntersectionArea( lanelet::ConstLanelet assigned_lane, lanelet::LaneletMapConstPtr lanelet_map_ptr); +/** + * @fn + * @brief check if the given lane has related traffic light + */ bool hasAssociatedTrafficLight(lanelet::ConstLanelet lane); -TrafficPrioritizedLevel getTrafficPrioritizedLevel( - lanelet::ConstLanelet lane, const std::map & tl_infos); - -std::vector generateDetectionLaneDivisions( - lanelet::ConstLanelets detection_lanelets, - const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution, - const double curvature_threshold, const double curvature_calculation_ds); - +/** + * @fn + * @brief interpolate PathWithLaneId + */ std::optional generateInterpolatedPath( const lanelet::Id lane_id, const std::set & associative_lane_ids, const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path, const double ds, @@ -125,56 +119,28 @@ std::optional generateInterpolatedPath( geometry_msgs::msg::Pose getObjectPoseWithVelocityDirection( const autoware_auto_perception_msgs::msg::PredictedObjectKinematics & obj_state); -bool checkStuckVehicleInIntersection( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr, - const Polygon2d & stuck_vehicle_detect_area, const double stuck_vehicle_vel_thr, - DebugData * debug_data); - -bool checkYieldStuckVehicleInIntersection( - const util::TargetObjects & target_objects, - const util::InterpolatedPathInfo & interpolated_path_info, - const lanelet::ConstLanelets & attention_lanelets, const std::string & turn_direction, - const double width, const double stuck_vehicle_vel_thr, const double yield_stuck_distance_thr, - DebugData * debug_data); - -Polygon2d generateStuckVehicleDetectAreaPolygon( - const util::PathLanelets & path_lanelets, const double stuck_vehicle_detect_dist); - -std::optional checkAngleForTargetLanelets( - const geometry_msgs::msg::Pose & pose, const lanelet::ConstLanelets & target_lanelets, - const double detection_area_angle_thr, const bool consider_wrong_direction_vehicle, - const double dist_margin, const bool is_parked_vehicle); - -void cutPredictPathWithDuration( - util::TargetObjects * target_objects, const rclcpp::Clock::SharedPtr clock, - const double time_thr); +/** + * @fn + * @brief this function sorts the set of lanelets topologically using topological sort and merges + * the lanelets from each root to each end. each branch is merged and returned with the original + * lanelets + * @param[in] lanelets the set of lanelets + * @param[in] routing_graph_ptr the routing graph + * @return the pair of merged lanelets and their corresponding original lanelets + */ +std::pair> +mergeLaneletsByTopologicalSort( + const lanelet::ConstLanelets & lanelets, + const lanelet::routing::RoutingGraphPtr routing_graph_ptr); -TimeDistanceArray calcIntersectionPassingTime( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const std::shared_ptr & planner_data, const lanelet::Id lane_id, - const std::set & associative_ids, const size_t closest_idx, - const size_t last_intersection_stopline_candidate_idx, const double time_delay, - const double intersection_velocity, const double minimum_ego_velocity, - const bool use_upstream_velocity, const double minimum_upstream_velocity, - tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array); - -double calcDistanceUntilIntersectionLanelet( - const lanelet::ConstLanelet & assigned_lanelet, - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx); - -lanelet::ConstLanelet generatePathLanelet( - const PathWithLaneId & path, const size_t start_idx, const size_t end_idx, const double width, - const double interval); - -std::optional generatePathLanelets( - const lanelet::ConstLanelets & lanelets_on_path, - const util::InterpolatedPathInfo & interpolated_path_info, - const std::set & associative_ids, - const lanelet::CompoundPolygon3d & first_conflicting_area, - const std::vector & conflicting_areas, - const std::optional & first_attention_area, - const std::vector & attention_areas, const size_t closest_idx, - const double width); +/** + * @fn + * @brief find the index of the first point where vehicle footprint intersects with the given + * polygon + */ +std::optional getFirstPointInsidePolygonByFootprint( + const lanelet::CompoundPolygon3d & polygon, const InterpolatedPathInfo & interpolated_path_info, + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length); } // namespace util } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index d05031bf19436..763d829dacf9b 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -34,178 +34,24 @@ namespace behavior_velocity_planner::util { -struct DebugData -{ - std::optional collision_stop_wall_pose{std::nullopt}; - std::optional occlusion_stop_wall_pose{std::nullopt}; - std::optional occlusion_first_stop_wall_pose{std::nullopt}; - std::optional pass_judge_wall_pose{std::nullopt}; - std::optional> attention_area{std::nullopt}; - std::optional> occlusion_attention_area{std::nullopt}; - std::optional ego_lane{std::nullopt}; - std::optional> adjacent_area{std::nullopt}; - std::optional stuck_vehicle_detect_area{std::nullopt}; - std::optional> yield_stuck_detect_area{std::nullopt}; - std::optional candidate_collision_ego_lane_polygon{std::nullopt}; - std::vector candidate_collision_object_polygons; - autoware_auto_perception_msgs::msg::PredictedObjects conflicting_targets; - autoware_auto_perception_msgs::msg::PredictedObjects amber_ignore_targets; - autoware_auto_perception_msgs::msg::PredictedObjects red_overshoot_ignore_targets; - autoware_auto_perception_msgs::msg::PredictedObjects stuck_targets; - autoware_auto_perception_msgs::msg::PredictedObjects yield_stuck_targets; - std::vector occlusion_polygons; - std::optional> - nearest_occlusion_projection{std::nullopt}; - autoware_auto_perception_msgs::msg::PredictedObjects blocking_attention_objects; - std::optional absence_traffic_light_creep_wall{std::nullopt}; - std::optional static_occlusion_with_traffic_light_timeout{std::nullopt}; -}; - +/** + * @struct + * @brief wrapper class of interpolated path with lane id + */ struct InterpolatedPathInfo { + /** the interpolated path */ autoware_auto_planning_msgs::msg::PathWithLaneId path; + /** discretization interval of interpolation */ double ds{0.0}; + /** the intersection lanelet id */ lanelet::Id lane_id{0}; + /** the associative lane ids of lane_id */ std::set associative_lane_ids{}; + /** the range of indices for the path points with associative lane id */ std::optional> lane_id_interval{std::nullopt}; }; -struct IntersectionLanelets -{ -public: - void update( - const bool is_prioritized, const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length); - const lanelet::ConstLanelets & attention() const - { - return is_prioritized_ ? attention_non_preceding_ : attention_; - } - const std::vector> & attention_stoplines() const - { - return is_prioritized_ ? attention_non_preceding_stoplines_ : attention_stoplines_; - } - const lanelet::ConstLanelets & conflicting() const { return conflicting_; } - const lanelet::ConstLanelets & adjacent() const { return adjacent_; } - const lanelet::ConstLanelets & occlusion_attention() const - { - return is_prioritized_ ? attention_non_preceding_ : occlusion_attention_; - } - const std::vector & attention_area() const - { - return is_prioritized_ ? attention_non_preceding_area_ : attention_area_; - } - const std::vector & conflicting_area() const - { - return conflicting_area_; - } - const std::vector & adjacent_area() const { return adjacent_area_; } - const std::vector & occlusion_attention_area() const - { - return occlusion_attention_area_; - } - const std::optional & first_conflicting_lane() const - { - return first_conflicting_lane_; - } - const std::optional & first_conflicting_area() const - { - return first_conflicting_area_; - } - const std::optional & first_attention_lane() const - { - return first_attention_lane_; - } - const std::optional & first_attention_area() const - { - return first_attention_area_; - } - - lanelet::ConstLanelets attention_; // topologically merged lanelets - std::vector> - attention_stoplines_; // the stop lines for each attention_ lanelets - lanelet::ConstLanelets attention_non_preceding_; - std::vector> - attention_non_preceding_stoplines_; // the stop lines for each attention_non_preceding_ - // lanelets - lanelet::ConstLanelets conflicting_; - lanelet::ConstLanelets adjacent_; - lanelet::ConstLanelets occlusion_attention_; // topologically merged lanelets - std::vector occlusion_attention_size_; // the area() of each occlusion attention lanelets - std::vector attention_area_; // topologically merged lanelets - std::vector attention_non_preceding_area_; - std::vector conflicting_area_; - std::vector adjacent_area_; - std::vector - occlusion_attention_area_; // topologically merged lanelets - // the first area intersecting with the path - // even if lane change/re-routing happened on the intersection, these areas area are supposed to - // be invariant under the 'associative' lanes. - std::optional first_conflicting_lane_{std::nullopt}; - std::optional first_conflicting_area_{std::nullopt}; - std::optional first_attention_lane_{std::nullopt}; - std::optional first_attention_area_{std::nullopt}; - bool is_prioritized_ = false; -}; - -struct IntersectionStopLines -{ - // NOTE: for baselink - size_t closest_idx{0}; - // NOTE: null if path does not conflict with first_conflicting_area - std::optional stuck_stopline{std::nullopt}; - // NOTE: null if path is over map stopline OR its value is calculated negative - std::optional default_stopline{std::nullopt}; - // NOTE: null if the index is calculated negative - std::optional first_attention_stopline{std::nullopt}; - // NOTE: null if footprints do not change from outside to inside of detection area - std::optional occlusion_peeking_stopline{std::nullopt}; - // if the value is calculated negative, its value is 0 - size_t pass_judge_line{0}; - size_t occlusion_wo_tl_pass_judge_line{0}; -}; - -struct PathLanelets -{ - lanelet::ConstLanelets prev; - // lanelet::ConstLanelet entry2ego; this is included in `all` if exists - lanelet::ConstLanelet - ego_or_entry2exit; // this is `assigned lane` part of the path(not from - // ego) if ego is before the intersection, otherwise from ego to exit - std::optional next = - std::nullopt; // this is nullopt is the goal is inside intersection - lanelet::ConstLanelets all; - lanelet::ConstLanelets - conflicting_interval_and_remaining; // the left/right-most interval of path conflicting with - // conflicting lanelets plus the next lane part of the - // path -}; - -struct TargetObject -{ - autoware_auto_perception_msgs::msg::PredictedObject object; - std::optional attention_lanelet{std::nullopt}; - std::optional stopline{std::nullopt}; - std::optional dist_to_stopline{std::nullopt}; - void calc_dist_to_stopline(); -}; - -struct TargetObjects -{ - std_msgs::msg::Header header; - std::vector attention_objects; - std::vector parked_attention_objects; - std::vector intersection_area_objects; - std::vector all_attention_objects; // TODO(Mamoru Sobue): avoid copy -}; - -enum class TrafficPrioritizedLevel { - // The target lane's traffic signal is red or the ego's traffic signal has an arrow. - FULLY_PRIORITIZED = 0, - // The target lane's traffic signal is amber - PARTIALLY_PRIORITIZED, - // The target lane's traffic signal is green - NOT_PRIORITIZED -}; } // namespace behavior_velocity_planner::util #endif // UTIL_TYPE_HPP_ From e3f49a1b85a78e5e935330a868eda80062854515 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 5 Jan 2024 16:05:55 +0900 Subject: [PATCH 180/276] fix(static_drivable_area_expansion): fix drivable bound edge process (#6014) Signed-off-by: satoshi-ota --- .../static_drivable_area.cpp | 45 +++++++++++++++++-- 1 file changed, 41 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index ec147a7bb2771..1aa55e5f350b3 100644 --- a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -31,6 +31,42 @@ namespace { +template +size_t findNearestSegmentIndexFromLateralDistance( + const std::vector & points, const geometry_msgs::msg::Point & target_point) +{ + using tier4_autoware_utils::calcAzimuthAngle; + using tier4_autoware_utils::calcDistance2d; + using tier4_autoware_utils::normalizeRadian; + + std::optional closest_idx{std::nullopt}; + double min_lateral_dist = std::numeric_limits::max(); + for (size_t seg_idx = 0; seg_idx < points.size() - 1; ++seg_idx) { + const double lon_dist = + motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, target_point); + const double segment_length = calcDistance2d(points.at(seg_idx), points.at(seg_idx + 1)); + const double lat_dist = [&]() { + if (lon_dist < 0.0) { + return calcDistance2d(points.at(seg_idx), target_point); + } + if (segment_length < lon_dist) { + return calcDistance2d(points.at(seg_idx + 1), target_point); + } + return std::abs(motion_utils::calcLateralOffset(points, target_point, seg_idx)); + }(); + if (lat_dist < min_lateral_dist) { + closest_idx = seg_idx; + min_lateral_dist = lat_dist; + } + } + + if (closest_idx) { + return *closest_idx; + } + + return motion_utils::findNearestSegmentIndex(points, target_point); +} + template size_t findNearestSegmentIndexFromLateralDistance( const std::vector & points, const geometry_msgs::msg::Pose & target_point, @@ -813,9 +849,9 @@ void generateDrivableArea( const auto right_start_point = calcLongitudinalOffsetStartPoint( right_bound, front_pose, front_right_start_idx, -front_length); const size_t left_start_idx = - motion_utils::findNearestSegmentIndex(left_bound, left_start_point); + findNearestSegmentIndexFromLateralDistance(left_bound, left_start_point); const size_t right_start_idx = - motion_utils::findNearestSegmentIndex(right_bound, right_start_point); + findNearestSegmentIndexFromLateralDistance(right_bound, right_start_point); // Insert a start point path.left_bound.push_back(left_start_point); @@ -835,9 +871,10 @@ void generateDrivableArea( const auto right_goal_point = calcLongitudinalOffsetGoalPoint(right_bound, goal_pose, goal_right_start_idx, vehicle_length); const size_t left_goal_idx = std::max( - goal_left_start_idx, motion_utils::findNearestSegmentIndex(left_bound, left_goal_point)); + goal_left_start_idx, findNearestSegmentIndexFromLateralDistance(left_bound, left_goal_point)); const size_t right_goal_idx = std::max( - goal_right_start_idx, motion_utils::findNearestSegmentIndex(right_bound, right_goal_point)); + goal_right_start_idx, + findNearestSegmentIndexFromLateralDistance(right_bound, right_goal_point)); // Insert middle points for (size_t i = left_start_idx + 1; i <= left_goal_idx; ++i) { From 04b8eead3ad8eb29a6d89d71b781a785a3571d01 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 5 Jan 2024 16:35:33 +0900 Subject: [PATCH 181/276] feat(path_smoother): add a plotter of calculation time (#6012) * feat(path_smoother): add a plotter of calculation time Signed-off-by: Takayuki Murooka * add x/y label Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * update cmake to install script Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../scripts/calculation_time_plotter.py | 2 + planning/path_smoother/CMakeLists.txt | 5 + .../scripts/calculation_time_plotter.py | 117 ++++++++++++++++++ 3 files changed, 124 insertions(+) create mode 100755 planning/path_smoother/scripts/calculation_time_plotter.py diff --git a/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py b/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py index daf6beea730d3..1904b45fb8225 100755 --- a/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py +++ b/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py @@ -49,6 +49,8 @@ def __init__(self, args): self.y_vec.append(deque()) plt.legend(loc="lower left") + plt.xlabel("step [-]") + plt.ylabel("calculation time [ms]") plt.show() def CallbackCalculationCost(self, msg): diff --git a/planning/path_smoother/CMakeLists.txt b/planning/path_smoother/CMakeLists.txt index b2fcf9076a7b3..b2f42181f9a0f 100644 --- a/planning/path_smoother/CMakeLists.txt +++ b/planning/path_smoother/CMakeLists.txt @@ -35,3 +35,8 @@ ament_auto_package( launch config ) + +install(PROGRAMS + scripts/calculation_time_plotter.py + DESTINATION lib/${PROJECT_NAME} +) diff --git a/planning/path_smoother/scripts/calculation_time_plotter.py b/planning/path_smoother/scripts/calculation_time_plotter.py new file mode 100755 index 0000000000000..3a18fc56f39bc --- /dev/null +++ b/planning/path_smoother/scripts/calculation_time_plotter.py @@ -0,0 +1,117 @@ +#!/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 +from collections import deque + +import matplotlib.pyplot as plt +import rclpy +from rclpy.node import Node +from tier4_debug_msgs.msg import StringStamped + + +class CalculationCostAnalyzer(Node): + def __init__(self, args): + super().__init__("calculation_cost_analyzer") + + self.functions_name = args.functions.split(",") + self.depth = args.depth + + self.calculation_cost_hist = [] + self.sub_calculation_cost = self.create_subscription( + StringStamped, + "/planning/scenario_planning/lane_driving/motion_planning/elastic_band_smoother/debug/calculation_time", + self.CallbackCalculationCost, + 1, + ) + + plt.ion() + plt.figure() + + self.lines = [] + self.y_vec = [] + for f_idx, function_name in enumerate(self.functions_name): + (line,) = plt.plot([], [], label="{}".format(function_name)) + self.lines.append(line) + self.y_vec.append(deque()) + + plt.legend(loc="lower left") + plt.xlabel("step [-]") + plt.ylabel("calculation time [ms]") + plt.show() + + def CallbackCalculationCost(self, msg): + max_y = 0 + max_x = 0 + + for f_idx, function_name in enumerate(self.functions_name): + is_found = False + for line in msg.data.split("\n"): + if function_name in line: + y = float(line.split(":=")[1].split("[ms]")[0]) + self.y_vec[f_idx].append(y) + + is_found = True + break + + if not is_found: + self.y_vec[f_idx].append(None) + + if len(self.y_vec[f_idx]) > self.depth: + self.y_vec[f_idx].popleft() + + x_vec = list(range(len(self.y_vec[f_idx]))) + + valid_x_vec = [] + valid_y_vec = [] + for i in range(len(x_vec)): + if self.y_vec[f_idx][i] is not None: + valid_x_vec.append(x_vec[i]) + valid_y_vec.append(self.y_vec[f_idx][i]) + + self.lines[f_idx].set_xdata(valid_x_vec) + self.lines[f_idx].set_ydata(valid_y_vec) + + if len(valid_y_vec) > 0: + max_x = max(max_x, max(valid_x_vec)) + max_y = max(max_y, max(valid_y_vec)) + + plt.xlim(0, max_x) + plt.ylim(0.0, max_y) + + plt.draw() + plt.pause(0.01) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument( + "-f", + "--functions", + type=str, + default="onPath,calcSmoothedTrajectory", + ) + parser.add_argument( + "-d", + "--depth", + type=float, + default=500, + ) + args = parser.parse_args() + + rclpy.init() + node = CalculationCostAnalyzer(args) + rclpy.spin(node) From bb7536f49fdad003cf6ebec3a6e80c785e4ee176 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 5 Jan 2024 16:35:59 +0900 Subject: [PATCH 182/276] fix(obstacle_avoidance_planner): use update_bounds instead of update_lower/upper_bounds (#6011) Signed-off-by: Takayuki Murooka --- planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index 765136b3cf6f6..47f5f59827267 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -1519,8 +1519,7 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( osqp_solver_ptr_->updateCscP(P_csc); osqp_solver_ptr_->updateQ(f); osqp_solver_ptr_->updateCscA(A_csc); - osqp_solver_ptr_->updateL(lower_bound); - osqp_solver_ptr_->updateU(upper_bound); + osqp_solver_ptr_->updateBounds(lower_bound, upper_bound); } else { RCLCPP_INFO_EXPRESSION(logger_, enable_debug_info_, "no warm start"); osqp_solver_ptr_ = std::make_unique( From 6fa7d07c136b6c0ec611b9aed67754c67a5f2353 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 5 Jan 2024 16:36:18 +0900 Subject: [PATCH 183/276] chore(traffic_light_module): use RCLCPP_DEBUG for the debug printing (#6010) Signed-off-by: Takayuki Murooka --- planning/behavior_velocity_traffic_light_module/src/scene.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp index d2d18d74a5c1a..35d44a22f6cf0 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp @@ -217,7 +217,7 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason * // Move to go out state if ego vehicle over deadline. constexpr double signed_deadline_length = -2.0; if (signed_arc_length_to_stop_point < signed_deadline_length) { - RCLCPP_INFO(logger_, "APPROACH -> GO_OUT"); + RCLCPP_DEBUG(logger_, "APPROACH -> GO_OUT"); state_ = State::GO_OUT; stop_signal_received_time_ptr_.reset(); return true; @@ -263,7 +263,7 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason * constexpr double restart_length = 1.0; if (use_initialization_after_start) { if (signed_arc_length_to_stop_point > restart_length) { - RCLCPP_INFO(logger_, "GO_OUT(RESTART) -> APPROACH"); + RCLCPP_DEBUG(logger_, "GO_OUT(RESTART) -> APPROACH"); state_ = State::APPROACH; } } From 2b3d3684d8f8c709ac93b7b525b758d6a8cf3a9e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 5 Jan 2024 16:36:54 +0900 Subject: [PATCH 184/276] chore(map_height_fitter): set log level of debug printing to DEBUG (#5997) Signed-off-by: Takayuki Murooka --- map/map_height_fitter/src/map_height_fitter.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/map/map_height_fitter/src/map_height_fitter.cpp b/map/map_height_fitter/src/map_height_fitter.cpp index 1eb1edd04a68a..a05c63d44ebce 100644 --- a/map/map_height_fitter/src/map_height_fitter.cpp +++ b/map/map_height_fitter/src/map_height_fitter.cpp @@ -101,11 +101,11 @@ bool MapHeightFitter::Impl::get_partial_point_cloud_map(const Point & point) req->area.center_y = point.y; req->area.radius = 50; - RCLCPP_INFO(logger, "Send request to map_loader"); + RCLCPP_DEBUG(logger, "Send request to map_loader"); auto future = cli_map_->async_send_request(req); auto status = future.wait_for(std::chrono::seconds(1)); while (status != std::future_status::ready) { - RCLCPP_INFO(logger, "waiting response"); + RCLCPP_DEBUG(logger, "waiting response"); if (!rclcpp::ok()) { return false; } @@ -113,7 +113,7 @@ bool MapHeightFitter::Impl::get_partial_point_cloud_map(const Point & point) } const auto res = future.get(); - RCLCPP_INFO( + RCLCPP_DEBUG( logger, "Loaded partial pcd map from map_loader (grid size: %lu)", res->new_pointcloud_with_ids.size()); @@ -168,7 +168,7 @@ std::optional MapHeightFitter::Impl::fit(const Point & position, const st const auto logger = node_->get_logger(); tf2::Vector3 point(position.x, position.y, position.z); - RCLCPP_INFO(logger, "original point: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ()); + RCLCPP_DEBUG(logger, "original point: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ()); if (cli_map_) { if (!get_partial_point_cloud_map(position)) { @@ -193,7 +193,7 @@ std::optional MapHeightFitter::Impl::fit(const Point & position, const st return std::nullopt; } - RCLCPP_INFO(logger, "modified point: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ()); + RCLCPP_DEBUG(logger, "modified point: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ()); Point result; result.x = point.getX(); From 96abeaeebb8a0cb34e51b5b82a6efc945adc23b7 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 5 Jan 2024 16:38:05 +0900 Subject: [PATCH 185/276] chore: set log level of debug printing in rviz plugin to DEBUG (#5996) Signed-off-by: Takayuki Murooka --- .../include/tier4_api_utils/rclcpp/client.hpp | 8 ++++---- .../src/tools/manual_controller.cpp | 4 ++-- .../tier4_state_rviz_plugin/src/autoware_state_panel.hpp | 6 +++--- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/common/tier4_api_utils/include/tier4_api_utils/rclcpp/client.hpp b/common/tier4_api_utils/include/tier4_api_utils/rclcpp/client.hpp index aedbe4b34ea22..16ff5a011536c 100644 --- a/common/tier4_api_utils/include/tier4_api_utils/rclcpp/client.hpp +++ b/common/tier4_api_utils/include/tier4_api_utils/rclcpp/client.hpp @@ -41,20 +41,20 @@ class Client const typename ServiceT::Request::SharedPtr & request, const std::chrono::nanoseconds & timeout = std::chrono::seconds(2)) { - RCLCPP_INFO(logger_, "client request"); + RCLCPP_DEBUG(logger_, "client request"); if (!client_->service_is_ready()) { - RCLCPP_INFO(logger_, "client available"); + RCLCPP_DEBUG(logger_, "client available"); return {response_error("Internal service is not available."), nullptr}; } auto future = client_->async_send_request(request); if (future.wait_for(timeout) != std::future_status::ready) { - RCLCPP_INFO(logger_, "client timeout"); + RCLCPP_DEBUG(logger_, "client timeout"); return {response_error("Internal service has timed out."), nullptr}; } - RCLCPP_INFO(logger_, "client response"); + RCLCPP_DEBUG(logger_, "client response"); return {response_success(), future.get()}; } diff --git a/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp b/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp index 9610bf1e2b7f1..fdd270fcce2ef 100644 --- a/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp +++ b/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp @@ -263,9 +263,9 @@ void ManualController::onClickEnableButton() { auto req = std::make_shared(); req->engage = true; - RCLCPP_INFO(raw_node_->get_logger(), "client request"); + RCLCPP_DEBUG(raw_node_->get_logger(), "client request"); if (!client_engage_->service_is_ready()) { - RCLCPP_INFO(raw_node_->get_logger(), "client is unavailable"); + RCLCPP_DEBUG(raw_node_->get_logger(), "client is unavailable"); return; } client_engage_->async_send_request( diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp index eba3e4eacd275..8f67a90215bd1 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp @@ -171,15 +171,15 @@ public Q_SLOTS: // NOLINT for Qt { auto req = std::make_shared(); - RCLCPP_INFO(raw_node_->get_logger(), "client request"); + RCLCPP_DEBUG(raw_node_->get_logger(), "client request"); if (!client->service_is_ready()) { - RCLCPP_INFO(raw_node_->get_logger(), "client is unavailable"); + RCLCPP_DEBUG(raw_node_->get_logger(), "client is unavailable"); return; } client->async_send_request(req, [this](typename rclcpp::Client::SharedFuture result) { - RCLCPP_INFO( + RCLCPP_DEBUG( raw_node_->get_logger(), "Status: %d, %s", result.get()->status.code, result.get()->status.message.c_str()); }); From 38a21c8747aca5d4f2fa30fef3998711f75f41db Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 5 Jan 2024 16:38:26 +0900 Subject: [PATCH 186/276] chore(component_interface_utils): set log level of debug printing to DEBUG (#5995) Signed-off-by: Takayuki Murooka --- .../include/component_interface_utils/rclcpp/interface.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/component_interface_utils/include/component_interface_utils/rclcpp/interface.hpp b/common/component_interface_utils/include/component_interface_utils/rclcpp/interface.hpp index bc48e2a0294e0..97f46933f2fe6 100644 --- a/common/component_interface_utils/include/component_interface_utils/rclcpp/interface.hpp +++ b/common/component_interface_utils/include/component_interface_utils/rclcpp/interface.hpp @@ -52,7 +52,7 @@ struct NodeInterface {ServiceLog::CLIENT_RESPONSE, "client exit"}, {ServiceLog::ERROR_UNREADY, "client unready"}, {ServiceLog::ERROR_TIMEOUT, "client timeout"}}); - RCLCPP_INFO_STREAM(node->get_logger(), type_text.at(type) << ": " << name); + RCLCPP_DEBUG_STREAM(node->get_logger(), type_text.at(type) << ": " << name); ServiceLog msg; msg.stamp = node->now(); From 1bec680ed6522b24da0a0b2d517f2c6e40c8779c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 5 Jan 2024 16:38:45 +0900 Subject: [PATCH 187/276] feat(dynamic_avoidance): apply ego's lateral acc/jerk constraints to object polygon (#5953) * feat(dynamic_avoidance): apply ego's lateral acc/jerk constraints to object polygon Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance.param.yaml | 4 + .../dynamic_avoidance_module.hpp | 103 ++++++---- .../dynamic_avoidance_module.cpp | 178 +++++++++++++++--- .../dynamic_avoidance/manager.cpp | 8 + .../marker_utils/utils.hpp | 4 + .../src/marker_utils/utils.cpp | 16 ++ 6 files changed, 249 insertions(+), 64 deletions(-) diff --git a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml index 29fdca78e5bcb..371f7da2fadf5 100644 --- a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml +++ b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml @@ -59,6 +59,10 @@ max_time_for_object_lat_shift: 0.0 # [s] lpf_gain_for_lat_avoid_to_offset: 0.9 # [-] + max_ego_lat_acc: 0.3 # [m/ss] + max_ego_lat_jerk: 0.3 # [m/sss] + delay_time_ego_shift: 1.0 # [s] + # for same directional object overtaking_object: max_time_to_collision: 40.0 # [s] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 3ceff4244f2c8..50f5b61e15169 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -35,6 +35,25 @@ #include #include +namespace +{ +template +bool isInVector(const T & val, const std::vector & vec) +{ + return std::find(vec.begin(), vec.end(), val) != vec.end(); +} + +template +std::vector getAllKeys(const std::unordered_map & map) +{ + std::vector keys; + for (const auto & pair : map) { + keys.push_back(pair.first); + } + return keys; +} +} // namespace + namespace behavior_path_planner { using autoware_auto_perception_msgs::msg::PredictedPath; @@ -97,6 +116,10 @@ struct DynamicAvoidanceParameters double max_time_for_lat_shift{0.0}; double lpf_gain_for_lat_avoid_to_offset{0.0}; + double max_ego_lat_acc{0.0}; + double max_ego_lat_jerk{0.0}; + double delay_time_ego_shift{0.0}; + double max_time_to_collision_overtaking_object{0.0}; double start_duration_to_avoid_overtaking_object{0.0}; double end_duration_to_avoid_overtaking_object{0.0}; @@ -113,6 +136,11 @@ struct TimeWhileCollision double time_to_end_collision; }; +struct LatFeasiblePaths +{ + std::vector left_path; + std::vector right_path; +}; class DynamicAvoidanceModule : public SceneModuleInterface { public: @@ -151,6 +179,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface bool is_collision_left{false}; bool should_be_avoided{false}; std::vector ref_path_points_for_obj_poly; + LatFeasiblePaths ego_lat_feasible_paths; void update( const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid, @@ -172,14 +201,18 @@ class DynamicAvoidanceModule : public SceneModuleInterface { } int max_count_{0}; - int min_count_{0}; + int min_count_{0}; // TODO(murooka): The sign needs to be opposite? void initialize() { current_uuids_.clear(); } void updateObject(const std::string & uuid, const DynamicAvoidanceObject & object) { // add/update object if (object_map_.count(uuid) != 0) { + const auto prev_object = object_map_.at(uuid); object_map_.at(uuid) = object; + // TODO(murooka) refactor this. Counter can be moved to DynamicObject, + // and TargetObjectsManager can be removed. + object_map_.at(uuid).ego_lat_feasible_paths = prev_object.ego_lat_feasible_paths; } else { object_map_.emplace(uuid, object); } @@ -195,14 +228,12 @@ class DynamicAvoidanceModule : public SceneModuleInterface current_uuids_.push_back(uuid); } - void finalize() + void finalize(const LatFeasiblePaths & ego_lat_feasible_paths) { // decrease counter for not updated uuids std::vector not_updated_uuids; for (const auto & object : object_map_) { - if ( - std::find(current_uuids_.begin(), current_uuids_.end(), object.first) == - current_uuids_.end()) { + if (!isInVector(object.first, current_uuids_)) { not_updated_uuids.push_back(object.first); } } @@ -214,45 +245,46 @@ class DynamicAvoidanceModule : public SceneModuleInterface } } - // remove objects whose counter is lower than threshold - std::vector obsolete_uuids; + // update valid object uuids and its variable for (const auto & counter : counter_map_) { - if (counter.second < min_count_) { - obsolete_uuids.push_back(counter.first); + if (!isInVector(counter.first, valid_object_uuids_) && max_count_ <= counter.second) { + valid_object_uuids_.push_back(counter.first); + object_map_.at(counter.first).ego_lat_feasible_paths = ego_lat_feasible_paths; } } - for (const auto & obsolete_uuid : obsolete_uuids) { - counter_map_.erase(obsolete_uuid); - object_map_.erase(obsolete_uuid); + valid_object_uuids_.erase( + std::remove_if( + valid_object_uuids_.begin(), valid_object_uuids_.end(), + [&](const auto & uuid) { + return counter_map_.count(uuid) == 0 || counter_map_.at(uuid) < max_count_; + }), + valid_object_uuids_.end()); + + // remove objects whose counter is lower than threshold + const auto counter_map_keys = getAllKeys(counter_map_); + for (const auto & key : counter_map_keys) { + if (counter_map_.at(key) < min_count_) { + counter_map_.erase(key); + object_map_.erase(key); + } } } std::vector getValidObjects() const { - std::vector objects; - for (const auto & object : object_map_) { - if (counter_map_.count(object.first) != 0) { - if (max_count_ <= counter_map_.at(object.first)) { - objects.push_back(object.second); - } + std::vector valid_objects; + for (const auto & valid_object_uuid : valid_object_uuids_) { + if (object_map_.count(valid_object_uuid) == 0) { + std::cerr + << "[DynamicAvoidance] Internal calculation has an error when getting valid objects." + << std::endl; + continue; } + valid_objects.push_back(object_map_.at(valid_object_uuid)); } - return objects; - } - std::optional getValidObject(const std::string & uuid) const - { - // add/update object - if (counter_map_.count(uuid) == 0) { - return std::nullopt; - } - if (counter_map_.at(uuid) < max_count_) { - return std::nullopt; - } - if (object_map_.count(uuid) == 0) { - return std::nullopt; - } - return object_map_.at(uuid); + + return valid_objects; } - void updateObject( + void updateObjectVariables( const std::string & uuid, const MinMaxValue & lon_offset_to_avoid, const MinMaxValue & lat_offset_to_avoid, const bool is_collision_left, const bool should_be_avoided, @@ -269,6 +301,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface // NOTE: positive is for meeting entry condition, and negative is for exiting. std::unordered_map counter_map_; std::unordered_map object_map_; + std::vector valid_object_uuids_{}; }; struct DecisionWithReason @@ -319,6 +352,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface bool isLabelTargetObstacle(const uint8_t label) const; void updateTargetObjects(); + LatFeasiblePaths generateLateralFeasiblePaths( + const geometry_msgs::msg::Pose & ego_pose, const double ego_vel) const; void updateRefPathBeforeLaneChange(const std::vector & ego_ref_path_points); bool willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 87a940d04e8d3..01635d7a6cb70 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -262,6 +262,35 @@ double calcDistanceToSegment( first_to_second * first_to_target.dot(first_to_second) / std::pow(first_to_second.norm(), 2); return (Eigen::Vector2d{p1.x, p1.y} - p2_nearest).norm(); } + +std::optional> intersectLines( + const std::vector & source_line, + const std::vector & target_line) +{ + for (int source_seg_idx = 0; source_seg_idx < static_cast(source_line.size()) - 1; + ++source_seg_idx) { + for (int target_seg_idx = 0; target_seg_idx < static_cast(target_line.size()) - 1; + ++target_seg_idx) { + const auto intersect_point = tier4_autoware_utils::intersect( + source_line.at(source_seg_idx).position, source_line.at(source_seg_idx + 1).position, + target_line.at(target_seg_idx), target_line.at(target_seg_idx + 1)); + if (intersect_point) { + return std::make_pair(source_seg_idx, *intersect_point); + } + } + } + return std::nullopt; +} + +std::vector convertToPoints( + const std::vector & poses) +{ + std::vector points; + for (const auto & pose : poses) { + points.push_back(pose.position); + } + return points; +} } // namespace DynamicAvoidanceModule::DynamicAvoidanceModule( @@ -310,6 +339,9 @@ bool DynamicAvoidanceModule::isExecutionReady() const void DynamicAvoidanceModule::updateData() { + info_marker_.markers.clear(); + debug_marker_.markers.clear(); + // calculate target objects updateTargetObjects(); @@ -329,9 +361,6 @@ bool DynamicAvoidanceModule::canTransitSuccessState() BehaviorModuleOutput DynamicAvoidanceModule::plan() { - info_marker_.markers.clear(); - debug_marker_.markers.clear(); - const auto & input_path = getPreviousModuleOutput().path; // create obstacles to avoid (= extract from the drivable area) @@ -425,6 +454,10 @@ void DynamicAvoidanceModule::updateTargetObjects() updateRefPathBeforeLaneChange(input_ref_path_points); + const auto & ego_pose = getEgoPose(); + const double ego_vel = getEgoSpeed(); + const auto ego_lat_feasible_paths = generateLateralFeasiblePaths(ego_pose, ego_vel); + // 1. Rough filtering of target objects target_objects_manager_.initialize(); for (const auto & predicted_object : predicted_objects) { @@ -509,7 +542,7 @@ void DynamicAvoidanceModule::updateTargetObjects() latest_time_inside_ego_path); target_objects_manager_.updateObject(obj_uuid, target_object); } - target_objects_manager_.finalize(); + target_objects_manager_.finalize(ego_lat_feasible_paths); // 2. Precise filtering of target objects and check if they should be avoided for (const auto & object : target_objects_manager_.getValidObjects()) { @@ -580,18 +613,24 @@ void DynamicAvoidanceModule::updateTargetObjects() parameters_->max_time_to_collision_overtaking_object < time_to_collision) || (object.vel <= 0 && parameters_->max_time_to_collision_oncoming_object < time_to_collision)) { + const auto time_to_collision_str = time_to_collision == std::numeric_limits::max() + ? "infinity" + : std::to_string(time_to_collision); RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, - "[DynamicAvoidance] Ignore obstacle (%s) since time to collision (%f) is large.", - obj_uuid.c_str(), time_to_collision); + "[DynamicAvoidance] Ignore obstacle (%s) since time to collision (%s) is large.", + obj_uuid.c_str(), time_to_collision_str.c_str()); continue; } if (time_to_collision < -parameters_->duration_to_hold_avoidance_overtaking_object) { + const auto time_to_collision_str = time_to_collision == std::numeric_limits::max() + ? "infinity" + : std::to_string(time_to_collision); RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, - "[DynamicAvoidance] Ignore obstacle (%s) since time to collision (%f) is a small " + "[DynamicAvoidance] Ignore obstacle (%s) since time to collision (%s) is a small " "negative value.", - obj_uuid.c_str(), time_to_collision); + obj_uuid.c_str(), time_to_collision_str.c_str()); continue; } } @@ -611,7 +650,7 @@ void DynamicAvoidanceModule::updateTargetObjects() const double signed_dist_ego_to_obj = [&]() { const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(input_path.points); const double lon_offset_ego_to_obj = motion_utils::calcSignedArcLength( - input_path.points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); + input_path.points, ego_pose.position, ego_seg_idx, lat_lon_offset.nearest_idx); if (0 < lon_offset_ego_to_obj) { return std::max( 0.0, lon_offset_ego_to_obj - planner_data_->parameters.front_overhang + @@ -649,7 +688,7 @@ void DynamicAvoidanceModule::updateTargetObjects() } const bool should_be_avoided = true; - target_objects_manager_.updateObject( + target_objects_manager_.updateObjectVariables( obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided, ref_path_points_for_obj_poly); } @@ -657,6 +696,42 @@ void DynamicAvoidanceModule::updateTargetObjects() prev_input_ref_path_points_ = input_ref_path_points; } +LatFeasiblePaths DynamicAvoidanceModule::generateLateralFeasiblePaths( + const geometry_msgs::msg::Pose & ego_pose, const double ego_vel) const +{ + const double lat_acc = parameters_->max_ego_lat_acc; + const double lat_jerk = parameters_->max_ego_lat_jerk; + const double delay_time = parameters_->delay_time_ego_shift; + + LatFeasiblePaths ego_lat_feasible_paths; + for (double t = 0; t < 10.0; t += 1.0) { + const double feasible_lat_offset = lat_acc * std::pow(std::max(t - delay_time, 0.0), 2) / 2.0 + + lat_jerk * std::pow(std::max(t - delay_time, 0.0), 3) / 6.0 - + planner_data_->parameters.vehicle_width / 2.0; + const double x = t * ego_vel; + const double y = feasible_lat_offset; + + const auto feasible_left_bound_point = + tier4_autoware_utils::calcOffsetPose(ego_pose, x, -y, 0.0).position; + ego_lat_feasible_paths.left_path.push_back(feasible_left_bound_point); + + const auto feasible_right_bound_point = + tier4_autoware_utils::calcOffsetPose(ego_pose, x, y, 0.0).position; + ego_lat_feasible_paths.right_path.push_back(feasible_right_bound_point); + } + + tier4_autoware_utils::appendMarkerArray( + marker_utils::createPointsMarkerArray( + ego_lat_feasible_paths.left_path, "ego_lat_feasible_left_path", 0, 0.6, 0.9, 0.9), + &debug_marker_); + tier4_autoware_utils::appendMarkerArray( + marker_utils::createPointsMarkerArray( + ego_lat_feasible_paths.right_path, "ego_lat_feasible_right_path", 0, 0.6, 0.9, 0.9), + &debug_marker_); + + return ego_lat_feasible_paths; +} + void DynamicAvoidanceModule::updateRefPathBeforeLaneChange( const std::vector & ego_ref_path_points) { @@ -1251,32 +1326,75 @@ DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( ? lon_bound_end_idx_opt.value() : static_cast(ref_path_points_for_obj_poly.size() - 1); - // create inner/outer bound points - std::vector obj_inner_bound_points; - std::vector obj_outer_bound_points; + // create inner bound points + std::vector obj_inner_bound_poses; for (size_t i = lon_bound_start_idx; i <= lon_bound_end_idx; ++i) { - obj_inner_bound_points.push_back(tier4_autoware_utils::calcOffsetPose( - ref_path_points_for_obj_poly.at(i).point.pose, 0.0, - object.lat_offset_to_avoid->min_value, 0.0) - .position); - obj_outer_bound_points.push_back(tier4_autoware_utils::calcOffsetPose( - ref_path_points_for_obj_poly.at(i).point.pose, 0.0, - object.lat_offset_to_avoid->max_value, 0.0) - .position); + // NOTE: object.lat_offset_to_avoid->min_value is not the minimum value but the inner value. + obj_inner_bound_poses.push_back(tier4_autoware_utils::calcOffsetPose( + ref_path_points_for_obj_poly.at(i).point.pose, 0.0, object.lat_offset_to_avoid->min_value, + 0.0)); } - // create obj_polygon from inner/outer bound points - tier4_autoware_utils::Polygon2d obj_poly; - for (const auto & bound_point : obj_inner_bound_points) { - const auto obj_poly_point = tier4_autoware_utils::Point2d(bound_point.x, bound_point.y); - obj_poly.outer().push_back(obj_poly_point); + // calculate start index laterally feasible for ego to shift considering maximum lateral jerk and + // acceleration + const auto obj_inner_bound_start_idx = [&]() -> std::optional { + const auto & ego_lat_feasible_path = object.is_collision_left + ? object.ego_lat_feasible_paths.left_path + : object.ego_lat_feasible_paths.right_path; + const auto intersect_result = intersectLines(obj_inner_bound_poses, ego_lat_feasible_path); + + // Check if the object polygon intersects with the ego_lat_feasible_path. + if (intersect_result) { + const auto & [bound_seg_idx, intersect_point] = *intersect_result; + const double lon_offset = tier4_autoware_utils::calcDistance2d( + obj_inner_bound_poses.at(bound_seg_idx), intersect_point); + + const auto obj_inner_bound_start_idx_opt = + motion_utils::insertTargetPoint(bound_seg_idx, lon_offset, obj_inner_bound_poses); + if (obj_inner_bound_start_idx_opt) { + return *obj_inner_bound_start_idx_opt; + } + } + + // Check if the object polygon is fully outside the ego_lat_feasible_path. + const double obj_poly_lat_offset = motion_utils::calcLateralOffset( + ego_lat_feasible_path, obj_inner_bound_poses.front().position); + if ( + (!object.is_collision_left && 0 < obj_poly_lat_offset) || + (object.is_collision_left && obj_poly_lat_offset < 0)) { + return std::nullopt; + } + + return 0; + }(); + if (!obj_inner_bound_start_idx) { + return std::nullopt; } - std::reverse(obj_outer_bound_points.begin(), obj_outer_bound_points.end()); - for (const auto & bound_point : obj_outer_bound_points) { - const auto obj_poly_point = tier4_autoware_utils::Point2d(bound_point.x, bound_point.y); - obj_poly.outer().push_back(obj_poly_point); + + // calculate feasible inner/outer bound points + const auto feasible_obj_inner_bound_poses = std::vector( + obj_inner_bound_poses.begin() + *obj_inner_bound_start_idx, obj_inner_bound_poses.end()); + const auto feasible_obj_inner_bound_points = convertToPoints(feasible_obj_inner_bound_poses); + std::vector feasible_obj_outer_bound_points; + for (const auto & feasible_obj_inner_bound_pose : feasible_obj_inner_bound_poses) { + feasible_obj_outer_bound_points.push_back( + tier4_autoware_utils::calcOffsetPose( + feasible_obj_inner_bound_pose, 0.0, + object.lat_offset_to_avoid->max_value - object.lat_offset_to_avoid->min_value, 0.0) + .position); } + // create obj_polygon from inner/outer bound points + tier4_autoware_utils::Polygon2d obj_poly; + const auto add_points_to_obj_poly = [&](const auto & bound_points) { + for (const auto & bound_point : bound_points) { + obj_poly.outer().push_back(tier4_autoware_utils::Point2d(bound_point.x, bound_point.y)); + } + }; + add_points_to_obj_poly(feasible_obj_inner_bound_points); + std::reverse(feasible_obj_outer_bound_points.begin(), feasible_obj_outer_bound_points.end()); + add_points_to_obj_poly(feasible_obj_outer_bound_points); + boost::geometry::correct(obj_poly); return obj_poly; } diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index 73d263319c2d9..f39727246d722 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -117,6 +117,10 @@ void DynamicAvoidanceModuleManager::init(rclcpp::Node * node) p.lpf_gain_for_lat_avoid_to_offset = node->declare_parameter(ns + "lpf_gain_for_lat_avoid_to_offset"); + p.max_ego_lat_acc = node->declare_parameter(ns + "max_ego_lat_acc"); + p.max_ego_lat_jerk = node->declare_parameter(ns + "max_ego_lat_jerk"); + p.delay_time_ego_shift = node->declare_parameter(ns + "delay_time_ego_shift"); + p.max_time_to_collision_overtaking_object = node->declare_parameter(ns + "overtaking_object.max_time_to_collision"); p.start_duration_to_avoid_overtaking_object = @@ -233,6 +237,10 @@ void DynamicAvoidanceModuleManager::updateModuleParams( updateParam( parameters, ns + "lpf_gain_for_lat_avoid_to_offset", p->lpf_gain_for_lat_avoid_to_offset); + updateParam(parameters, ns + "max_ego_lat_acc", p->max_ego_lat_acc); + updateParam(parameters, ns + "max_ego_lat_jerk", p->max_ego_lat_jerk); + updateParam(parameters, ns + "delay_time_ego_shift", p->delay_time_ego_shift); + updateParam( parameters, ns + "overtaking_object.max_time_to_collision", p->max_time_to_collision_overtaking_object); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp index f34c0266ac081..6426f16a44259 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp @@ -66,6 +66,10 @@ MarkerArray createFootprintMarkerArray( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info, const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b); +MarkerArray createPointsMarkerArray( + const std::vector points, const std::string & ns, const int32_t id, const float r, + const float g, const float b); + MarkerArray createPoseMarkerArray( const Pose & pose, std::string && ns, const int32_t & id, const float & r, const float & g, const float & b); diff --git a/planning/behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/behavior_path_planner_common/src/marker_utils/utils.cpp index 7933c21305432..d97ea2e09a89d 100644 --- a/planning/behavior_path_planner_common/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/marker_utils/utils.cpp @@ -74,7 +74,23 @@ MarkerArray createFootprintMarkerArray( MarkerArray marker_array; addFootprintMarker(marker, base_link_pose, vehicle_info); + msg.markers.push_back(marker); + return msg; +} + +MarkerArray createPointsMarkerArray( + const std::vector points, const std::string & ns, const int32_t id, const float r, + const float g, const float b) +{ + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, id, Marker::LINE_STRIP, + createMarkerScale(0.1, 0.0, 0.0), createMarkerColor(r, g, b, 0.999)); + + for (const auto & point : points) { + marker.points.push_back(point); + } + MarkerArray msg; msg.markers.push_back(marker); return msg; } From 2e883b6cd7d2b17bb021b85aec3a91cbe6c61743 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 7 Jan 2024 13:48:49 +0900 Subject: [PATCH 188/276] fix(motion_utils): fix the right bound assignment in resamplePath (#6020) Signed-off-by: Takayuki Murooka --- common/motion_utils/src/resample/resample.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/motion_utils/src/resample/resample.cpp b/common/motion_utils/src/resample/resample.cpp index 1566b493c82f8..834d07a87ea09 100644 --- a/common/motion_utils/src/resample/resample.cpp +++ b/common/motion_utils/src/resample/resample.cpp @@ -486,7 +486,7 @@ autoware_auto_planning_msgs::msg::Path resamplePath( autoware_auto_planning_msgs::msg::Path resampled_path; resampled_path.header = input_path.header; resampled_path.left_bound = input_path.left_bound; - resampled_path.right_bound = resampled_path.right_bound; + resampled_path.right_bound = input_path.right_bound; resampled_path.points.resize(interpolated_pose.size()); for (size_t i = 0; i < resampled_path.points.size(); ++i) { autoware_auto_planning_msgs::msg::PathPoint path_point; From 1d32fb7e0cb2d2cba2869e27416baf3e7e6f5faa Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 7 Jan 2024 13:49:56 +0900 Subject: [PATCH 189/276] feat(motion_utils, etc): add header argument in convertToTrajectory (#6021) * feat(motion_utils, etc): add header argument in convertToTrajectory Signed-off-by: Takayuki Murooka * fix include Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../include/motion_utils/trajectory/conversion.hpp | 4 +++- common/motion_utils/src/trajectory/conversion.cpp | 4 +++- .../utils/trajectory_utils.hpp | 3 --- .../obstacle_avoidance_planner/src/mpt_optimizer.cpp | 9 +++++---- planning/obstacle_avoidance_planner/src/node.cpp | 7 ++++--- .../src/utils/trajectory_utils.cpp | 9 --------- planning/obstacle_cruise_planner/src/node.cpp | 11 +---------- .../include/path_smoother/utils/trajectory_utils.hpp | 3 --- planning/path_smoother/src/elastic_band.cpp | 5 +++-- planning/path_smoother/src/elastic_band_smoother.cpp | 5 +++-- planning/path_smoother/src/utils/trajectory_utils.cpp | 9 --------- .../src/path_to_trajectory.cpp | 11 +---------- .../include/path_sampler/utils/trajectory_utils.hpp | 3 --- .../sampling_based_planner/path_sampler/src/node.cpp | 6 +++--- .../path_sampler/src/utils/trajectory_utils.cpp | 9 --------- 15 files changed, 26 insertions(+), 72 deletions(-) diff --git a/common/motion_utils/include/motion_utils/trajectory/conversion.hpp b/common/motion_utils/include/motion_utils/trajectory/conversion.hpp index 804ae47ff0f4e..6e77c1ec4a186 100644 --- a/common/motion_utils/include/motion_utils/trajectory/conversion.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/conversion.hpp @@ -17,6 +17,7 @@ #include "autoware_auto_planning_msgs/msg/detail/trajectory__struct.hpp" #include "autoware_auto_planning_msgs/msg/detail/trajectory_point__struct.hpp" +#include "std_msgs/msg/header.hpp" #include @@ -34,7 +35,8 @@ namespace motion_utils * points larger than the capacity. (Tier IV) */ autoware_auto_planning_msgs::msg::Trajectory convertToTrajectory( - const std::vector & trajectory); + const std::vector & trajectory, + const std_msgs::msg::Header & header = std_msgs::msg::Header{}); /** * @brief Convert autoware_auto_planning_msgs::msg::Trajectory to diff --git a/common/motion_utils/src/trajectory/conversion.cpp b/common/motion_utils/src/trajectory/conversion.cpp index 97a0bcd06e8cc..f198003d84091 100644 --- a/common/motion_utils/src/trajectory/conversion.cpp +++ b/common/motion_utils/src/trajectory/conversion.cpp @@ -30,9 +30,11 @@ namespace motion_utils * points larger than the capacity. (Tier IV) */ autoware_auto_planning_msgs::msg::Trajectory convertToTrajectory( - const std::vector & trajectory) + const std::vector & trajectory, + const std_msgs::msg::Header & header) { autoware_auto_planning_msgs::msg::Trajectory output{}; + output.header = header; for (const auto & pt : trajectory) output.points.push_back(pt); return output; } diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp index efc75f4c90bba..99c01dcf66960 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp @@ -154,9 +154,6 @@ size_t findEgoSegmentIndex( points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold); } -Trajectory createTrajectory( - const std_msgs::msg::Header & header, const std::vector & traj_points); - std::vector resampleTrajectoryPoints( const std::vector traj_points, const double interval); diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index 47f5f59827267..ee974db9506f8 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -15,6 +15,7 @@ #include "obstacle_avoidance_planner/mpt_optimizer.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "obstacle_avoidance_planner/utils/geometry_utils.hpp" #include "obstacle_avoidance_planner/utils/trajectory_utils.hpp" @@ -1708,17 +1709,17 @@ void MPTOptimizer::publishDebugTrajectories( time_keeper_ptr_->tic(__func__); // reference points - const auto ref_traj = trajectory_utils::createTrajectory( - header, trajectory_utils::convertToTrajectoryPoints(ref_points)); + const auto ref_traj = motion_utils::convertToTrajectory( + trajectory_utils::convertToTrajectoryPoints(ref_points), header); debug_ref_traj_pub_->publish(ref_traj); // fixed reference points const auto fixed_traj_points = extractFixedPoints(ref_points); - const auto fixed_traj = trajectory_utils::createTrajectory(header, fixed_traj_points); + const auto fixed_traj = motion_utils::convertToTrajectory(fixed_traj_points, header); debug_fixed_traj_pub_->publish(fixed_traj); // mpt points - const auto mpt_traj = trajectory_utils::createTrajectory(header, mpt_traj_points); + const auto mpt_traj = motion_utils::convertToTrajectory(mpt_traj_points, header); debug_mpt_traj_pub_->publish(mpt_traj); time_keeper_ptr_->toc(__func__, " "); diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index 6d7367af835b6..cc6b0710c75d5 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -16,6 +16,7 @@ #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/marker/marker_helper.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "obstacle_avoidance_planner/debug_marker.hpp" #include "obstacle_avoidance_planner/utils/geometry_utils.hpp" #include "obstacle_avoidance_planner/utils/trajectory_utils.hpp" @@ -236,7 +237,7 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr) "Backward path is NOT supported. Just converting path to trajectory"); const auto traj_points = trajectory_utils::convertToTrajectoryPoints(path_ptr->points); - const auto output_traj_msg = trajectory_utils::createTrajectory(path_ptr->header, traj_points); + const auto output_traj_msg = motion_utils::convertToTrajectory(traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); return; } @@ -268,7 +269,7 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr) createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime())); const auto output_traj_msg = - trajectory_utils::createTrajectory(path_ptr->header, full_traj_points); + motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); } @@ -656,7 +657,7 @@ void ObstacleAvoidancePlanner::publishDebugData(const Header & header) const // publish trajectories const auto debug_extended_traj = - trajectory_utils::createTrajectory(header, debug_data_ptr_->extended_traj_points); + motion_utils::convertToTrajectory(debug_data_ptr_->extended_traj_points, header); debug_extended_traj_pub_->publish(debug_extended_traj); time_keeper_ptr_->toc(__func__, " "); diff --git a/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp b/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp index b836cee1aeaa6..453d55bd7f770 100644 --- a/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp +++ b/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp @@ -117,15 +117,6 @@ geometry_msgs::msg::Point getNearestPosition( return points.back().pose.position; } -Trajectory createTrajectory( - const std_msgs::msg::Header & header, const std::vector & traj_points) -{ - auto traj = motion_utils::convertToTrajectory(traj_points); - traj.header = header; - - return traj; -} - std::vector resampleTrajectoryPoints( const std::vector traj_points, const double interval) { diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index ccfd731416475..ee1d97f2c6c01 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -171,15 +171,6 @@ std::vector extendTrajectoryPoints( return output_points; } -Trajectory createTrajectory( - const std::vector & traj_points, const std_msgs::msg::Header & header) -{ - auto traj = motion_utils::convertToTrajectory(traj_points); - traj.header = header; - - return traj; -} - std::vector getTargetObjectType(rclcpp::Node & node, const std::string & param_prefix) { std::unordered_map types_map{ @@ -525,7 +516,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms publishVelocityLimit(slow_down_vel_limit, "slow_down"); // 7. Publish trajectory - const auto output_traj = createTrajectory(slow_down_traj_points, msg->header); + const auto output_traj = motion_utils::convertToTrajectory(slow_down_traj_points, msg->header); trajectory_pub_->publish(output_traj); // 8. Publish debug data diff --git a/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp b/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp index a8a97964f21a4..724c1a966781f 100644 --- a/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp +++ b/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp @@ -113,9 +113,6 @@ size_t findEgoSegmentIndex( points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold); } -Trajectory createTrajectory( - const std_msgs::msg::Header & header, const std::vector & traj_points); - Path create_path(Path path_msg, const std::vector & traj_points); std::vector resampleTrajectoryPoints( diff --git a/planning/path_smoother/src/elastic_band.cpp b/planning/path_smoother/src/elastic_band.cpp index ecf847d496f34..8e538a0d6507f 100644 --- a/planning/path_smoother/src/elastic_band.cpp +++ b/planning/path_smoother/src/elastic_band.cpp @@ -14,6 +14,7 @@ #include "path_smoother/elastic_band.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "path_smoother/type_alias.hpp" #include "path_smoother/utils/geometry_utils.hpp" @@ -262,7 +263,7 @@ std::vector EBPathSmoother::smoothTrajectory( // 8. publish eb trajectory const auto eb_traj = - trajectory_utils::createTrajectory(createHeader(clock_.now()), *eb_traj_points); + motion_utils::convertToTrajectory(*eb_traj_points, createHeader(clock_.now())); debug_eb_traj_pub_->publish(eb_traj); time_keeper_ptr_->toc(__func__, " "); @@ -389,7 +390,7 @@ void EBPathSmoother::updateConstraint( // publish fixed trajectory const auto eb_fixed_traj = - trajectory_utils::createTrajectory(createHeader(clock_.now()), debug_fixed_traj_points); + motion_utils::convertToTrajectory(debug_fixed_traj_points, createHeader(clock_.now())); debug_eb_fixed_traj_pub_->publish(eb_fixed_traj); time_keeper_ptr_->toc(__func__, " "); diff --git a/planning/path_smoother/src/elastic_band_smoother.cpp b/planning/path_smoother/src/elastic_band_smoother.cpp index 3247bfd7d3390..8227882cbb61c 100644 --- a/planning/path_smoother/src/elastic_band_smoother.cpp +++ b/planning/path_smoother/src/elastic_band_smoother.cpp @@ -15,6 +15,7 @@ #include "path_smoother/elastic_band_smoother.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "path_smoother/utils/geometry_utils.hpp" #include "path_smoother/utils/trajectory_utils.hpp" #include "rclcpp/time.hpp" @@ -167,7 +168,7 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) "Backward path is NOT supported. Just converting path to trajectory"); const auto traj_points = trajectory_utils::convertToTrajectoryPoints(path_ptr->points); - const auto output_traj_msg = trajectory_utils::createTrajectory(path_ptr->header, traj_points); + const auto output_traj_msg = motion_utils::convertToTrajectory(traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); path_pub_->publish(*path_ptr); return; @@ -220,7 +221,7 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime())); const auto output_traj_msg = - trajectory_utils::createTrajectory(path_ptr->header, full_traj_points); + motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); const auto output_path_msg = trajectory_utils::create_path(*path_ptr, full_traj_points); path_pub_->publish(output_path_msg); diff --git a/planning/path_smoother/src/utils/trajectory_utils.cpp b/planning/path_smoother/src/utils/trajectory_utils.cpp index 872fc65a9d456..6409c61700f34 100644 --- a/planning/path_smoother/src/utils/trajectory_utils.cpp +++ b/planning/path_smoother/src/utils/trajectory_utils.cpp @@ -34,15 +34,6 @@ namespace path_smoother { namespace trajectory_utils { -Trajectory createTrajectory( - const std_msgs::msg::Header & header, const std::vector & traj_points) -{ - auto traj = motion_utils::convertToTrajectory(traj_points); - traj.header = header; - - return traj; -} - Path create_path(Path path_msg, const std::vector & traj_points) { path_msg.points.clear(); diff --git a/planning/planning_topic_converter/src/path_to_trajectory.cpp b/planning/planning_topic_converter/src/path_to_trajectory.cpp index f5df79121029b..757dcd0d9f632 100644 --- a/planning/planning_topic_converter/src/path_to_trajectory.cpp +++ b/planning/planning_topic_converter/src/path_to_trajectory.cpp @@ -40,15 +40,6 @@ std::vector convertToTrajectoryPoints(const std::vector & trajectory_points) -{ - auto trajectory = motion_utils::convertToTrajectory(trajectory_points); - trajectory.header = header; - - return trajectory; -} } // namespace PathToTrajectory::PathToTrajectory(const rclcpp::NodeOptions & options) @@ -59,7 +50,7 @@ PathToTrajectory::PathToTrajectory(const rclcpp::NodeOptions & options) void PathToTrajectory::process(const Path::ConstSharedPtr msg) { const auto trajectory_points = convertToTrajectoryPoints(msg->points); - const auto output = createTrajectory(msg->header, trajectory_points); + const auto output = motion_utils::convertToTrajectory(trajectory_points, msg->header); pub_->publish(output); } diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/utils/trajectory_utils.hpp b/planning/sampling_based_planner/path_sampler/include/path_sampler/utils/trajectory_utils.hpp index c0a3c1d917c25..d848e9b209d28 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/utils/trajectory_utils.hpp +++ b/planning/sampling_based_planner/path_sampler/include/path_sampler/utils/trajectory_utils.hpp @@ -138,9 +138,6 @@ size_t findEgoSegmentIndex( points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold); } -Trajectory createTrajectory( - const std_msgs::msg::Header & header, const std::vector & traj_points); - std::vector resampleTrajectoryPoints( const std::vector traj_points, const double interval); diff --git a/planning/sampling_based_planner/path_sampler/src/node.cpp b/planning/sampling_based_planner/path_sampler/src/node.cpp index e61f635de67c4..748486edf9ff6 100644 --- a/planning/sampling_based_planner/path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/path_sampler/src/node.cpp @@ -16,6 +16,7 @@ #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/marker/marker_helper.hpp" +#include "motion_utils/trajectory/conversion.hpp" #include "path_sampler/path_generation.hpp" #include "path_sampler/prepare_inputs.hpp" #include "path_sampler/utils/geometry_utils.hpp" @@ -244,13 +245,12 @@ void PathSampler::onPath(const Path::SharedPtr path_ptr) if (!generated_traj_points.empty()) { auto full_traj_points = extendTrajectory(planner_data.traj_points, generated_traj_points); const auto output_traj_msg = - trajectory_utils::createTrajectory(path_ptr->header, full_traj_points); + motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); } else { auto stopping_traj = trajectory_utils::convertToTrajectoryPoints(planner_data.traj_points); for (auto & p : stopping_traj) p.longitudinal_velocity_mps = 0.0; - const auto output_traj_msg = - trajectory_utils::createTrajectory(path_ptr->header, stopping_traj); + const auto output_traj_msg = motion_utils::convertToTrajectory(stopping_traj, path_ptr->header); traj_pub_->publish(output_traj_msg); } diff --git a/planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp b/planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp index 76fa90c6baa4b..ad516faa717ff 100644 --- a/planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp +++ b/planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp @@ -58,15 +58,6 @@ void compensateLastPose( } } -Trajectory createTrajectory( - const std_msgs::msg::Header & header, const std::vector & traj_points) -{ - auto traj = motion_utils::convertToTrajectory(traj_points); - traj.header = header; - - return traj; -} - std::vector resampleTrajectoryPoints( const std::vector traj_points, const double interval) { From 5a1560dbdeb4bba009e8b334124e688ffe3c06b4 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 7 Jan 2024 20:13:00 +0900 Subject: [PATCH 190/276] chore(mission_planner): use RCLCPP_DEBUG for debug printing (#6024) Signed-off-by: Takayuki Murooka --- .../mission_planner/src/lanelet2_plugins/default_planner.cpp | 2 +- .../mission_planner/src/mission_planner/mission_planner.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index ed364f0987f4f..5d1c0c68d8208 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -400,7 +400,7 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) log_ss << "x: " << point.position.x << " " << "y: " << point.position.y << std::endl; } - RCLCPP_INFO_STREAM( + RCLCPP_DEBUG_STREAM( logger, "start planning route with check points: " << std::endl << log_ss.str()); diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index a1536a1bebfbf..9ee874928d7d1 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -144,7 +144,7 @@ void MissionPlanner::checkInitialization() } // All data is ready. Now API is available. - RCLCPP_INFO(get_logger(), "Route API is ready."); + RCLCPP_DEBUG(get_logger(), "Route API is ready."); change_state(RouteState::Message::UNSET); data_check_timer_->cancel(); // stop timer callback } From 2c185133aadc4d54eca1506e4557d10bdfbd4e70 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Mon, 8 Jan 2024 22:26:27 +0900 Subject: [PATCH 191/276] chore(autoware_auto_perception_rviz_plugin): add existence probability for rviz (#5986) * chore: add existence prob for rviz objects Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * chore: adjust text position Signed-off-by: badai-nguyen * fix: add existence prob for tracked and predicted objects Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- .../object_polygon_detail.hpp | 6 +++++ .../object_polygon_display_base.hpp | 22 ++++++++++++++++++- .../detected_objects_display.cpp | 16 ++++++++++++++ .../object_polygon_detail.cpp | 17 ++++++++++++++ .../predicted_objects_display.cpp | 19 ++++++++++++++++ .../tracked_objects_display.cpp | 16 +++++++++++++- 6 files changed, 94 insertions(+), 2 deletions(-) diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp index 1fdc44df11183..b661010c19a4d 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_detail.hpp @@ -19,6 +19,7 @@ #include #include +#include #include #include #include @@ -98,6 +99,11 @@ get_label_marker_ptr( const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, const std::string label, const std_msgs::msg::ColorRGBA & color_rgba); +AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr +get_existence_probability_marker_ptr( + const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, + const float existence_probability, const std_msgs::msg::ColorRGBA & color_rgba); + AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr get_uuid_marker_ptr( const std::string & uuid, const geometry_msgs::msg::Point & centroid, diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp index 683877f6429bd..9157dffe97785 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp @@ -77,6 +77,11 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase m_display_path_confidence_property{ "Display Predicted Path Confidence", true, "Enable/disable predicted paths visualization", this}, + + m_display_existence_probability_property{ + "Display Existence Probability", false, "Enable/disable existence probability visualization", + this}, + m_line_width_property{"Line Width", 0.03, "Line width of object-shape", this}, m_default_topic{default_topic} { @@ -202,6 +207,19 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase return std::nullopt; } } + template + std::optional get_existence_probability_marker_ptr( + const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, + const float existence_probability, const ClassificationContainerT & labels) const + { + if (m_display_existence_probability_property.getBool()) { + const std_msgs::msg::ColorRGBA color_rgba = get_color_rgba(labels); + return detail::get_existence_probability_marker_ptr( + centroid, orientation, existence_probability, color_rgba); + } else { + return std::nullopt; + } + } template std::optional get_uuid_marker_ptr( @@ -326,7 +344,6 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase } return (it->second).label; } - std::string uuid_to_string(const unique_identifier_msgs::msg::UUID & u) const { std::stringstream ss; @@ -415,6 +432,9 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase rviz_common::properties::BoolProperty m_display_predicted_paths_property; // Property to enable/disable predicted path confidence visualization rviz_common::properties::BoolProperty m_display_path_confidence_property; + + rviz_common::properties::BoolProperty m_display_existence_probability_property; + // Property to decide line width of object shape rviz_common::properties::FloatProperty m_line_width_property; // Default topic name to be visualized diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp index 2ba80fddc1f34..5dcdce791c585 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp @@ -57,6 +57,22 @@ void DetectedObjectsDisplay::processMessage(DetectedObjects::ConstSharedPtr msg) add_marker(label_marker_ptr); } + // Get marker for existence probability + geometry_msgs::msg::Point existence_probability_position; + existence_probability_position.x = object.kinematics.pose_with_covariance.pose.position.x + 0.5; + existence_probability_position.y = object.kinematics.pose_with_covariance.pose.position.y; + existence_probability_position.z = object.kinematics.pose_with_covariance.pose.position.z + 0.5; + const float existence_probability = object.existence_probability; + auto existence_prob_marker = get_existence_probability_marker_ptr( + existence_probability_position, object.kinematics.pose_with_covariance.pose.orientation, + existence_probability, object.classification); + if (existence_prob_marker) { + auto existence_prob_marker_ptr = existence_prob_marker.value(); + existence_prob_marker_ptr->header = msg->header; + existence_prob_marker_ptr->id = id++; + add_marker(existence_prob_marker_ptr); + } + // Get marker for velocity text geometry_msgs::msg::Point vel_vis_position; vel_vis_position.x = object.kinematics.pose_with_covariance.pose.position.x - 0.5; diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp index d10bc8ef5ab9d..d87541b7840a9 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp @@ -242,6 +242,23 @@ visualization_msgs::msg::Marker::SharedPtr get_label_marker_ptr( return marker_ptr; } +visualization_msgs::msg::Marker::SharedPtr get_existence_probability_marker_ptr( + const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, + const float existence_probability, const std_msgs::msg::ColorRGBA & color_rgba) +{ + auto marker_ptr = std::make_shared(); + marker_ptr->type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + marker_ptr->ns = std::string("existence probability"); + marker_ptr->scale.x = 0.5; + marker_ptr->scale.z = 0.5; + marker_ptr->text = std::to_string(existence_probability); + marker_ptr->action = visualization_msgs::msg::Marker::MODIFY; + marker_ptr->pose = marker_ptr->pose = to_pose(centroid, orientation); + marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.2); + marker_ptr->color = color_rgba; + return marker_ptr; +} + visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp index 5aca4290e5ac3..438d70f052b4a 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp @@ -121,6 +121,25 @@ std::vector PredictedObjectsDisplay: markers.push_back(pose_with_covariance_marker_ptr); } + // Get marker for existence probability + geometry_msgs::msg::Point existence_probability_position; + existence_probability_position.x = + object.kinematics.initial_pose_with_covariance.pose.position.x + 0.5; + existence_probability_position.y = + object.kinematics.initial_pose_with_covariance.pose.position.y; + existence_probability_position.z = + object.kinematics.initial_pose_with_covariance.pose.position.z + 0.5; + const float existence_probability = object.existence_probability; + auto existence_prob_marker = get_existence_probability_marker_ptr( + existence_probability_position, + object.kinematics.initial_pose_with_covariance.pose.orientation, existence_probability, + object.classification); + if (existence_prob_marker) { + auto existence_prob_marker_ptr = existence_prob_marker.value(); + existence_prob_marker_ptr->header = msg->header; + existence_prob_marker_ptr->id = uuid_to_marker_id(object.object_id); + markers.push_back(existence_prob_marker_ptr); + } // Get marker for velocity text geometry_msgs::msg::Point vel_vis_position; vel_vis_position.x = uuid_vis_position.x - 0.5; diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp index 603e39f0c46b5..75b094b49a762 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp @@ -102,7 +102,21 @@ void TrackedObjectsDisplay::processMessage(TrackedObjects::ConstSharedPtr msg) pose_with_covariance_marker_ptr->id = uuid_to_marker_id(object.object_id); add_marker(pose_with_covariance_marker_ptr); } - + // Get marker for existence probability + geometry_msgs::msg::Point existence_probability_position; + existence_probability_position.x = object.kinematics.pose_with_covariance.pose.position.x + 0.5; + existence_probability_position.y = object.kinematics.pose_with_covariance.pose.position.y; + existence_probability_position.z = object.kinematics.pose_with_covariance.pose.position.z + 0.5; + const float existence_probability = object.existence_probability; + auto existence_prob_marker = get_existence_probability_marker_ptr( + existence_probability_position, object.kinematics.pose_with_covariance.pose.orientation, + existence_probability, object.classification); + if (existence_prob_marker) { + auto existence_prob_marker_ptr = existence_prob_marker.value(); + existence_prob_marker_ptr->header = msg->header; + existence_prob_marker_ptr->id = uuid_to_marker_id(object.object_id); + add_marker(existence_prob_marker_ptr); + } // Get marker for velocity text geometry_msgs::msg::Point vel_vis_position; vel_vis_position.x = uuid_vis_position.x - 0.5; From 261e915c9ea06ef7e7427a57ae6f8b5d3ddd5b4c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 8 Jan 2024 23:28:46 +0900 Subject: [PATCH 192/276] fix(static_centerline_optimizer): fix several bugs and refactor the code (#6022) * fix(static_centerline_optimizer): fix several bugs and refactor the code Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../mpt_optimizer.hpp | 3 +- .../obstacle_avoidance_planner/node.hpp | 5 + .../src/mpt_optimizer.cpp | 7 +- .../obstacle_avoidance_planner/src/node.cpp | 2 +- .../path_smoother/elastic_band_smoother.hpp | 6 +- .../CMakeLists.txt | 1 - .../static_centerline_optimizer_node.hpp | 2 + .../successive_trajectory_optimizer_node.hpp | 45 ------ .../static_centerline_optimizer.launch.xml | 7 + .../static_centerline_optimizer/package.xml | 1 + .../scripts/tmp/run.sh | 3 + .../src/static_centerline_optimizer_node.cpp | 133 +++++++++++++++--- .../successive_trajectory_optimizer_node.cpp | 111 --------------- .../test_static_centerline_optimizer.test.py | 8 ++ 14 files changed, 152 insertions(+), 182 deletions(-) delete mode 100644 planning/static_centerline_optimizer/include/static_centerline_optimizer/successive_trajectory_optimizer_node.hpp create mode 100755 planning/static_centerline_optimizer/scripts/tmp/run.sh delete mode 100644 planning/static_centerline_optimizer/src/successive_trajectory_optimizer_node.cpp diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp index b87cfc7a1e743..edcabec14930d 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp @@ -109,8 +109,7 @@ class MPTOptimizer const std::shared_ptr debug_data_ptr, const std::shared_ptr time_keeper_ptr); - std::vector optimizeTrajectory( - const PlannerData & planner_data, const std::vector & smoothed_points); + std::vector optimizeTrajectory(const PlannerData & planner_data); std::optional> getPrevOptimizedTrajectoryPoints() const; void initialize(const bool enable_debug_info, const TrajectoryParam & traj_param); diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp index fe7c416799231..9ca2f31b6ec5a 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp @@ -37,6 +37,11 @@ class ObstacleAvoidancePlanner : public rclcpp::Node public: explicit ObstacleAvoidancePlanner(const rclcpp::NodeOptions & node_options); + // NOTE: This is for the static_centerline_optimizer package which utilizes the following + // instance. + std::shared_ptr getMPTOptimizer() const { return mpt_optimizer_ptr_; } + + // private: protected: // for the static_centerline_optimizer package // TODO(murooka) move this node to common class DrivingDirectionChecker diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index ee974db9506f8..7057a2885fd52 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -468,8 +468,7 @@ void MPTOptimizer::onParam(const std::vector & parameters) debug_data_ptr_->mpt_visualize_sampling_num = mpt_param_.mpt_visualize_sampling_num; } -std::vector MPTOptimizer::optimizeTrajectory( - const PlannerData & planner_data, const std::vector & smoothed_points) +std::vector MPTOptimizer::optimizeTrajectory(const PlannerData & planner_data) { time_keeper_ptr_->tic(__func__); @@ -480,11 +479,11 @@ std::vector MPTOptimizer::optimizeTrajectory( if (prev_optimized_traj_points_ptr_) { return *prev_optimized_traj_points_ptr_; } - return smoothed_points; + return traj_points; }; // 1. calculate reference points - auto ref_points = calcReferencePoints(planner_data, smoothed_points); + auto ref_points = calcReferencePoints(planner_data, traj_points); if (ref_points.size() < 2) { RCLCPP_INFO_EXPRESSION( logger_, enable_debug_info_, "return std::nullopt since ref_points size is less than 2."); diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index cc6b0710c75d5..23b146a3e5280 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -364,7 +364,7 @@ std::vector ObstacleAvoidancePlanner::optimizeTrajectory( // 2. make trajectory kinematically-feasible and collision-free (= inside the drivable area) // with model predictive trajectory - const auto mpt_traj = mpt_optimizer_ptr_->optimizeTrajectory(planner_data, p.traj_points); + const auto mpt_traj = mpt_optimizer_ptr_->optimizeTrajectory(planner_data); time_keeper_ptr_->toc(__func__, " "); return mpt_traj; diff --git a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp index bbcc8e7c071f6..364e1e3cc43d8 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp +++ b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp @@ -36,7 +36,11 @@ class ElasticBandSmoother : public rclcpp::Node public: explicit ElasticBandSmoother(const rclcpp::NodeOptions & node_options); -protected: + // NOTE: This is for the static_centerline_optimizer package which utilizes the following + // instance. + std::shared_ptr getElasticBandSmoother() const { return eb_path_smoother_ptr_; } + +private: class DrivingDirectionChecker { public: diff --git a/planning/static_centerline_optimizer/CMakeLists.txt b/planning/static_centerline_optimizer/CMakeLists.txt index 4731d44ed30bb..a2091dffd061a 100644 --- a/planning/static_centerline_optimizer/CMakeLists.txt +++ b/planning/static_centerline_optimizer/CMakeLists.txt @@ -24,7 +24,6 @@ autoware_package() ament_auto_add_executable(main src/main.cpp src/static_centerline_optimizer_node.cpp - src/successive_trajectory_optimizer_node.cpp src/utils.cpp ) diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index cfee93fbc0bbe..fa7043de42f5c 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -52,6 +52,7 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node // plan path std::vector plan_path(const std::vector & route_lane_ids); + std::vector optimize_trajectory(const Path & raw_path) const; void on_plan_path( const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response); @@ -62,6 +63,7 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node const std::string & lanelet2_output_file_path, const std::vector & route_lane_ids, const std::vector & optimized_traj_points); + lanelet::LaneletMapPtr original_map_ptr_{nullptr}; HADMapBin::ConstSharedPtr map_bin_ptr_{nullptr}; std::shared_ptr route_handler_ptr_{nullptr}; diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/successive_trajectory_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/successive_trajectory_optimizer_node.hpp deleted file mode 100644 index 57ebb947b03c2..0000000000000 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/successive_trajectory_optimizer_node.hpp +++ /dev/null @@ -1,45 +0,0 @@ -// Copyright 2022 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -// NOTE: This file was copied from a part of implementation in -// https://github.com/autowarefoundation/autoware.universe/blob/main/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp - -#ifndef STATIC_CENTERLINE_OPTIMIZER__SUCCESSIVE_TRAJECTORY_OPTIMIZER_NODE_HPP_ -#define STATIC_CENTERLINE_OPTIMIZER__SUCCESSIVE_TRAJECTORY_OPTIMIZER_NODE_HPP_ - -#include "obstacle_avoidance_planner/node.hpp" -#include "static_centerline_optimizer/type_alias.hpp" - -#include -#include -#include -#include - -namespace static_centerline_optimizer -{ -class SuccessiveTrajectoryOptimizer : public obstacle_avoidance_planner::ObstacleAvoidancePlanner -{ -private: - // subscriber - rclcpp::Subscription::SharedPtr centerline_sub_; - -public: - explicit SuccessiveTrajectoryOptimizer(const rclcpp::NodeOptions & node_options); - - // subscriber callback functions - Trajectory on_centerline(const Path & path); -}; -} // namespace static_centerline_optimizer - -#endif // STATIC_CENTERLINE_OPTIMIZER__SUCCESSIVE_TRAJECTORY_OPTIMIZER_NODE_HPP_ diff --git a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml index f727c0e58d327..f8b96ca0db146 100644 --- a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml +++ b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml @@ -17,6 +17,11 @@ + + + + diff --git a/planning/static_centerline_optimizer/package.xml b/planning/static_centerline_optimizer/package.xml index 89976be5bdd47..51bd9e87d6ba2 100644 --- a/planning/static_centerline_optimizer/package.xml +++ b/planning/static_centerline_optimizer/package.xml @@ -28,6 +28,7 @@ motion_utils obstacle_avoidance_planner osqp_interface + path_smoother rclcpp rclcpp_components route_handler diff --git a/planning/static_centerline_optimizer/scripts/tmp/run.sh b/planning/static_centerline_optimizer/scripts/tmp/run.sh new file mode 100755 index 0000000000000..07857a9d923a1 --- /dev/null +++ b/planning/static_centerline_optimizer/scripts/tmp/run.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml run_background:=false lanelet2_input_file_path:="$HOME/AutonomousDrivingScenarios/map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index 0aeec7be0b55d..f2d9dc68a8cdc 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -18,9 +18,11 @@ #include "lanelet2_extension/utility/query.hpp" #include "lanelet2_extension/utility/utilities.hpp" #include "map_loader/lanelet2_map_loader_node.hpp" +#include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" +#include "obstacle_avoidance_planner/node.hpp" +#include "path_smoother/elastic_band_smoother.hpp" #include "static_centerline_optimizer/msg/points_with_lane_id.hpp" -#include "static_centerline_optimizer/successive_trajectory_optimizer_node.hpp" #include "static_centerline_optimizer/type_alias.hpp" #include "static_centerline_optimizer/utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -62,6 +64,21 @@ Path convert_to_path(const PathWithLaneId & path_with_lane_id) return path; } +Trajectory convert_to_trajectory(const Path & path) +{ + Trajectory traj; + for (const auto & point : path.points) { + TrajectoryPoint traj_point; + traj_point.pose = point.pose; + traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; + traj_point.lateral_velocity_mps = point.lateral_velocity_mps; + traj_point.heading_rate_rps = point.heading_rate_rps; + + traj.points.push_back(traj_point); + } + return traj; +} + [[maybe_unused]] lanelet::ConstLanelets get_lanelets_from_route( const RouteHandler & route_handler, const LaneletRoute & route) { @@ -249,14 +266,22 @@ void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_ // load map by the map_loader package map_bin_ptr_ = [&]() -> HADMapBin::ConstSharedPtr { // load map - lanelet::LaneletMapPtr map_ptr; tier4_map_msgs::msg::MapProjectorInfo map_projector_info; map_projector_info.projector_type = tier4_map_msgs::msg::MapProjectorInfo::MGRS; - map_ptr = Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, map_projector_info); + const auto map_ptr = + Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, map_projector_info); if (!map_ptr) { return nullptr; } + // NOTE: The original map is stored here since the various ids in the lanelet map will change + // after lanelet::utils::overwriteLaneletCenterline, and saving map will fail. + original_map_ptr_ = + Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, map_projector_info); + + // overwrite more dense centerline + lanelet::utils::overwriteLaneletsCenterline(map_ptr, 5.0, false); + // create map bin msg const auto map_bin_msg = Lanelet2MapLoaderNode::create_map_bin_msg(map_ptr, lanelet2_input_file_path, now()); @@ -388,7 +413,7 @@ std::vector StaticCenterlineOptimizerNode::plan_path( const auto start_center_pose = utils::get_center_pose(*route_handler_ptr_, route_lane_ids.front()); - // ego nearest search parameters + // get ego nearest search parameters and resample interval in behavior_path_planner const double ego_nearest_dist_threshold = has_parameter("ego_nearest_dist_threshold") ? get_parameter("ego_nearest_dist_threshold").as_double() @@ -397,31 +422,105 @@ std::vector StaticCenterlineOptimizerNode::plan_path( has_parameter("ego_nearest_yaw_threshold") ? get_parameter("ego_nearest_yaw_threshold").as_double() : declare_parameter("ego_nearest_yaw_threshold"); + const double behavior_path_interval = has_parameter("output_path_interval") + ? get_parameter("output_path_interval").as_double() + : declare_parameter("output_path_interval"); // extract path with lane id from lanelets - const auto raw_path_with_lane_id = utils::get_path_with_lane_id( - *route_handler_ptr_, route_lanelets, start_center_pose, ego_nearest_dist_threshold, - ego_nearest_yaw_threshold); - + const auto raw_path_with_lane_id = [&]() { + const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id( + *route_handler_ptr_, route_lanelets, start_center_pose, ego_nearest_dist_threshold, + ego_nearest_yaw_threshold); + return motion_utils::resamplePath(non_resampled_path_with_lane_id, behavior_path_interval); + }(); pub_raw_path_with_lane_id_->publish(raw_path_with_lane_id); RCLCPP_INFO(get_logger(), "Calculated raw path with lane id and published."); // convert path with lane id to path - const auto raw_path = convert_to_path(raw_path_with_lane_id); + const auto raw_path = [&]() { + const auto non_resampled_path = convert_to_path(raw_path_with_lane_id); + // NOTE: The behavior_velocity_planner resamples with the interval 1.0 somewhere. + return motion_utils::resamplePath(non_resampled_path, 1.0); + }(); pub_raw_path_->publish(raw_path); RCLCPP_INFO(get_logger(), "Converted to path and published."); - // optimize trajectory by the obstacle_avoidance_planner package - SuccessiveTrajectoryOptimizer successive_trajectory_optimizer(create_node_options()); - const auto optimized_traj = successive_trajectory_optimizer.on_centerline(raw_path); - pub_optimized_centerline_->publish(optimized_traj); - const auto optimized_traj_points = motion_utils::convertToTrajectoryPointArray(optimized_traj); - - RCLCPP_INFO(get_logger(), "Optimized trajectory and published."); + // smooth trajectory and road collision avoidance + const auto optimized_traj_points = optimize_trajectory(raw_path); + pub_optimized_centerline_->publish( + motion_utils::convertToTrajectory(optimized_traj_points, raw_path.header)); + RCLCPP_INFO( + get_logger(), "Smoothed trajectory and made it collision free with the road and published."); return optimized_traj_points; } +std::vector StaticCenterlineOptimizerNode::optimize_trajectory( + const Path & raw_path) const +{ + // convert to trajectory points + const auto raw_traj_points = [&]() { + const auto raw_traj = convert_to_trajectory(raw_path); + return motion_utils::convertToTrajectoryPointArray(raw_traj); + }(); + + // create an instance of elastic band and model predictive trajectory. + const auto eb_path_smoother_ptr = + path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); + const auto mpt_optimizer_ptr = + obstacle_avoidance_planner::ObstacleAvoidancePlanner(create_node_options()).getMPTOptimizer(); + + // NOTE: The optimization is executed every valid_optimized_traj_points_num points. + constexpr int valid_optimized_traj_points_num = 10; + const int traj_segment_num = raw_traj_points.size() / valid_optimized_traj_points_num; + + // NOTE: num_initial_optimization exists to make the both optimizations stable since they may use + // warm start. + constexpr int num_initial_optimization = 2; + + std::vector whole_optimized_traj_points; + for (int virtual_ego_pose_idx = -num_initial_optimization; + virtual_ego_pose_idx < traj_segment_num; ++virtual_ego_pose_idx) { + // calculate virtual ego pose for the optimization + constexpr int virtual_ego_pose_offset_idx = 1; + const auto virtual_ego_pose = + raw_traj_points + .at( + valid_optimized_traj_points_num * std::max(virtual_ego_pose_idx, 0) + + virtual_ego_pose_offset_idx) + .pose; + + // smooth trajectory by elastic band in the path_smoother package + const auto smoothed_traj_points = + eb_path_smoother_ptr->smoothTrajectory(raw_traj_points, virtual_ego_pose); + + // road collision avoidance by model predictive trajectory in the obstacle_avoidance_planner + // package + const obstacle_avoidance_planner::PlannerData planner_data{ + raw_path.header, smoothed_traj_points, raw_path.left_bound, raw_path.right_bound, + virtual_ego_pose}; + const auto optimized_traj_points = mpt_optimizer_ptr->optimizeTrajectory(planner_data); + + // connect the previously and currently optimized trajectory points + for (size_t j = 0; j < whole_optimized_traj_points.size(); ++j) { + const double dist = tier4_autoware_utils::calcDistance2d( + whole_optimized_traj_points.at(j), optimized_traj_points.front()); + if (dist < 0.5) { + const std::vector extracted_whole_optimized_traj_points{ + whole_optimized_traj_points.begin(), + whole_optimized_traj_points.begin() + std::max(j, 1UL) - 1}; + whole_optimized_traj_points = extracted_whole_optimized_traj_points; + break; + } + } + for (size_t j = 0; j < optimized_traj_points.size(); ++j) { + whole_optimized_traj_points.push_back(optimized_traj_points.at(j)); + } + } + + return whole_optimized_traj_points; +} + void StaticCenterlineOptimizerNode::on_plan_path( const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response) { @@ -581,7 +680,7 @@ void StaticCenterlineOptimizerNode::save_map( RCLCPP_INFO(get_logger(), "Updated centerline in map."); // save map with modified center line - lanelet::write(lanelet2_output_file_path, *route_handler_ptr_->getLaneletMapPtr()); + lanelet::write(lanelet2_output_file_path, *original_map_ptr_); RCLCPP_INFO(get_logger(), "Saved map."); } } // namespace static_centerline_optimizer diff --git a/planning/static_centerline_optimizer/src/successive_trajectory_optimizer_node.cpp b/planning/static_centerline_optimizer/src/successive_trajectory_optimizer_node.cpp deleted file mode 100644 index a8663abb2eab7..0000000000000 --- a/planning/static_centerline_optimizer/src/successive_trajectory_optimizer_node.cpp +++ /dev/null @@ -1,111 +0,0 @@ -// Copyright 2022 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "static_centerline_optimizer/successive_trajectory_optimizer_node.hpp" - -#include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/conversion.hpp" -#include "motion_utils/trajectory/trajectory.hpp" -#include "obstacle_avoidance_planner/utils/trajectory_utils.hpp" -#include "tier4_autoware_utils/geometry/geometry.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" - -#include -#include -#include -#include -#include -#include - -namespace static_centerline_optimizer -{ -SuccessiveTrajectoryOptimizer::SuccessiveTrajectoryOptimizer( - const rclcpp::NodeOptions & node_options) -: ObstacleAvoidancePlanner(node_options) -{ - // subscriber - centerline_sub_ = create_subscription( - "debug/raw_centerline", rclcpp::QoS{1}.transient_local(), - std::bind(&SuccessiveTrajectoryOptimizer::on_centerline, this, std::placeholders::_1)); - - // update parameters for replan_checker to execute optimization every cycle - std::vector parameters; - parameters.push_back(rclcpp::Parameter("replan.max_path_shape_around_ego_lat_dist", 100.0)); - parameters.push_back(rclcpp::Parameter("replan.max_ego_moving_dist", 100.0)); - parameters.push_back(rclcpp::Parameter("replan.max_goal_moving_dist", 100.0)); - parameters.push_back(rclcpp::Parameter("replan.max_delta_time_sec", 0.0)); - onParam(parameters); -} - -Trajectory SuccessiveTrajectoryOptimizer::on_centerline(const Path & path) -{ - if (path.points.size() < 2) { - RCLCPP_WARN(get_logger(), "Input path size is less than 2."); - return Trajectory{}; - } - - // parameters for input path sampling - const double resample_interval = 2.0; - const double valid_optimized_path_length = 30.0; - const double path_length = motion_utils::calcArcLength(path.points); - const size_t path_segment_num = static_cast(path_length / valid_optimized_path_length); - - const auto resampled_path = motion_utils::resamplePath(path, resample_interval); // TODO(murooka) - const auto resampled_traj_points = - obstacle_avoidance_planner::trajectory_utils::convertToTrajectoryPoints(resampled_path.points); - - const size_t initial_index = 3; - std::vector whole_optimized_traj_points; - - for (size_t i = 0; i < path_segment_num; ++i) { - // calculate initial pose to start optimization - const auto initial_pose = - resampled_path.points.at(initial_index + valid_optimized_path_length / resample_interval * i) - .pose; - - // create planner data - obstacle_avoidance_planner::PlannerData planner_data; - planner_data.traj_points = resampled_traj_points; - planner_data.left_bound = path.left_bound; - planner_data.right_bound = path.right_bound; - planner_data.ego_pose = initial_pose; - - const auto optimized_traj_points = optimizeTrajectory(planner_data); - - for (size_t j = 0; j < whole_optimized_traj_points.size(); ++j) { - const double dist = tier4_autoware_utils::calcDistance2d( - whole_optimized_traj_points.at(j), optimized_traj_points.front()); - if (dist < 0.5) { - const std::vector extracted_whole_optimized_traj_points{ - whole_optimized_traj_points.begin(), whole_optimized_traj_points.begin() + j - 1}; - whole_optimized_traj_points = extracted_whole_optimized_traj_points; - } - } - - for (size_t j = 0; j < optimized_traj_points.size(); ++j) { - whole_optimized_traj_points.push_back(optimized_traj_points.at(j)); - } - } - - // resample - auto output_traj_msg = motion_utils::resampleTrajectory( - motion_utils::convertToTrajectory(whole_optimized_traj_points), 1.0); - output_traj_msg.header = path.header; - - return output_traj_msg; -} -} // namespace static_centerline_optimizer - -#include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(static_centerline_optimizer::SuccessiveTrajectoryOptimizer) diff --git a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py b/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py index 549ddbd7e5245..141743deb007c 100644 --- a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py +++ b/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py @@ -52,6 +52,14 @@ def generate_test_description(): get_package_share_directory("static_centerline_optimizer"), "config/static_centerline_optimizer.param.yaml", ), + os.path.join( + get_package_share_directory("behavior_path_planner"), + "config/behavior_path_planner.param.yaml", + ), + os.path.join( + get_package_share_directory("path_smoother"), + "config/elastic_band_smoother.param.yaml", + ), os.path.join( get_package_share_directory("obstacle_avoidance_planner"), "config/obstacle_avoidance_planner.param.yaml", From 01770488b9876aea927f9fe748e8b861113d1f32 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Mon, 8 Jan 2024 18:51:59 +0000 Subject: [PATCH 193/276] build(multi_object_tracker): add missing diagnostic_updater dependency (#6025) Signed-off-by: Esteve Fernandez --- perception/multi_object_tracker/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/perception/multi_object_tracker/package.xml b/perception/multi_object_tracker/package.xml index 3d2e4662f7ea5..763bd12fab79e 100644 --- a/perception/multi_object_tracker/package.xml +++ b/perception/multi_object_tracker/package.xml @@ -13,6 +13,7 @@ eigen3_cmake_module autoware_auto_perception_msgs + diagnostic_updater eigen kalman_filter libgoogle-glog-dev From 4a08ed410e22c6120f4e40a891ed3f389bb2b450 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 9 Jan 2024 09:36:15 +0900 Subject: [PATCH 194/276] refactor(ndt_scan_matcher): removed tf2_listener_module (#6008) Removed tf2_listener_module Signed-off-by: Shintaro SAKODA --- localization/localization_util/CMakeLists.txt | 1 - .../localization_util/tf2_listener_module.hpp | 43 ------------- .../src/tf2_listener_module.cpp | 60 ------------------- .../ndt_scan_matcher/map_update_module.hpp | 1 - .../ndt_scan_matcher_core.hpp | 6 +- .../src/ndt_scan_matcher_core.cpp | 50 ++++++++++++---- 6 files changed, 43 insertions(+), 118 deletions(-) delete mode 100644 localization/localization_util/include/localization_util/tf2_listener_module.hpp delete mode 100644 localization/localization_util/src/tf2_listener_module.cpp diff --git a/localization/localization_util/CMakeLists.txt b/localization/localization_util/CMakeLists.txt index ade446020d101..fe65077d89649 100644 --- a/localization/localization_util/CMakeLists.txt +++ b/localization/localization_util/CMakeLists.txt @@ -6,7 +6,6 @@ autoware_package() ament_auto_add_library(localization_util SHARED src/util_func.cpp - src/tf2_listener_module.cpp src/smart_pose_buffer.cpp ) diff --git a/localization/localization_util/include/localization_util/tf2_listener_module.hpp b/localization/localization_util/include/localization_util/tf2_listener_module.hpp deleted file mode 100644 index b332f9effe0e0..0000000000000 --- a/localization/localization_util/include/localization_util/tf2_listener_module.hpp +++ /dev/null @@ -1,43 +0,0 @@ -// Copyright 2015-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef LOCALIZATION_UTIL__TF2_LISTENER_MODULE_HPP_ -#define LOCALIZATION_UTIL__TF2_LISTENER_MODULE_HPP_ - -#include - -#include -#include -#include - -#include - -class Tf2ListenerModule -{ - using TransformStamped = geometry_msgs::msg::TransformStamped; - -public: - explicit Tf2ListenerModule(rclcpp::Node * node); - bool get_transform( - const builtin_interfaces::msg::Time & timestamp, const std::string & target_frame, - const std::string & source_frame, - const geometry_msgs::msg::TransformStamped::SharedPtr & transform_stamped_ptr) const; - -private: - rclcpp::Logger logger_; - tf2_ros::Buffer tf2_buffer_; - tf2_ros::TransformListener tf2_listener_; -}; - -#endif // LOCALIZATION_UTIL__TF2_LISTENER_MODULE_HPP_ diff --git a/localization/localization_util/src/tf2_listener_module.cpp b/localization/localization_util/src/tf2_listener_module.cpp deleted file mode 100644 index 8a19ceec9f30d..0000000000000 --- a/localization/localization_util/src/tf2_listener_module.cpp +++ /dev/null @@ -1,60 +0,0 @@ -// Copyright 2015-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "localization_util/tf2_listener_module.hpp" - -#include - -geometry_msgs::msg::TransformStamped identity_transform_stamped( - const builtin_interfaces::msg::Time & timestamp, const std::string & header_frame_id, - const std::string & child_frame_id) -{ - geometry_msgs::msg::TransformStamped transform; - transform.header.stamp = timestamp; - transform.header.frame_id = header_frame_id; - transform.child_frame_id = child_frame_id; - transform.transform.rotation = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); - transform.transform.translation = tier4_autoware_utils::createTranslation(0.0, 0.0, 0.0); - return transform; -} - -Tf2ListenerModule::Tf2ListenerModule(rclcpp::Node * node) -: logger_(node->get_logger()), tf2_buffer_(node->get_clock()), tf2_listener_(tf2_buffer_) -{ -} - -bool Tf2ListenerModule::get_transform( - const builtin_interfaces::msg::Time & timestamp, const std::string & target_frame, - const std::string & source_frame, const TransformStamped::SharedPtr & transform_stamped_ptr) const -{ - const TransformStamped identity = - identity_transform_stamped(timestamp, target_frame, source_frame); - - if (target_frame == source_frame) { - *transform_stamped_ptr = identity; - return true; - } - - try { - *transform_stamped_ptr = - tf2_buffer_.lookupTransform(target_frame, source_frame, tf2::TimePointZero); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN(logger_, "%s", ex.what()); - RCLCPP_ERROR(logger_, "Please publish TF %s to %s", target_frame.c_str(), source_frame.c_str()); - - *transform_stamped_ptr = identity; - return false; - } - return true; -} 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 5457a6c310f5d..8b192b0186b42 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 @@ -15,7 +15,6 @@ #ifndef NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_ #define NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_ -#include "localization_util/tf2_listener_module.hpp" #include "localization_util/util_func.hpp" #include "ndt_scan_matcher/particle.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 6a5c61041f0da..b8792c20c323e 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 @@ -18,7 +18,6 @@ #define FMT_HEADER_ONLY #include "localization_util/smart_pose_buffer.hpp" -#include "localization_util/tf2_listener_module.hpp" #include "ndt_scan_matcher/map_module.hpp" #include "ndt_scan_matcher/map_update_module.hpp" @@ -41,6 +40,8 @@ #include #include #include +#include +#include #ifdef ROS_DISTRO_GALACTIC #include @@ -176,6 +177,8 @@ class NDTScanMatcher : public rclcpp::Node rclcpp::Service::SharedPtr service_trigger_node_; tf2_ros::TransformBroadcaster tf2_broadcaster_; + tf2_ros::Buffer tf2_buffer_; + tf2_ros::TransformListener tf2_listener_; rclcpp::CallbackGroup::SharedPtr timer_callback_group_; @@ -213,7 +216,6 @@ class NDTScanMatcher : public rclcpp::Node std::unique_ptr regularization_pose_buffer_; std::atomic is_activated_; - std::shared_ptr tf2_listener_module_; std::unique_ptr map_module_; std::unique_ptr map_update_module_; std::unique_ptr logger_configure_; 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 7f6fe605c42b0..7108dca20d8d7 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -68,6 +68,8 @@ Eigen::Matrix2d find_rotation_matrix_aligning_covariance_to_principal_axes( NDTScanMatcher::NDTScanMatcher() : Node("ndt_scan_matcher"), tf2_broadcaster_(*this), + tf2_buffer_(this->get_clock()), + tf2_listener_(tf2_buffer_), ndt_ptr_(new NormalDistributionsTransform), state_ptr_(new std::map), output_pose_covariance_({}), @@ -262,8 +264,6 @@ NDTScanMatcher::NDTScanMatcher() &NDTScanMatcher::service_trigger_node, this, std::placeholders::_1, std::placeholders::_2), rclcpp::ServicesQoS().get_rmw_qos_profile(), sensor_callback_group); - tf2_listener_module_ = std::make_shared(this); - use_dynamic_map_loading_ = this->declare_parameter("use_dynamic_map_loading"); if (use_dynamic_map_loading_) { map_update_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_); @@ -574,11 +574,25 @@ void NDTScanMatcher::transform_sensor_measurement( const pcl::shared_ptr> & sensor_points_input_ptr, pcl::shared_ptr> & sensor_points_output_ptr) { - auto tf_target_to_source_ptr = std::make_shared(); - tf2_listener_module_->get_transform( - this->now(), target_frame, source_frame, tf_target_to_source_ptr); + if (source_frame == target_frame) { + sensor_points_output_ptr = sensor_points_input_ptr; + return; + } + + geometry_msgs::msg::TransformStamped transform; + try { + transform = tf2_buffer_.lookupTransform(target_frame, source_frame, tf2::TimePointZero); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN(this->get_logger(), "%s", ex.what()); + RCLCPP_WARN( + this->get_logger(), "Please publish TF %s to %s", target_frame.c_str(), source_frame.c_str()); + // Since there is no clear error handling policy, temporarily return as is. + sensor_points_output_ptr = sensor_points_input_ptr; + return; + } + const geometry_msgs::msg::PoseStamped target_to_source_pose_stamped = - tier4_autoware_utils::transform2pose(*tf_target_to_source_ptr); + tier4_autoware_utils::transform2pose(transform); const Eigen::Matrix4f base_to_sensor_matrix = pose_to_matrix4f(target_to_source_pose_stamped.pose); tier4_autoware_utils::transformPointCloud( @@ -863,13 +877,27 @@ void NDTScanMatcher::service_ndt_align( tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res) { // get TF from pose_frame to map_frame - auto tf_pose_to_map_ptr = std::make_shared(); - tf2_listener_module_->get_transform( - get_clock()->now(), map_frame_, req->pose_with_covariance.header.frame_id, tf_pose_to_map_ptr); + const std::string & target_frame = map_frame_; + const std::string & source_frame = req->pose_with_covariance.header.frame_id; + + geometry_msgs::msg::TransformStamped transform_s2t; + try { + transform_s2t = tf2_buffer_.lookupTransform(target_frame, source_frame, tf2::TimePointZero); + } catch (tf2::TransformException & ex) { + // Note: Up to AWSIMv1.1.0, there is a known bug where the GNSS frame_id is incorrectly set to + // "gnss_link" instead of "map". The ndt_align is designed to return identity when this issue + // occurs. However, in the future, converting to a non-existent frame_id should be prohibited. + RCLCPP_WARN(this->get_logger(), "%s", ex.what()); + RCLCPP_WARN( + this->get_logger(), "Please publish TF %s to %s", target_frame.c_str(), source_frame.c_str()); + transform_s2t.header.stamp = get_clock()->now(); + transform_s2t.header.frame_id = target_frame; + transform_s2t.child_frame_id = source_frame; + transform_s2t.transform = tf2::toMsg(tf2::Transform::getIdentity()); + } // transform pose_frame to map_frame - const auto initial_pose_msg_in_map_frame = - transform(req->pose_with_covariance, *tf_pose_to_map_ptr); + const auto initial_pose_msg_in_map_frame = transform(req->pose_with_covariance, transform_s2t); if (use_dynamic_map_loading_) { map_update_module_->update_map(initial_pose_msg_in_map_frame.pose.pose.position); } From 1df42092fec79beae51098d2453bcea6857b22ac Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Tue, 9 Jan 2024 09:49:43 +0900 Subject: [PATCH 195/276] docs(ekf_localizer): improve readme and explain confusing process (#5834) * update ekf_localizer/README.md Signed-off-by: Kento Yabuuchi * add comment to explain Signed-off-by: Kento Yabuuchi * style(pre-commit): autofix * update readme Signed-off-by: Kento Yabuuchi * rename pi Signed-off-by: Kento Yabuuchi * style(pre-commit): autofix * fix typo Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/ekf_localizer/README.md | 76 +++++-------------- localization/ekf_localizer/src/ekf_module.cpp | 10 ++- 2 files changed, 29 insertions(+), 57 deletions(-) diff --git a/localization/ekf_localizer/README.md b/localization/ekf_localizer/README.md index bda1c84a2747c..87cc510c5fe14 100644 --- a/localization/ekf_localizer/README.md +++ b/localization/ekf_localizer/README.md @@ -32,71 +32,33 @@ This package includes the following features: